From f8a94e60543d5205602ac560f6995324222d0b7b Mon Sep 17 00:00:00 2001 From: robin_shaun Date: Sat, 27 Feb 2021 08:21:50 +0800 Subject: [PATCH] add sicktoolbox --- sitl_config/ugv/sicktoolbox/AUTHORS | 43 + sitl_config/ugv/sicktoolbox/CHANGELOG.rst | 96 + sitl_config/ugv/sicktoolbox/CMakeLists.txt | 121 + sitl_config/ugv/sicktoolbox/COPYING | 39 + sitl_config/ugv/sicktoolbox/README | 23 + sitl_config/ugv/sicktoolbox/THANKS | 31 + .../c++/drivers/ld/sickld/.deps/SickLD.Plo | 1 + .../ld/sickld/.deps/SickLDBufferMonitor.Plo | 1 + .../drivers/ld/sickld/.deps/SickLDMessage.Plo | 1 + .../c++/drivers/ld/sickld/SickLD.cc | 4760 +++++++++++++++ .../drivers/ld/sickld/SickLDBufferMonitor.cc | 132 + .../c++/drivers/ld/sickld/SickLDMessage.cc | 153 + .../lms1xx/sicklms1xx/.deps/SickLMS1xx.Plo | 1 + .../.deps/SickLMS1xxBufferMonitor.Plo | 1 + .../sicklms1xx/.deps/SickLMS1xxMessage.Plo | 1 + .../drivers/lms1xx/sicklms1xx/SickLMS1xx.cc | 2294 ++++++++ .../sicklms1xx/SickLMS1xxBufferMonitor.cc | 127 + .../lms1xx/sicklms1xx/SickLMS1xxMessage.cc | 201 + .../lms2xx/sicklms2xx/.deps/SickLMS2xx.Plo | 1 + .../.deps/SickLMS2xxBufferMonitor.Plo | 1 + .../sicklms2xx/.deps/SickLMS2xxMessage.Plo | 1 + .../drivers/lms2xx/sicklms2xx/SickLMS2xx.cc | 5203 +++++++++++++++++ .../sicklms2xx/SickLMS2xxBufferMonitor.cc | 133 + .../lms2xx/sicklms2xx/SickLMS2xxMessage.cc | 181 + .../c++/examples/ld/ld_config/Doxyfile | 1227 ++++ .../examples/ld/ld_config/conf/sickld.conf | 21 + .../examples/ld/ld_config/doxygen-html-header | 3 + .../ld/ld_config/src/.deps/ConfigFile.Po | 1 + .../examples/ld/ld_config/src/.deps/main.Po | 1 + .../examples/ld/ld_config/src/ConfigFile.cpp | 142 + .../examples/ld/ld_config/src/ConfigFile.h | 253 + .../c++/examples/ld/ld_config/src/main.cc | 430 ++ .../ld/ld_more_config/src/.deps/main.Po | 1 + .../examples/ld/ld_more_config/src/main.cc | 113 + .../ld/ld_multi_sector/src/.deps/main.Po | 1 + .../examples/ld/ld_multi_sector/src/main.cc | 124 + .../ld/ld_single_sector/src/.deps/main.Po | 1 + .../examples/ld/ld_single_sector/src/main.cc | 105 + .../lms1xx_simple_app/src/.deps/main.Po | 1 + .../lms1xx/lms1xx_simple_app/src/main.cc | 94 + .../c++/examples/lms2xx/lms2xx_config/README | 14 + .../lms2xx/lms2xx_config/src/.deps/main.Po | 1 + .../examples/lms2xx/lms2xx_config/src/main.cc | 627 ++ .../examples/lms2xx/lms2xx_mean_values/README | 11 + .../lms2xx_mean_values/src/.deps/main.Po | 1 + .../lms2xx/lms2xx_mean_values/src/main.cc | 114 + .../lms2xx/lms2xx_partial_scan/README | 12 + .../lms2xx_partial_scan/src/.deps/main.Po | 1 + .../lms2xx/lms2xx_partial_scan/src/main.cc | 140 + .../lms2xx/lms2xx_real_time_indices/README | 12 + .../src/.deps/main.Po | 1 + .../lms2xx_real_time_indices/src/main.cc | 125 + .../examples/lms2xx/lms2xx_set_variant/README | 12 + .../lms2xx_set_variant/src/.deps/main.Po | 1 + .../lms2xx/lms2xx_set_variant/src/main.cc | 155 + .../examples/lms2xx/lms2xx_simple_app/README | 13 + .../lms2xx_simple_app/src/.deps/main.Po | 1 + .../lms2xx/lms2xx_simple_app/src/main.cc | 104 + .../lms2xx_stream_range_and_reflect/README | 12 + .../src/.deps/main.Po | 1 + .../src/main.cc | 117 + .../examples/lms2xx/lms2xx_subrange/README | 12 + .../lms2xx/lms2xx_subrange/src/.deps/main.Po | 1 + .../lms2xx/lms2xx_subrange/src/main.cc | 109 + sitl_config/ugv/sicktoolbox/doxygen.cfg | 241 + .../include/sicktoolbox/SickBufferMonitor.hh | 471 ++ .../include/sicktoolbox/SickConfig.hh | 186 + .../include/sicktoolbox/SickException.hh | 244 + .../sicktoolbox/include/sicktoolbox/SickLD.hh | 805 +++ .../sicktoolbox/SickLDBufferMonitor.hh | 50 + .../include/sicktoolbox/SickLDMessage.hh | 80 + .../include/sicktoolbox/SickLDUtility.hh | 120 + .../include/sicktoolbox/SickLIDAR.hh | 452 ++ .../include/sicktoolbox/SickLMS1xx.hh | 335 ++ .../sicktoolbox/SickLMS1xxBufferMonitor.hh | 56 + .../include/sicktoolbox/SickLMS1xxMessage.hh | 83 + .../include/sicktoolbox/SickLMS1xxUtility.hh | 137 + .../include/sicktoolbox/SickLMS2xx.hh | 996 ++++ .../sicktoolbox/SickLMS2xxBufferMonitor.hh | 51 + .../include/sicktoolbox/SickLMS2xxMessage.hh | 99 + .../include/sicktoolbox/SickLMS2xxUtility.hh | 121 + .../include/sicktoolbox/SickMessage.hh | 230 + .../manuals/sicktoolbox-RS-422.pdf | Bin 0 -> 224402 bytes .../manuals/sicktoolbox-quickstart.pdf | Bin 0 -> 795749 bytes sitl_config/ugv/sicktoolbox/package.xml | 27 + 85 files changed, 22445 insertions(+) create mode 100644 sitl_config/ugv/sicktoolbox/AUTHORS create mode 100644 sitl_config/ugv/sicktoolbox/CHANGELOG.rst create mode 100644 sitl_config/ugv/sicktoolbox/CMakeLists.txt create mode 100644 sitl_config/ugv/sicktoolbox/COPYING create mode 100644 sitl_config/ugv/sicktoolbox/README create mode 100644 sitl_config/ugv/sicktoolbox/THANKS create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/.deps/SickLD.Plo create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/.deps/SickLDBufferMonitor.Plo create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/.deps/SickLDMessage.Plo create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/SickLD.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/SickLDBufferMonitor.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/SickLDMessage.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/.deps/SickLMS1xx.Plo create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/.deps/SickLMS1xxBufferMonitor.Plo create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/.deps/SickLMS1xxMessage.Plo create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/SickLMS1xx.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/SickLMS1xxBufferMonitor.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/SickLMS1xxMessage.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/.deps/SickLMS2xx.Plo create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/.deps/SickLMS2xxBufferMonitor.Plo create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/.deps/SickLMS2xxMessage.Plo create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/SickLMS2xx.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/SickLMS2xxBufferMonitor.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/SickLMS2xxMessage.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/Doxyfile create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/conf/sickld.conf create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/doxygen-html-header create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/.deps/ConfigFile.Po create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/.deps/main.Po create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/ConfigFile.cpp create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/ConfigFile.h create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/main.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_more_config/src/.deps/main.Po create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_more_config/src/main.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_multi_sector/src/.deps/main.Po create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_multi_sector/src/main.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_single_sector/src/.deps/main.Po create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_single_sector/src/main.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms1xx/lms1xx_simple_app/src/.deps/main.Po create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms1xx/lms1xx_simple_app/src/main.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_config/README create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_config/src/.deps/main.Po create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_config/src/main.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_mean_values/README create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_mean_values/src/.deps/main.Po create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_mean_values/src/main.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_partial_scan/README create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_partial_scan/src/.deps/main.Po create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_partial_scan/src/main.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_real_time_indices/README create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_real_time_indices/src/.deps/main.Po create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_real_time_indices/src/main.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_set_variant/README create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_set_variant/src/.deps/main.Po create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_set_variant/src/main.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_simple_app/README create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_simple_app/src/.deps/main.Po create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_simple_app/src/main.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_stream_range_and_reflect/README create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_stream_range_and_reflect/src/.deps/main.Po create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_stream_range_and_reflect/src/main.cc create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_subrange/README create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_subrange/src/.deps/main.Po create mode 100644 sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_subrange/src/main.cc create mode 100644 sitl_config/ugv/sicktoolbox/doxygen.cfg create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickBufferMonitor.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickConfig.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickException.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLD.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLDBufferMonitor.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLDMessage.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLDUtility.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLIDAR.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xx.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xxBufferMonitor.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xxMessage.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xxUtility.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xx.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xxBufferMonitor.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xxMessage.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xxUtility.hh create mode 100644 sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickMessage.hh create mode 100644 sitl_config/ugv/sicktoolbox/manuals/sicktoolbox-RS-422.pdf create mode 100644 sitl_config/ugv/sicktoolbox/manuals/sicktoolbox-quickstart.pdf create mode 100644 sitl_config/ugv/sicktoolbox/package.xml diff --git a/sitl_config/ugv/sicktoolbox/AUTHORS b/sitl_config/ugv/sicktoolbox/AUTHORS new file mode 100644 index 0000000..148ccec --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/AUTHORS @@ -0,0 +1,43 @@ +------------------------------------------------------------------- +------------------------------------------------------------------- +The Sick LIDAR Matlab/C++ Toolbox +------------------------------------------------------------------- + +The Sick LIDAR Matlab/C++ Toolbox was originally developed +and is currently maintained by Jason Derenick and Thomas Miller +at Lehigh University. It is branched from the source code used +by the Ben Franklin Racing Team, whose robot car, "Little Ben", +was only one of six to successfully finish the 2007 DARPA Urban +Grand Challenge. + +***AUTHORS + + ----------------------------------------- + Jason Derenick, Ph.D. Candidate + Computer Science and Engineering + Lehigh University + 19 Memorial Drive West + Bethlehem, PA 18015 USA + + derenick(at)lehigh(dot)edu + http://vader.cse.lehigh.edu/~derenick + ----------------------------------------- + + ----------------------------------------- + Thomas Miller + Computer Science and Engineering + Lehigh University + 19 Memorial Drive West + Bethlehem, PA 18015 USA + + thm204(at)lehigh(dot)edu + http://www.lehigh.edu/~thm204 + ----------------------------------------- + + Jason and Thomas are advised by Professor John Spletzer + in the Department of Computer Science and Engineering. + +***ACKNOWLEDGEMENTS +Please see the THANKS file :o) + +------------------------------------------------------------------- \ No newline at end of file diff --git a/sitl_config/ugv/sicktoolbox/CHANGELOG.rst b/sitl_config/ugv/sicktoolbox/CHANGELOG.rst new file mode 100644 index 0000000..fd4f690 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/CHANGELOG.rst @@ -0,0 +1,96 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package sicktoolbox +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.0.104 (2019-05-04) +-------------------- + +1.0.103 (2013-08-21) +-------------------- +* No more Willow Garage email. +* Update CMakeLists.txt +* Contributors: Chad Rockey + +1.0.102 (2013-03-28) +-------------------- +* Update README +* Catkinized and converted to CMake. +* Initial package.xml and CmakeLists.txt +* Applied power_delay.patch. +* Applying unistd.patch +* Applied stdlib_include.patch +* Removing Matlab support. +* Commiting configured files for cmake conversion. +* Forgot an installation step for the INSTALL readme. +* Updated install files, updated install directions. +* Some minor changes +* Cleaned up and began adjusting mex interface a bit for the lms1xx +* Actually, the previous post should have been renamaing 1ms to lms2xx. Now I am adding lms1xx +* Added directory for lms1xx in matlab examples directory +* Added include for GCC4.3 +* A number of improvements, bug fixes. Also put together mex file for streaming values via the lms 1xx using the given C++ driver. Adjusted mex build scripts to build and include lms1xx. +* deleting sicklms2xxlite +* Changed name of sickld-1.0 to sickld +* Moving mex lms dir to lms2xx +* fixed some bugs and restructured the driver to provide more low-level control +* Added range and reflectivity streaming; however, still can't figure out how to successfully transition between measurement modes without uninitializing. Lots of cleanup +* Adjusted the lms1xx app and some minor cleanup +* Added some range measurement acquisition to driver +* Polished configuration functions +* Adjusted lms1xx example file +* committing cahnges to base and sick ld & lms2xx drivers +* Fixed some bugs and setup configuration capability for the lms 1xx driver +* Started adding _getSickStatus and began writing the message parsing code for the Sick LMS 1xx - currently the LMS 1xx will compile but is unstable +* Setup connect/disconnect routines and buffer monitor for SickLMS1xx driver. Also, included an example for testing the code right now. +* Started adding driver files for SickLMS1xx unit +* Adjusted lms examples to using renamed sicklms2xx class. Also fixed corresponding makefiles and changed the prefix for each lms example to lms2xx (e.g. lms_config is now lms2xx_config) +* Moved c++/examples/lms to c++/examples/lms2xx +* Supplanted SickLMS with SickLMS2xx and sick_lms with sick_lms_2xx where appropriate. Currently compiles, but needs a sanity test +* Created sicklms1xx driver directory and Makefile.am for each directory (currently, they are empty) +* Updating configure.ac to use the new AX macros for lms1xx and lms2xx source directories +* changes sicklms-1.0 to sicklms2xx and sicklmslite-1.0 to sicklms1xx +* Adding macros for setting lms2xx and lms1xx source directories +* Changed lms driver directory to lms2xx and created lms1xx drive directory in c++/drivers +* Fixed a bug concerning dynamically allocating strings on the stack of an active exception. Thanks to Philipp Aumayr and Simon Opelt for their original patch, which motivated this fix. +* Fixed quotation bug for newer versions of autoconf/aclocal. + See http://www.gnu.org/software/autoconf/manual/html_node/Quoting-and-Parameters.html +* Added stdlib.h to ld_config's main.cc and lms_config's main.cc +* +* +* +* +* Added ld_lite directory +* Addedd lms_lite directory +* +* +* Added ld_lite folder for ld_lite driver +* Added lms_lite directory for lms_lite driver +* lmsmex.cc now supports up to four separate Sick LMS units. +* Set lmsmex.cc to also return a vector of bearings for range and/or reflectivity values. The coordinate system corresponds to that defined in the Sick LMS 2xx manuals. Adjusted lms_cart and lms_stream examples to use this vector. +* Removed SickConfig.hh from the driver headers and adjusted the installation to leave out SickConfig.hh and the utility headers as per Tully's suggestion. +* Changed std::cerr to std::cout for printing 'cancel buffer monitor' string +* Adjusted m-file comments for sickld and sicklms +* Adjusted m-file comments +* Fixing permissions +* Still fixing file permissions +* Adjusting file permissions +* Took out std::cerr in bad checksum exception handler. +* Took out std::cerr in bad checksum exception handler. +* Monitor now clears buffer on bad checksum +* Monitor now clears msg container on bad checksum +* Fixed print-out in build_mex script +* Took out packed attribute for structs in SickLMS.hh. +* Removed try/catch in buffer monitor base +* Adjusted the examples to exit more cleanly. +* Fixed rm -r bug in build_mex and install_mex +* Adjusted configure.ac +* Fixing README +* testing +* Adjusted NEWS +* Modified INSTALL +* Fixing permissions on matlab/install_mex. +* Fixing permissions with mex bash script. +* Changed dates in mex installation bash scripts. +* Removed doc directory from c++/drivers/ld. +* Initial project import. +* Contributors: Chad Rockey, Chris Mansley, Jason Derenick, Michael Sands, Tom Miller, chadrockey diff --git a/sitl_config/ugv/sicktoolbox/CMakeLists.txt b/sitl_config/ugv/sicktoolbox/CMakeLists.txt new file mode 100644 index 0000000..6e21fca --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/CMakeLists.txt @@ -0,0 +1,121 @@ +cmake_minimum_required(VERSION 2.8.3) +project(sicktoolbox) + +find_package(catkin REQUIRED) + +## System dependencies are found with CMake's conventions +find_package(Threads REQUIRED) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + INCLUDE_DIRS include + LIBRARIES SickLD SickLMS1xx SickLMS2xx + CATKIN_DEPENDS + DEPENDS Threads +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories(include ${catkin_INCLUDE_DIRS}) + +# Driver libraries +add_library(SickLD c++/drivers/ld/sickld/SickLD.cc c++/drivers/ld/sickld/SickLDBufferMonitor.cc c++/drivers/ld/sickld/SickLDMessage.cc) +target_link_libraries(SickLD ${catkin_LIBRARIES} ${CMAKE_THREAD_LIBS_INIT}) + +add_library(SickLMS1xx c++/drivers/lms1xx/sicklms1xx/SickLMS1xx.cc c++/drivers/lms1xx/sicklms1xx/SickLMS1xxBufferMonitor.cc c++/drivers/lms1xx/sicklms1xx/SickLMS1xxMessage.cc) +target_link_libraries(SickLMS1xx ${catkin_LIBRARIES} ${CMAKE_THREAD_LIBS_INIT}) + +add_library(SickLMS2xx c++/drivers/lms2xx/sicklms2xx/SickLMS2xx.cc c++/drivers/lms2xx/sicklms2xx/SickLMS2xxBufferMonitor.cc c++/drivers/lms2xx/sicklms2xx/SickLMS2xxMessage.cc) +target_link_libraries(SickLMS2xx ${catkin_LIBRARIES} ${CMAKE_THREAD_LIBS_INIT}) + +# Examples +add_library(LDConfigLib c++/examples/ld/ld_config/src/ConfigFile.cpp) +add_executable(ld_config c++/examples/ld/ld_config/src/main.cc) +target_link_libraries(ld_config SickLD LDConfigLib ${catkin_LIBRARIES}) + +add_executable(ld_more_config c++/examples/ld/ld_more_config/src/main.cc) +target_link_libraries(ld_more_config SickLD ${catkin_LIBRARIES}) + +add_executable(ld_multi_sector c++/examples/ld/ld_multi_sector/src/main.cc) +target_link_libraries(ld_multi_sector SickLD ${catkin_LIBRARIES}) + +add_executable(ld_single_sector c++/examples/ld/ld_single_sector/src/main.cc) +target_link_libraries(ld_single_sector SickLD ${catkin_LIBRARIES}) + +add_executable(lms1xx_simple_app c++/examples/lms1xx/lms1xx_simple_app/src/main.cc) +target_link_libraries(lms1xx_simple_app SickLMS1xx ${catkin_LIBRARIES}) + +add_executable(lms2xx_config c++/examples/lms2xx/lms2xx_config/src/main.cc) +target_link_libraries(lms2xx_config SickLMS2xx ${catkin_LIBRARIES}) + +add_executable(lms2xx_mean_values c++/examples/lms2xx/lms2xx_mean_values/src/main.cc) +target_link_libraries(lms2xx_mean_values SickLMS2xx ${catkin_LIBRARIES}) + +add_executable(lms2xx_partial_scan c++/examples/lms2xx/lms2xx_partial_scan/src/main.cc) +target_link_libraries(lms2xx_partial_scan SickLMS2xx ${catkin_LIBRARIES}) + +add_executable(lms2xx_real_time_indices c++/examples/lms2xx/lms2xx_real_time_indices/src/main.cc) +target_link_libraries(lms2xx_real_time_indices SickLMS2xx ${catkin_LIBRARIES}) + +add_executable(lms2xx_set_variant c++/examples/lms2xx/lms2xx_set_variant/src/main.cc) +target_link_libraries(lms2xx_set_variant SickLMS2xx ${catkin_LIBRARIES}) + +add_executable(lms2xx_simple_app c++/examples/lms2xx/lms2xx_simple_app/src/main.cc) +target_link_libraries(lms2xx_simple_app SickLMS2xx ${catkin_LIBRARIES}) + +add_executable(lms2xx_stream_range_and_reflect c++/examples/lms2xx/lms2xx_stream_range_and_reflect/src/main.cc) +target_link_libraries(lms2xx_stream_range_and_reflect SickLMS2xx ${catkin_LIBRARIES}) + +add_executable(lms2xx_subrange c++/examples/lms2xx/lms2xx_subrange/src/main.cc) +target_link_libraries(lms2xx_subrange SickLMS2xx ${catkin_LIBRARIES}) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/groovy/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +install(TARGETS SickLD SickLMS1xx SickLMS2xx LDConfigLib ld_config + ld_more_config ld_multi_sector ld_single_sector lms1xx_simple_app + lms2xx_config lms2xx_mean_values lms2xx_partial_scan lms2xx_real_time_indices + lms2xx_set_variant lms2xx_simple_app lms2xx_stream_range_and_reflect lms2xx_subrange + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +## TODO Move headers that aren't needed externally back into the source +## Mark cpp header files for installation +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.hh" + PATTERN ".svn" EXCLUDE +) + +## TODO There are readmes, etc, create install rules for these +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) diff --git a/sitl_config/ugv/sicktoolbox/COPYING b/sitl_config/ugv/sicktoolbox/COPYING new file mode 100644 index 0000000..f47c3f1 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/COPYING @@ -0,0 +1,39 @@ +-------------------------------------------------------------------- +-------------------------------------------------------------------- +The Sick LIDAR Matlab/C++ Toolbox (BSD) License +-------------------------------------------------------------------- + +The Sick LIDAR Matlab/C++ Toolbox +Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller +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(s) of the copyright holders 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 OWNER 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. + +-------------------------------------------------------------------- diff --git a/sitl_config/ugv/sicktoolbox/README b/sitl_config/ugv/sicktoolbox/README new file mode 100644 index 0000000..3a75269 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/README @@ -0,0 +1,23 @@ +------------------------------------------------------------------- +------------------------------------------------------------------- +The Sick LIDAR C++ Toolbox +------------------------------------------------------------------- + +This is the ROS fork of the Sick LIDAR C++ Toolbox. If you're +looking for Matlab, please see the original at: +http://sicktoolbox.sourceforge.net/ + +*** Quick Start +To get up and running quickly with the toolbox, be sure to read +the quick start guide in the manuals directory. Additionally, to +enable 500Kbps communication via a USB-COMi-M be sure to see the +RS-422 tutorial in said directory. + +*** Other Files +Please see the following documents for additional info: + + COPYING - Information regarding the software license + AUTHORS - Information about the authors + THANKS - Acknowledgements + +------------------------------------------------------------------- diff --git a/sitl_config/ugv/sicktoolbox/THANKS b/sitl_config/ugv/sicktoolbox/THANKS new file mode 100644 index 0000000..f7d82c8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/THANKS @@ -0,0 +1,31 @@ +------------------------------------------------------------------- +------------------------------------------------------------------- +The Sick LIDAR Matlab/C++ Toolbox +------------------------------------------------------------------- + +The authors would like to express their sincere gratitude to the +following members of the Ben Franklin Racing Team for their key +insights and help in developing the toolbox: + + Aleksandr Kushleyev + Tully Foote + Alex Stewart + Jon Bohren + Brian Satterfield + Professor Daniel Lee + Professor John Spetzer + +Additionally, we'd like to thank Douglas Paul for his work on the +initial Sick LMS 2xx serial driver. + +*** Additional Acknowledgments +This software makes use of the following open-source +packages for its package configuration: + +doxample - by Oren Ben-kiki +http://www.ben-kiki.org/oren/doxample + +acx_pthread - by Steven G. Johnson +http://autoconf-archive.cryp.to/acx_pthread.html + +------------------------------------------------------------------- \ No newline at end of file diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/.deps/SickLD.Plo b/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/.deps/SickLD.Plo new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/.deps/SickLD.Plo @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/.deps/SickLDBufferMonitor.Plo b/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/.deps/SickLDBufferMonitor.Plo new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/.deps/SickLDBufferMonitor.Plo @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/.deps/SickLDMessage.Plo b/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/.deps/SickLDMessage.Plo new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/.deps/SickLDMessage.Plo @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/SickLD.cc b/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/SickLD.cc new file mode 100644 index 0000000..9d68f83 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/SickLD.cc @@ -0,0 +1,4760 @@ +/*! + * \file SickLD.cc + * \brief Implements the SickLD driver class. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +/* Auto-generated header */ +#include + +/* Implementation dependencies */ +#include +#include +#include +#include +#include // for converting numerical values to strings +#include // for socket function definitions +#include // for sockaddr_in, inet_addr, and htons +#include // for using ioctl functionality for the socket input buffer +#include // for select functionality (e.g. FD_SET, etc...) +#include // for fd data types +#include // for select timeout parameter +#include // for getting file flags +#include // for POSIX threads +#include // for parsing ip addresses +#include // for returning the results of parsed strings +#include // for timing connect() + +#include +#include +#include +#include +#include + +/* Associate the namespace */ +namespace SickToolbox { + + /** + * \brief A standard constructor + * \param sick_ip_address The ip address of the Sick LD + * \param sick_tcp_port The TCP port associated w/ the Sick LD server + */ + SickLD::SickLD( const std::string sick_ip_address, const uint16_t sick_tcp_port ) : + SickLIDAR< SickLDBufferMonitor, SickLDMessage >( ), + _sick_ip_address(sick_ip_address), + _sick_tcp_port(sick_tcp_port), + _sick_sensor_mode(SICK_SENSOR_MODE_UNKNOWN), + _sick_motor_mode(SICK_MOTOR_MODE_UNKNOWN), + _sick_streaming_range_data(false), + _sick_streaming_range_and_echo_data(false) + { + /* Initialize the sick identity */ + _sick_identity.sick_part_number = + _sick_identity.sick_name = + _sick_identity.sick_version = + _sick_identity.sick_serial_number = + _sick_identity.sick_edm_serial_number = + _sick_identity.sick_firmware_part_number = + _sick_identity.sick_firmware_name = + _sick_identity.sick_firmware_version = + _sick_identity.sick_application_software_part_number = + _sick_identity.sick_application_software_name = + _sick_identity.sick_application_software_version = "UNKNOWN"; + + /* Initialize the global configuration structure */ + memset(&_sick_global_config,0,sizeof(sick_ld_config_global_t)); + + /* Initialize the Ethernet configuration structure */ + memset(&_sick_ethernet_config,0,sizeof(sick_ld_config_ethernet_t)); + + /* Initialize the sector configuration structure */ + memset(&_sick_sector_config,0,sizeof(sick_ld_config_sector_t)); + } + + /** + * A standard destructor + */ + SickLD::~SickLD( ) { } + + /** + * \brief Initializes the driver and syncs it with Sick LD unit. Uses sector config given in flash. + */ + void SickLD::Initialize( ) throw( SickIOException, SickThreadException, SickTimeoutException, SickErrorException ) { + + std::cout << "\t*** Attempting to initialize the Sick LD..." << std::endl; + + try { + + /* Attempt to connect to the Sick LD */ + std::cout << "\tAttempting to connect to Sick LD @ " << _sick_ip_address << ":" << _sick_tcp_port << std::endl; + _setupConnection(); + std::cout << "\t\tConnected to Sick LD!" << std::endl; + + /* Start the buffer monitor */ + std::cout << "\tAttempting to start buffer monitor..." << std::endl; + _startListening(); + std::cout << "\t\tBuffer monitor started!" << std::endl; + + /* Ok, lets sync the driver with the Sick */ + std::cout << "\tAttempting to sync driver with Sick LD..." << std::endl; + _syncDriverWithSick(); + + } + + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + catch(...) { + std::cerr << "SickLD::Initialize - Unknown exception!" << std::endl; + throw; + } + + std::cout << "\t\tSynchronized!" << std::endl; + + _sick_initialized = true; + _printInitFooter(); + + /* Success */ + } + + /** + * \brief Acquires the status of the Sick from the device + * \param &sick_sensor_mode The returned sensor mode of the device + * \param &sick_motor_mode The returned motor mode of the device + */ + void SickLD::GetSickStatus( unsigned int &sick_sensor_mode, unsigned int &sick_motor_mode ) + throw( SickIOException, SickTimeoutException ){ + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLD::GetSickStatus: Device NOT Initialized!!!"); + } + + /* Acquire the sensor and motor mode from the device */ + try { + _getSickStatus(); + } + + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + catch(...) { + std::cerr << "SickLD::GetSickStatus - Unknown exception!" << std::endl; + throw; + } + + /* Now that the driver is updated, assign the return values */ + sick_sensor_mode = _sick_sensor_mode; + sick_motor_mode = _sick_motor_mode; + + /* Success */ + } + + /** + * \brief Set the temporary scan areas for the Sick LD + * \param *active_sector_start_angles Angles marking the beginning of each desired active sector/area + * \param *active_sector_stop_angles Angles marking the end of each desired active sector/area + * \param num_active_sectors The number of active sectors + * + * NOTE: The active scan areas set at this point are only maintained until a device + * reset occurs. In other words, they are not written to flash. + */ + void SickLD::SetSickTempScanAreas( const double * active_sector_start_angles, const double * active_sector_stop_angles, + const unsigned int num_active_sectors ) + throw( SickTimeoutException, SickIOException, SickConfigException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLD::SetSickTempScanAreas: Device NOT Initialized!!!"); + } + + /* Do the standard initialization */ + try { + + /* Set the temporary scan configuration */ + std::cout << "\tAttempting to set desired scan config..." << std::endl; + _setSickTemporaryScanAreas(active_sector_start_angles,active_sector_stop_angles,num_active_sectors); + std::cout << "\t\tUsing desired scan area(s)!" << std::endl; + + } + + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + catch(...) { + std::cerr << "SickLD::Initialize - Unknown exception!" << std::endl; + throw; + } + + /* Success */ + } + + + /** + * \brief Set the absolute time of the Sick LD unit. + * \param absolute_clock_time The absolute clock time in milliseconds + * \param new_sick_clock_time The clock time in milliseconds returned from the device + * + * ALERT: If the Sick LD is in MEASUREMENT mode, this method will first set the device + * to ROTATE mode after killing any active data streams (as per the protocol). + */ + void SickLD::SetSickTimeAbsolute( const uint16_t absolute_clock_time, uint16_t &new_sick_clock_time ) + throw( SickErrorException, SickTimeoutException, SickIOException, SickConfigException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLD::SetSickTimeAbsolute: Device NOT Initialized!!!"); + } + + /* Ensure the device is not in MEASURE mode */ + if (_sick_sensor_mode == SICK_SENSOR_MODE_MEASURE) { + + /* If it is then set it to rotate */ + try { + _setSickSensorModeToRotate(); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::SetSickTimeAbsolute: Unknown exception!!!" << std::endl; + throw; + } + + } + + std::cout << "\tSetting Sick LD absolute clock time..." << std::endl; + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the service codes */ + payload_buffer[0] = SICK_CONF_SERV_CODE; + payload_buffer[1] = SICK_CONF_SERV_SET_TIME_ABSOLUTE; + + /* Set the new time value */ + uint16_t temp_buffer = host_to_sick_ld_byte_order(absolute_clock_time); + memcpy(&payload_buffer[2],&temp_buffer,2); + + /* Create the Sick LD send/receive message objects */ + SickLDMessage send_message(payload_buffer,4); + SickLDMessage recv_message; + + /* Send the message and check for the reply */ + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSensorMode: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the payload buffer */ + memset(payload_buffer,0,4); + + /* Get the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Extract the new Sick LD clock time from the response */ + uint16_t clock_time; + memcpy(&clock_time,&payload_buffer[2],2); + new_sick_clock_time = sick_ld_to_host_byte_order(clock_time); + + std::cout << "\t\tClock time set!" << std::endl; + + /* Success */ + } + + /** + * \brief Set the relative time of the Sick LD unit. + * \param delta_time The relative clock time in milliseconds. + * \param &new_sick_clock_time The new time as reported by the Sick LD. + * + * ALERT: If the Sick LD is in MEASUREMENT mode, this method will first set the device + * to ROTATE mode after killing any active data streams (as per the protocol). + */ + void SickLD::SetSickTimeRelative( const int16_t delta_time, uint16_t &new_sick_clock_time ) + throw( SickErrorException, SickTimeoutException, SickIOException, SickConfigException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLD::SetSickTimeRelative: Device NOT Initialized!!!"); + } + + /* Ensure the device is not in MEASURE mode */ + if (_sick_sensor_mode == SICK_SENSOR_MODE_MEASURE) { + + /* If it is then set it to rotate */ + try { + _setSickSensorModeToRotate(); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::SetSickTimeRelative: Unknown exception!!!" << std::endl; + throw; + } + + } + + std::cout << "\tSetting Sick LD relative clock time..." << std::endl; + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the service codes */ + payload_buffer[0] = SICK_CONF_SERV_CODE; + payload_buffer[1] = SICK_CONF_SERV_SET_TIME_RELATIVE; + + /* Set the new time value */ + uint16_t temp_buffer = host_to_sick_ld_byte_order((uint16_t)delta_time); + memcpy(&payload_buffer[2],&temp_buffer,2); + + /* Create the Sick LD send/receive message objects */ + SickLDMessage send_message(payload_buffer,4); + SickLDMessage recv_message; + + /* Send the message and check for the expected reply */ + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickTimeRelative: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the payload buffer */ + memset(payload_buffer,0,4); + + /* Get the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Extract the new Sick LD clock time from the response */ + uint16_t clock_time; + memcpy(&clock_time,&payload_buffer[2],2); + new_sick_clock_time = sick_ld_to_host_byte_order(clock_time); + + std::cout << "\t\tClock time set!" << std::endl; + + /* Success */ + } + + /** + * \brief Sets the Sick LD signal LED's and switching outputs + * \param sick_signal_flags Indicates the LEDs and switches to set/unset. + * + * NOTE: This method does not preserve the previous state of the Sick's signals. + * In other words, only the signals flagged in sick_signal_flags will be + * set - all others will be off! + */ + void SickLD::SetSickSignals( const uint8_t sick_signal_flags ) + throw( SickIOException, SickTimeoutException, SickErrorException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLD::SetSickSignals: Device NOT Initialized!!!"); + } + + /* Attempt to set the signal flags */ + try { + _setSickSignals(sick_signal_flags); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_syncDriverWithSick: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + } + + /** + * \brief Gets the Sick LD signal LED's and switching outputs. + * \param &sick_signal_flags The destination buffer to hold the returned flags. + */ + void SickLD::GetSickSignals( uint8_t &sick_signal_flags ) throw( SickIOException, SickTimeoutException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLD::GetSickSignals: Device NOT Initialized!!!"); + } + + /* Initialize the destination buffer */ + sick_signal_flags = 0; + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the service IDs */ + payload_buffer[0] = SICK_STAT_SERV_CODE; // Requested service type + payload_buffer[1] = SICK_STAT_SERV_GET_SIGNAL; // Requested service subtype + + /* Create the Sick message */ + SickLDMessage send_message(payload_buffer,2); + SickLDMessage recv_message; + + /* Send the message and get the reply */ + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::GetSickSignals: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the payload buffer */ + memset(payload_buffer,0,2); + + /* Extract the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Extract the Signal flags */ + sick_signal_flags = payload_buffer[3]; + + /* Success */ + } + + /** + * \brief Gets the internal clock time of the Sick LD unit. + * \param &sick_time The sick clock time in milliseconds. + */ + void SickLD::GetSickTime( uint16_t &sick_time ) + throw( SickIOException, SickTimeoutException, SickErrorException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLD::GetSickTime: Device NOT Initialized!!!"); + } + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the service IDs */ + payload_buffer[0] = SICK_CONF_SERV_CODE; // Requested service type + payload_buffer[1] = SICK_CONF_SERV_GET_SYNC_CLOCK; // Requested service subtype + + /* Create the Sick messages */ + SickLDMessage send_message(payload_buffer,2); + SickLDMessage recv_message; + + /* Send the message and check the reply */ + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::GetSickTime: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the payload buffer */ + memset(payload_buffer,0,2); + + /* Acquire the returned payload */ + recv_message.GetPayload(payload_buffer); + + /* Extract actual time */ + uint16_t current_time; + memcpy(¤t_time,&payload_buffer[2],2); + sick_time = sick_ld_to_host_byte_order(current_time); + + /* Success */ + } + + /** + * \brief Enables nearfield suppressive filtering + * + * NOTE: This method writes this option to the Sick LD's flash, so there is no + * need to use it except when configuring the device. + */ + void SickLD::EnableNearfieldSuppression( ) + throw( SickErrorException, SickTimeoutException, SickIOException ) { + + /* Ensure the device has been initialized */ + if(!_sick_initialized) { + throw SickIOException("SickLD::EnableNearfieldSuppression: Device NOT Initialized!!!"); + } + + /* Tell the Sick LD to use nearfield suppression! */ + std::cout << "\tEnabling nearfield suppression..." << std::endl; + try { + _setSickFilter(SICK_CONF_SERV_SET_FILTER_NEARFIELD_ON); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::EnableNearfieldSuppression: Unknown exception!!!" << std::endl; + throw; + } + + std::cout << "\t\tSuppression is enabled!" << std::endl; + + /* Success */ + } + + /** + * \brief Disables nearfield suppressive filtering + * + * NOTE: This method writes this option to the Sick LD's flash, so there is no + * need to use it except when configuring the device. + */ + void SickLD::DisableNearfieldSuppression( ) + throw( SickErrorException, SickTimeoutException, SickIOException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLD::DisableNearfieldSuppression: Device NOT Initialized!!!"); + } + + /* Tell the Sick LD to use nearfield suppression! */ + std::cout << "\tDisabling nearfield suppression..." << std::endl; + try { + _setSickFilter(SICK_CONF_SERV_SET_FILTER_NEARFIELD_OFF); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::DisableNearfieldSuppression: Unknown exception!!!" << std::endl; + throw; + } + + std::cout << "\t\tSuppression is disabled!" << std::endl; + + /* Success */ + } + + /** + * \brief Acquires measurements and corresponding sector data from the Sick LD. + * \param *range_measurements A single array to hold ALL RANGE MEASUREMENTS from the current scan for all active + * sectors. Range values from each sector are stored block sequentially in this buffer. + * The respective index into the array marking the first data value returned by active + * sector i can be found by getting: range_measurement[sector_data_offsets[i]]. + * \param *echo_measurements A single array to hold ALL ECHO MEASUREMENTS from the current scan for all active sectors. + * It is indexed the same as range_measurements. This argument is optional and if it is not + * provided the driver will request a RANGE ONLY data stream as opposed to a RANGE+ECHO thereby + * reducing consumed bandwidth (Default: NULL). + * \param *num_measurements An array where the ith element denotes the number of range/echo measurements obtained from + * active sector i (Default: NULL). + * \param *sector_ids An array where the ith element corresponds to the actual sector number/id of the ith active + * sector. (Default: NULL) + * \param *sector_data_offsets The index offsets mapping the ith active sector to the position in range_measurements + * where its first measured value can be found (Default: NULL). + * \param *sector_step_angles An array where the ith element corresponds to the angle step for the ith active sector. + * (Default: NULL) + * \param *sector_start_angles An array where the ith element corresponds to the starting scan angle of the ith active + * sector. + * \param *sector_stop_angles An array where the ith element corresponds to the stop scan angle of the ith active sector. + * \param *sector_start_timestamps An array where the ith element denotes the time at which the first scan was taken for + * the ith active sector. + * \param *sector_stop_timestamps An array where the ith element denotes the time at which the last scan was taken for + * the ith active sector. + * + * ALERT: The user is responsible for ensuring that enough space is allocated for the return buffers to avoid overflow. + * See the example code for an easy way to do this. + */ + void SickLD::GetSickMeasurements( double * const range_measurements, + unsigned int * const echo_measurements, + unsigned int * const num_measurements, + unsigned int * const sector_ids, + unsigned int * const sector_data_offsets, + double * const sector_step_angles, + double * const sector_start_angles, + double * const sector_stop_angles, + unsigned int * const sector_start_timestamps, + unsigned int * const sector_stop_timestamps ) + throw( SickErrorException, SickIOException, SickTimeoutException, SickConfigException ){ + + /* Ensure the device has been initialized */ + if(!_sick_initialized) { + throw SickIOException("SickLD::GetSickMeasurements: Device NOT Initialized!!!"); + } + + /* The following conditional holds true if the user wants a RANGE+ECHO data + * stream but already has an active RANGE-ONLY stream. + */ + if (_sick_streaming_range_data && echo_measurements != NULL) { + + try { + + /* Cancel the current RANGE-ONLY data stream */ + _cancelSickScanProfiles(); + + /* Request a RANGE+ECHO data stream */ + _getSickScanProfiles(SICK_SCAN_PROFILE_RANGE_AND_ECHO); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::GetSickMeasurements: Unknown exception!!!" << std::endl; + throw; + } + + } + + /* The following conditional holds true if the user wants a RANGE-ONLY data + * stream but already has an active RANGE+ECHO stream. + */ + if (_sick_streaming_range_and_echo_data && echo_measurements == NULL) { + + try { + + /* Cancel the current RANGE+ECHO data stream */ + _cancelSickScanProfiles(); + + /* Request a RANGE-ONLY data stream */ + _getSickScanProfiles(SICK_SCAN_PROFILE_RANGE); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::GetSickMeasurements: Unknown exception!!!" << std::endl; + throw; + } + + } + + /* If there aren't any active data streams, setup a new one */ + if (!_sick_streaming_range_data && !_sick_streaming_range_and_echo_data) { + + try { + + /* Determine the target data stream by checking the value of echo_measurements */ + if (echo_measurements != NULL) { + + /* Request a RANGE+ECHO data stream */ + _getSickScanProfiles(SICK_SCAN_PROFILE_RANGE_AND_ECHO); + + } + else { + + /* Request a RANGE+ONLY data stream */ + _getSickScanProfiles(SICK_SCAN_PROFILE_RANGE); + + } + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSensorMode: Unknown exception!!!" << std::endl; + throw; + } + + } + + /* Declare the receive message object */ + SickLDMessage recv_message; + + /* Acquire the most recently buffered message */ + try { + _recvMessage(recv_message,(unsigned int)1e6); + } + + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + catch(...) { + std::cerr << "SickLD::GetSickMeasurements - Unknown exception!" << std::endl; + throw; + } + + /* A single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Get the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Define the destination Sick LD scan profile struct */ + sick_ld_scan_profile_t profile_data; + + /* Extract the scan profile */ + _parseScanProfile(&payload_buffer[2],profile_data); + + /* Update and check the returned sensor status */ + if ((_sick_sensor_mode = profile_data.sensor_status) != SICK_SENSOR_MODE_MEASURE) { + throw SickConfigException("SickLD::GetSickMeasurements: Unexpected sensor mode! " + _sickSensorModeToString(_sick_sensor_mode)); + } + + /* Update and check the returned motor status */ + if ((_sick_motor_mode = profile_data.motor_status) != SICK_MOTOR_MODE_OK) { + throw SickConfigException("SickLD::GetSickMeasurements: Unexpected motor mode! (Are you using a valid motor speed!)"); + } + + /* Everything is OK, so now populate the relevant return buffers */ + for (unsigned int i = 0, total_measurements = 0; i < _sick_sector_config.sick_num_active_sectors; i++) { + + /* Copy over the returned range values */ + memcpy(&range_measurements[total_measurements],profile_data.sector_data[_sick_sector_config.sick_active_sector_ids[i]].range_values, + profile_data.sector_data[_sick_sector_config.sick_active_sector_ids[i]].num_data_points*sizeof(double)); + + /* Copy the returned echo values if requested */ + if (echo_measurements != NULL) { + memcpy(&echo_measurements[total_measurements],profile_data.sector_data[_sick_sector_config.sick_active_sector_ids[i]].echo_values, + profile_data.sector_data[_sick_sector_config.sick_active_sector_ids[i]].num_data_points*sizeof(unsigned int)); + } + + /* Set the number of measurements */ + if (num_measurements != NULL) { + num_measurements[i] = profile_data.sector_data[_sick_sector_config.sick_active_sector_ids[i]].num_data_points; + } + + /* Set the associated sector's id if requested */ + if (sector_ids != NULL) { + sector_ids[i] = profile_data.sector_data[_sick_sector_config.sick_active_sector_ids[i]].sector_num; + } + + /* Set the associated sector's index into the range measurement buffer if requested */ + if (sector_data_offsets != NULL) { + sector_data_offsets[i] = total_measurements; + } + + /* Set the step angle if requested */ + if (sector_step_angles != NULL) { + sector_step_angles[i] = profile_data.sector_data[_sick_sector_config.sick_active_sector_ids[i]].angle_step; + } + + /* Set the sector start angle if requested */ + if (sector_start_angles != NULL) { + sector_start_angles[i] = profile_data.sector_data[_sick_sector_config.sick_active_sector_ids[i]].angle_start; + } + + /* Set the sector stop angle if requested */ + if (sector_stop_angles != NULL) { + sector_stop_angles[i] = profile_data.sector_data[_sick_sector_config.sick_active_sector_ids[i]].angle_stop; + } + + /* Set the sector start timestamp if requested */ + if (sector_start_timestamps != NULL) { + sector_start_timestamps[i] = profile_data.sector_data[_sick_sector_config.sick_active_sector_ids[i]].timestamp_start; + } + + /* Set the sector stop timestamp if requested */ + if (sector_stop_timestamps != NULL) { + sector_stop_timestamps[i] = profile_data.sector_data[_sick_sector_config.sick_active_sector_ids[i]].timestamp_stop; + } + + /* Update the total number of measurements */ + total_measurements += profile_data.sector_data[_sick_sector_config.sick_active_sector_ids[i]].num_data_points; + } + + /* Success */ + + } + + /** + * \brief Attempts to set a new sensor ID for the device (in flash) + * \param sick_sensor_id The desired sensor ID + */ + void SickLD::SetSickSensorID( const unsigned int sick_sensor_id ) + throw( SickErrorException, SickTimeoutException, SickIOException ){ + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLD::SetSickSensorID: Device NOT Initialized!!!"); + } + + /* Check that the given ID is valid */ + if (!_validSickSensorID(sick_sensor_id)) { + throw SickConfigException("SickLD::SetSickSensorID: Invalid sensor ID!!!"); + } + + /* Attempt to set the new sensor ID in the flash! */ + try { + _setSickGlobalConfig(sick_sensor_id,GetSickMotorSpeed(),GetSickScanResolution()); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::SetSickSensorID: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + } + + /** + * \brief Attempts to set a new motor speed for the device (in flash) + * \param sick_motor_speed The desired motor speed (Hz) + */ + void SickLD::SetSickMotorSpeed( const unsigned int sick_motor_speed ) + throw( SickErrorException, SickTimeoutException, SickIOException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLD::SetSickMotorSpeed: Device NOT Initialized!!!"); + } + + /* Check that the given motor speed is valid */ + if (!_validSickMotorSpeed(sick_motor_speed)) { + throw SickConfigException("SickLD::SetSickMotorSpeed: Invalid sick motor speed!!!"); + } + + /* Check to ensure a valid pulse frequency for the device */ + if (!_validPulseFrequency(sick_motor_speed,GetSickScanResolution())) { + throw SickConfigException("SickLD::SetSickMotorSpeed: Invalid pulse frequency!!!"); + } + + /* Attempt to set the new global config in the flash! */ + try { + _setSickGlobalConfig(GetSickSensorID(),sick_motor_speed,GetSickScanResolution()); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::SetSickMotorSpeed: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + } + + /** + * \brief Attempts to set a new scan resolution for the device (in flash) while + * retaining the previously defined active scan areas. + * \param sick_angle_step The desired scan resolution (deg) + * + * NOTE: Since the Sick determines the active sector bounds based upon the current + * scan resolution and sector stop angles, it is possible that when the scan + * resolution is changed so too are the active sector bounds. As such, we + * also write the correct sector config to flash as opposed to letting the + * Sick LD just figure it out itself. Doing so ensures the previous active + * sector definitions remain intact. + */ + void SickLD::SetSickScanResolution( const double sick_angle_step ) + throw( SickTimeoutException, SickIOException, SickConfigException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLD::SetSickScanResolution: Device NOT Initialized!!!"); + } + + /* Buffers to hold the active sector data */ + double active_sector_start_angles[SICK_MAX_NUM_SECTORS] = {0}; + double active_sector_stop_angles[SICK_MAX_NUM_SECTORS] = {0}; + + /* Extract the start and stop angles for the current active sectors */ + for (unsigned int i = 0; i < _sick_sector_config.sick_num_active_sectors; i++) { + active_sector_start_angles[i] = _sick_sector_config.sick_sector_start_angles[_sick_sector_config.sick_active_sector_ids[i]]; + active_sector_stop_angles[i] = _sick_sector_config.sick_sector_stop_angles[_sick_sector_config.sick_active_sector_ids[i]]; + } + + /* Set the operating parameters accordingly */ + try { + SetSickGlobalParamsAndScanAreas(GetSickMotorSpeed(),sick_angle_step, + active_sector_start_angles,active_sector_stop_angles, + _sick_sector_config.sick_num_active_sectors); + } + + catch(...) { } + + /* Success! */ + } + + /** + * \brief Attempts to set the scan resolution and active sectors/scan areas for the device (in flash) + * \param sick_motor_speed Desired sick motor speed (Hz) + * \param sick_angle_step Desired scan angular resolution (deg) + * \param active_sector_start_angles Angles marking the beginning of each desired active sector/area + * \param active_sector_stop_angles Angles marking the end of each desired active sector/area + * \param num_active_sectors The number of active sectors/scan areas are given + */ + void SickLD::SetSickGlobalParamsAndScanAreas( const unsigned int sick_motor_speed, + const double sick_angle_step, + const double * const active_sector_start_angles, + const double * const active_sector_stop_angles, + const unsigned int num_active_sectors ) + throw( SickTimeoutException, SickIOException, SickConfigException, SickErrorException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLD::SetSickGlobalParamsAndScanAreas: Device NOT Initialized!!!"); + } + + /* Attempt to write both a new scan resolution and scan area config */ + try { + _setSickGlobalParamsAndScanAreas(sick_motor_speed,sick_angle_step, + active_sector_start_angles,active_sector_stop_angles,num_active_sectors); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle config exception */ + catch (SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::SetSickGlobalParamsAndScanAreas: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + + } + + /** + * \brief Attempts to set the active scan areas for the device (in flash) + * \param active_sector_start_angles Angles marking the beginning of each desired active sector/area + * \param active_sector_stop_angles Angles marking the end of each desired active sector/area + * \param num_active_sectors The number of active sectors/scan areas are given + */ + void SickLD::SetSickScanAreas( const double * const active_sector_start_angles, + const double * const active_sector_stop_angles, + const unsigned int num_active_sectors ) + throw( SickTimeoutException, SickIOException, SickConfigException, SickErrorException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLD::SetSickScanAreas: Device NOT Initialized!!!"); + } + + /* Attempt to write both a new scan resolution and scan area config */ + try { + _setSickGlobalParamsAndScanAreas(GetSickMotorSpeed(),GetSickScanResolution(), + active_sector_start_angles,active_sector_stop_angles,num_active_sectors); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle config exception */ + catch (SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::SetSickScanAreas: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + + } + + /** + * \brief Resets the device according to the given reset level + * \param reset_level The desired reset level (see page 33 of the telegram listing) + */ + void SickLD::ResetSick( const unsigned int reset_level ) + throw( SickErrorException, SickTimeoutException, SickIOException, SickConfigException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLD::ResetSick: Device NOT Initialized!!!"); + } + + /* Ensure a valid reset level was given */ + if (reset_level > SICK_WORK_SERV_RESET_HALT_APP) { + throw SickConfigException("SickLD::ResetSick: Invalid given reset level!"); + } + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the service IDs */ + payload_buffer[0] = SICK_WORK_SERV_CODE; // Requested service type + payload_buffer[1] = SICK_WORK_SERV_RESET; // Requested service subtype + payload_buffer[3] = (uint8_t)reset_level; // RESETLEVEL + + /* Create the Sick messages */ + SickLDMessage send_message(payload_buffer,4); + SickLDMessage recv_message; + + /* Send the message and check the reply */ + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSensorMode: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the payload buffer */ + memset(payload_buffer,0,4); + + /* Acquire the returned payload */ + recv_message.GetPayload(payload_buffer); + + /* Extract the returned reset level */ + uint16_t current_reset_level; + memcpy(¤t_reset_level,&payload_buffer[2],2); + current_reset_level = sick_ld_to_host_byte_order(current_reset_level); + + /* Verify the returned reset level */ + if (current_reset_level != (uint16_t)reset_level) { + throw SickErrorException("SickLD::ResetSick: Unexpected returned reset level!"); + } + + /* Success */ + } + + /** + * \brief Acquire the number of sectors that are measuring + * \return The number of sectors currently measuring + */ + unsigned int SickLD::GetSickNumActiveSectors( ) const { + return _sick_sector_config.sick_num_active_sectors; + } + + /** + * \brief Acquire the Sick LD's sensor ID + * \return The Sick LD sensor ID + */ + unsigned int SickLD::GetSickSensorID( ) const { + return _sick_global_config.sick_sensor_id; + } + + /** + * \brief Acquire the Sick LD's current motor speed in Hz + * \return The Sick LD motor speed + */ + unsigned int SickLD::GetSickMotorSpeed( ) const { + return _sick_global_config.sick_motor_speed; + } + + /** + * \brief Acquire the Sick LD's current scan resolution + * \return The Sick LD scan resolution + */ + double SickLD::GetSickScanResolution( ) const { + return _sick_global_config.sick_angle_step; + } + + /** + * \brief Acquire the current IP address of the Sick + * \return The Sick LD IP (Inet4) address + */ + std::string SickLD::GetSickIPAddress( ) const { + + /* Declare the string stream */ + std::ostringstream str_stream; + + str_stream << _sick_ethernet_config.sick_ip_address[0] << "." + << _sick_ethernet_config.sick_ip_address[1] << "." + << _sick_ethernet_config.sick_ip_address[2] << "." + << _sick_ethernet_config.sick_ip_address[3]; + + /* Return the std string representation */ + return str_stream.str(); + + } + + /** + * \brief Acquire the subnet mask for the Sick + * \return The Sick LD subnet mask + */ + std::string SickLD::GetSickSubnetMask( ) const { + + /* Declare the string stream */ + std::ostringstream str_stream; + + str_stream << _sick_ethernet_config.sick_subnet_mask[0] << "." + << _sick_ethernet_config.sick_subnet_mask[1] << "." + << _sick_ethernet_config.sick_subnet_mask[2] << "." + << _sick_ethernet_config.sick_subnet_mask[3]; + + /* Return the std string representation */ + return str_stream.str(); + + } + + /** + * \brief Acquire the IP address of the Sick gateway + * \return The Sick LD gateway IP address + */ + std::string SickLD::GetSickGatewayIPAddress( ) const { + + /* Declare the string stream */ + std::ostringstream str_stream; + + str_stream << _sick_ethernet_config.sick_gateway_ip_address[0] << "." + << _sick_ethernet_config.sick_gateway_ip_address[1] << "." + << _sick_ethernet_config.sick_gateway_ip_address[2] << "." + << _sick_ethernet_config.sick_gateway_ip_address[3]; + + /* Return the std string representation */ + return str_stream.str(); + + } + + /** + * \brief Acquire the Sick LD's part number + * \return The Sick LD part number + */ + std::string SickLD::GetSickPartNumber( ) const { + return _sick_identity.sick_part_number; + } + + /** + * \brief Acquire the Sick LD's name + * \return The Sick LD sensor name + */ + std::string SickLD::GetSickName( ) const { + return _sick_identity.sick_name; + } + + /** + * \brief Acquire the Sick LD's version number + * \return The Sick LD version number + */ + std::string SickLD::GetSickVersion( ) const { + return _sick_identity.sick_version; + } + + /** + * \brief Acquire the Sick LD's serial number + * \return The Sick LD serial number + */ + std::string SickLD::GetSickSerialNumber( ) const { + return _sick_identity.sick_serial_number; + } + + /** + * \brief Acquire the Sick LD's EDM serial number + * \return The Sick LD EDM serial number + */ + std::string SickLD::GetSickEDMSerialNumber( ) const { + return _sick_identity.sick_edm_serial_number; + } + + /** + * \brief Acquire the Sick LD's firmware part number + * \return The Sick LD firmware part number + */ + std::string SickLD::GetSickFirmwarePartNumber( ) const { + return _sick_identity.sick_firmware_part_number; + } + + /** + * \brief Acquire the Sick LD's firmware number + * \return The Sick LD firmware name + */ + std::string SickLD::GetSickFirmwareName( ) const { + return _sick_identity.sick_firmware_name; + } + + /** + * \brief Acquire the Sick LD's firmware version + * \return The Sick LD firmware version + */ + std::string SickLD::GetSickFirmwareVersion( ) const { + return _sick_identity.sick_firmware_version; + } + + /** + * \brief Acquire the Sick LD's application software part number + * \return The Sick LD application software part number + */ + std::string SickLD::GetSickAppSoftwarePartNumber( ) const { + return _sick_identity.sick_application_software_part_number; + } + + /** + * \brief Acquire the Sick LD's application software name + * \return The Sick LD application software name + */ + std::string SickLD::GetSickAppSoftwareName( ) const { + return _sick_identity.sick_application_software_name; + } + + /** + * \brief Acquire the Sick LD's application software version number + * \return The Sick LD application software version number + */ + std::string SickLD::GetSickAppSoftwareVersionNumber( ) const { + return _sick_identity.sick_application_software_version; + } + + /** + * \brief Acquire the Sick LD's status as a printable string + * \return The Sick LD status as a well-formatted string + */ + std::string SickLD::GetSickStatusAsString() const { + + std::stringstream str_stream; + + str_stream << "\t============= Sick LD Status =============" << std::endl; + str_stream << "\tSensor Mode: " << _sickSensorModeToString(_sick_sensor_mode) << std::endl; + str_stream << "\tMotor Mode: " << _sickMotorModeToString(_sick_motor_mode) << std::endl; + str_stream << "\t==========================================" << std::endl; + + return str_stream.str(); + + } + + /** + * \brief Acquire the Sick LD's identity as a printable string + * \return The Sick LD identity as a well-formatted string + */ + std::string SickLD::GetSickIdentityAsString() const { + + std::ostringstream str_stream; + + str_stream << "\t============ Sick LD Identity ============" << std::endl; + str_stream << "\tSensor Part #: " << GetSickPartNumber() << std::endl; + str_stream << "\tSensor Name: " << GetSickName() << std::endl; + str_stream << "\tSensor Version: " << GetSickVersion() << std::endl; + str_stream << "\tSensor Serial #: " << GetSickSerialNumber() << std::endl; + str_stream << "\tSensor EDM Serial #: " << GetSickEDMSerialNumber() << std::endl; + str_stream << "\tFirmware Part #: " << GetSickFirmwarePartNumber() << std::endl; + str_stream << "\tFirmware Version: " << GetSickFirmwareVersion() << std::endl; + str_stream << "\tFirmware Name: " << GetSickFirmwareName() << std::endl; + str_stream << "\tApp. Software Part #: " << GetSickAppSoftwarePartNumber() << std::endl; + str_stream << "\tApp. Software Name: " << GetSickAppSoftwareName() << std::endl; + str_stream << "\tApp. Software Version: " << GetSickAppSoftwareVersionNumber() << std::endl; + str_stream << "\t==========================================" << std::endl; + + return str_stream.str(); + + } + + /** + * \brief Acquire the Sick LD's global config as a printable string + * \return The Sick LD global config as a well-formatted string + */ + std::string SickLD::GetSickGlobalConfigAsString() const { + + std::stringstream str_stream; + + str_stream << "\t=========== Sick Global Config ===========" << std::endl; + str_stream << "\tSensor ID: " << GetSickSensorID() << std::endl; + str_stream << "\tMotor Speed (5 to 20Hz): " << GetSickMotorSpeed() << std::endl; + str_stream << "\tAngle Step (deg): " << GetSickScanResolution() << std::endl; + str_stream << "\t==========================================" << std::endl; + + return str_stream.str(); + + } + + /** + * \brief Acquire the Sick LD's global config as a printable string + * \return The Sick LD Ethernet config as a well-formatted string + */ + std::string SickLD::GetSickEthernetConfigAsString() const { + + std::stringstream str_stream; + + str_stream << "\t========== Sick Ethernet Config ==========" << std::endl; + str_stream << "\tIP Address: " << GetSickIPAddress() << std::endl; + str_stream << "\tSubnet Mask: " << GetSickSubnetMask() << std::endl; + str_stream << "\tGateway IP Address: " << GetSickGatewayIPAddress() << std::endl; + str_stream << "\t==========================================" << std::endl; + + return str_stream.str(); + + } + + /** + * \brief Acquire the Sick LD's sector config as a printable string + * \return The Sick LD Sick LD's config as a well-formatted string + */ + std::string SickLD::GetSickSectorConfigAsString() const { + + std::stringstream str_stream; + + str_stream << "\t=========== Sick Sector Config ===========" << std::endl; + str_stream << "\tNum. Active Sectors: " << (int)_sick_sector_config.sick_num_active_sectors << std::endl; + str_stream << "\tNum. Initialized Sectors: " << (int)_sick_sector_config.sick_num_initialized_sectors << std::endl; + + str_stream << "\tSector Configs.:" << std::endl; + for (unsigned int i = 0; i < _sick_sector_config.sick_num_initialized_sectors; i++) { + str_stream << "\t\t" << i << " [" + << _sick_sector_config.sick_sector_start_angles[i] << "," + << _sick_sector_config.sick_sector_stop_angles[i] << "] (" + << _sickSectorFunctionToString(_sick_sector_config.sick_sector_functions[i]) << ")" << std::endl; + } + + str_stream << "\t==========================================" << std::endl; + + return str_stream.str(); + + } + + /** + * \brief Computes the active area over all measuring sectors + * \return The Sick LD active scan area + */ + double SickLD::GetSickScanArea( ) const { + + /* Some temp buffers */ + double sector_start_angles[SICK_MAX_NUM_SECTORS] = {0}; + double sector_stop_angles[SICK_MAX_NUM_SECTORS] = {0}; + + /* Sum the active areas over all sectors */ + for (unsigned int i = 0; i < _sick_sector_config.sick_num_active_sectors; i++) { + sector_start_angles[i] = _sick_sector_config.sick_sector_start_angles[_sick_sector_config.sick_active_sector_ids[i]]; + sector_stop_angles[i] = _sick_sector_config.sick_sector_stop_angles[_sick_sector_config.sick_active_sector_ids[i]]; + } + + /* Return the computed total scan area */ + return _computeScanArea(GetSickScanResolution(),sector_start_angles,sector_stop_angles,_sick_sector_config.sick_num_active_sectors); + } + + /** + * \brief Print the status of the Sick LD + */ + void SickLD::PrintSickStatus( ) const { + std::cout << GetSickStatusAsString() << std::flush; + } + + /** + * \brief Print the parameters comprising the Sick LD's identity + */ + void SickLD::PrintSickIdentity( ) const { + std::cout << GetSickIdentityAsString() << std::flush; + } + + /** + * \brief Print the Sick LD's global configuration + */ + void SickLD::PrintSickGlobalConfig( ) const { + std::cout << GetSickGlobalConfigAsString() << std::flush; + } + + /** + * \brief Print the Sick LD's Ethernet configuration + */ + void SickLD::PrintSickEthernetConfig( ) const { + std::cout << GetSickEthernetConfigAsString() << std::flush; + } + + /** + * \brief Print the Sick LD's sector configuration + */ + void SickLD::PrintSickSectorConfig( ) const { + std::cout << GetSickSectorConfigAsString() << std::flush; + } + + /** + * \brief Tear down the connection between the host and the Sick LD + */ + void SickLD::Uninitialize( ) throw( SickIOException, SickTimeoutException, SickErrorException, SickThreadException ){ + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLD::Uninitialize: Device NOT Initialized!!!"); + } + + std::cout << std::endl << "\t*** Attempting to uninitialize the Sick LD..." << std::endl; + + /* If necessary, tell the Sick LD to stop streaming data */ + try { + + std::cout << "\tSetting Sick LD to idle mode..." << std::endl; + _setSickSensorModeToIdle(); + std::cout << "\t\tSick LD is now idle!" << std::endl; + + /* Clear any signals that were set */ + SetSickSignals(); + + /* Attempt to cancel the buffer monitor */ + std::cout << "\tAttempting to cancel buffer monitor..." << std::endl; + _stopListening(); + std::cout << "\t\tBuffer monitor canceled!" << std::endl; + + /* Attempt to close the tcp connection */ + std::cout << "\tClosing connection to Sick LD..." << std::endl; + _teardownConnection(); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSensorMode: Unknown exception!!!" << std::endl; + throw; + } + + std::cout << "\t\tConnection closed!" << std::endl; + + std::cout << "\t*** Uninit. complete - Sick LD is now offline!" << std::endl; + + /* Mark the device as uninitialized */ + _sick_initialized = false; + + /* Success! */ + } + + /** + * \brief Establish a TCP connection to the unit + */ + void SickLD::_setupConnection( ) throw( SickIOException, SickTimeoutException ) { + + /* Create the TCP socket */ + if ((_sick_fd = socket(PF_INET,SOCK_STREAM,IPPROTO_TCP)) < 0) { + throw SickIOException("SickLD::_setupConnection: socket() failed!"); + } + + /* Initialize the buffer */ + memset(&_sick_inet_address_info,0,sizeof(struct sockaddr_in)); + + /* Setup the Sick LD inet address structure */ + _sick_inet_address_info.sin_family = AF_INET; // Internet protocol address family + _sick_inet_address_info.sin_port = htons(_sick_tcp_port); // TCP port number + _sick_inet_address_info.sin_addr.s_addr = inet_addr(_sick_ip_address.c_str()); // Convert ip string to numerical address + + try { + + /* Set to non-blocking so we can time connect */ + _setNonBlockingIO(); + + /* Try to connect to the Sick LD */ + int conn_return; + if ((conn_return = connect(_sick_fd,(struct sockaddr *)&_sick_inet_address_info,sizeof(struct sockaddr_in))) < 0) { + + /* Check whether it is b/c it would block */ + if (errno != EINPROGRESS) { + throw SickIOException("SickLD::_setupConnection: connect() failed!"); + } + + /* Use select to wait on the socket */ + int valid_opt = 0; + int num_active_files = 0; + struct timeval timeout_val; // This structure will be used for setting our timeout values + fd_set file_desc_set; // File descriptor set for monitoring I/O + + /* Initialize and set the file descriptor set for select */ + FD_ZERO(&file_desc_set); + FD_SET(_sick_fd,&file_desc_set); + + /* Setup the timeout structure */ + memset(&timeout_val,0,sizeof(timeout_val)); // Initialize the buffer + timeout_val.tv_usec = DEFAULT_SICK_CONNECT_TIMEOUT; // Wait for specified time before throwing a timeout + + /* Wait for the OS to tell us that the connection is established! */ + num_active_files = select(getdtablesize(),0,&file_desc_set,0,&timeout_val); + + /* Figure out what to do based on the output of select */ + if (num_active_files > 0) { + + /* This is just a sanity check */ + if (!FD_ISSET(_sick_fd,&file_desc_set)) { + throw SickIOException("SickLD::_setupConnection: Unexpected file descriptor!"); + } + + /* Check for any errors on the socket - just to be sure */ + socklen_t len = sizeof(int); + if (getsockopt(_sick_fd,SOL_SOCKET,SO_ERROR,(void*)(&valid_opt),&len) < 0) { + throw SickIOException("SickLD::_setupConnection: getsockopt() failed!"); + } + + /* Check whether the opt value indicates error */ + if (valid_opt) { + throw SickIOException("SickLD::_setupConnection: socket error on connect()!"); + } + + } + else if (num_active_files == 0) { + + /* A timeout has occurred! */ + throw SickTimeoutException("SickLD::_setupConnection: select() timeout!"); + + } + else { + + /* An error has occurred! */ + throw SickIOException("SickLD::_setupConnection: select() failed!"); + + } + + } + + /* Restore blocking IO */ + _setBlockingIO(); + + } + + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + catch(...) { + std::cerr << "SickLD::_setupConnection - Unknown exception occurred!" << std::endl; + throw; + } + + /* Success */ + } + + /** + * \brief Synchronizes buffer driver parameters with those of the Sick LD. + * + * \todo Add support in this method for acquiring RS-232/RS-422, and CAN configurations + */ + void SickLD::_syncDriverWithSick( ) throw( SickIOException, SickTimeoutException, SickErrorException ) { + + try { + + /* Acquire current configuration */ + _getSickStatus(); + _getSickIdentity(); + _getSickEthernetConfig(); + _getSickGlobalConfig(); + _getSickSectorConfig(); + + /* Reset Sick signals */ + _setSickSignals(); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_syncDriverWithSick: Unknown exception!!!" << std::endl; + throw; + } + + /* Success */ + } + + /** \brief Sets the function for a particular scan sector. + * \param sector_number The number of the sector (should be in [0,7]) + * \param sector_function The function of the sector (e.g. no measurement, reserved, normal measurement, ...) + * \param sector_stop_angle The last angle of the sector (in odometer ticks) + * \param write_to_flash Indicates whether the sector configuration should be written to flash + */ + void SickLD::_setSickSectorFunction ( const uint8_t sector_number, const uint8_t sector_function, + const double sector_stop_angle, const bool write_to_flash ) + throw( SickErrorException, SickTimeoutException, SickIOException, SickConfigException ) { + + /* Ensure the device is not measuring */ + if (_sick_sensor_mode == SICK_SENSOR_MODE_MEASURE) { + + /* Set the Sick LD to rotate mode */ + try { + _setSickSensorModeToRotate(); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSectorFunction: Unknown exception!!!" << std::endl; + throw; + } + + } + + /* Ensure a valid sector number */ + if (sector_number >= SICK_MAX_NUM_SECTORS) { + throw SickConfigException("SickLD::_setSickSectorFunction: Invalid sector number!"); + } + + /* Check that a valid sector_function was given */ + if (sector_function != SICK_CONF_SECTOR_NOT_INITIALIZED && + sector_function != SICK_CONF_SECTOR_NO_MEASUREMENT && + sector_function != SICK_CONF_SECTOR_RESERVED && + sector_function != SICK_CONF_SECTOR_NORMAL_MEASUREMENT && + sector_function != SICK_CONF_SECTOR_REFERENCE_MEASUREMENT) { + + throw SickConfigException("SickLD::_setSickSectorFunction: Invalid sector function code!"); + } + + /* Check that a valid stop angle was given */ + if (sector_stop_angle > SICK_MAX_SCAN_AREA) { + throw SickConfigException("SickLD::_setSickSectorFunction: Invalid sector stop angle!"); + } + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* A temporary buffer for byte order conversion */ + uint16_t temp_buff = 0; + + /* Set the service IDs */ + payload_buffer[0] = SICK_CONF_SERV_CODE; // Requested service type + payload_buffer[1] = SICK_CONF_SERV_SET_FUNCTION; // Requested service subtype + + /* Assign the payload data */ + payload_buffer[3] = sector_number; // SECTORNUM + payload_buffer[5] = sector_function; // SECTORFUNC + + /* Set the sector stop value */ + temp_buff = host_to_sick_ld_byte_order(_angleToTicks(sector_stop_angle)); + memcpy(&payload_buffer[6],&temp_buff,2); // SECTORSTOP + + /* Include the flash flag */ + payload_buffer[9] = (uint8_t)write_to_flash; // FLASHFLAG + + /* Create the Sick LD messages */ + SickLDMessage send_message(payload_buffer,10); + SickLDMessage recv_message; + + /* Send the message and get the reply */ + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSectorFunction: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the payload buffer (not necessary, but it doesn't hurt to be careful) */ + memset(payload_buffer,0,10); + + /* Extract the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Check the response for an error */ + if (payload_buffer[2] == 0xFF && payload_buffer[3] == 0xFF) { + throw SickConfigException("SickLD::_setSickSectorFunction: Invalid request!"); + } + + /* Success! */ + } + + /** + * \brief Acquires the function of the given sector + * \param sector_num The target sector number + * \param §or_config The configuration word returned by the Sick LD + * \param §or_stop The stop angle of the given sector + */ + void SickLD::_getSickSectorFunction( const uint8_t sector_num, uint8_t §or_function, double §or_stop_angle ) + throw( SickErrorException, SickTimeoutException, SickIOException ) { + + /* Ensure the device is not measuring */ + if (_sick_sensor_mode == SICK_SENSOR_MODE_MEASURE) { + + /* Set the Sick LD to rotate mode */ + try { + _setSickSensorModeToRotate(); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getSickSectorFunction: Unknown exception!!!" << std::endl; + throw; + } + + } + + /* Declare the message payload buffer */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the service IDs */ + payload_buffer[0] = SICK_CONF_SERV_CODE; // Requested service type + payload_buffer[1] = SICK_CONF_SERV_GET_FUNCTION; // Requested service subtype + payload_buffer[3] = sector_num; // Sector number + + /* Declare the send/recv Sick LD message objects */ + SickLDMessage send_message(payload_buffer,4); + SickLDMessage recv_message; + + /* Send the message and get a response */ + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getSickSectorFunction: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the payload buffer */ + memset(payload_buffer,0,4); + + /* Extract the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Extract the returned sector number */ + uint16_t temp_buffer = 0; + memcpy(&temp_buffer,&payload_buffer[2],2); + temp_buffer = sick_ld_to_host_byte_order(temp_buffer); + + /* Check to make sure the returned sector number matches + * the requested sector number. + */ + if (temp_buffer != sector_num) { + throw SickConfigException("SickLD::_getSickSectorFunction: Unexpected sector number returned by Sick LD!"); + } + + /* Extract the sector function */ + memcpy(&temp_buffer,&payload_buffer[4],2); + sector_function = sick_ld_to_host_byte_order(temp_buffer); + + /* Extract the sector stop angle (in ticks) */ + memcpy(&temp_buffer,&payload_buffer[6],2); + sector_stop_angle = _ticksToAngle(sick_ld_to_host_byte_order(temp_buffer)); + + /* S'ok */ + } + + /** + * \brief Sets the Sick LD sensor mode to IDLE + */ + void SickLD::_setSickSensorModeToIdle( ) + throw( SickErrorException, SickTimeoutException, SickIOException ) { + + /* If necessary adjust the operating mode of the sensor */ + if (_sick_sensor_mode != SICK_SENSOR_MODE_IDLE) { + + /* Switch the sensor's operating mode to IDLE */ + try { + _setSickSensorMode(SICK_SENSOR_MODE_IDLE); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSensorModeToIdle: Unknown exception!!!" << std::endl; + throw; + } + + } + + /* Success */ + } + + /** + * \brief Sets the Sick LD sensor mode to ROTATE + */ + void SickLD::_setSickSensorModeToRotate( ) + throw( SickErrorException, SickTimeoutException, SickIOException ) { + + /* If necessary adjust the operating mode of the sensor */ + if (_sick_sensor_mode != SICK_SENSOR_MODE_ROTATE) { + + /* Switch the sensor's operating mode to ROTATE */ + try { + _setSickSensorMode(SICK_SENSOR_MODE_ROTATE); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSensorModeToRotate: Unknown exception!!!" << std::endl; + throw; + } + + } + + /* Success */ + } + + /** + * \brief Sets the Sick LD sensor mode to ROTATE + */ + void SickLD::_setSickSensorModeToMeasure( ) + throw( SickErrorException, SickTimeoutException, SickIOException ) { + + /* If necessary adjust the operating mode of the sensor */ + if (_sick_sensor_mode != SICK_SENSOR_MODE_MEASURE) { + + /* Switch the sensor's operating mode to MEASURE */ + try { + _setSickSensorMode(SICK_SENSOR_MODE_MEASURE); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSensorModeToMeasure: Unknown exception!!!" << std::endl; + throw; + } + + } + + /* Success */ + } + + /** + * \brief Sets the Sick LD to the requested sensor mode + * \param new_sick_sensor_mode The desired sensor mode + */ + void SickLD::_setSickSensorMode( const uint8_t new_sick_sensor_mode ) + throw( SickErrorException, SickTimeoutException, SickIOException ) { + + /* If the new mode matches the current mode then just return */ + if (_sick_sensor_mode == new_sick_sensor_mode) { + return; + } + + try { + + /* If the current sensor mode is MEASURE and streaming data */ + if ((_sick_sensor_mode == SICK_SENSOR_MODE_MEASURE) && + (_sick_streaming_range_data || _sick_streaming_range_and_echo_data)) { + + /* Cancel the current stream */ + _cancelSickScanProfiles(); + + } + + /* The Sick LD must be in rotate mode before: going from IDLE to MEASURE or going from MEASURE to IDLE */ + if ((_sick_sensor_mode == SICK_SENSOR_MODE_IDLE && new_sick_sensor_mode == SICK_SENSOR_MODE_MEASURE) || + (_sick_sensor_mode == SICK_SENSOR_MODE_MEASURE && new_sick_sensor_mode == SICK_SENSOR_MODE_IDLE)) { + + /* Set to rotate mode */ + _setSickSensorModeToRotate(); + + } + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSensorMode: Unknown exception!!!" << std::endl; + throw; + } + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* The payload length */ + uint32_t payload_length = 2; + + /* Set the service IDs */ + payload_buffer[0] = SICK_WORK_SERV_CODE; // Requested service type + payload_buffer[1] = _sickSensorModeToWorkServiceSubcode(new_sick_sensor_mode); // Requested service subtype + + /* If the target sensor mode is rotate then we add two more bytes + * to the payload length. Doing so adds two zero values to the payload + * which tells it to use the angular step and scan freqeuncy values + * stored in its flash. + */ + if (new_sick_sensor_mode == SICK_SENSOR_MODE_ROTATE) { + payload_length += 2; + } + + /* Define the send/receive message objects */ + SickLDMessage send_message(payload_buffer,payload_length); + SickLDMessage recv_message; + + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSensorMode: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the payload buffer */ + memset(payload_buffer,0,payload_length); + + /* Extract the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Ensure the returned mode matches the requested mode */ + if ((_sick_sensor_mode = (payload_buffer[5] & 0x0F)) != new_sick_sensor_mode) { + + /* Check whether there is an error code we can use */ + if (new_sick_sensor_mode == SICK_SENSOR_MODE_MEASURE) { + + uint16_t return_code = 0; + std::string errMsg = "SickLD::_setSickSensorMode: Unexpected sensor mode returned from Sick LD!"; + memcpy(&return_code,&payload_buffer[6],2); + return_code = sick_ld_to_host_byte_order(return_code); + + /* Print the error code associated with the TRANS_MEASURE request */ + errMsg = errMsg + " (TRANS_MEAS Error Code: " + _sickTransMeasureReturnToString(return_code) + ")"; + throw SickErrorException(errMsg.c_str()); + + } + + } + + /* Make sure the motor is Ok */ + if ((_sick_motor_mode = ((payload_buffer[5] >> 4) & 0x0F)) != SICK_MOTOR_MODE_OK) { + throw SickErrorException("SickLD::_setSickSensorMode: Unexpected motor mode returned from Sick LD!"); + } + + /* Success */ + + } + + /** + * \brief Request n scan profiles from the Sick LD unit + * \param profile_format The format for the requested scan profiles + * \param num_profiles The number of profiles to request from Sick LD. (Default: 0) + * (NOTE: When num_profiles = 0, the Sick LD continuously streams profile data) + */ + void SickLD::_getSickScanProfiles( const uint16_t profile_format, const uint16_t num_profiles ) + throw( SickErrorException, SickTimeoutException, SickIOException, SickConfigException ) { + + /* Ensure the device is in measurement mode */ + try { + _setSickSensorModeToMeasure(); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSensorMode: Unknown exception!!!" << std::endl; + throw; + } + + /* A quick check to ensure the requested format is supported by the driver */ + if (!_supportedScanProfileFormat(profile_format)) { + throw SickConfigException("SickLD::_getSickScanProfiles: Unsupported profile format!"); + } + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the service code and subcode */ + payload_buffer[0] = SICK_MEAS_SERV_CODE; + payload_buffer[1] = SICK_MEAS_SERV_GET_PROFILE; + + /* Write the number of profiles to request to the payload buffer */ + uint16_t temp_buffer = host_to_sick_ld_byte_order(num_profiles); + memcpy(&payload_buffer[2],&temp_buffer,2); + + /* Set the profile format mask (for now, we request everything from the Sick LD) */ + temp_buffer = profile_format; + temp_buffer = host_to_sick_ld_byte_order(temp_buffer); + memcpy(&payload_buffer[4],&temp_buffer,2); + + /* Define the send message object */ + SickLDMessage send_message(payload_buffer,6); + SickLDMessage recv_message; + + /* Send the request */ + if (num_profiles == 0) { + std::cout << "\tRequesting " << _sickProfileFormatToString(profile_format) << " data stream from Sick LD..." << std::endl; + } else { + std::cout << "\tRequesting " << num_profiles << " " << _sickProfileFormatToString(profile_format) << " profiles from Sick LD..." << std::endl; + } + + /* Request scan profiles from the Sick (empirically it can take the Sick up to a few seconds to respond) */ + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSensorMode: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the payload buffer */ + memset(payload_buffer,0,6); + + /* Acquire the payload of the response */ + recv_message.GetPayload(payload_buffer); + + /* Check to make sure the returned format is correct and there were no errors */ + memcpy(&temp_buffer,&payload_buffer[2],2); + temp_buffer = sick_ld_to_host_byte_order(temp_buffer); + + /* Another sanity check */ + if (temp_buffer != profile_format) { + throw SickErrorException("SickLD::_getSickScanProfiles: Incorrect profile format was returned by the Sick LD!"); + } + + /* Check if the data stream flags need to be set */ + if (num_profiles == 0 && profile_format == SICK_SCAN_PROFILE_RANGE) { + _sick_streaming_range_data = true; + } + else if (num_profiles == 0 && profile_format == SICK_SCAN_PROFILE_RANGE_AND_ECHO) { + _sick_streaming_range_and_echo_data = true; + } + + /* Show some output */ + if (num_profiles == 0) { + std::cout << "\t\tData stream started!" << std::endl; + } else { + std::cout << "\t\tSick LD sending " << num_profiles << " scan profiles!" << std::endl; + } + + /* Success */ + } + + /** + * \brief Parses a well-formed sequence of bytes into a corresponding scan profile + * \param *src_buffer The source data buffer + * \param &profile_data The destination data structure + */ + void SickLD::_parseScanProfile( uint8_t * const src_buffer, sick_ld_scan_profile_t &profile_data ) const { + + uint16_t profile_format = 0; + unsigned int data_offset = 0; + + /* Extract the scan profile format from the buffer */ + memcpy(&profile_format,&src_buffer[data_offset],2); + profile_format = sick_ld_to_host_byte_order(profile_format); + data_offset += 2; + + /* Extract the number of sectors in the scan area */ + profile_data.num_sectors = src_buffer[data_offset+1]; + data_offset += 2; + + /* NOTE: For the following field definitions see page 32 of the + * Sick LD telegram listing. + */ + uint16_t temp_buffer; // A temporary buffer + + /* Check if PROFILESENT is included */ + if (profile_format & 0x0001) { + memcpy(&temp_buffer,&src_buffer[data_offset],2); + profile_data.profile_number = sick_ld_to_host_byte_order(temp_buffer); + data_offset += 2; + } + + /* Check if PROFILECOUNT is included */ + if (profile_format & 0x0002) { + memcpy(&temp_buffer,&src_buffer[data_offset],2); + profile_data.profile_counter = sick_ld_to_host_byte_order(temp_buffer); + data_offset += 2; + } + + /* Check if LAYERNUM is included */ + if (profile_format & 0x0004) { + memcpy(&temp_buffer,&src_buffer[data_offset],2); + profile_data.layer_num = sick_ld_to_host_byte_order(temp_buffer); + data_offset += 2; + } + + /* The extraneous stuff is out of the way, now extract the data + * for each of the sectors in the scan area... + */ + for (unsigned int i=0; i < profile_data.num_sectors; i++) { + + /* Check if SECTORNUM is included */ + if (profile_format & 0x0008) { + memcpy(&temp_buffer,&src_buffer[data_offset],2); + profile_data.sector_data[i].sector_num = sick_ld_to_host_byte_order(temp_buffer); + data_offset += 2; + } + else { + profile_data.sector_data[i].sector_num = 0; + } + + /* Check if DIRSTEP is included */ + if (profile_format & 0x0010) { + memcpy(&temp_buffer,&src_buffer[data_offset],2); + profile_data.sector_data[i].angle_step = ((double)sick_ld_to_host_byte_order(temp_buffer))/16; + data_offset += 2; + } + else { + profile_data.sector_data[i].angle_step = 0; + } + + /* Check if POINTNUM is included */ + if (profile_format & 0x0020) { + memcpy(&temp_buffer,&src_buffer[data_offset],2); + profile_data.sector_data[i].num_data_points = sick_ld_to_host_byte_order(temp_buffer); + data_offset += 2; + } + else { + profile_data.sector_data[i].num_data_points = 0; + } + + /* Check if TSTART is included */ + if (profile_format & 0x0040) { + memcpy(&temp_buffer,&src_buffer[data_offset],2); + profile_data.sector_data[i].timestamp_start = sick_ld_to_host_byte_order(temp_buffer); + data_offset += 2; + } + else { + profile_data.sector_data[i].timestamp_start = 0; + } + + /* Check if STARTDIR is included */ + if (profile_format & 0x0080) { + memcpy(&temp_buffer,&src_buffer[data_offset],2); + profile_data.sector_data[i].angle_start = ((double)sick_ld_to_host_byte_order(temp_buffer))/16; + data_offset += 2; + } + else { + profile_data.sector_data[i].angle_start = 0; + } + + /* Acquire the range and echo values for the sector */ + for (unsigned int j=0; j < profile_data.sector_data[i].num_data_points; j++) { + + /* Check if DISTANCE-n is included */ + if (profile_format & 0x0100) { + memcpy(&temp_buffer,&src_buffer[data_offset],2); + profile_data.sector_data[i].range_values[j] = ((double)sick_ld_to_host_byte_order(temp_buffer))/256; + data_offset += 2; + } + else { + profile_data.sector_data[i].range_values[j] = 0; + } + + /* Check if DIRECTION-n is included */ + if (profile_format & 0x0200) { + memcpy(&temp_buffer,&src_buffer[data_offset],2); + profile_data.sector_data[i].scan_angles[j] = ((double)sick_ld_to_host_byte_order(temp_buffer))/16; + data_offset += 2; + } + else { + profile_data.sector_data[i].scan_angles[j] = 0; + } + + /* Check if ECHO-n is included */ + if (profile_format & 0x0400) { + memcpy(&temp_buffer,&src_buffer[data_offset],2); + profile_data.sector_data[i].echo_values[j] = sick_ld_to_host_byte_order(temp_buffer); + data_offset += 2; + } + else { + profile_data.sector_data[i].echo_values[j] = 0; + } + + } + + /* Check if TEND is included */ + if (profile_format & 0x0800) { + memcpy(&temp_buffer,&src_buffer[data_offset],2); + profile_data.sector_data[i].timestamp_stop = sick_ld_to_host_byte_order(temp_buffer); + data_offset += 2; + } + else { + profile_data.sector_data[i].timestamp_stop = 0; + } + + /* Check if ENDDIR is included */ + if (profile_format & 0x1000) { + memcpy(&temp_buffer,&src_buffer[data_offset],2); + profile_data.sector_data[i].angle_stop = ((double)sick_ld_to_host_byte_order(temp_buffer))/16; + data_offset += 2; + } + else { + profile_data.sector_data[i].angle_stop = 0; + } + + } + + /* Check if SENSTAT is included */ + if (profile_format & 0x2000) { + profile_data.sensor_status = src_buffer[data_offset+3] & 0x0F; + profile_data.motor_status = (src_buffer[data_offset+3] >> 4) & 0x0F; + } + else { + profile_data.sensor_status = SICK_SENSOR_MODE_UNKNOWN; + profile_data.motor_status = SICK_MOTOR_MODE_UNKNOWN; + } + + } + + /** + * \brief Kills the current data stream + */ + void SickLD::_cancelSickScanProfiles( ) + throw( SickErrorException, SickTimeoutException, SickIOException ) { + + /* Ensure the device is in measurement mode */ + try { + _setSickSensorModeToMeasure(); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_cancelSickScanProfiles: Unknown exception!!!" << std::endl; + throw; + } + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the service IDs */ + payload_buffer[0] = SICK_MEAS_SERV_CODE; // Requested service type + payload_buffer[1] = SICK_MEAS_SERV_CANCEL_PROFILE; // Requested service subtype + + /* Create the Sick messages */ + SickLDMessage send_message(payload_buffer,2); + SickLDMessage recv_message; + + std::cout << "\tStopping the data stream..." << std::endl; + + /* Send the message and check the reply */ + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getFirmwareName: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the payload buffer */ + memset(payload_buffer,0,2); + + /* Update the status of ths Sick LD */ + recv_message.GetPayload(payload_buffer); + + /* Extract and assign the sensor and motor status */ + _sick_sensor_mode = payload_buffer[5] & 0x0F; + _sick_motor_mode = (payload_buffer[5] >> 4) & 0x0F; + + /* Since we just updated them, let's make sure everything s'ok */ + if (_sick_sensor_mode == SICK_SENSOR_MODE_ERROR) { + throw SickErrorException("SickLD::_cancelSickScanProfiles: Sick LD returned sensor mode ERROR!"); + } + + /* Check the motor mode */ + if (_sick_motor_mode == SICK_MOTOR_MODE_ERROR) { + throw SickErrorException("SickLD::_cancelSickScanProfiles: Sick LD returned motor mode ERROR!"); + } + + /* Set the stream flag for the driver */ + if (_sick_streaming_range_data) { + _sick_streaming_range_data = false; + } + else { + _sick_streaming_range_and_echo_data = false; + } + + std::cout << "\t\tStream stopped!" << std::endl; + } + + /** + * \brief Enables/disables nearfield suppression on the Sick LD + * \param suppress_code Code indicating whether to enable or diable the nearfield suppression + */ + void SickLD::_setSickFilter( const uint8_t suppress_code ) + throw( SickErrorException, SickTimeoutException, SickIOException ) { + + /* Ensure the device is not measuring */ + if (_sick_sensor_mode == SICK_SENSOR_MODE_MEASURE) { + + /* Set the Sick LD to rotate mode */ + try { + _setSickSensorModeToRotate(); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickFilter: Unknown exception!!!" << std::endl; + throw; + } + + } + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the service IDs */ + payload_buffer[0] = SICK_CONF_SERV_CODE; // Requested service type + payload_buffer[1] = SICK_CONF_SERV_SET_FILTER; // Requested service subtype + payload_buffer[3] = SICK_CONF_SERV_SET_FILTER_NEARFIELD; // Setting nearfield suppression filter + payload_buffer[5] = suppress_code; // Code telling whether to turn it on or off + + /* Create the Sick messages */ + SickLDMessage send_message(payload_buffer,6); + SickLDMessage recv_message; + + /* Send the message and check the reply */ + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickFilter: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the payload buffer */ + memset(payload_buffer,0,6); + + /* Acquire the returned payload */ + recv_message.GetPayload(payload_buffer); + + /* Extract FILTERITEM */ + uint16_t filter_item; + memcpy(&filter_item,&payload_buffer[2],2); + filter_item = sick_ld_to_host_byte_order(filter_item); + + /* Check that the returned filter item matches nearfiled suppression */ + if (filter_item != SICK_CONF_SERV_SET_FILTER_NEARFIELD) { + throw SickErrorException("SickLD::_setSickFilter: Unexpected filter item returned from Sick LD!"); + } + + /* Success */ + } + + /** + * \brief Get the parameters that define the Sick LD's identity + */ + void SickLD::_getSickIdentity( ) throw( SickTimeoutException, SickIOException ) { + + try { + + _getSensorPartNumber(); + _getSensorName(); + _getSensorVersion(); + _getSensorSerialNumber(); + _getSensorEDMSerialNumber(); + _getFirmwarePartNumber(); + _getFirmwareName(); + _getFirmwareVersion(); + _getApplicationSoftwarePartNumber(); + _getApplicationSoftwareName(); + _getApplicationSoftwareVersion(); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getSickIdentity: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + } + + /** + * \brief Get the status of the Sick LD + */ + void SickLD::_getSickStatus( ) throw( SickTimeoutException, SickIOException ) { + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the service IDs */ + payload_buffer[0] = SICK_STAT_SERV_CODE; // Requested service type + payload_buffer[1] = SICK_STAT_SERV_GET_STATUS; // Requested service subtype + + /* Create the Sick messages */ + SickLDMessage send_message(payload_buffer,2); + SickLDMessage recv_message; + + /* Send the message and check the reply */ + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + catch(...) { + std::cerr << "SickLD::_getSickStatus - Unknown exception!" << std::endl; + throw; + } + + /* Reset the buffer (not necessary, but its better to do so just in case) */ + memset(payload_buffer,0,2); + + /* Extract the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Extract the Sick LD's current sensor mode */ + _sick_sensor_mode = payload_buffer[5] & 0x0F; + + /* Extract the Sick LD's current motor mode */ + _sick_motor_mode = (payload_buffer[5] >> 4) & 0x0F; + + /* Success */ + } + + /** + * \brief Sets the Sick LD's global parameters (sensor id, motor speed, and angular step) in flash. + * \param sick_sensor_id The sensor id to be assigned to the unit. + * \param sick_motor_speed The speed of the motor in Hz (must be in [5,20]) + * \param sick_angular_step The difference between two laser pulses in 1/16 degrees (e.g. sick_angular_step = 4 => 0.25 deg step). + * Also, this value must evenly divide into 5760 and be greater than 1 (see telegram listing page 21). + * + * ALERT: This method writes the parameters to the Sick LD's flash, so there is no + * need to use it except when configuring the device. + * + * ALERT: This method DOES NOT DO ERROR CHECKING on the given parameter values. It is the responsibility + * of the caller function to do error checking beforehand. + */ + void SickLD::_setSickGlobalConfig( const uint8_t sick_sensor_id, const uint8_t sick_motor_speed, const double sick_angle_step ) + throw( SickErrorException, SickTimeoutException, SickIOException ) { + + /* Ensure the device is in IDLE mode */ + try { + _setSickSensorModeToIdle(); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickGlobalConfig: Unknown exception!!!" << std::endl; + throw; + } + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the service IDs */ + payload_buffer[0] = SICK_CONF_SERV_CODE; // Requested service type + payload_buffer[1] = SICK_CONF_SERV_SET_CONFIGURATION; // Requested service subtype + + /* Set the configuration key */ + payload_buffer[3] = SICK_CONF_KEY_GLOBAL; // Use the global configuration key + + /* Set the message parameters */ + payload_buffer[5] = sick_sensor_id; // Include the given sensor ID + payload_buffer[7] = sick_motor_speed; // Include the new Sick Motor speed value + + /* Set the angular step */ + uint16_t temp_buffer = _angleToTicks(sick_angle_step); + temp_buffer = host_to_sick_ld_byte_order(temp_buffer); + memcpy(&payload_buffer[8],&temp_buffer,2); + + /* Create the Sick messages */ + SickLDMessage send_message(payload_buffer,10); + SickLDMessage recv_message; + + /* Send the message and check the reply */ + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickGlobalConfig: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the payload buffer */ + memset(payload_buffer,0,10); + + /* Extract the response payload */ + recv_message.GetPayload(payload_buffer); + + /* Check to make sure there wasn't an error */ + if (payload_buffer[2] != 0 || payload_buffer[3] != 0) { + throw SickErrorException("SickLD::_setSickGlobalConfig: Configuration setting was NOT sucessful!"); + } + + /* Update the device driver with the new values */ + _sick_global_config.sick_sensor_id = sick_sensor_id; + _sick_global_config.sick_motor_speed = sick_motor_speed; + _sick_global_config.sick_angle_step = sick_angle_step; + + /* Success! */ + } + + /** + * \brief Get the global configuration of the Sick LD. + */ + void SickLD::_getSickGlobalConfig( ) throw( SickErrorException, SickTimeoutException, SickIOException ) { + + /* Ensure the device is in IDLE mode */ + try { + _setSickSensorModeToIdle(); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getSickGlobalConfig: Unknown exception!!!" << std::endl; + throw; + } + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the service IDs */ + payload_buffer[0] = SICK_CONF_SERV_CODE; // Requested service type + payload_buffer[1] = SICK_CONF_SERV_GET_CONFIGURATION; // Requested service subtype + payload_buffer[3] = SICK_CONF_KEY_GLOBAL; // Configuration key + + /* Create the Sick messages */ + SickLDMessage send_message(payload_buffer,4); + SickLDMessage recv_message; + + /* Send the message and check the reply */ + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getSickGlobalConfig: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the buffer (not necessary, but its better to do so just in case) */ + memset(payload_buffer,0,4); + + /* Extract the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Extract the configuration key */ + uint16_t temp_buffer = 0; + unsigned int data_offset = 2; + memcpy(&temp_buffer,&payload_buffer[data_offset],2); + temp_buffer = sick_ld_to_host_byte_order(temp_buffer); + data_offset += 2; + + /* A quick sanity check */ + if (temp_buffer != SICK_CONF_KEY_GLOBAL) { + throw SickErrorException("SickLD::_getSickGlobalConfig: Unexpected message contents!"); + } + + /* Extract the global sensor ID */ + memcpy(&_sick_global_config.sick_sensor_id,&payload_buffer[data_offset],2); + _sick_global_config.sick_sensor_id = sick_ld_to_host_byte_order(_sick_global_config.sick_sensor_id); + data_offset += 2; + + /* Extract the nominal motor speed */ + memcpy(&_sick_global_config.sick_motor_speed,&payload_buffer[data_offset],2); + _sick_global_config.sick_motor_speed = sick_ld_to_host_byte_order(_sick_global_config.sick_motor_speed); + data_offset += 2; + + /* Extract the angular step */ + memcpy(&temp_buffer,&payload_buffer[data_offset],2); + _sick_global_config.sick_angle_step = _ticksToAngle(sick_ld_to_host_byte_order(temp_buffer)); + + /* Success */ + } + + /** + * \brief Get the Sick LD's Ethernet configuration. + */ + void SickLD::_getSickEthernetConfig( ) + throw( SickErrorException, SickTimeoutException, SickIOException ) { + + /* Ensure the device is in IDLE mode */ + try { + _setSickSensorModeToIdle(); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSensorMode: Unknown exception!!!" << std::endl; + throw; + } + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the service IDs */ + payload_buffer[0] = SICK_CONF_SERV_CODE; // Requested service type + payload_buffer[1] = SICK_CONF_SERV_GET_CONFIGURATION; // Requested service subtype + payload_buffer[3] = SICK_CONF_KEY_ETHERNET; // Configuration key + + /* Create the Sick messages */ + SickLDMessage send_message(payload_buffer,4); + SickLDMessage recv_message; + + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSensorMode: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the buffer (not necessary, but its better to do so just in case) */ + memset(payload_buffer,0,4); + + /* Extract the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Extract the configuration key */ + uint16_t temp_buffer = 0; + unsigned int data_offset = 2; + memcpy(&temp_buffer,&payload_buffer[data_offset],2); + temp_buffer = sick_ld_to_host_byte_order(temp_buffer); + data_offset += 2; + + /* A quick sanity check */ + if (temp_buffer != SICK_CONF_KEY_ETHERNET) { + throw SickErrorException("SickLD::_getSickEthernetConfig: Unexpected message contents!"); + } + + /* Extract the IP address of the Sick LD */ + for(unsigned int i=0; i < 4; i++,data_offset+=2) { + memcpy(&_sick_ethernet_config.sick_ip_address[i],&payload_buffer[data_offset],2); + _sick_ethernet_config.sick_ip_address[i] = sick_ld_to_host_byte_order(_sick_ethernet_config.sick_ip_address[i]); + } + + /* Extract the associated subnet mask */ + for(unsigned int i=0; i < 4; i++,data_offset+=2) { + memcpy(&_sick_ethernet_config.sick_subnet_mask[i],&payload_buffer[data_offset],2); + _sick_ethernet_config.sick_subnet_mask[i] = sick_ld_to_host_byte_order(_sick_ethernet_config.sick_subnet_mask[i]); + } + + /* Extract the default gateway */ + for(unsigned int i=0; i < 4; i++,data_offset+=2) { + memcpy(&_sick_ethernet_config.sick_gateway_ip_address[i],&payload_buffer[data_offset],2); + _sick_ethernet_config.sick_gateway_ip_address[i] = sick_ld_to_host_byte_order(_sick_ethernet_config.sick_gateway_ip_address[i]); + } + + /* Extract the sick node ID (NOTE: This value doesn't matter, but we buffer it anyways) */ + memcpy(&_sick_ethernet_config.sick_node_id,&payload_buffer[data_offset],2); + _sick_ethernet_config.sick_node_id = sick_ld_to_host_byte_order(_sick_ethernet_config.sick_node_id); + data_offset += 2; + + /* Extract the transparent TCP port (NOTE: The significance of this value is unclear as + * it doesn't affect the actual TCP port number that the Sick server is operating at. + * But, we buffer it anyways as it is included in the configuration.) + */ + memcpy(&_sick_ethernet_config.sick_transparent_tcp_port,&payload_buffer[data_offset],2); + _sick_ethernet_config.sick_transparent_tcp_port = sick_ld_to_host_byte_order(_sick_ethernet_config.sick_transparent_tcp_port); + data_offset += 2; + + /* Success */ + } + + /** + * \brief Query the Sick for its current sector configuration. + * + * NOTE: Here we only buffer the sector stop angle as this is the + * only value returned by the GET_FUNCTION command. Using the + * stop angle does not give enough information to extract the + * start angle of sectors that aren't "normal measurement". + */ + void SickLD::_getSickSectorConfig( ) + throw( SickErrorException, SickTimeoutException, SickIOException ) { + + /* Reset the sector config struct */ + memset(&_sick_sector_config,0,sizeof(sick_ld_config_sector_t)); + + /* Get the configuration for all initialized sectors */ + for (unsigned int i = 0; i < SICK_MAX_NUM_SECTORS; i++) { + + /* Query the Sick for the function of the ith sector */ + try { + _getSickSectorFunction(i,_sick_sector_config.sick_sector_functions[i],_sick_sector_config.sick_sector_stop_angles[i]); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getSickSectorConfig: Unknown exception!!!" << std::endl; + throw; + } + + /* Check if the sector is initialized */ + if (_sick_sector_config.sick_sector_functions[i] != SICK_CONF_SECTOR_NOT_INITIALIZED) { + + /* Check whether the sector is active (i.e. measuring) */ + if (_sick_sector_config.sick_sector_functions[i] == SICK_CONF_SECTOR_NORMAL_MEASUREMENT) { + _sick_sector_config.sick_active_sector_ids[_sick_sector_config.sick_num_active_sectors] = i; + _sick_sector_config.sick_num_active_sectors++; + } + + /* Update the number of initialized sectors */ + _sick_sector_config.sick_num_initialized_sectors++; + } + else { + + /* An uninitialized sector marks the end of the sector configuration */ + break; + } + + } + + /* Compute the starting angle for each of the initialized sectors */ + for (unsigned int i = 1; i < _sick_sector_config.sick_num_initialized_sectors; i++) { + _sick_sector_config.sick_sector_start_angles[i] = fmod(_sick_sector_config.sick_sector_stop_angles[i-1]+_sick_global_config.sick_angle_step,360); + } + + /* Determine the starting angle for the first sector */ + if (_sick_sector_config.sick_num_initialized_sectors > 1) { + _sick_sector_config.sick_sector_start_angles[0] = + fmod(_sick_sector_config.sick_sector_stop_angles[_sick_sector_config.sick_num_initialized_sectors-1]+_sick_global_config.sick_angle_step,360); + } + + /* Success! */ + } + + /** + * \brief Query the Sick LD for a particular ID string. + * \param id_request_code The code indicating what ID string is being requested. + * \param &id_return_string A reference to hold the string returned from the Sick LD.x + */ + void SickLD::_getIdentificationString( const uint8_t id_request_code, std::string &id_return_string ) + throw( SickTimeoutException, SickIOException ) { + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the service IDs */ + payload_buffer[0] = SICK_STAT_SERV_CODE; // Requested service type + payload_buffer[1] = SICK_STAT_SERV_GET_ID; // Requested service subtype + payload_buffer[3] = id_request_code; // ID information that is being requested + + /* Create the Sick LD messages */ + SickLDMessage send_message(payload_buffer,4); + SickLDMessage recv_message; + + /* Send the message and get the reply */ + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getIdentificationString: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the payload buffer (not necessary, but it doesn't hurt to be careful) */ + memset(payload_buffer,0,4); + + /* Extract the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Assign the string */ + id_return_string = (char *) &payload_buffer[2]; + + /* Success, woohooo! */ + } + + /** + * \brief Get the Sick LD's part number + */ + void SickLD::_getSensorPartNumber( ) throw( SickTimeoutException, SickIOException ) { + + /* Query the Sick LD */ + try { + _getIdentificationString(SICK_STAT_SERV_GET_ID_SENSOR_PART_NUM,_sick_identity.sick_part_number); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getSensorPartNumber: Unknown exception!!!" << std::endl; + throw; + } + + /* Success, woohooo! */ + } + + /** + * \brief Get the Sick LD's assigned sensor name + */ + void SickLD::_getSensorName( ) throw( SickTimeoutException, SickIOException ) { + + /* Query the Sick LD */ + try { + _getIdentificationString(SICK_STAT_SERV_GET_ID_SENSOR_NAME,_sick_identity.sick_name); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getSensorName: Unknown exception!!!" << std::endl; + throw; + } + + /* Ok */ + } + + /** + * \brief Get the Sick LD's sensor version + */ + void SickLD::_getSensorVersion( ) throw( SickTimeoutException, SickIOException ) { + + /* Get the id info */ + try { + _getIdentificationString(SICK_STAT_SERV_GET_ID_SENSOR_VERSION,_sick_identity.sick_version); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getSensorVersion: Unknown exception!!!" << std::endl; + throw; + } + + /* Ok */ + } + + /** + * \brief Get the Sick LD's serial number + */ + void SickLD::_getSensorSerialNumber( ) throw( SickTimeoutException, SickIOException ) { + + try { + _getIdentificationString(SICK_STAT_SERV_GET_ID_SENSOR_SERIAL_NUM,_sick_identity.sick_serial_number); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getSensorSerialNumber: Unknown exception!!!" << std::endl; + throw; + } + + /* Ok */ + } + + /** + * \brief Get sensor EDM serial number + */ + void SickLD::_getSensorEDMSerialNumber( ) throw( SickTimeoutException, SickIOException ) { + + try { + _getIdentificationString(SICK_STAT_SERV_GET_ID_SENSOR_EDM_SERIAL_NUM,_sick_identity.sick_edm_serial_number); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getSensorEDMSerialNumber: Unknown exception!!!" << std::endl; + throw; + } + + /* Ok */ + } + + /** + * \brief Get firmware part number + */ + void SickLD::_getFirmwarePartNumber( ) throw( SickTimeoutException, SickIOException ) { + + try { + _getIdentificationString(SICK_STAT_SERV_GET_ID_FIRMWARE_PART_NUM,_sick_identity.sick_firmware_part_number); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getFirmwarePartNumber: Unknown exception!!!" << std::endl; + throw; + } + + /* Ok */ + } + + /** + * \brief Get firmware name + */ + void SickLD::_getFirmwareName( ) throw( SickTimeoutException, SickIOException ) { + + try { + _getIdentificationString(SICK_STAT_SERV_GET_ID_FIRMWARE_NAME,_sick_identity.sick_firmware_name); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getFirmwareName: Unknown exception!!!" << std::endl; + throw; + } + + /* Ok */ + } + + /** + * \brief Get firmware version number + */ + void SickLD::_getFirmwareVersion( ) throw( SickTimeoutException, SickIOException ){ + + try { + _getIdentificationString(SICK_STAT_SERV_GET_ID_FIRMWARE_VERSION,_sick_identity.sick_firmware_version); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getFirmwareVersion: Unknown exception!!!" << std::endl; + throw; + } + + /* Ok */ + } + + /** + * \brief Get application software part number + */ + void SickLD::_getApplicationSoftwarePartNumber( ) throw( SickTimeoutException, SickIOException ) { + + try { + _getIdentificationString(SICK_STAT_SERV_GET_ID_APP_PART_NUM,_sick_identity.sick_application_software_part_number); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getApplicationSoftwarePartNumber: Unknown exception!!!" << std::endl; + throw; + } + + /* Ok */ + } + + /** + * \brief Get application software name + */ + void SickLD::_getApplicationSoftwareName( ) throw( SickTimeoutException, SickIOException ) { + + try { + _getIdentificationString(SICK_STAT_SERV_GET_ID_APP_NAME,_sick_identity.sick_application_software_name); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getApplication Software Name: Unknown exception!!!" << std::endl; + throw; + } + + /* Ok */ + } + + /** + * \brief Get application software part number + */ + void SickLD::_getApplicationSoftwareVersion( ) throw( SickTimeoutException, SickIOException ) { + + try { + _getIdentificationString(SICK_STAT_SERV_GET_ID_APP_VERSION,_sick_identity.sick_application_software_version); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_getApplicationSoftwareVersion: Unknown exception!!!" << std::endl; + throw; + } + + /* Ok */ + } + + /** + * \brief Attempts to set the "permanent" (by writing flash) operating values for the device + * \param sick_motor_speed Desired motor speed for the device (hz) + * \param sick_angle_step Desired scan angular resolution (deg) + * \param active_sector_start_angles Angles marking the beginning of each desired active sector/area + * \param active_sector_stop_angles Angles marking the end of each desired active sector/area + * \param num_active_sectors The number of active sectors + */ + void SickLD::_setSickGlobalParamsAndScanAreas( const unsigned int sick_motor_speed, const double sick_angle_step, + const double * const active_sector_start_angles, + const double * const active_sector_stop_angles, + const unsigned int num_active_sectors ) + throw( SickTimeoutException, SickIOException, SickConfigException, SickErrorException ) { + + /* Define buffers to hold the device-ready configuration */ + unsigned int num_sectors = 0; + unsigned int sector_functions[SICK_MAX_NUM_SECTORS] = {0}; + double sector_stop_angles[SICK_MAX_NUM_SECTORS] = {0}; + + /* A few dummy buffers */ + double sorted_active_sector_start_angles[SICK_MAX_NUM_SECTORS] = {0}; + double sorted_active_sector_stop_angles[SICK_MAX_NUM_SECTORS] = {0}; + + /* Begin by checking the num of active sectors */ + if (num_active_sectors > SICK_MAX_NUM_SECTORS/2) { + throw SickConfigException("SickLD::_setSickGlobalParamsAndScanAreas: Invalid number of active scan sectors!"); + } + + /* Ensure the given motor speed is valid (within proper bounds, etc...) */ + if (!_validSickMotorSpeed(sick_motor_speed)) { + throw SickConfigException("SickLD::_setSickGlobalParamsAndScanAreas: Invalid motor speed!"); + } + + /* Ensure the scan resolution is valid (within proper bounds, etc...) */ + if (!_validSickScanResolution(sick_angle_step,active_sector_start_angles,active_sector_stop_angles,num_active_sectors)) { + throw SickConfigException("SickLD::_setSickGlobalParamsAndScanAreas: Invalid scan resolution!"); + } + + /* Copy the input arguments */ + memcpy(sorted_active_sector_start_angles,active_sector_start_angles,sizeof(sorted_active_sector_start_angles)); + memcpy(sorted_active_sector_stop_angles,active_sector_stop_angles,sizeof(sorted_active_sector_stop_angles)); + + /* Ensure a proper ordering of the given sector angle sets */ + _sortScanAreas(sorted_active_sector_start_angles,sorted_active_sector_stop_angles,num_active_sectors); + + /* Check for an invalid configuration */ + if (!_validActiveSectors(sorted_active_sector_start_angles,sorted_active_sector_stop_angles,num_active_sectors)) { + throw SickConfigException("SickLD::_setSickGlobalParamsAndScanAreas: Invalid sector configuration!"); + } + + /* Ensure the resulting pulse frequency is valid for the device */ + if (!_validPulseFrequency(sick_motor_speed,sick_angle_step,sorted_active_sector_start_angles, sorted_active_sector_stop_angles,num_active_sectors)) { + throw SickConfigException("SickLD::_setSickGlobalParamsAndScanAreas: Invalid pulse frequency!"); + } + + /* Generate the corresponding device-ready sector config */ + _generateSickSectorConfig(sorted_active_sector_start_angles,sorted_active_sector_stop_angles,num_active_sectors,sick_angle_step, + sector_functions,sector_stop_angles,num_sectors); + + try { + + /* Set the new sector configuration */ + _setSickSectorConfig(sector_functions,sector_stop_angles,num_sectors,false); + + /* Assign the new configuration in the flash + * + * NOTE: The following function must be called, even if the global parameters (motor speed, + * and angular resolution) are the same, in order to write the sector configuration. + * Why this is the case isn't exactly clear as the manual does not explain. + */ + _setSickGlobalConfig(GetSickSensorID(),sick_motor_speed,sick_angle_step); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickGlobalParamsAndScanAreas: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + } + + /** + * \brief Attempts to set the "temporary" (until a device reset) scan area config for the device + * \param active_sector_start_angles Angles marking the beginning of each desired active sector/area + * \param active_sector_stop_angles Angles marking the end of each desired active sector/area + * \param num_active_sectors The number of active sectors + */ + void SickLD::_setSickTemporaryScanAreas( const double * const active_sector_start_angles, + const double * const active_sector_stop_angles, + const unsigned int num_active_sectors ) throw( SickTimeoutException, SickIOException, SickConfigException ) { + + /* Define buffers to hold the device-ready configuration */ + unsigned int num_sectors = 0; + unsigned int sector_functions[SICK_MAX_NUM_SECTORS] = {0}; + double sector_stop_angles[SICK_MAX_NUM_SECTORS] = {0}; + + /* A few dummy buffers */ + double sorted_active_sector_start_angles[SICK_MAX_NUM_SECTORS] = {0}; + double sorted_active_sector_stop_angles[SICK_MAX_NUM_SECTORS] = {0}; + + /* Begin by checking the num of active sectors */ + if (num_active_sectors > SICK_MAX_NUM_SECTORS/2) + throw SickConfigException("_setSickTemporaryScanAreas: Invalid number of active scan sectors!"); + + /* Copy the input arguments */ + memcpy(sorted_active_sector_start_angles,active_sector_start_angles,sizeof(sorted_active_sector_start_angles)); + memcpy(sorted_active_sector_stop_angles,active_sector_stop_angles,sizeof(sorted_active_sector_stop_angles)); + + /* Ensure a proper ordering of the given sector angle sets */ + _sortScanAreas(sorted_active_sector_start_angles,sorted_active_sector_stop_angles,num_active_sectors); + + /* Check for an invalid configuration */ + if (!_validActiveSectors(sorted_active_sector_start_angles,sorted_active_sector_stop_angles,num_active_sectors)) { + throw SickConfigException("SickLD::_setSickGlobalParamsAndScanAreas: Invalid sector configuration!"); + } + + /* Ensure the resulting pulse frequency is valid for the device */ + if (!_validPulseFrequency(GetSickMotorSpeed(),GetSickScanResolution(),sorted_active_sector_start_angles, + sorted_active_sector_stop_angles,num_active_sectors)) { + throw SickConfigException("SickLD::_setSickGlobalParamsAndScanAreas: Invalid pulse frequency!"); + } + + /* Generate the corresponding device-ready sector config */ + _generateSickSectorConfig(sorted_active_sector_start_angles,sorted_active_sector_stop_angles,num_active_sectors,GetSickScanResolution(), + sector_functions,sector_stop_angles,num_sectors); + + /* Set the new sector configuration */ + try { + _setSickSectorConfig(sector_functions,sector_stop_angles,num_sectors); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickTemporaryScanAreas: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + } + + /** + * \brief Sets the sector configuration for the device + * \param sector_functions Angles marking the beginning of each desired active sector/area + * \param sector_stop_angles Angles marking the end of each desired active sector/area + * \param num_sectors The total number of sectors in the configuration + * \param set_flash_flag Indicates whether to mark the sectors for writing to flash w/ the next SET_CONFIG (global) + */ + void SickLD::_setSickSectorConfig( const unsigned int * const sector_functions, const double * const sector_stop_angles, + const unsigned int num_sectors, const bool write_to_flash ) + throw( SickErrorException, SickTimeoutException, SickIOException, SickConfigException ) { + + /* Assign the new sector configuration to the device */ + for (unsigned int sector_id = 0; sector_id < num_sectors; sector_id++) { + + try { + + /* Set the corresponding sector function */ + _setSickSectorFunction(sector_id,sector_functions[sector_id],sector_stop_angles[sector_id],write_to_flash); + + /* Resync the driver with the new sector configuration */ + _getSickSectorConfig(); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSectorConfig: Unknown exception!!!" << std::endl; + throw; + } + + } + + /* Success */ + } + + /** + * \brief Sets the Sick LEDs and switching outputs + * \param sick_signal_flags Flags indicating which LEDs and SWITCHES to activate + * + * NOTE: This method does not preserve the previous state of the Sick's signals. + * In other words, only the signals flagged in sick_signal_flags will be + * set - all others will be off! + */ + void SickLD::_setSickSignals( const uint8_t sick_signal_flags ) throw( SickIOException, SickTimeoutException, SickErrorException ) { + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLDMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the service IDs */ + payload_buffer[0] = SICK_STAT_SERV_CODE; // Requested service type + payload_buffer[1] = SICK_STAT_SERV_SET_SIGNAL; // Requested service subtype + payload_buffer[3] = sick_signal_flags; // PORTVAL + + /* Create the Sick message */ + SickLDMessage send_message(payload_buffer,4); + SickLDMessage recv_message; + + /* Send the message and get a response */ + try { + _sendMessageAndGetReply(send_message,recv_message); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::_setSickSensorMode: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the payload buffer */ + memset(payload_buffer,0,4); + + /* Extract the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Check to see if there was an error */ + if (payload_buffer[2] != 0) { + throw SickErrorException("SickLD::_setSickSignals: Command failed!"); + } + + /* Success */ + } + + /** + * \brief Send a message to the Sick LD and get its reply. + * \param &send_message A reference to the well-formed message object that is to be sent. + * \param &recv_message The destination message object for the received reply. + * \param timeout_value The maximum time to allow for a response in seconds + * + * NOTE: This method also verifies the correct reply to the given send_message + * object is received. So, if it fails, it may be due to an unexpected reply. + */ + void SickLD::_sendMessageAndGetReply( const SickLDMessage &send_message, + SickLDMessage &recv_message, + const unsigned int timeout_value ) throw( SickIOException, SickTimeoutException ) { + + uint8_t byte_sequence[2] = {0}; + + byte_sequence[0] = send_message.GetServiceCode() | 0x80; + byte_sequence[1] = send_message.GetServiceSubcode(); + + /* Send message and get reply using parent's method */ + try { + SickLIDAR< SickLDBufferMonitor, SickLDMessage >::_sendMessageAndGetReply(send_message,recv_message,byte_sequence,2,0,DEFAULT_SICK_MESSAGE_TIMEOUT,1); + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLD::_sendMessageAndGetReply: Unknown exception!!!" << std::endl; + throw; + } + + } + + /** + * \brief Flushes TCP receive buffer contents + */ + void SickLD::_flushTCPRecvBuffer( ) throw( SickIOException, SickThreadException ) { + + uint8_t null_byte; + int num_bytes_waiting = 0; + + try { + + /* Acquire access to the data stream */ + _sick_buffer_monitor->AcquireDataStream(); + + /* Acquire the number of the bytes awaiting read */ + if (ioctl(_sick_fd,FIONREAD,&num_bytes_waiting)) { + throw SickIOException("SickLD::_flushTCPRecvBuffer: ioctl() failed! (Couldn't get the number of bytes awaiting read!)"); + } + + /* Read off the bytes awaiting in the buffer */ + for (int i = 0; i < num_bytes_waiting; i++) { + read(_sick_fd,&null_byte,1); + } + + /* Release the stream */ + _sick_buffer_monitor->ReleaseDataStream(); + + } + + /* Catch any serious IO exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* A sanity check */ + catch(...) { + std::cerr << "SickLMS::_flushTerminalBuffer: Unknown exception!" << std::endl; + throw; + } + + } + + /** + * \brief Teardown TCP connection to Sick LD + */ + void SickLD::_teardownConnection( ) throw( SickIOException ) { + + /* Close the socket! */ + if (close(_sick_fd) < 0) { + throw SickIOException("SickLD::_teardownConnection: close() failed!"); + } + + } + + /** + * \brief Generates a device-ready sector set given only an active sector spec. + * \param *active_sector_start_angles Start angles for the active (measuring) sectors + * \param *active_sector_stop_angles Stop angles for the active sectors + * \param num_active_sectors The number of active sectors given + * \param sick_angle_step The step angle (angular resolution) to be used in generating the config + * \param *sector_functions An output buffer to hold the function assigned to each sector + * \param *sector_stop_angles An output buffer to hold the stop angles associated w/ the generated sector set + * \param &num_sectors The number of sectors in the final device-ready configuration + */ + void SickLD::_generateSickSectorConfig( const double * const active_sector_start_angles, + const double * const active_sector_stop_angles, + const unsigned int num_active_sectors, + const double sick_angle_step, + unsigned int * const sector_functions, + double * const sector_stop_angles, + unsigned int &num_sectors ) const { + + num_sectors = 0; + + /* Generate the sector configuration for multiple sectors */ + double final_diff = 0; + if (num_active_sectors > 1) { + + /* Generate the actual sector configuration for the device */ + for (unsigned int i = 0; i < num_active_sectors; i++) { + + /* Insert the measurement sector for the active area */ + sector_functions[num_sectors] = SICK_CONF_SECTOR_NORMAL_MEASUREMENT; + sector_stop_angles[num_sectors] = active_sector_stop_angles[i]; + num_sectors++; + + /* Check whether to insert a non-measurement sector */ + if ((i < num_active_sectors - 1) && (active_sector_start_angles[i+1]-active_sector_stop_angles[i] >= 2*sick_angle_step)) { + + /* Set the next sector function as non-measurement */ + sector_functions[num_sectors] = SICK_CONF_SECTOR_NO_MEASUREMENT; + sector_stop_angles[num_sectors] = active_sector_start_angles[i+1] - sick_angle_step; + num_sectors++; + + } + + } + + /* Compute the difference between the final stop angle and the first start angle*/ + if (active_sector_stop_angles[num_active_sectors-1] < active_sector_start_angles[0]) { + final_diff = active_sector_start_angles[0] - active_sector_stop_angles[num_active_sectors-1]; + } + else { + final_diff = active_sector_start_angles[0] + (360 - active_sector_stop_angles[num_active_sectors-1]); + } + + } + else { + + /* Insert the measurement sector for the active area */ + sector_functions[num_sectors] = SICK_CONF_SECTOR_NORMAL_MEASUREMENT; + sector_stop_angles[num_sectors] = active_sector_stop_angles[0]; + num_sectors++; + + /* Compute the difference between the final stop angle and the first start angle*/ + if (active_sector_stop_angles[0] <= active_sector_start_angles[0]) { + final_diff = active_sector_start_angles[0] - active_sector_stop_angles[num_active_sectors-1]; + } + else { + final_diff = active_sector_start_angles[0] + (360 - active_sector_stop_angles[num_active_sectors-1]); + } + + } + + /* Check whether to add a final non-measurement sector */ + if (final_diff >= 2*sick_angle_step) { + + /* Include the final non-measurement sector */ + sector_functions[num_sectors] = SICK_CONF_SECTOR_NO_MEASUREMENT; + sector_stop_angles[num_sectors] = active_sector_start_angles[0]-sick_angle_step + + 360*(sick_angle_step > active_sector_start_angles[0]); + num_sectors++; + + } + + /* If necessary insert the non-initialized sector */ + if (num_sectors < SICK_MAX_NUM_SECTORS) { + + /* Include the uninitialized sector */ + sector_functions[num_sectors] = SICK_CONF_SECTOR_NOT_INITIALIZED; + sector_stop_angles[num_sectors] = 0; + num_sectors++; + + } + + } + + /** + * \brief Converts encoder ticks to equivalent angle representation. + * \param ticks The tick value to be converted + * \return The corresponding angle value + */ + double SickLD::_ticksToAngle( const uint16_t ticks ) const { + return (((double)ticks)/16); + } + + /** + * \brief Converts encoder ticks to equivalent angle representation. + * \param ticks The tick value to be converted + * \return The corresponding ticks value + * + * NOTE: This function assumes that the angle value it receives is + * a multiple of 1/16 degree (which is the resolution of the + * encoder) + */ + uint16_t SickLD::_angleToTicks( const double angle ) const { + return (uint16_t)(angle*16); + } + + /** + * \brief Compute the mean pulse frequency (see page 22 of the operator's manual) + * \param active_scan_area The total area where the Sick is actively scanning (in deg) (i.e. total area where the laser isn't blanked) + * \param curr_motor_speed The current motor speed (in Hz) + * \param curr_angular_resolution The current angular resolution of the Sick (in deg) + * \return The mean pulse frequency for the given configuration parameters + */ + double SickLD::_computeMeanPulseFrequency( const double active_scan_area, const double curr_motor_speed, + const double curr_angular_resolution ) const { + /* Compute the mean pulse frequency */ + return _computeMaxPulseFrequency(SICK_MAX_SCAN_AREA,curr_motor_speed,curr_angular_resolution)*(active_scan_area/((double)SICK_MAX_SCAN_AREA)); + } + + /** + * \brief Compute the mean pulse frequency (see page 22 of the operator's manual) + * \param active_scan_area The total scan area that can be covered by the Sick + * \param curr_motor_speed The current motor speed (in Hz) + * \param curr_angular_resolution The current angular resolution of the Sick (in deg) + * \return The maximum pulse frequency for the given configuration parameters + */ + double SickLD::_computeMaxPulseFrequency( const double total_scan_area, const double curr_motor_speed, + const double curr_angular_resolution ) const { + /* Compute the maximum pulse frequency */ + return total_scan_area*curr_motor_speed*(1/curr_angular_resolution); + } + + /** + * \brief Checks whether the given senor id is valid for the device. + * \param sick_sensor_id Sick sensor ID + */ + bool SickLD::_validSickSensorID( const unsigned int sick_sensor_id ) const { + + /* Ensure the sensor ID is valid */ + if (sick_sensor_id < SICK_MIN_VALID_SENSOR_ID || sick_sensor_id > SICK_MAX_VALID_SENSOR_ID) { + return false; + } + + /* Success */ + return true; + } + + /** + * \brief Checks whether the given sick motor speed is valid for the device. + * \param sick_motor_speed The sick motor speed (Hz) + */ + bool SickLD::_validSickMotorSpeed( const unsigned int sick_motor_speed ) const { + + /* Check the validity of the new Sick LD motor speed */ + if (sick_motor_speed < SICK_MIN_MOTOR_SPEED || sick_motor_speed > SICK_MAX_MOTOR_SPEED) { + return false; + } + + /* Success */ + return true; + } + + /** + * \brief Checks whether the given scan resolution is valid + * \param sick_scan_resolution Scan resolution of the device + * \param sector_start_angles An array of the sector start angles + * \param sector_stop_angles An array of the sector stop angles + */ + bool SickLD::_validSickScanResolution( const double sick_angle_step, const double * const sector_start_angles, + const double * const sector_stop_angles, const unsigned int num_sectors ) const { + + /* Check the validity of the new Sick LD angular step */ + if (sick_angle_step < SICK_MAX_SCAN_ANGULAR_RESOLUTION || fmod(sick_angle_step,SICK_MAX_SCAN_ANGULAR_RESOLUTION) != 0) { + std::cerr << "Invalid scan resolution! (should be a positive multiple of " << SICK_MAX_SCAN_ANGULAR_RESOLUTION << ")" << std::endl; + return false; + } + + /* Ensure that the sector boundaries are divisible by the desired step angle */ + for(unsigned int i = 0; i < num_sectors; i++) { + + /* Check both the sector start and stop angles */ + if (fmod(sector_start_angles[i],sick_angle_step) != 0 || fmod(sector_stop_angles[i],sick_angle_step) != 0) { + std::cerr << "Invalid scan resolution! (sector boundaries must be evenly divisible by the step angle)" << std::endl; + return false; + } + + } + + /* Success */ + return true; + } + + /** + * \brief Checks whether the given configuration yields a valid mean and max pulse frequency (uses current sector config) + * \param sick_motor_speed Desired sick motor speed (Hz) + * \param sick_angle_step Desired scan angular resolution (deg) + */ + bool SickLD::_validPulseFrequency( const unsigned int sick_motor_speed, const double sick_angle_step ) const { + + /* Simply call the other function w/ the current sector config and the given motor and step angle values */ + if(!_validPulseFrequency(sick_motor_speed,sick_angle_step,_sick_sector_config.sick_sector_start_angles, + _sick_sector_config.sick_sector_stop_angles,_sick_sector_config.sick_num_active_sectors)) { + return false; + } + + /* Valid! */ + return true; + } + + /** + * \brief Checks whether the given configuration yields a valid mean and max pulse frequency (uses given sector config) + * \param sick_motor_speed Desired sick motor speed (Hz) + * \param sick_angle_step Desired scan angular resolution (deg) + * \param active_sector_start_angles Angles marking the beginning of each desired active sector/area + * \param active_sector_stop_angles Angles marking the end of each desired active sector/area + * \param num_active_sectors The number of active sectors/scan areas are given + */ + bool SickLD::_validPulseFrequency( const unsigned int sick_motor_speed, const double sick_angle_step, + const double * const active_sector_start_angles, + const double * const active_sector_stop_angles, + const unsigned int num_active_sectors ) const { + + /* Compute the scan area */ + double scan_area = _computeScanArea(sick_angle_step,active_sector_start_angles,active_sector_stop_angles,num_active_sectors); + + /* Check the mean pulse rate of the desired configuration */ + if (_computeMeanPulseFrequency(scan_area,sick_motor_speed,sick_angle_step) > SICK_MAX_MEAN_PULSE_FREQUENCY) { + std::cerr << "Max mean pulse frequency exceeded! (try a slower motor speed, a larger step angle and/or a smaller active scan area)" << std::endl; + return false; + } + + /* Check the maximum pulse rate of the desired configuration */ + if (_computeMaxPulseFrequency(SICK_MAX_SCAN_AREA,sick_motor_speed,sick_angle_step) > SICK_MAX_PULSE_FREQUENCY) { + std::cerr << "Max pulse frequency exceeded! (try a slower motor speed, a larger step angle and/or a smaller active scan area)" << std::endl; + return false; + } + + /* Valid! */ + return true; + } + + /** + * \brief Computes the active scan area for the Sick given the current + * sector configuration + * \param sick_angle_step The angular resolution of the Sick LD + * \param active_sector_start_angles The start angles for the active scan sectors + * \param active_sector_stop_angles The stop angles for the active scan sectors + * \param num_active_sectors The number of active sectors + * \return The Sick LD scan area corresponding to the given bounds + * + * NOTE: The Sick LD computes scan area by subtracting the end of the + * previous sector from the end of the current sector. As such, we have + * to add a single step angle to our computation in order to get the scan + * area that is used by the Sick LD. Unfortunately, this is how the device + * does its computation (as opposed to using the angle at which the first + * scan in the given sector is taken) so this is how we do it. + * + */ + double SickLD::_computeScanArea( const double sick_angle_step, const double * const active_sector_start_angles, + const double * const active_sector_stop_angles, const unsigned int num_active_sectors ) const { + + /* Define the current scan area */ + double total_scan_area = 0; + double curr_sector_scan_area = 0; + + /* For each sector given sum the absolute scan area for it */ + for (unsigned int i = 0; i < num_active_sectors; i++) { + + /* Compute the total scan area for this sector */ + curr_sector_scan_area = fabs(active_sector_start_angles[i]-active_sector_stop_angles[i]); + + /* Update the total scan area */ + total_scan_area += curr_sector_scan_area + sick_angle_step; + } + + /* Return the computed area */ + return total_scan_area; + + } + + /** + * \brief Sort the scan areas based on the given angles to place them in device "scan" order + * \param sector_start_angles Array of angles (deg) defining the starting position of each active sector + * \param sector_stop_angles Array of angles (deg) defining the stopping position of each active sector + * \param num_active_sectors Number of active sectors + */ + void SickLD::_sortScanAreas( double * const sector_start_angles, double * const sector_stop_angles, + const unsigned int num_sectors ) const { + + /* A dummy temp variable */ + double temp = 0; + + /* Employ a simple bubblesort (NOTE: Only at most a handful of values will have to be sorted) */ + for (unsigned int i = 0; i < num_sectors; i++) { + for (unsigned int j = (num_sectors-1); j > i; j--) { + if (sector_start_angles[j] < sector_start_angles[j-1]) { + SWAP_VALUES(sector_start_angles[j],sector_start_angles[j-1],temp); + SWAP_VALUES(sector_stop_angles[j],sector_stop_angles[j-1],temp); + } + } + } + + } + + /** + * \brief Determines wheter a given set of sector bounds are valid. + * \param sector_start_angles Array of angles (deg) defining the starting position of each active sector + * \param sector_stop_angles Array of angles (deg) defining the stopping position of each active sector + * \param num_active_sectors Number of active sectors + */ + bool SickLD::_validActiveSectors( const double * const sector_start_angles, const double * const sector_stop_angles, + const unsigned int num_sectors ) const { + + /* A sanity check to make sure all are in [0,360) */ + for (unsigned int i = 0; i < num_sectors; i++) { + + if (sector_start_angles[i] < 0 || sector_stop_angles[i] < 0 || + sector_start_angles[i] >= 360 || sector_stop_angles[i] >= 360) { + + std::cerr << "Invalid sector config! (all degree values must be in [0,360))" << std::endl; + return false; + } + + } + + /* If multiple sectors are defined */ + if (num_sectors > 1) { + + /* Check whether the given sector arrangement is overlapping */ + for (unsigned int i = 0; i < (num_sectors - 1); i++) { + if (sector_start_angles[i] > sector_stop_angles[i] || sector_stop_angles[i] >= sector_start_angles[i+1]) { + std::cerr << "Invalid sector definitions! (check sector bounds)" << std::endl; + return false; + } + } + + /* Check the last sector against the first */ + if (sector_stop_angles[num_sectors-1] <= sector_start_angles[num_sectors-1] && + sector_stop_angles[num_sectors-1] >= sector_start_angles[0]) { + std::cerr << "Invalid sector definitions! (check sector bounds)" << std::endl; + return false; + } + + } + + /* Valid! */ + return true; + } + + /** + * \brief Check that the given profile format is supported by the current driver version. + * \param profile_format The requested profile format. + * \return True if the given scan profile is supported by the driver + */ + bool SickLD::_supportedScanProfileFormat( const uint16_t profile_format ) const { + + /* Check the supplied scan profile format */ + switch(profile_format) { + case SICK_SCAN_PROFILE_RANGE: + return true; + case SICK_SCAN_PROFILE_RANGE_AND_ECHO: + return true; + default: + return false; + } + } + + /** + * \brief Print data corresponding to the referenced sector data structure. + * \param §or_data The sector configuration to be printed + */ + void SickLD::_printSectorProfileData( const sick_ld_sector_data_t §or_data ) const { + + std::cout << "\t---- Sector Data " << sector_data.sector_num << " ----" << std::endl; + std::cout << "\tSector Num.: " << sector_data.sector_num << std::endl; + std::cout << "\tSector Angle Step (deg): " << sector_data.angle_step<< std::endl; + std::cout << "\tSector Num. Data Points: " << sector_data.num_data_points << std::endl; + std::cout << "\tSector Start Timestamp (ms): " << sector_data.timestamp_start << std::endl; + std::cout << "\tSector Stop Timestamp (ms): " << sector_data.timestamp_stop << std::endl; + std::cout << "\tSector Start Angle (deg): " << sector_data.angle_start << std::endl; + std::cout << "\tSector Stop Angle (deg): " << sector_data.angle_stop << std::endl; + std::cout << std::flush; + } + + /** + * \brief Prints data fields of the given scan profile. + * \param profile_data The scan profile to be printed. + * \param print_sector_data Indicates whether to print the sector data fields associated + * with the given profile. + */ + void SickLD::_printSickScanProfile( const sick_ld_scan_profile_t profile_data, const bool print_sector_data ) const { + + std::cout << "\t========= Sick Scan Prof. =========" << std::endl; + std::cout << "\tProfile Num.: " << profile_data.profile_number << std::endl; + std::cout << "\tProfile Counter: " << profile_data.profile_counter << std::endl; + std::cout << "\tLayer Num.: " << profile_data.layer_num << std::endl; + std::cout << "\tSensor Status: " << _sickSensorModeToString(profile_data.sensor_status) << std::endl; + std::cout << "\tMotor Status: " << _sickMotorModeToString(profile_data.motor_status) << std::endl; + std::cout << "\tNum. Sectors: " << profile_data.num_sectors << std::endl; + + // Print the corresponding active and non-active sector data + for (unsigned int i=0; i < profile_data.num_sectors && print_sector_data; i++) { + _printSectorProfileData(profile_data.sector_data[i]); + } + + std::cout << "\t====================================" << std::endl; + std::cout << std::flush; + } + + /** + * \brief Map Sick LD sensor modes to their equivalent service subcode representations + * \param sick_sensor_mode The sensor mode to be converted + * \return The corresponding work service subcode + */ + uint8_t SickLD::_sickSensorModeToWorkServiceSubcode( const uint8_t sick_sensor_mode ) const { + + switch(sick_sensor_mode) { + case SICK_SENSOR_MODE_IDLE: + return SICK_WORK_SERV_TRANS_IDLE; + case SICK_SENSOR_MODE_ROTATE: + return SICK_WORK_SERV_TRANS_ROTATE; + case SICK_SENSOR_MODE_MEASURE: + return SICK_WORK_SERV_TRANS_MEASURE; + default: + std::cerr << "SickLD::_sickSensorModeToWorkServiceSubcode: Invalid sensor mode! (Returning 0)" << std::endl; + return 0; //Something is seriously wrong if we end up here! + } + } + + /** + * \brief Converts the Sick LD numerical sensor mode to a representative string + * \param sick_sensor_mode The sensor mode to be converted + * \return The corresponding sensor_mode string + */ + std::string SickLD::_sickSensorModeToString( const uint8_t sick_sensor_mode ) const { + + switch(sick_sensor_mode) { + case SICK_SENSOR_MODE_IDLE: + return "IDLE"; + case SICK_SENSOR_MODE_ROTATE: + return "ROTATE (laser is off)"; + case SICK_SENSOR_MODE_MEASURE: + return "MEASURE (laser is on)"; + case SICK_SENSOR_MODE_ERROR: + return "ERROR"; + case SICK_SENSOR_MODE_UNKNOWN: + return "UNKNOWN"; + default: + return "UNRECOGNIZED!!!"; + } + } + + /** + * \brief Converts the Sick LD numerical motor mode to a representative string + * \param sick_motor_mode The sick motor mode code to be converted + * \return The corresponding string + */ + std::string SickLD::_sickMotorModeToString( const uint8_t sick_motor_mode ) const { + + switch(sick_motor_mode) { + case SICK_MOTOR_MODE_OK: + return "OK"; + case SICK_MOTOR_MODE_SPIN_TOO_HIGH: + return "SPIN TOO HIGH"; + case SICK_MOTOR_MODE_SPIN_TOO_LOW: + return "SPIN TOO LOW"; + case SICK_MOTOR_MODE_ERROR: + return "ERROR"; + case SICK_MOTOR_MODE_UNKNOWN: + return "UNKNOWN"; + default: + return "UNRECOGNIZED!!!"; + } + } + + /** + * \brief Converts return value from TRANS_MEASURE to a representative string + * \param return_value The TRANS_MEASURE numeric return code + * \return The corresponding string + */ + std::string SickLD::_sickTransMeasureReturnToString( const uint8_t return_value ) const { + + switch(return_value) { + case SICK_WORK_SERV_TRANS_MEASURE_RET_OK: + return "LD-OEM/LD-LRS Measures"; + case SICK_WORK_SERV_TRANS_MEASURE_RET_ERR_MAX_PULSE: + return "Max Pulse Frequency Too High"; + case SICK_WORK_SERV_TRANS_MEASURE_RET_ERR_MEAN_PULSE: + return "Mean Pulse Frequency Too High"; + case SICK_WORK_SERV_TRANS_MEASURE_RET_ERR_SECT_BORDER: + return "Sector Borders Not Configured Correctly"; + case SICK_WORK_SERV_TRANS_MEASURE_RET_ERR_SECT_BORDER_MULT: + return "Sector Borders Not Multiple of Angle Step"; + default: + return "UNRECOGNIZED!!!"; + } + + } + + /** + * \brief Converts the Sick LD numerical reset level to a representative string + * \param The numeric reset level code + * \return The corresponding string + */ + std::string SickLD::_sickResetLevelToString( const uint16_t reset_level ) const { + + switch(reset_level) { + case SICK_WORK_SERV_RESET_INIT_CPU: + return "RESET (CPU Reinitialized)"; + case SICK_WORK_SERV_RESET_KEEP_CPU: + return "RESET (CPU Not Reinitialized)"; + case SICK_WORK_SERV_RESET_HALT_APP: + return "RESET (Halt App. and Enter IDLE)"; + default: + return "UNRECOGNIZED!!!"; + } + + } + + /** + * \brief Converts the Sick LD numerical sector config to a representative string + * \param sick_sector_function The numeric sector function to be converted + * \return The corresponding string + */ + std::string SickLD::_sickSectorFunctionToString( const uint16_t sick_sector_function ) const { + + switch(sick_sector_function) { + case SICK_CONF_SECTOR_NOT_INITIALIZED: + return "NOT INITIALIZED"; + case SICK_CONF_SECTOR_NO_MEASUREMENT: + return "NOT MEASURING"; + case SICK_CONF_SECTOR_RESERVED: + return "RESERVED"; + case SICK_CONF_SECTOR_NORMAL_MEASUREMENT: + return "MEASURING"; + case SICK_CONF_SECTOR_REFERENCE_MEASUREMENT: + return "REFERENCE"; + default: + return "UNRECOGNIZED!!!"; + } + + } + + /** + * \brief Converts the Sick LD numerical motor mode to a representative string + * \param profile_format The profile format to be converted + * \return The corresponding string + */ + std::string SickLD::_sickProfileFormatToString( const uint16_t profile_format ) const { + + switch(profile_format) { + case SICK_SCAN_PROFILE_RANGE: + return "RANGE ONLY"; + case SICK_SCAN_PROFILE_RANGE_AND_ECHO: + return "RANGE + ECHO"; + default: + return "UNRECOGNIZED!!!"; + } + + } + + /** + * \brief Prints the initialization footer. + */ + void SickLD::_printInitFooter( ) const { + + std::cout << "\t*** Init. complete: Sick LD is online and ready!" << std::endl; + std::cout << "\tNum. Active Sectors: " << (int)_sick_sector_config.sick_num_active_sectors << std::endl; + std::cout << "\tMotor Speed: " << _sick_global_config.sick_motor_speed << " (Hz)" << std::endl; + std::cout << "\tScan Resolution: " << _sick_global_config.sick_angle_step << " (deg)" << std::endl; + std::cout << std::endl; + + } + +} //namespace SickToolbox diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/SickLDBufferMonitor.cc b/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/SickLDBufferMonitor.cc new file mode 100644 index 0000000..ea93bb9 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/SickLDBufferMonitor.cc @@ -0,0 +1,132 @@ +/*! + * \file SickLDBufferMonitor.cc + * \brief Implements a class for monitoring the receive + * buffer when interfacing w/ a Sick LD LIDAR. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +/* Auto-generated header */ +#include + +/* Implementation dependencies */ +#include +#include + +#include +#include +#include +#include + +/* Associate the namespace */ +namespace SickToolbox { + + /** + * \brief A standard constructor + */ + SickLDBufferMonitor::SickLDBufferMonitor( ) : SickBufferMonitor< SickLDBufferMonitor, SickLDMessage >(this) { } + + /** + * \brief Acquires the next message from the SickLD byte stream + * \param &sick_message The returned message object + */ + void SickLDBufferMonitor::GetNextMessageFromDataStream( SickLDMessage &sick_message ) throw( SickIOException ) { + + /* Flush the input buffer */ + uint8_t byte_buffer; + + /* A buffer to hold the current byte out of the stream */ + const uint8_t sick_response_header[4] = {0x02,'U','S','P'}; + + uint8_t checksum = 0; + uint8_t message_buffer[SickLDMessage::MESSAGE_MAX_LENGTH] = {0}; + uint32_t payload_length = 0; + + try { + + /* Search for the header in the byte stream */ + for (unsigned int i = 0; i < sizeof(sick_response_header);) { + + /* Acquire the next byte from the stream */ + _readBytes(&byte_buffer,1,DEFAULT_SICK_BYTE_TIMEOUT); + + /* Check if the current byte matches the expected header byte */ + if (byte_buffer == sick_response_header[i]) { + i++; + } + else { + i = 0; + } + + } + + /* Populate message buffer w/ response header */ + memcpy(message_buffer,sick_response_header,4); + + /* Acquire the payload length! */ + _readBytes(&message_buffer[4],4,DEFAULT_SICK_BYTE_TIMEOUT); + + /* Extract the payload size and adjust the byte order */ + memcpy(&payload_length,&message_buffer[4],4); + payload_length = sick_ld_to_host_byte_order(payload_length); + + /* Read the packet payload */ + _readBytes(&message_buffer[8],payload_length,DEFAULT_SICK_BYTE_TIMEOUT); + + /* Read the checksum */ + _readBytes(&checksum,1,DEFAULT_SICK_BYTE_TIMEOUT); + + /* Build the return message object based upon the received payload + * and compute the associated checksum. + * + * NOTE: In constructing this message we ignore the header bytes + * buffered since the BuildMessage routine will insert the + * correct header automatically and compute the payload's + * checksum for us. We could probably get away with using + * just ParseMessage here and not computing the checksum as + * we are using TCP. However, its safer this way. + */ + sick_message.BuildMessage(&message_buffer[SickLDMessage::MESSAGE_HEADER_LENGTH],payload_length); + + /* Verify the checksum is correct (this is probably unnecessary since we are using TCP/IP) */ + if (sick_message.GetChecksum() != checksum) { + throw SickBadChecksumException("SickLD::GetNextMessageFromDataStream: BAD CHECKSUM!!!"); + } + + /* Success */ + + } + + catch(SickTimeoutException &sick_timeout) { /* This is ok! */ } + + /* Catch a bad checksum! */ + catch(SickBadChecksumException &sick_checksum_exception) { + sick_message.Clear(); // Clear the message container + } + + /* Catch any serious IO buffer exceptions */ + catch(SickIOException &sick_io_exception) { + throw; + } + + /* A sanity check */ + catch (...) { + throw; + } + + } + + /** + * \brief A standard destructor + */ + SickLDBufferMonitor::~SickLDBufferMonitor( ) { } + +} /* namespace SickToolbox */ diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/SickLDMessage.cc b/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/SickLDMessage.cc new file mode 100644 index 0000000..17c9e11 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/ld/sickld/SickLDMessage.cc @@ -0,0 +1,153 @@ +/*! + * \file SickLDMessage.cc + * \brief Implements the class SickLDMessage. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +/* Auto-generated header */ +#include + +/* Implementation dependencies */ +#include +#include +#include + +#include +#include // for byye-order conversions where necessary + +/* Associate the namespace */ +namespace SickToolbox { + + /** + * \brief A default constructor + */ + SickLDMessage::SickLDMessage( ) : + SickMessage< SICK_LD_MSG_HEADER_LEN, SICK_LD_MSG_PAYLOAD_MAX_LEN, SICK_LD_MSG_TRAILER_LEN >() { + + /* Initialize the object */ + Clear(); + } + + /** + * \brief Another constructor. + * \param *payload_buffer The payload for the packet as an array of bytes (including the header) + * \param payload_length The length of the payload array in bytes + */ + SickLDMessage::SickLDMessage( const uint8_t * const payload_buffer, const unsigned int payload_length ) : + SickMessage< SICK_LD_MSG_HEADER_LEN, SICK_LD_MSG_PAYLOAD_MAX_LEN, SICK_LD_MSG_TRAILER_LEN >() { + + /* Build the message object (implicit initialization) */ + BuildMessage(payload_buffer,payload_length); + } + + /** + * \brief Another constructor. + * \param *message_buffer A well-formed message to be parsed into the class' fields + */ + SickLDMessage::SickLDMessage( const uint8_t * const message_buffer ) : + SickMessage< SICK_LD_MSG_HEADER_LEN, SICK_LD_MSG_PAYLOAD_MAX_LEN, SICK_LD_MSG_TRAILER_LEN >() { + + /* Parse the message into the container (implicit initialization) */ + ParseMessage(message_buffer); + } + + /** + * \brief Constructs a Sick LD message given parameter values + * \param *payload_buffer An address of the first byte to be copied into the message's payload + * \param payload_length The number of bytes to be copied into the message buffer + */ + void SickLDMessage::BuildMessage( const uint8_t * const payload_buffer, const unsigned int payload_length ) { + + /* Call the parent method + * NOTE: The parent method resets the object and assigns _message_length, _payload_length, + * _populated and copies the payload into the message buffer at the correct position + */ + SickMessage< SICK_LD_MSG_HEADER_LEN, SICK_LD_MSG_PAYLOAD_MAX_LEN, SICK_LD_MSG_TRAILER_LEN > + ::BuildMessage(payload_buffer,payload_length); + + /* + * Set the message header! + */ + _message_buffer[0] = 0x02; // STX + _message_buffer[1] = 'U'; // User + _message_buffer[2] = 'S'; // Service + _message_buffer[3] = 'P'; // Protocol + + /* Include the payload length in the header */ + uint32_t payload_length_32 = host_to_sick_ld_byte_order((uint32_t)_payload_length); + memcpy(&_message_buffer[4],&payload_length_32,4); + + /* + * Set the message trailer (just a checksum)! + */ + _message_buffer[_message_length-1] = _computeXOR(&_message_buffer[8],(uint32_t)_payload_length); + } + + /** + * \brief Parses a sequence of bytes into a SickLDMessage object + * \param *message_buffer A well-formed message to be parsed into the class' fields + */ + void SickLDMessage::ParseMessage( const uint8_t * const message_buffer ) { + + /* Call the parent method + * NOTE: This method resets the object and assigns _populated as true + */ + SickMessage< SICK_LD_MSG_HEADER_LEN, SICK_LD_MSG_PAYLOAD_MAX_LEN, SICK_LD_MSG_TRAILER_LEN > + ::ParseMessage(message_buffer); + + /* Extract the payload length */ + uint32_t payload_length_32 = 0; + memcpy(&payload_length_32,&message_buffer[4],4); + _payload_length = (unsigned int)sick_ld_to_host_byte_order(payload_length_32); + + /* Compute the total message length */ + _message_length = MESSAGE_HEADER_LENGTH + MESSAGE_TRAILER_LENGTH + _payload_length; + + /* Copy the given packet into the buffer */ + memcpy(_message_buffer,message_buffer,_message_length); + } + + /** + * \brief Print the message contents. + */ + void SickLDMessage::Print( ) const { + + std::cout.setf(std::ios::hex,std::ios::basefield); + std::cout << "Checksum: " << (unsigned int) GetChecksum() << std::endl; + std::cout << "Service code: " << (unsigned int) GetServiceCode() << std::endl; + std::cout << "Service subcode: " << (unsigned int) GetServiceSubcode() << std::endl; + std::cout << std::flush; + + /* Call parent's print function */ + SickMessage< SICK_LD_MSG_HEADER_LEN, SICK_LD_MSG_PAYLOAD_MAX_LEN, SICK_LD_MSG_TRAILER_LEN >::Print(); + } + + /** + * \brief Compute the message checksum (single-byte XOR). + * \param data The address of the first data element in a sequence of bytes to be included in the sum + * \param length The number of byte in the data sequence + */ + uint8_t SickLDMessage::_computeXOR( const uint8_t * const data, const uint32_t length ) { + + /* Compute the XOR by summing all of the bytes */ + uint8_t checksum = 0; + for (uint32_t i = 0; i < length; i++) { + checksum ^= data[i]; // NOTE: this is equivalent to simply summing all of the bytes + } + + /* done */ + return checksum; + } + + SickLDMessage::~SickLDMessage( ) { } + +} /* namespace SickToolbox */ diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/.deps/SickLMS1xx.Plo b/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/.deps/SickLMS1xx.Plo new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/.deps/SickLMS1xx.Plo @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/.deps/SickLMS1xxBufferMonitor.Plo b/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/.deps/SickLMS1xxBufferMonitor.Plo new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/.deps/SickLMS1xxBufferMonitor.Plo @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/.deps/SickLMS1xxMessage.Plo b/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/.deps/SickLMS1xxMessage.Plo new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/.deps/SickLMS1xxMessage.Plo @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/SickLMS1xx.cc b/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/SickLMS1xx.cc new file mode 100644 index 0000000..f8a96d7 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/SickLMS1xx.cc @@ -0,0 +1,2294 @@ +/*! + * \file SickLMS1xx.cc + * \brief Implements the SickLMS1xx driver class. + * + * Code by Jason C. Derenick and Christopher R. Mansley. + * Contact jasonder(at)seas(dot)upenn(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2009, Jason C. Derenick and Christopher R. Mansley + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +/* Auto-generated header */ +#include + +/* Implementation dependencies */ +#include +#include +#include +#include +#include +#include // for socket function definitions +#include // for sockaddr_in, inet_addr, and htons +#include // for using ioctl functionality for the socket input buffer +#include // for select functionality (e.g. FD_SET, etc...) +#include // for fd data types +#include // for select timeout parameter +#include // for getting file flags +#include // for POSIX threads +#include // for parsing ip addresses +#include // for returning the results of parsed strings +#include // for timing connect() +#include + +#include +#include +#include +#include +#include + +/* Associate the namespace */ +namespace SickToolbox { + + /** + * \brief A standard constructor + * \param sick_ip_address The ip address of the Sick LD + * \param sick_tcp_port The TCP port associated w/ the Sick LD server + */ + SickLMS1xx::SickLMS1xx( const std::string sick_ip_address, const uint16_t sick_tcp_port ) : + SickLIDAR< SickLMS1xxBufferMonitor, SickLMS1xxMessage >( ), + _sick_ip_address(sick_ip_address), + _sick_tcp_port(sick_tcp_port), + _sick_scan_format(SICK_LMS_1XX_SCAN_FORMAT_UNKNOWN), + _sick_device_status(SICK_LMS_1XX_STATUS_UNKNOWN), + _sick_temp_safe(false), + _sick_streaming(false) + { + memset(&_sick_scan_config,0,sizeof(sick_lms_1xx_scan_config_t)); + } + + /** + * A standard destructor + */ + SickLMS1xx::~SickLMS1xx( ) { } + + /** + * \brief Initializes the driver and syncs it with Sick LMS 1xx unit. Uses flash params. + */ + void SickLMS1xx::Initialize( const bool disp_banner ) throw( SickIOException, SickThreadException, SickTimeoutException, SickErrorException ) { + + if (disp_banner) { + std::cout << "\t*** Attempting to initialize the Sick LMS 1xx..." << std::endl; + } + + try { + + /* Attempt to connect to the Sick LD */ + if (disp_banner) { + std::cout << "\tAttempting to connect to Sick LMS 1xx @ " << _sick_ip_address << ":" << _sick_tcp_port << std::endl; + } + _setupConnection(); + if (disp_banner) { + std::cout << "\t\tConnected to Sick LMS 1xx!" << std::endl; + } + + /* Start the buffer monitor */ + if (disp_banner) { + std::cout << "\tAttempting to start buffer monitor..." << std::endl; + } + _startListening(); + if (disp_banner) { + std::cout << "\t\tBuffer monitor started!" << std::endl; + } + + /* Ok, lets sync the driver with the Sick */ + if (disp_banner) { + std::cout << "\tSyncing driver with Sick..." << std::endl; + } + _getSickScanConfig(); + _setAuthorizedClientAccessMode(); + if (disp_banner) { + std::cout << "\t\tSuccess!" << std::endl; + _printInitFooter(); + } + + } + + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + catch(SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + catch(...) { + std::cerr << "SickLMS1xx::Initialize - Unknown exception!" << std::endl; + throw; + } + + //std::cout << "\t\tSynchronized!" << std::endl; + _sick_initialized = true; + + /* Success */ + } + + /** + * \brief Sets the Sick LMS 1xx scan frequency and resolution + * \param scan_freq Desired scan frequency (e.g. SickLMS1xx::SICK_LMS_1XX_SCAN_FREQ_50) + * \param scan_res Desired scan angular resolution (e.g. SickLMS1xx::SICK_LMS_1XX_SCAN_RES_50) + * \param write_to_eeprom Write the configuration to EEPROM + */ + void SickLMS1xx::SetSickScanFreqAndRes( const sick_lms_1xx_scan_freq_t scan_freq, + const sick_lms_1xx_scan_res_t scan_res ) throw( SickTimeoutException, SickIOException, SickErrorException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLMS1xx::SetSickScanFreqAndRes: Device NOT Initialized!!!"); + } + + try { + + /* Is the device streaming? */ + if (_sick_streaming) { + _stopStreamingMeasurements(); + } + + /* Set the desired configuration */ + _setSickScanConfig(scan_freq, + scan_res, + _sick_scan_config.sick_start_angle, + _sick_scan_config.sick_stop_angle); + + } + + /* Handle config exceptions */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::SetSickScanFreqAndRes: Unknown exception!!!" << std::endl; + throw; + } + + } + + /** + * \brief Gets the Sick LMS 1xx scan frequency + * \returns Sick LMS 1xx scan frequency {25,50} Hz + */ + sick_lms_1xx_scan_freq_t SickLMS1xx::GetSickScanFreq( ) const throw( SickIOException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLMS1xx::GetSickScanFreq: Device NOT Initialized!!!"); + } + + return IntToSickScanFreq(_convertSickFreqUnitsToHz(_sick_scan_config.sick_scan_freq)); + + } + + /** + * \brief Gets the Sick LMS 1xx scan resolution + * \returns Sick LMS 1xx scan resolution {0.25 or 0.5} deg + */ + sick_lms_1xx_scan_res_t SickLMS1xx::GetSickScanRes( ) const throw( SickIOException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLMS1xx::GetSickScanRes: Device NOT Initialized!!!"); + } + + return DoubleToSickScanRes(_convertSickAngleUnitsToDegs(_sick_scan_config.sick_scan_res)); + + } + + /** + * \brief Gets the Sick LMS 1xx scan area start angle [-45,270] deg + * \returns Sick LMS 1xx start angle as double + */ + double SickLMS1xx::GetSickStartAngle( ) const throw( SickIOException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLMS1xx::GetSickStartAngle: Device NOT Initialized!!!"); + } + + return _convertSickAngleUnitsToDegs(_sick_scan_config.sick_start_angle); + + } + + /** + * \brief Gets the Sick LMS 1xx scan area start angle [-45,270] deg + * \returns Sick LMS 1xx start angle as double + */ + double SickLMS1xx::GetSickStopAngle( ) const throw( SickIOException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLMS1xx::GetSickStopAngle: Device NOT Initialized!!!"); + } + + return _convertSickAngleUnitsToDegs(_sick_scan_config.sick_stop_angle); + + } + + /** + * Set device to output only range values + */ + void SickLMS1xx::SetSickScanDataFormat( const sick_lms_1xx_scan_format_t scan_format ) throw( SickTimeoutException, SickIOException, SickThreadException, SickErrorException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLMS1xx::SetSickScanDataFormat: Device NOT Initialized!!!"); + } + + /* If scan data format matches current format ignore it (perhaps a warning is in order?) */ + if (scan_format == _sick_scan_format) { + return; + } + + try { + + /* Is the device streaming? */ + if (_sick_streaming ) { + _stopStreamingMeasurements(); + } + + std::cout << "\t*** Setting scan format " << _sickScanDataFormatToString(scan_format) << "..." << std::endl; + + /* Set the desired data format! */ + _setSickScanDataFormat(scan_format); + + std::cout << "\t\tSuccess!" << std::endl; + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + catch (...) { + std::cerr << "SickLMS1xx::SetSickScanDataFormat: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + + } + + /** + * \brief Acquire multi-pulse sick range measurements + * \param range_1_vals A buffer to hold the range measurements + * \param range_2_vals A buffer to hold the second pulse range measurements + * \param refelct_1_vals A buffer to hold the frist pulse reflectivity + * \param reflect_2_vals A buffer to hold the second pulse reflectivity + */ + void SickLMS1xx::GetSickMeasurements( unsigned int * const range_1_vals, + unsigned int * const range_2_vals, + unsigned int * const reflect_1_vals, + unsigned int * const reflect_2_vals, + unsigned int & num_measurements, + unsigned int * const dev_status ) throw ( SickIOException, SickConfigException, SickTimeoutException ) { + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLMS1xx::GetSickMeasurements: Device NOT Initialized!!!"); + } + + try { + + /* Is the device already streaming? */ + if (!_sick_streaming) { + _requestDataStream(); + } + + } + + /* Handle config exceptions */ + catch (SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + catch (...) { + std::cerr << "SickLMS1xx::GetSickMeasurements: Unknown exception!!!" << std::endl; + throw; + } + + /* Allocate receive message */ + SickLMS1xxMessage recv_message; + + try { + + /* Grab the next message from the stream */ + _recvMessage(recv_message); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + catch (...) { + std::cerr << "SickLMS1xx::GetSickMeasurements: Unknown exception!!!" << std::endl; + throw; + } + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLMS1xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH+1] = {0}; + + recv_message.GetPayloadAsCStr((char *)payload_buffer); + + char * payload_str = NULL; + unsigned int null_int = 0; + + /* + * Acquire status + */ + if (dev_status != NULL) { + + payload_str = (char *)&payload_buffer[16]; + for (unsigned int i = 0; i < 3; i++) { + payload_str = _convertNextTokenToUInt(payload_str,null_int); + } + + /* Grab the contaimination value */ + _convertNextTokenToUInt(payload_str,*dev_status); + + } + + /* + * Process DIST1 + */ + unsigned int num_dist_1_vals = 0; + unsigned int num_dist_2_vals = 0; + unsigned int num_rssi_1_vals = 0; + unsigned int num_rssi_2_vals = 0; + + /* Locate DIST1 Section */ + if (range_1_vals != NULL) { + + const char * substr_dist_1 = "DIST1"; + unsigned int substr_dist_1_pos = 0; + if (!_findSubString((char *)payload_buffer,substr_dist_1,recv_message.GetPayloadLength()+1,5,substr_dist_1_pos)) { + throw SickIOException("SickLMS1xx::GetSickMeasurements: _findSubString() failed!"); + } + + /* Extract Num DIST1 Values */ + payload_str = (char *)&payload_buffer[substr_dist_1_pos+6]; + for (unsigned int i = 0; i < 4; i++) { + payload_str = _convertNextTokenToUInt(payload_str,null_int); + } + + payload_str = _convertNextTokenToUInt(payload_str,num_dist_1_vals); + + /* Grab the DIST1 values */ + for (unsigned int i = 0; i < num_dist_1_vals; i++) { + payload_str = _convertNextTokenToUInt(payload_str,range_1_vals[i]); + } + + } + + /* + * Process DIST2 + */ + + /* Locate DIST2 Section */ + if (range_2_vals != NULL) { + + const char * substr_dist_2 = "DIST2"; + unsigned int substr_dist_2_pos = 0; + if (_findSubString((char *)payload_buffer,substr_dist_2,recv_message.GetPayloadLength()+1,5,substr_dist_2_pos)) { + + /* Extract Num DIST2 Values */ + payload_str = (char *)&payload_buffer[substr_dist_2_pos+6]; + for (unsigned int i = 0; i < 4; i++) { + payload_str = _convertNextTokenToUInt(payload_str,null_int); + } + + payload_str = _convertNextTokenToUInt(payload_str,num_dist_2_vals); + + /* Acquire the DIST2 values */ + for (unsigned int i = 0; i < num_dist_2_vals; i++) { + payload_str = _convertNextTokenToUInt(payload_str,range_2_vals[i]); + } + } + else { + std::cerr << "SickLMS1xx::GetSickMeasurements: WARNING! It seems you are expecting double-pulse range values, which are not being streamed! "; + std::cerr << "Use SetSickScanDataFormat to configure the LMS 1xx to stream these values - or - set the corresponding buffer input to NULL to avoid this warning." << std::endl; + } + + } + + /* + * Process RSSI1 + */ + + if (reflect_1_vals != NULL) { + + /* Locate RSSI1 Section */ + const char * substr_rssi_1 = "RSSI1"; + unsigned int substr_rssi_1_pos = 0; + if (_findSubString((char *)payload_buffer,substr_rssi_1,recv_message.GetPayloadLength()+1,5,substr_rssi_1_pos)) { + + /* Extract Num RSSI1 Values */ + payload_str = (char *)&payload_buffer[substr_rssi_1_pos+6]; + for (unsigned int i = 0; i < 4; i++) { + payload_str = _convertNextTokenToUInt(payload_str,null_int); + } + + payload_str = _convertNextTokenToUInt(payload_str,num_rssi_1_vals); + + /* Grab the RSSI1 values */ + for (unsigned int i = 0; i < num_rssi_1_vals; i++) { + payload_str = _convertNextTokenToUInt(payload_str,reflect_1_vals[i]); + } + } + else { + std::cerr << "SickLMS1xx::GetSickMeasurements: WARNING! It seems you are expecting single-pulse reflectivity values, which are not being streamed! "; + std::cerr << "Use SetSickScanDataFormat to configure the LMS 1xx to stream these values - or - set the corresponding buffer input to NULL to avoid this warning." << std::endl; + } + + } + + /* + * Process RSSI2 + */ + + if (reflect_2_vals != NULL) { + + /* Locate RSSI2 Section */ + const char * substr_rssi_2 = "RSSI2"; + unsigned int substr_rssi_2_pos = 0; + if (_findSubString((char *)payload_buffer,substr_rssi_2,recv_message.GetPayloadLength()+1,5,substr_rssi_2_pos)) { + + /* Extract Num RSSI1 Values */ + payload_str = (char *)&payload_buffer[substr_rssi_2_pos+6]; + for (unsigned int i = 0; i < 4; i++) { + payload_str = _convertNextTokenToUInt(payload_str,null_int); + } + + payload_str = _convertNextTokenToUInt(payload_str,num_rssi_2_vals); + + /* Grab the RSSI1 values */ + for (unsigned int i = 0; i < num_rssi_2_vals; i++) { + payload_str = _convertNextTokenToUInt(payload_str,reflect_2_vals[i]); + } + } + else { + std::cerr << "SickLMS1xx::GetSickMeasurements: WARNING! It seems you are expecting double-pulse reflectivity values, which are not being streamed! "; + std::cerr << "Use SetSickScanDataFormat to configure the LMS 1xx to stream these values - or - set the corresponding buffer input to NULL to avoid this warning." << std::endl; + } + + } + + /* Assign number of measurements */ + num_measurements = num_dist_1_vals; + + /* Success! */ + + } + + /** + * \brief Tear down the connection between the host and the Sick LD + */ + void SickLMS1xx::Uninitialize( const bool disp_banner ) throw( SickIOException, SickTimeoutException, SickErrorException, SickThreadException ){ + + /* Ensure the device has been initialized */ + if (!_sick_initialized) { + throw SickIOException("SickLMS1xx::Uninitialize: Device NOT Initialized!!!"); + } + + if (disp_banner) { + std::cout << std::endl << "\t*** Attempting to uninitialize the Sick LMS 1xx..." << std::endl; + } + + /* If necessary, tell the Sick LD to stop streaming data */ + try { + + /* Is the device streaming? */ + if (_sick_streaming) { + _stopStreamingMeasurements(disp_banner); + } + + /* Attempt to cancel the buffer monitor */ + if (disp_banner) { + std::cout << "\tAttempting to cancel buffer monitor..." << std::endl; + } + _stopListening(); + if (disp_banner) { + std::cout << "\t\tBuffer monitor canceled!" << std::endl; + } + + /* Attempt to close the tcp connection */ + if (disp_banner) { + std::cout << "\tClosing connection to Sick LMS 1xx..." << std::endl; + } + _teardownConnection(); + + if (disp_banner) { + std::cout << "\t\tConnection closed!" << std::endl; + std::cout << "\t*** Uninit. complete - Sick LMS 1xx is now offline!" << std::endl; + } + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle I/O exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + /* Handle a returned error code */ + catch (SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS::Uninitialize: Unknown exception!!!" << std::endl; + throw; + } + + /* Mark the device as uninitialized */ + _sick_initialized = false; + + /* Success! */ + } + + /** + * \brief Convert integer to corresponding sick_lms_1xx_scan_freq_t + */ + SickLMS1xx::sick_lms_1xx_scan_freq_t SickLMS1xx::IntToSickScanFreq( const int scan_freq ) const { + + if (scan_freq == 25) { + return SICK_LMS_1XX_SCAN_FREQ_25; + } + else if (scan_freq == 50) { + return SICK_LMS_1XX_SCAN_FREQ_50; + } + + return SICK_LMS_1XX_SCAN_FREQ_UNKNOWN; + + } + + /** + * \brief Convert sick_lms_1xx_scan_freq_t to corresponding integer + */ + int SickLMS1xx::SickScanFreqToInt( const sick_lms_1xx_scan_freq_t scan_freq ) const { + + switch(scan_freq) { + case SICK_LMS_1XX_SCAN_FREQ_25: + return 25; + case SICK_LMS_1XX_SCAN_FREQ_50: + return 50; + default: + return -1; + } + + } + + /** + * \brief Convert double to corresponding sick_lms_1xx_scan_res_t + */ + SickLMS1xx::sick_lms_1xx_scan_res_t SickLMS1xx::DoubleToSickScanRes( const double scan_res ) const { + + if (scan_res == 0.25) { + return SICK_LMS_1XX_SCAN_RES_25; + } + else if (scan_res == 0.50) { + return SICK_LMS_1XX_SCAN_RES_50; + } + + return SICK_LMS_1XX_SCAN_RES_UNKNOWN; + + } + + /** + * \brief Convert sick_lms_1xx_scan_res_t to corresponding double + */ + double SickLMS1xx::SickScanResToDouble( const sick_lms_1xx_scan_res_t scan_res ) const { + + switch(scan_res) { + case SICK_LMS_1XX_SCAN_RES_25: + return 0.25; + case SICK_LMS_1XX_SCAN_RES_50: + return 0.50; + default: + return -1; + } + + } + + /** + * \brief Establish a TCP connection to the unit + */ + void SickLMS1xx::_setupConnection( ) throw( SickIOException, SickTimeoutException ) { + + /* Create the TCP socket */ + if ((_sick_fd = socket(PF_INET,SOCK_STREAM,IPPROTO_TCP)) < 0) { + throw SickIOException("SickLMS1xx::_setupConnection: socket() failed!"); + } + + /* Initialize the buffer */ + memset(&_sick_inet_address_info,0,sizeof(struct sockaddr_in)); + + /* Setup the Sick LD inet address structure */ + _sick_inet_address_info.sin_family = AF_INET; // Internet protocol address family + _sick_inet_address_info.sin_port = htons(_sick_tcp_port); // TCP port number + _sick_inet_address_info.sin_addr.s_addr = inet_addr(_sick_ip_address.c_str()); // Convert ip string to numerical address + + try { + + /* Set to non-blocking so we can time connect */ + _setNonBlockingIO(); + + /* Try to connect to the Sick LD */ + int conn_return; + if ((conn_return = connect(_sick_fd,(struct sockaddr *)&_sick_inet_address_info,sizeof(struct sockaddr_in))) < 0) { + + /* Check whether it is b/c it would block */ + if (errno != EINPROGRESS) { + throw SickIOException("SickLMS1xx::_setupConnection: connect() failed!"); + } + + /* Use select to wait on the socket */ + int valid_opt = 0; + int num_active_files = 0; + struct timeval timeout_val; // This structure will be used for setting our timeout values + fd_set file_desc_set; // File descriptor set for monitoring I/O + + /* Initialize and set the file descriptor set for select */ + FD_ZERO(&file_desc_set); + FD_SET(_sick_fd,&file_desc_set); + + /* Setup the timeout structure */ + memset(&timeout_val,0,sizeof(timeout_val)); // Initialize the buffer + timeout_val.tv_usec = DEFAULT_SICK_LMS_1XX_CONNECT_TIMEOUT; // Wait for specified time before throwing a timeout + + /* Wait for the OS to tell us that the connection is established! */ + num_active_files = select(getdtablesize(),0,&file_desc_set,0,&timeout_val); + + /* Figure out what to do based on the output of select */ + if (num_active_files > 0) { + + /* This is just a sanity check */ + if (!FD_ISSET(_sick_fd,&file_desc_set)) { + throw SickIOException("SickLMS1xx::_setupConnection: Unexpected file descriptor!"); + } + + /* Check for any errors on the socket - just to be sure */ + socklen_t len = sizeof(int); + if (getsockopt(_sick_fd,SOL_SOCKET,SO_ERROR,(void*)(&valid_opt),&len) < 0) { + throw SickIOException("SickLMS1xx::_setupConnection: getsockopt() failed!"); + } + + /* Check whether the opt value indicates error */ + if (valid_opt) { + throw SickIOException("SickLMS1xx::_setupConnection: socket error on connect()!"); + } + + } + else if (num_active_files == 0) { + + /* A timeout has occurred! */ + throw SickTimeoutException("SickLMS1xx::_setupConnection: select() timeout!"); + + } + else { + + /* An error has occurred! */ + throw SickIOException("SickLMS1xx::_setupConnection: select() failed!"); + + } + + } + + /* Restore blocking IO */ + _setBlockingIO(); + + } + + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + catch(...) { + std::cerr << "SickLMS1xx::_setupConnection - Unknown exception occurred!" << std::endl; + throw; + } + + /* Success */ + } + + /** + * \brief Re-initializes the Sick LMS 1xx + */ + void SickLMS1xx::_reinitialize( ) throw( SickIOException, SickThreadException, SickTimeoutException, SickErrorException ) { + + try { + + //std::cout << "\t*** Reinitializing Sick LMS 1xx..." << std::endl; + + /* Uninitialize the device */ + Uninitialize(false); + + /* Initialize the device */ + Initialize(false); + + //std::cout << "\t\tSuccess!" << std::endl; + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle a timeout! */ + catch (SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle a timeout! */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + catch (...) { + std::cerr << "SickLMS1xx::_reinitialize: Unknown exception!!!" << std::endl; + throw; + } + + } + + /** + * \brief Teardown TCP connection to Sick LMS 1xx + */ + void SickLMS1xx::_teardownConnection( ) throw( SickIOException ) { + + /* Close the socket! */ + if (close(_sick_fd) < 0) { + throw SickIOException("SickLMS1xx::_teardownConnection: close() failed!"); + } + + } + + /** + * \brief Get the status of the Sick LMS 1xx + */ + void SickLMS1xx::_updateSickStatus( ) throw( SickTimeoutException, SickIOException ) { + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLMS1xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the command type */ + payload_buffer[0] = 's'; + payload_buffer[1] = 'R'; + payload_buffer[2] = 'N'; + + payload_buffer[3] = ' '; + + /* Set the command */ + payload_buffer[4] = 'S'; + payload_buffer[5] = 'T'; + payload_buffer[6] = 'l'; + payload_buffer[7] = 'm'; + payload_buffer[8] = 's'; + + /* Construct command message */ + SickLMS1xxMessage send_message(payload_buffer,9); + + /* Setup container for recv message */ + SickLMS1xxMessage recv_message; + + /* Send message and get reply using parent's method */ + try { + + _sendMessageAndGetReply(send_message, recv_message, "sRA", "STlms"); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::_sendMessageAndGetReply: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the buffer (not necessary, but its better to do so just in case) */ + memset(payload_buffer,0,9); + + /* Extract the message payload */ + recv_message.GetPayload(payload_buffer); + + _sick_device_status = _intToSickStatus(atoi((char *)&payload_buffer[10])); + _sick_temp_safe = (bool)atoi((char *)&payload_buffer[12]); + + /* Success */ + + } + + /** + * \brief Get the scan configuration of the Sick LMS 1xx + */ + void SickLMS1xx::_getSickScanConfig( ) throw( SickTimeoutException, SickIOException ) { + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLMS1xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the command type */ + payload_buffer[0] = 's'; + payload_buffer[1] = 'R'; + payload_buffer[2] = 'N'; + + payload_buffer[3] = ' '; + + /* Set the command */ + payload_buffer[4] = 'L'; + payload_buffer[5] = 'M'; + payload_buffer[6] = 'P'; + payload_buffer[7] = 's'; + payload_buffer[8] = 'c'; + payload_buffer[9] = 'a'; + payload_buffer[10] = 'n'; + payload_buffer[11] = 'c'; + payload_buffer[12] = 'f'; + payload_buffer[13] = 'g'; + + /* Construct command message */ + SickLMS1xxMessage send_message(payload_buffer,14); + + /* Setup container for recv message */ + SickLMS1xxMessage recv_message; + + /* Send message and get reply using parent's method */ + try { + + _sendMessageAndGetReply(send_message, recv_message, "sRA", "LMPscancfg"); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::_sendMessageAndGetReply: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the buffer (not necessary, but its better to do so just in case) */ + memset(payload_buffer,0,14); + + /* Extract the message payload */ + recv_message.GetPayloadAsCStr((char *)payload_buffer); + + /* Utility variables */ + uint32_t scan_freq = 0, scan_res = 0; + uint32_t sick_start_angle = 0, sick_stop_angle = 0; + + /* + * Grab the scanning frequency + */ + const char * token = NULL; + if ((token = strtok((char *)&payload_buffer[15]," ")) == NULL) { + throw SickIOException("SickLMS1xx::_getSickConfig: strtok() failed!"); + } + + if (sscanf(token,"%x",&scan_freq) == EOF) { + throw SickIOException("SickLMS1xx::_getSickConfig: sscanf() failed!"); + } + + sick_lms_1xx_scan_freq_t sick_scan_freq; + sick_scan_freq = (sick_lms_1xx_scan_freq_t)sick_lms_1xx_to_host_byte_order(scan_freq); + + /* Ignore the number of segments value (its always 1 for the LMS 1xx) */ + if ((token = strtok(NULL," ")) == NULL) { + throw SickIOException("SickLMS1xx::_getSickConfig: strtok() failed!"); + } + + /* + * Grab the angular resolution + */ + if ((token = strtok(NULL," ")) == NULL) { + throw SickIOException("SickLMS1xx::_getSickConfig: strtok() failed!"); + } + + if (sscanf(token,"%x",&scan_res) == EOF) { + throw SickIOException("SickLMS1xx::_getSickConfig: sscanf() failed!"); + } + + sick_lms_1xx_scan_res_t sick_scan_res; + sick_scan_res = (sick_lms_1xx_scan_res_t)sick_lms_1xx_to_host_byte_order(scan_res); + + /* + * Grab the start angle + */ + if ((token = strtok(NULL," ")) == NULL) { + throw SickIOException("SickLMS1xx::_getSickConfig: strtok() failed!"); + } + + if (sscanf(token,"%x",&sick_start_angle) == EOF) { + throw SickIOException("SickLMS1xx::_getSickConfig: sscanf() failed!"); + } + + sick_start_angle = sick_lms_1xx_to_host_byte_order(sick_start_angle); + + /* + * Grab the stop angle + */ + if ((token = strtok(NULL," ")) == NULL) { + throw SickIOException("SickLMS1xx::_getSickConfig: strtok() failed!"); + } + + if (sscanf(token,"%x",&sick_stop_angle) == EOF) { + throw SickIOException("SickLMS1xx::_getSickConfig: sscanf() failed!"); + } + + sick_stop_angle = sick_lms_1xx_to_host_byte_order(sick_stop_angle); + + /* + * Assign the config values! + */ + _sick_scan_config.sick_scan_freq = sick_scan_freq; + _sick_scan_config.sick_scan_res = sick_scan_res; + _sick_scan_config.sick_start_angle = sick_start_angle; + _sick_scan_config.sick_stop_angle = sick_stop_angle; + + /* Success */ + + } + + /** + * \brief Set the Sick LMS 1xx scan configuration (volatile, does not write to EEPROM) + * \param scan_freq Desired scan frequency (Either SickLMS1xx::SICK_LMS_1XX_SCAN_FREQ_25 or SickLMS1xx::SICK_LMS_1XX_SCAN_FREQ_50) + * \param scan_res Desired angular resolution (SickLMS1xx::SICK_LMS_1XX_SCAN_RES_25 or SickLMS1xx::SICK_LMS_1XX_SCAN_RES_50) + * \param start_angle Desired start angle in (1/10000) deg (-450000 to 2250000) + * \param stop_angle Desired stop angle in (1/10000) deg (-450000 to 2250000) + * \param write_to_eeprom Indicates whether the value should be written to EEPROM + */ + void SickLMS1xx::_setSickScanConfig( const sick_lms_1xx_scan_freq_t scan_freq, + const sick_lms_1xx_scan_res_t scan_res, + const int start_angle, const int stop_angle ) throw( SickTimeoutException, SickIOException, SickErrorException ) { + + /* Verify valid inputs */ + if (!_validScanArea(start_angle, stop_angle)) { + throw SickConfigException("SickLMS1xx::_setSickScanConfig - Invalid Sick LMS 1xx Scan Area!"); + } + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLMS1xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + std::cout << std::endl << "\t*** Attempting to configure device..." << std::endl; + + /* Set the command type */ + payload_buffer[0] = 's'; + payload_buffer[1] = 'M'; + payload_buffer[2] = 'N'; + + payload_buffer[3] = ' '; + + /* Set the command */ + payload_buffer[4] = 'm'; + payload_buffer[5] = 'L'; + payload_buffer[6] = 'M'; + payload_buffer[7] = 'P'; + payload_buffer[8] = 's'; + payload_buffer[9] = 'e'; + payload_buffer[10] = 't'; + payload_buffer[11] = 's'; + payload_buffer[12] = 'c'; + payload_buffer[13] = 'a'; + payload_buffer[14] = 'n'; + payload_buffer[15] = 'c'; + payload_buffer[16] = 'f'; + payload_buffer[17] = 'g'; + + payload_buffer[18] = ' '; + + /* Desired scanning frequency */ + std::string freq_str = int_to_str((int)scan_freq); + + payload_buffer[19] = '+'; + + for (int i = 0; i < 4; i++) { + payload_buffer[20+i] = (uint8_t)((freq_str.c_str())[i]); + } + + payload_buffer[24] = ' '; + + /* Desired number of segments (always 1) */ + payload_buffer[25] = '+'; + payload_buffer[26] = '1'; + + payload_buffer[27] = ' '; + + /* Desired angular resolution */ + std::string res_str = int_to_str((int)scan_res); + + payload_buffer[28] = '+'; + + for (int i = 0; i < 4; i++) { + payload_buffer[29+i] = (uint8_t)((res_str.c_str())[i]); + } + + payload_buffer[33] = ' '; + + /* Desired starting angle */ + std::string start_angle_str = int_to_str(start_angle); + + unsigned int idx = 34; + if (start_angle >= 0) { + payload_buffer[idx] = '+'; + idx++; + } + + for (int i = 0; i < start_angle_str.length(); idx++, i++) { + payload_buffer[idx] = (uint8_t)(start_angle_str.c_str())[i]; + } + + payload_buffer[idx] = ' '; + idx++; + + /* Desired stopping angle */ + std::string stop_angle_str = int_to_str(stop_angle); + + if (stop_angle >= 0) { + payload_buffer[idx] = '+'; + idx++; + } + + for (int i = 0; i < stop_angle_str.length(); idx++, i++) { + payload_buffer[idx] = (uint8_t)(stop_angle_str.c_str())[i]; + } + + /* Construct command message */ + SickLMS1xxMessage send_message(payload_buffer,idx); + + /* Setup container for recv message */ + SickLMS1xxMessage recv_message; + + try { + + /* Send message and get reply */ + _sendMessageAndGetReply(send_message, recv_message, "sAN", "mLMPsetscancfg"); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::_sendMessageAndGetReply: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the buffer (not necessary, but its better to do so just in case) */ + memset(payload_buffer,0,SickLMS1xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH); + + /* Extract the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Check if it worked... */ + if (payload_buffer[19] != '0') { + throw SickErrorException("SickLMS1xx::_setSickScanConfig: " + _intToSickConfigErrorStr(atoi((char *)&payload_buffer[19]))); + } + + std::cout << "\t\tDevice configured!" << std::endl << std::endl; + + /* Update the scan configuration! */ + try { + + _getSickScanConfig(); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::_setSickScanConfig: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + _printSickScanConfig(); + + } + + + /** + * \brief Login as an authorized client + */ + void SickLMS1xx::_setAuthorizedClientAccessMode() throw( SickTimeoutException, SickErrorException, SickIOException ) { + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLMS1xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the command type */ + payload_buffer[0] = 's'; + payload_buffer[1] = 'M'; + payload_buffer[2] = 'N'; + + payload_buffer[3] = ' '; + + /* Set the command */ + payload_buffer[4] = 'S'; + payload_buffer[5] = 'e'; + payload_buffer[6] = 't'; + payload_buffer[7] = 'A'; + payload_buffer[8] = 'c'; + payload_buffer[9] = 'c'; + payload_buffer[10] = 'e'; + payload_buffer[11] = 's'; + payload_buffer[12] = 's'; + payload_buffer[13] = 'M'; + payload_buffer[14] = 'o'; + payload_buffer[15] = 'd'; + payload_buffer[16] = 'e'; + + payload_buffer[17] = ' '; + + /* Set as authorized client */ + payload_buffer[18] = '0'; + payload_buffer[19] = '3'; + + payload_buffer[20] = ' '; + + /* Encoded value for client */ + payload_buffer[21] = 'F'; + payload_buffer[22] = '4'; + payload_buffer[23] = '7'; + payload_buffer[24] = '2'; + payload_buffer[25] = '4'; + payload_buffer[26] = '7'; + payload_buffer[27] = '4'; + payload_buffer[28] = '4'; + + /* Construct command message */ + SickLMS1xxMessage send_message(payload_buffer,29); + + /* Setup container for recv message */ + SickLMS1xxMessage recv_message; + + /* Send message and get reply using parent's method */ + try { + + _sendMessageAndGetReply(send_message, recv_message, "sAN", "SetAccessMode"); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::_setAuthorizedClientAccessMode: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the buffer (not necessary, but its better to do so just in case) */ + memset(payload_buffer,0,29); + + /* Extract the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Check Response */ + if (payload_buffer[18] != '1') { + throw SickErrorException("SickLMS1xx::_setAuthorizedClientAccessMode: Setting Access Mode Failed!"); + } + + /* Success! Woohoo! */ + + } + + /** + * \brief Login as an authorized client + */ + void SickLMS1xx::_writeToEEPROM( ) throw( SickTimeoutException, SickIOException ) { + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLMS1xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the command type */ + payload_buffer[0] = 's'; + payload_buffer[1] = 'M'; + payload_buffer[2] = 'N'; + + payload_buffer[3] = ' '; + + /* Set the command */ + payload_buffer[4] = 'm'; + payload_buffer[5] = 'E'; + payload_buffer[6] = 'E'; + payload_buffer[7] = 'w'; + payload_buffer[8] = 'r'; + payload_buffer[9] = 'i'; + payload_buffer[10] = 't'; + payload_buffer[11] = 'e'; + payload_buffer[12] = 'a'; + payload_buffer[13] = 'l'; + payload_buffer[14] = 'l'; + + /* Construct command message */ + SickLMS1xxMessage send_message(payload_buffer,15); + + /* Setup container for recv message */ + SickLMS1xxMessage recv_message; + + try { + + /* Send message and get reply */ + _sendMessageAndGetReply(send_message, recv_message, "sAN", "mEEwriteall"); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::_writeToEEPROM: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the buffer (not necessary, but its better to do so just in case) */ + memset(payload_buffer,0,15); + + /* Extract the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Check Response */ + if (payload_buffer[13] != '1') { + throw SickIOException("SickLMS1xx::_writeToEEPROM: Failed to Write Data!"); + } + + /* Success! Woohoo! */ + + } + + /** + * \brief Tell the device to start measuring + */ + void SickLMS1xx::_startMeasuring( ) throw( SickTimeoutException, SickIOException ) { + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLMS1xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the command type */ + payload_buffer[0] = 's'; + payload_buffer[1] = 'M'; + payload_buffer[2] = 'N'; + payload_buffer[3] = ' '; + + /* Set the command */ + payload_buffer[4] = 'L'; + payload_buffer[5] = 'M'; + payload_buffer[6] = 'C'; + payload_buffer[7] = 's'; + payload_buffer[8] = 't'; + payload_buffer[9] = 'a'; + payload_buffer[10] = 'r'; + payload_buffer[11] = 't'; + payload_buffer[12] = 'm'; + payload_buffer[13] = 'e'; + payload_buffer[14] = 'a'; + payload_buffer[15] = 's'; + + /* Construct command message */ + SickLMS1xxMessage send_message(payload_buffer,16); + + /* Setup container for recv message */ + SickLMS1xxMessage recv_message; + + try { + + /* Send message and get reply */ + _sendMessageAndGetReply(send_message, recv_message, "sAN", "LMCstartmeas"); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::_startMeasuring: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the buffer (not necessary, but its better to do so just in case) */ + memset(payload_buffer,0,16); + + /* Extract the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Check if it worked... */ + if (payload_buffer[17] != '0') { + throw SickConfigException("SickLMS1xx::_startMeasuring: Unable to start measuring!"); + } + + } + + /** + * \brief Tell the device to start measuring + */ + void SickLMS1xx::_stopMeasuring( ) throw( SickTimeoutException, SickIOException ) { + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLMS1xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the command type */ + payload_buffer[0] = 's'; + payload_buffer[1] = 'M'; + payload_buffer[2] = 'N'; + payload_buffer[3] = ' '; + + /* Set the command */ + payload_buffer[4] = 'L'; + payload_buffer[5] = 'M'; + payload_buffer[6] = 'C'; + payload_buffer[7] = 's'; + payload_buffer[8] = 't'; + payload_buffer[9] = 'o'; + payload_buffer[10] = 'p'; + payload_buffer[11] = 'm'; + payload_buffer[12] = 'e'; + payload_buffer[13] = 'a'; + payload_buffer[14] = 's'; + + /* Construct command message */ + SickLMS1xxMessage send_message(payload_buffer,15); + + /* Setup container for recv message */ + SickLMS1xxMessage recv_message; + + try { + + /* Send message and get reply */ + _sendMessageAndGetReply(send_message, recv_message, "sAN", "LMCstopmeas"); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::_stopMeasuring: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the buffer (not necessary, but its better to do so just in case) */ + memset(payload_buffer,0,15); + + /* Extract the message payload */ + recv_message.GetPayload(payload_buffer); + + /* Check if it worked... */ + if (payload_buffer[16] != '0') { + throw SickConfigException("SickLMS1xx::_stopMeasuring: Unable to start measuring!"); + } + + } + + /** + * \brief Request a data data stream type + * \param dist_opt Desired distance returns (single-pulse or multi-pulse) + * \param reflect_opt Desired reflectivity returns (none, 8-bit or 16-bit) + */ + void SickLMS1xx::_requestDataStream( ) throw( SickTimeoutException, SickConfigException, SickIOException ) { + + std::cout << std::endl << "\tRequesting data stream..." << std::endl; + + try { + + /* Wait for device to be measuring */ + _checkForMeasuringStatus(); + + /* Request the data stream... */ + _startStreamingMeasurements(); + + } + + /* Handle config exceptions */ + catch (SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + catch (...) { + std::cerr << "SickLMS1xx::SetSickScanArea: Unknown exception!!!" << std::endl; + throw; + } + + std::cout << "\t\tStream started!" << std::endl; + + } + + /* + * \brief Start Streaming Values + */ + void SickLMS1xx::_startStreamingMeasurements( ) throw( SickTimeoutException, SickIOException ) { + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLMS1xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the command type */ + payload_buffer[0] = 's'; + payload_buffer[1] = 'E'; + payload_buffer[2] = 'N'; + payload_buffer[3] = ' '; + + /* Set the command */ + payload_buffer[4] = 'L'; + payload_buffer[5] = 'M'; + payload_buffer[6] = 'D'; + payload_buffer[7] = 's'; + payload_buffer[8] = 'c'; + payload_buffer[9] = 'a'; + payload_buffer[10] = 'n'; + payload_buffer[11] = 'd'; + payload_buffer[12] = 'a'; + payload_buffer[13] = 't'; + payload_buffer[14] = 'a'; + payload_buffer[15] = ' '; + + /* Start streaming! */ + payload_buffer[16] = '1'; + + /* Construct command message */ + SickLMS1xxMessage send_message(payload_buffer,17); + + /* Setup container for recv message */ + SickLMS1xxMessage recv_message; + + try { + + /* Send message and get reply */ + _sendMessageAndGetReply(send_message, recv_message, "sSN", "LMDscandata"); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::_startStreamingMeasurements: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + _sick_streaming = true; + + } + + /** + * \brief Stop Measurment Stream + */ + void SickLMS1xx::_stopStreamingMeasurements( const bool disp_banner ) throw( SickTimeoutException, SickIOException ) { + + if (disp_banner) { + std::cout << "\tStopping data stream..." << std::endl; + } + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLMS1xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the command type */ + payload_buffer[0] = 's'; + payload_buffer[1] = 'E'; + payload_buffer[2] = 'N'; + payload_buffer[3] = ' '; + + /* Set the command */ + payload_buffer[4] = 'L'; + payload_buffer[5] = 'M'; + payload_buffer[6] = 'D'; + payload_buffer[7] = 's'; + payload_buffer[8] = 'c'; + payload_buffer[9] = 'a'; + payload_buffer[10] = 'n'; + payload_buffer[11] = 'd'; + payload_buffer[12] = 'a'; + payload_buffer[13] = 't'; + payload_buffer[14] = 'a'; + payload_buffer[15] = ' '; + + /* Start streaming! */ + payload_buffer[16] = '0'; + + /* Construct command message */ + SickLMS1xxMessage send_message(payload_buffer,17); + + /* Setup container for recv message */ + SickLMS1xxMessage recv_message; + + try { + + /* Send message and get reply */ + _sendMessage(send_message); + + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::_stopStreamingMeasurements: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + if (disp_banner) { + std::cout << "\t\tStream stopped!" << std::endl; + } + + _sick_streaming = false; + + } + + /** + * \brief Attempts to set and waits until device has in measuring status + * \param timeout_value Timeout value in usecs + */ + void SickLMS1xx::_checkForMeasuringStatus( unsigned int timeout_value ) throw( SickTimeoutException, SickIOException ) { + + /* Timeval structs for handling timeouts */ + struct timeval beg_time, end_time; + + /* Acquire the elapsed time since epoch */ + gettimeofday(&beg_time,NULL); + + /* Get device status */ + _updateSickStatus( ); + + /* Check the shared object */ + bool first_pass = true; + while( _sick_device_status != SICK_LMS_1XX_STATUS_READY_FOR_MEASUREMENT ) { + + if (first_pass) { + + try { + + /* Tell the device to start measuring ! */ + _startMeasuring(); + first_pass = false; + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::_checkForMeasuringStatus: Unknown exception!!!" << std::endl; + throw; + } + + } + + /* Sleep a little bit */ + usleep(1000); + + /* Check whether the allowed time has expired */ + gettimeofday(&end_time,NULL); + if (_computeElapsedTime(beg_time,end_time) > timeout_value) { + throw SickTimeoutException("SickLMS1xx::_checkForMeasuringStatus: Timeout occurred!"); + } + + /* Grab the latest device status */ + _updateSickStatus(); + + } + + } + + /** + * Set device to output only range values + */ + void SickLMS1xx::_setSickScanDataFormat( const sick_lms_1xx_scan_format_t scan_format ) throw( SickTimeoutException, SickIOException, SickThreadException, SickErrorException ) { + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLMS1xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the command type */ + payload_buffer[0] = 's'; + payload_buffer[1] = 'W'; + payload_buffer[2] = 'N'; + payload_buffer[3] = ' '; + + /* Set the command */ + payload_buffer[4] = 'L'; + payload_buffer[5] = 'M'; + payload_buffer[6] = 'D'; + payload_buffer[7] = 's'; + payload_buffer[8] = 'c'; + payload_buffer[9] = 'a'; + payload_buffer[10] = 'n'; + payload_buffer[11] = 'd'; + payload_buffer[12] = 'a'; + payload_buffer[13] = 't'; + payload_buffer[14] = 'a'; + payload_buffer[15] = 'c'; + payload_buffer[16] = 'f'; + payload_buffer[17] = 'g'; + payload_buffer[18] = ' '; + + /* Specify the channel */ + payload_buffer[19] = '0'; + + if (scan_format == SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_NONE || + scan_format == SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_8BIT || + scan_format == SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_16BIT) { + payload_buffer[20] = '1'; + } + else { + payload_buffer[20] = '3'; + } + + payload_buffer[21] = ' '; + + /* Values should be 0 */ + payload_buffer[22] = '0'; + payload_buffer[23] = '0'; + payload_buffer[24] = ' '; + + /* Send remission values? */ + if (scan_format == SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_NONE || + scan_format == SICK_LMS_1XX_SCAN_FORMAT_DIST_DOUBLE_PULSE_REFLECT_NONE) { + payload_buffer[25] = '0'; // 0 = no, 1 = yes + } + else { + payload_buffer[25] = '1'; // 0 = no, 1 = yes + } + payload_buffer[26] = ' '; + + /* Remission resolution */ + if (scan_format == SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_16BIT || + scan_format == SICK_LMS_1XX_SCAN_FORMAT_DIST_DOUBLE_PULSE_REFLECT_16BIT) { + payload_buffer[27] = '1'; // 0 = 8bit, 1 = 16bit + } + else { + payload_buffer[27] = '0'; // 0 = 8bit, 1 = 16bit + } + payload_buffer[28] = ' '; + + /* Units (always 0) */ + payload_buffer[29] = '0'; + payload_buffer[30] = ' '; + + /* Encoder data? */ + payload_buffer[31] = '0'; // (00 = no encode data, 01 = channel 1 encoder) + payload_buffer[32] = '0'; + payload_buffer[33] = ' '; + + /* These values should be 0 */ + payload_buffer[34] = '0'; + payload_buffer[35] = '0'; + payload_buffer[36] = ' '; + + /* Send position values? */ + payload_buffer[37] = '0'; // (0 = no position, 1 = send position) + payload_buffer[38] = ' '; + + /* Send device name? */ + payload_buffer[39] = '0'; // (0 = no, 1 = yes) + payload_buffer[40] = ' '; + + /* Send comment? */ + payload_buffer[41] = '0'; // (0 = no, 1 = yes) + payload_buffer[42] = ' '; + + /* Send time info? */ + payload_buffer[43] = '0'; // (0 = no, 1 = yes) + payload_buffer[44] = ' '; + + /* Send time info? */ + payload_buffer[45] = '+'; // +1 = send all scans, +2 every second scan, etc + payload_buffer[46] = '1'; + + /* Construct command message */ + SickLMS1xxMessage send_message(payload_buffer,47); + + /* Setup container for recv message */ + SickLMS1xxMessage recv_message; + + try { + + /* Send message and get reply */ + _sendMessageAndGetReply(send_message, recv_message, "sWA", "LMDscandatacfg"); + + /* Reinitialize the Sick so it uses the requested format */ + _reinitialize(); + + /* Set the sick scan data format */ + _sick_scan_format = scan_format; + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle thread exception */ + catch (SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle Sick error */ + catch (SickErrorException &sick_error_exception) { + std::cerr << sick_error_exception.what() << std::endl; + throw; + } + + catch (...) { + std::cerr << "SickLMS1xx::_setSickScanDataFormat: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + + } + + /** + * Set device to output only range values + */ + void SickLMS1xx::_restoreMeasuringMode( ) throw( SickTimeoutException, SickIOException ) { + + /* Allocate a single buffer for payload contents */ + uint8_t payload_buffer[SickLMS1xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Set the command type */ + payload_buffer[0] = 's'; + payload_buffer[1] = 'M'; + payload_buffer[2] = 'N'; + payload_buffer[3] = ' '; + + /* Set the command */ + payload_buffer[4] = 'R'; + payload_buffer[5] = 'u'; + payload_buffer[6] = 'n'; + + /* Construct command message */ + SickLMS1xxMessage send_message(payload_buffer,7); + + /* Setup container for recv message */ + SickLMS1xxMessage recv_message; + + try { + + /* Send message and get reply */ + _sendMessageAndGetReply(send_message, recv_message, "sWA", "LMDscandatacfg"); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::_restoreMeasuringMode: Unknown exception!!!" << std::endl; + throw; + } + + memset(payload_buffer,0,7); + recv_message.GetPayload(payload_buffer); + + /* Check return value */ + if (payload_buffer[8] != '0') { + std::cerr << "SickLMS1xx::_restoreMeasuringMode: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + + } + + /** + * \brief Utility function to ensure valid scan area + */ + bool SickLMS1xx::_validScanArea( const int start_angle, const int stop_angle ) const { + + /* Ensure stop is greater than start */ + if (start_angle >= stop_angle) { + return false; + } + + /* Check angular bounds */ + if (start_angle < SICK_LMS_1XX_SCAN_AREA_MIN_ANGLE || start_angle > SICK_LMS_1XX_SCAN_AREA_MAX_ANGLE) { + return false; + } + + /* Check angular bounds */ + if (stop_angle < SICK_LMS_1XX_SCAN_AREA_MIN_ANGLE || stop_angle > SICK_LMS_1XX_SCAN_AREA_MAX_ANGLE) { + return false; + } + + /* Valid! */ + return true; + + } + + /** + * \brief Sends a message without waiting for reply + */ + void SickLMS1xx::_sendMessage( const SickLMS1xxMessage &send_message ) const throw( SickIOException ) { + + try { + + /* Send a message using parent's method */ + SickLIDAR< SickLMS1xxBufferMonitor, SickLMS1xxMessage >::_sendMessage(send_message,DEFAULT_SICK_LMS_1XX_BYTE_TIMEOUT); + + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_error) { + std::cerr << sick_io_error.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::_sendMessageAndGetReply: Unknown exception!!!" << std::endl; + throw; + } + + /* Success */ + + } + + /** + * \brief Sends a message and searches for the reply with given command type and command + * \param &send_message The message to be sent to the Sick LMS 2xx unit + * \param &recv_message The expected message reply from the Sick LMS + * \param reply_command_code The expected command code for the recv_message + * \param reply_command The expected command for the recv_message + * \param timeout_value The epoch to wait before considering a sent frame lost (in usecs) + * \param num_tries The number of times to send the message in the event the LMS fails to reply + */ + void SickLMS1xx::_sendMessageAndGetReply( const SickLMS1xxMessage &send_message, + SickLMS1xxMessage &recv_message, + const std::string reply_command_type, + const std::string reply_command, + const unsigned int timeout_value, + const unsigned int num_tries ) throw( SickIOException, SickTimeoutException ) { + + /* Construct the expected string */ + std::string expected_str = reply_command_type + " " + reply_command; + + try { + + /* Send a message and get reply using parent's method */ + SickLIDAR< SickLMS1xxBufferMonitor, SickLMS1xxMessage >::_sendMessageAndGetReply(send_message,recv_message,(uint8_t *)expected_str.c_str(),expected_str.length(),DEFAULT_SICK_LMS_1XX_BYTE_TIMEOUT,timeout_value,num_tries); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout) { + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_error) { + std::cerr << sick_io_error.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::_sendMessageAndGetReply: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + + } + + /** \brief Receive a message + * \param sick_message Reference to container to hold received message + */ + void SickLMS1xx::_recvMessage( SickLMS1xxMessage &sick_message ) const throw ( SickTimeoutException ) { + + try { + + /* Receive message using parent's method */ + SickLIDAR< SickLMS1xxBufferMonitor, SickLMS1xxMessage >::_recvMessage(sick_message,DEFAULT_SICK_LMS_1XX_MESSAGE_TIMEOUT); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout) { + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS1xx::_sendMessageAndGetReply: Unknown exception!!!" << std::endl; + throw; + } + + } + + /** + * \brief Converts int to status + * \param status integer corresponding to sick status + */ + sick_lms_1xx_status_t SickLMS1xx::_intToSickStatus( const int status ) const + { + switch(status) { + case 1: + return SICK_LMS_1XX_STATUS_INITIALIZATION; + case 2: + return SICK_LMS_1XX_STATUS_CONFIGURATION; + case 3: + return SICK_LMS_1XX_STATUS_IDLE; + case 4: + return SICK_LMS_1XX_STATUS_ROTATED; + case 5: + return SICK_LMS_1XX_STATUS_IN_PREP; + case 6: + return SICK_LMS_1XX_STATUS_READY; + case 7: + return SICK_LMS_1XX_STATUS_READY_FOR_MEASUREMENT; + default: + return SICK_LMS_1XX_STATUS_UNKNOWN; + } + } + + /** Utility function to convert config error int to str */ + std::string SickLMS1xx::_intToSickConfigErrorStr( const int error ) const { + + switch(error) { + case 1: + return "Invalid Scan Frequency"; + case 2: + return "Invalid Scan Resolution"; + case 3: + return "Invalid Scan Frequency and Scan Resolution"; + case 4: + return "Invalid Scan Area"; + default: + return "Other Error"; + } + + } + + /** + * \brief Prints Sick LMS 1xx scan configuration + */ + void SickLMS1xx::_printSickScanConfig( ) const { + + std::cout << "\t========= Sick Scan Config =========" << std::endl; + std::cout << "\tScan Frequency: " << ((double)_sick_scan_config.sick_scan_freq)/100 << "(Hz)" << std::endl; + std::cout << "\tScan Resolution: " << ((double)_sick_scan_config.sick_scan_res)/10000 << " (deg)" << std::endl; + std::cout << "\tScan Area: " << "[" << ((double)_sick_scan_config.sick_start_angle)/10000 << "," << ((double)_sick_scan_config.sick_stop_angle)/10000 << "]" << std::endl; + std::cout << "\t====================================" << std::endl; + std::cout << std::endl << std::flush; + } + + /** + * \brief Prints the initialization footer. + */ + void SickLMS1xx::_printInitFooter( ) const { + + std::cout << "\t*** Init. complete: Sick LMS 1xx is online and ready!" << std::endl; + std::cout << "\tScan Frequency: " << _convertSickFreqUnitsToHz(_sick_scan_config.sick_scan_freq) << "(Hz)" << std::endl; + std::cout << "\tScan Resolution: " << _convertSickAngleUnitsToDegs(_sick_scan_config.sick_scan_res) << " (deg)" << std::endl; + std::cout << "\tScan Area: " << "[" << _convertSickAngleUnitsToDegs(_sick_scan_config.sick_start_angle) << "," << _convertSickAngleUnitsToDegs(_sick_scan_config.sick_stop_angle) << "]" << std::endl; + std::cout << std::endl; + + } + + /** + * \brief Utility function for returning scan format as string + * \param dist_opt Distance option corresponding to scan format + * \param reflect_opt Reflectivity option corresponding to + */ + std::string SickLMS1xx::_sickScanDataFormatToString( const sick_lms_1xx_scan_format_t scan_format ) const { + + /* Determine the type of distance measurements */ + switch (scan_format) { + case SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_NONE: + return "(single-pulse dist, no reflect)"; + case SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_8BIT: + return "(single-pulse dist, 8Bit reflect)"; + case SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_16BIT: + return "(single-pulse dist, 16Bit reflect)"; + case SICK_LMS_1XX_SCAN_FORMAT_DIST_DOUBLE_PULSE_REFLECT_NONE: + return "(double-pulse dist, no reflect)"; + case SICK_LMS_1XX_SCAN_FORMAT_DIST_DOUBLE_PULSE_REFLECT_8BIT: + return "(double-pulse dist, 8Bit reflect)"; + case SICK_LMS_1XX_SCAN_FORMAT_DIST_DOUBLE_PULSE_REFLECT_16BIT: + return "(double-pulse dist, 16Bit reflect)"; + default: + return "Unknown"; + } + + } + + /** + * \brief Searches a string for a substring + * \param str String to be searched + * \param substr Substring being sought + * \param str_length String's length + * \param substr_length Substring's length + * \param substr_pos Reference holding the location in the main string where substr was found + * \param start_pos Index into main string to indicate where to start searching + * \return True if substring found, false otherwise + */ + bool SickLMS1xx::_findSubString( const char * const str, const char * const substr, + const unsigned int str_length, const unsigned int substr_length, + unsigned int &substr_pos, unsigned int start_pos ) const { + + /* Init substring position */ + substr_pos = 0; + + /* Look for the substring */ + bool substr_found = false; + for (unsigned int i = start_pos; !substr_found && (i < (str_length - substr_length) + 1); i++) { + + unsigned int j = 0; + for (unsigned int k = i; (str[k] == substr[j]) && (j < substr_length); k++, j++); + + if (j == substr_length) { + substr_found = true; + substr_pos = i; + } + + } + + /* Found! */ + return substr_found; + + } + + /** + * \brief Utility function for converting next token into unsigned int + * \param str_buffer Source (c-string) buffer + * \param next_token Pointer to the next string token + * \param delimeter Token delimiter (default is " ") + * \returns Unsigned integer corresponding to numeric string token value + */ + char * SickLMS1xx::_convertNextTokenToUInt( char * const str_buffer, unsigned int & num_val, + const char * const delimeter ) const { + + const char * token = NULL; + uint32_t curr_val = 0; + if ((token = strtok(str_buffer,delimeter)) == NULL) { + throw SickIOException("SickLMS1xx::_getextTokenAsUInt: strtok() failed!"); + } + + if (sscanf(token,"%x",&curr_val) == EOF) { + throw SickIOException("SickLMS1xx::_getNextTokenAsUInt: sscanf() failed!"); + } + + num_val = (unsigned int)sick_lms_1xx_to_host_byte_order(curr_val); + + return str_buffer + strlen(token) + 1; + + } + +} //namespace SickToolbox diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/SickLMS1xxBufferMonitor.cc b/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/SickLMS1xxBufferMonitor.cc new file mode 100644 index 0000000..0586d0b --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/SickLMS1xxBufferMonitor.cc @@ -0,0 +1,127 @@ +/*! + * \file SickLMS1xxBufferMonitor.cc + * \brief Implements a class for monitoring the receive + * buffer when interfacing w/ a Sick LMS 1xx LIDAR. + * + * Code by Jason C. Derenick and Christopher R. Mansley. + * Contact jasonder(at)seas(dot)upenn(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2009, Jason C. Derenick and Christopher R. Mansley + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +/* Auto-generated header */ +#include + +/* Implementation dependencies */ +#include +#include + +#include +#include +#include +#include + +/* Associate the namespace */ +namespace SickToolbox { + + /** + * \brief A standard constructor + */ + SickLMS1xxBufferMonitor::SickLMS1xxBufferMonitor( ) : SickBufferMonitor< SickLMS1xxBufferMonitor, SickLMS1xxMessage >(this) { } + + /** + * \brief Acquires the next message from the SickLMS1xx byte stream + * \param &sick_message The returned message object + */ + void SickLMS1xxBufferMonitor::GetNextMessageFromDataStream( SickLMS1xxMessage &sick_message ) throw( SickIOException ) { + + /* Flush the input buffer */ + uint8_t byte_buffer = 0; + uint8_t payload_buffer[SickLMS1xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + try { + + /* Flush the TCP receive buffer */ + _flushTCPRecvBuffer(); + + /* Search for STX in the byte stream */ + do { + + /* Grab the next byte from the stream */ + _readBytes(&byte_buffer,1,DEFAULT_SICK_LMS_1XX_BYTE_TIMEOUT); + + } + while (byte_buffer != 0x02); + + /* Ok, now acquire the payload! (until ETX) */ + int payload_length = 0; + do { + + payload_length++; + _readBytes(&payload_buffer[payload_length-1],1,DEFAULT_SICK_LMS_1XX_BYTE_TIMEOUT); + + } + while (payload_buffer[payload_length-1] != 0x03); + payload_length--; + + /* Build the return message object based upon the received payload + * NOTE: In constructing this message we ignore the header bytes + * buffered since the BuildMessage routine will insert the + * correct header automatically and verify the message size + */ + sick_message.BuildMessage(payload_buffer,payload_length); + + /* Success */ + + } + + catch(SickTimeoutException &sick_timeout) { /* This is ok! */ } + + /* Catch any serious IO buffer exceptions */ + catch(SickIOException &sick_io_exception) { + throw; + } + + /* A sanity check */ + catch (...) { + throw; + } + + } + + /** + * \brief Flushes TCP receive buffer contents + */ + void SickLMS1xxBufferMonitor::_flushTCPRecvBuffer( ) const throw (SickIOException) { + + char null_byte; + int num_bytes_waiting = 0; + + /* Acquire number of awaiting bytes */ + if (ioctl(_sick_fd,FIONREAD,&num_bytes_waiting)) { + throw SickIOException("SickLMS1xxBufferMonitor::_flushTCPRecvBuffer: ioctl() failed!"); + } + + /* Flush awaiting bytes */ + for (int i = 0; i < num_bytes_waiting; i++) { + + /* Capture a single byte from the stream! */ + if (read(_sick_fd,&null_byte,1) != 1) { + throw SickIOException("SickLMS1xxBufferMonitor::_flushTCPRecvBuffer: ioctl() failed!"); + } + + } + + } + + /** + * \brief A standard destructor + */ + SickLMS1xxBufferMonitor::~SickLMS1xxBufferMonitor( ) { } + +} /* namespace SickToolbox */ diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/SickLMS1xxMessage.cc b/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/SickLMS1xxMessage.cc new file mode 100644 index 0000000..1f8da11 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/lms1xx/sicklms1xx/SickLMS1xxMessage.cc @@ -0,0 +1,201 @@ +/*! + * \file SickLMS1xxMessage.cc + * \brief Implements the class SickLMS1xxMessage. + * + * Code by Jason C. Derenick and Christopher R. Mansley. + * Contact jasonder(at)seas(dot)upenn(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2009, Jason C. Derenick and Christopher R. Mansley + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +/* Auto-generated header */ +#include + +/* Implementation dependencies */ +#include +#include +#include + +#include +#include // for byye-order conversions where necessary + +/* Associate the namespace */ +namespace SickToolbox { + + /** + * \brief A default constructor + */ + SickLMS1xxMessage::SickLMS1xxMessage( ) : + SickMessage< SICK_LMS_1XX_MSG_HEADER_LEN, SICK_LMS_1XX_MSG_PAYLOAD_MAX_LEN, SICK_LMS_1XX_MSG_TRAILER_LEN >(), + _command_type(""), + _command("") + { + + /* Initialize the object */ + Clear(); + + } + + /** + * \brief Another constructor. + * \param *payload_buffer The payload for the packet as an array of bytes (including the header) + * \param payload_length The length of the payload array in bytes + */ + SickLMS1xxMessage::SickLMS1xxMessage( const uint8_t * const payload_buffer, const unsigned int payload_length ) : + SickMessage< SICK_LMS_1XX_MSG_HEADER_LEN, SICK_LMS_1XX_MSG_PAYLOAD_MAX_LEN, SICK_LMS_1XX_MSG_TRAILER_LEN >(), + _command_type("Unknown"), + _command("Unknown") + { + + /* Build the message object (implicit initialization) */ + BuildMessage(payload_buffer,payload_length); + + } + + /** + * \brief Another constructor. + * \param *message_buffer A well-formed message to be parsed into the class' fields + */ + SickLMS1xxMessage::SickLMS1xxMessage( const uint8_t * const message_buffer ) : + SickMessage< SICK_LMS_1XX_MSG_HEADER_LEN, SICK_LMS_1XX_MSG_PAYLOAD_MAX_LEN, SICK_LMS_1XX_MSG_TRAILER_LEN >(), + _command_type("Unknown"), + _command("Unknown") + { + + /* Parse the message into the container (implicit initialization) */ + ParseMessage(message_buffer); + + } + + /** + * \brief Constructs a well-formed Sick LMS 1xx message + * \param *payload_buffer An address of the first byte to be copied into the message's payload + * \param payload_length The number of bytes to be copied into the message buffer + */ + void SickLMS1xxMessage::BuildMessage( const uint8_t * const payload_buffer, const unsigned int payload_length ) { + + /* Call the parent method + * NOTE: The parent method resets the object and assigns _message_length, _payload_length, + * _populated and copies the payload into the message buffer at the correct position + */ + SickMessage< SICK_LMS_1XX_MSG_HEADER_LEN, SICK_LMS_1XX_MSG_PAYLOAD_MAX_LEN, SICK_LMS_1XX_MSG_TRAILER_LEN > + ::BuildMessage(payload_buffer,payload_length); + + /* + * Set the message header! + */ + _message_buffer[0] = 0x02; // STX + + /* + * Set the message trailer! + */ + _message_buffer[_message_length-1] = 0x03; // ETX + + /* Grab the (3-byte) command type */ + char command_type[4] = {0}; + for (int i = 0; i < 3; i++) { + command_type[i] = _message_buffer[i+1]; + } + command_type[4] = '\0'; + _command_type = command_type; + + /* Grab the command (max length is 14 bytes) */ + char command[15] = {0}; + int i = 0; + for (; (i < 14) && (_message_buffer[5+i] != 0x20); i++) { + command[i] = _message_buffer[5+i]; + } + command[i] = '\0'; + _command = command; + + } + + /** + * \brief Parses a sequence of bytes into a SickLMS1xxMessage object + * \param *message_buffer A well-formed message to be parsed into the class' fields + */ + void SickLMS1xxMessage::ParseMessage( const uint8_t * const message_buffer ) throw (SickIOException) { + + /* Call the parent method + * NOTE: This method resets the object and assigns _populated as true + */ + SickMessage< SICK_LMS_1XX_MSG_HEADER_LEN, SICK_LMS_1XX_MSG_PAYLOAD_MAX_LEN, SICK_LMS_1XX_MSG_TRAILER_LEN > + ::ParseMessage(message_buffer); + + /* Compute the message length */ + int i = 1; + const char * token = NULL; + while (message_buffer[i-1] != 0x03) { + + if (i == 1) { + + /* Grab the command type */ + if ((token = strtok((char *)&_message_buffer[1]," ")) == NULL) { + throw SickIOException("SickLMS1xxMessage::ParseMessage: strtok() failed!"); + } + + _command_type = token; + + /* Grab the Command Code */ + if ((token = strtok(NULL," ")) == NULL) { + throw SickIOException("SickLMS1xxMessage::ParseMessage: strtok() failed!"); + } + + _command = token; + + } + + i++; // Update message length + + /* A sanity check */ + if (i > SickLMS1xxMessage::MESSAGE_MAX_LENGTH) { + throw SickIOException("SickLMS1xxMessage::ParseMessage: Message Exceeds Max Message Length!"); + } + + } + + /* Compute the total message length */ + _payload_length = _message_length - MESSAGE_HEADER_LENGTH - MESSAGE_TRAILER_LENGTH; + + /* Copy the given packet into the buffer */ + memcpy(_message_buffer,message_buffer,_message_length); + + } + + /** + * \brief Reset all internal fields and buffers associated with the object. + */ + void SickLMS1xxMessage::Clear( ) { + + /* Call the parent method and clear out class' protected members */ + SickMessage< SICK_LMS_1XX_MSG_HEADER_LEN, SICK_LMS_1XX_MSG_PAYLOAD_MAX_LEN, SICK_LMS_1XX_MSG_TRAILER_LEN >::Clear(); + + /* Reset the class' additional fields */ + _command_type = "Unknown"; + _command = "Unknown"; + + } + + /** + * \brief Print the message contents. + */ + void SickLMS1xxMessage::Print( ) const { + + //std::cout.setf(std::ios::hex,std::ios::basefield); + std::cout << "Command Type: " << GetCommandType() << std::endl; + std::cout << "Command Code: " << GetCommand() << std::endl; + std::cout << std::flush; + + /* Call parent's print function */ + SickMessage< SICK_LMS_1XX_MSG_HEADER_LEN, SICK_LMS_1XX_MSG_PAYLOAD_MAX_LEN, SICK_LMS_1XX_MSG_TRAILER_LEN >::Print(); + + } + + SickLMS1xxMessage::~SickLMS1xxMessage( ) { } + +} /* namespace SickToolbox */ diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/.deps/SickLMS2xx.Plo b/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/.deps/SickLMS2xx.Plo new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/.deps/SickLMS2xx.Plo @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/.deps/SickLMS2xxBufferMonitor.Plo b/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/.deps/SickLMS2xxBufferMonitor.Plo new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/.deps/SickLMS2xxBufferMonitor.Plo @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/.deps/SickLMS2xxMessage.Plo b/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/.deps/SickLMS2xxMessage.Plo new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/.deps/SickLMS2xxMessage.Plo @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/SickLMS2xx.cc b/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/SickLMS2xx.cc new file mode 100644 index 0000000..9dc7470 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/SickLMS2xx.cc @@ -0,0 +1,5203 @@ +/*! + * \file SickLMS2xx.cc + * \brief Definition of the class SickLMS2xx + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +/* Auto-generated header */ +#include + +/* Implementation dependencies */ +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#ifdef HAVE_LINUX_SERIAL_H +#include +#else +#define B500000 0010005 +#endif + +/* Associate the namespace */ +namespace SickToolbox { + + /*! + * \brief Primary constructor + * \param sick_device_path The path of the device + */ + SickLMS2xx::SickLMS2xx( const std::string sick_device_path ): SickLIDAR< SickLMS2xxBufferMonitor, SickLMS2xxMessage >( ), + _sick_device_path(sick_device_path), + _curr_session_baud(SICK_BAUD_UNKNOWN), + _desired_session_baud(SICK_BAUD_UNKNOWN), + _sick_type(SICK_LMS_TYPE_UNKNOWN), + _sick_mean_value_sample_size(0), + _sick_values_subrange_start_index(0), + _sick_values_subrange_stop_index(0) + { + + /* Initialize the protected/private structs */ + memset(&_sick_operating_status,0,sizeof(sick_lms_2xx_operating_status_t)); + memset(&_sick_software_status,0,sizeof(sick_lms_2xx_software_status_t)); + memset(&_sick_restart_status,0,sizeof(sick_lms_2xx_restart_status_t)); + memset(&_sick_pollution_status,0,sizeof(sick_lms_2xx_pollution_status_t)); + memset(&_sick_signal_status,0,sizeof(sick_lms_2xx_signal_status_t)); + memset(&_sick_field_status,0,sizeof(sick_lms_2xx_field_status_t)); + memset(&_sick_baud_status,0,sizeof(sick_lms_2xx_baud_status_t)); + memset(&_sick_device_config,0,sizeof(sick_lms_2xx_device_config_t)); + memset(&_old_term,0,sizeof(struct termios)); + + } + + /** + * \brief Destructor + */ + SickLMS2xx::~SickLMS2xx() { + + try { + + /* Attempt to uninitialize the device */ + _teardownConnection(); + + } + + /* Catch an I/O exception */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + } + + /* Catch anything else */ + catch(...) { + std::cerr << "SickLMS2xx::~SickLMS2xx: Unknown exception!" << std::endl; + } + + } + + /** + * \brief Attempts to initialize the Sick LMS 2xx and then sets communication at + * at the given baud rate. + * \param desired_baud_rate Desired session baud rate + * \param delay Delay to wait for SICK to power on (in seconds) + */ + void SickLMS2xx::Initialize( const sick_lms_2xx_baud_t desired_baud_rate, const uint32_t delay ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) { + + /* Buffer the desired baud rate in case we have to reset */ + _desired_session_baud = desired_baud_rate; + + try { + + std::cout << std::endl << "\t*** Attempting to initialize the Sick LMS..." << std::endl << std::flush; + + /* Initialize the serial term for communication */ + std::cout << "\tAttempting to open device @ " << _sick_device_path << std::endl << std::flush; + _setupConnection(delay); + std::cout << "\t\tDevice opened!" << std::endl << std::flush; + + /* Start/reset the buffer monitor */ + if (!_sick_monitor_running) { + std::cout << "\tAttempting to start buffer monitor..." << std::endl; + _startListening(); + std::cout << "\t\tBuffer monitor started!" << std::endl; + } + else { + std::cout << "\tAttempting to reset buffer monitor..." << std::endl; + _sick_buffer_monitor->SetDataStream(_sick_fd); + std::cout << "\t\tBuffer monitor reset!" << std::endl; + } + + try { + + std::cout << "\tAttempting to set requested baud rate..." << std::endl; + _setSessionBaud(_desired_session_baud); + + } + + /* Assume a timeout is due to a misconfigured terminal baud */ + catch(SickTimeoutException &sick_timeout) { + + /* Check whether to do an autodetect */ + sick_lms_2xx_baud_t default_baud = _baudToSickBaud(DEFAULT_SICK_LMS_2XX_SICK_BAUD); + std::cout << "\tFailed to set requested baud rate..." << std::endl << std::flush; + std::cout << "\tAttempting to detect LMS baud rate..." << std::endl << std::flush; + if((default_baud != SICK_BAUD_9600) && _testSickBaud(SICK_BAUD_9600)) { + std::cout << "\t\tDetected LMS baud @ " << SickBaudToString(SICK_BAUD_9600) << "!" << std::endl; + } else if((default_baud != SICK_BAUD_19200) && _testSickBaud(SICK_BAUD_19200)) { + std::cout << "\t\tDetected LMS baud @ " << SickBaudToString(SICK_BAUD_19200) << "!" << std::endl; + } else if((default_baud != SICK_BAUD_38400) && _testSickBaud(SICK_BAUD_38400)) { + std::cout << "\t\tDetected LMS baud @ " << SickBaudToString(SICK_BAUD_38400) << "!" << std::endl; + } else if((default_baud) != SICK_BAUD_500K && _testSickBaud(SICK_BAUD_500K)) { + std::cout << "\t\tDetected LMS baud @ " << SickBaudToString(SICK_BAUD_500K) << "!" << std::endl; + } else { + _stopListening(); + throw SickIOException("SickLMS2xx::Initialize: failed to detect baud rate!"); + } + std::cout << std::flush; + + /* Try again! */ + if (_curr_session_baud != _desired_session_baud) { + std::cout << "\tAttempting to setup desired baud (again)..." << std::endl << std::flush; + _setSessionBaud(_desired_session_baud); + } + + } + + /* Catch anything else */ + catch(...) { + std::cerr << "SickLMS2xx::Initialize: Unknown exception!" << std::endl; + throw; + } + + std::cout << "\t\tOperating @ " << SickBaudToString(_curr_session_baud) << std::endl; + + /* Set the device to request range mode */ + _setSickOpModeMonitorRequestValues(); + + /* Acquire the type of device that we are working with */ + std::cout << "\tAttempting to sync driver..." << std::endl << std::flush; + _getSickType(); // Get the Sick device type string + _getSickStatus(); // Get the Sick device status + _getSickConfig(); // Get the Sick current config + std::cout << "\t\tDriver synchronized!" << std::endl << std::flush; + + /* Set the flag */ + _sick_initialized = true; + + } + + /* Handle a config exception */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a timeout exception */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle anything else */ + catch(...) { + std::cerr << "SickLMS2xx::Initialize: Unknown exception!" << std::endl; + throw; + } + + /* Initialization was successful! */ + std::cout << "\t*** Init. complete: Sick LMS is online and ready!" << std::endl; + std::cout << "\tSick Type: " << SickTypeToString(GetSickType()) << std::endl; + std::cout << "\tScan Angle: " << GetSickScanAngle() << " (deg)" << std::endl; + std::cout << "\tScan Resolution: " << GetSickScanResolution() << " (deg)" << std::endl; + std::cout << "\tMeasuring Mode: " << SickMeasuringModeToString(GetSickMeasuringMode()) << std::endl; + std::cout << "\tMeasuring Units: " << SickMeasuringUnitsToString(GetSickMeasuringUnits()) << std::endl; + std::cout << std::endl << std::flush; + + } + + /** + * \brief Uninitializes the LMS by putting it in a mode where it stops streaming data, + * and returns it to the default baud rate (specified in the header). + */ + void SickLMS2xx::Uninitialize( ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) { + + if (_sick_initialized) { + + std::cout << std::endl << "\t*** Attempting to uninitialize the Sick LMS..." << std::endl; + + try { + + /* Restore original operating mode */ + _setSickOpModeMonitorRequestValues(); + + /* Restore original baud rate settings */ + _setSessionBaud(_baudToSickBaud(DEFAULT_SICK_LMS_2XX_SICK_BAUD)); + + /* Attempt to cancel the buffer monitor */ + if (_sick_monitor_running) { + std::cout << "\tAttempting to stop buffer monitor..." << std::endl; + _stopListening(); + std::cout << "\t\tBuffer monitor stopped!" << std::endl; + } + + std::cout << "\t*** Uninit. complete - Sick LMS is now offline!" << std::endl << std::flush; + + } + + /* Handle any config exceptions */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << " (attempting to kill connection anyways)" << std::endl; + throw; + } + + /* Handle a timeout exception */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << " (attempting to kill connection anyways)" << std::endl; + throw; + } + + /* Handle any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << " (attempting to kill connection anyways)" << std::endl; + throw; + } + + /* Handle any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << " (attempting to kill connection anyways)" << std::endl; + throw; + } + + /* Handle anything else */ + catch(...) { + std::cerr << "SickLMS2xx::Unintialize: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the flag */ + _sick_initialized = false; + + } + + } + + /** + * \brief Gets the Sick LMS 2xx device path + * \return The device path as a std::string + */ + std::string SickLMS2xx::GetSickDevicePath( ) const { + return _sick_device_path; + } + + /** + * \brief Gets the Sick LMS 2xx type + * \return The device type + */ + sick_lms_2xx_type_t SickLMS2xx::GetSickType( ) const throw( SickConfigException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickType: Sick LMS is not initialized!"); + } + + /* Return the Sick LMS type */ + return _sick_type; + + } + + /** + * \brief Gets the current scan angle of the device + * \return Scan angle of the device (sick_lms_2xx_scan_angle_t) + */ + double SickLMS2xx::GetSickScanAngle( ) const throw( SickConfigException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickScanAngle: Sick LMS is not initialized!"); + } + + /* Return the Sick scan angle */ + return (double)_sick_operating_status.sick_scan_angle; + + } + + /** + * \brief Gets the current angular resolution + * \return Angular resolution of the Sick LMS 2xx (sick_lms_2xx_scan_resolution_t) + */ + double SickLMS2xx::GetSickScanResolution( ) const throw( SickConfigException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickScanResolution: Sick LMS is not initialized!"); + } + + /* Return the scan resolution */ + return _sick_operating_status.sick_scan_resolution*(0.01); + + } + + /** + * \brief Sets the measurement units for the device + * \param sick_units Desired measurement units for the device + */ + void SickLMS2xx::SetSickMeasuringUnits( const sick_lms_2xx_measuring_units_t sick_units ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::SetSickMeasuringUnits: Sick LMS is not initialized!"); + } + + /* Ensure a valid units type was given */ + if (!_validSickMeasuringUnits(sick_units)) { + throw SickConfigException("SickLMS2xx::SetSickMeasuringUnits: Undefined measurement units!"); + } + + /* Make sure the write is necessary */ + if (sick_units != _sick_device_config.sick_measuring_units) { + + /* Setup a local copy of the config */ + sick_lms_2xx_device_config_t sick_device_config; + + /* Copy the configuration locally */ + sick_device_config = _sick_device_config; + + /* Set the units value */ + sick_device_config.sick_measuring_units = sick_units; + + try { + + /* Attempt to set the new configuration */ + _setSickConfig(sick_device_config); + + } + + /* Handle any config exceptions */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a timeout exception */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle anything else */ + catch(...) { + std::cerr << "SickLMS2xx::SetSickMeasuringUnits: Unknown exception!!!" << std::endl; + throw; + } + + } + else { + std::cerr << "\tSickLMS2xx::SetSickMeasuringUnits - Device is already configured w/ these units. (skipping write)" << std::endl; + } + + } + + /** + * \brief Gets the current Sick LMS 2xx measuring units + * \return Measuring units (sick_lms_2xx_measuring_units_t) + */ + sick_lms_2xx_measuring_units_t SickLMS2xx::GetSickMeasuringUnits( ) const throw( SickConfigException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickMeasuringUnits: Sick LMS is not initialized!"); + } + + /* Return the measurement units */ + return (sick_lms_2xx_measuring_units_t)_sick_operating_status.sick_measuring_units; + + } + + /** + * \brief Sets the Sick LMS sensitivity level + * \param sick_sensitivity Desired sensitivity level + */ + void SickLMS2xx::SetSickSensitivity( const sick_lms_2xx_sensitivity_t sick_sensitivity ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::SetSickSensitivity: Sick LMS is not initialized!"); + } + + /* Ensure the command is supported by the given Sick model */ + if (!_isSickLMS211() && !_isSickLMS221() && !_isSickLMS291()) { + throw SickConfigException("SickLMS2xx::SetSickSensitivity: This command is not supported by this Sick model!"); + } + + /* Ensure this is a valid sick sensitivity value*/ + if (!_validSickSensitivity(sick_sensitivity)) { + throw SickConfigException("SickLMS2xx::SetSickSensitivity: Undefined sensitivity level!"); + } + + /* Make sure the write is necessary */ + if (sick_sensitivity != _sick_device_config.sick_peak_threshold) { + + /* Setup a local copy of the config */ + sick_lms_2xx_device_config_t sick_device_config; + + /* Copy the configuration locally */ + sick_device_config = _sick_device_config; + + /* Set the units value */ + sick_device_config.sick_peak_threshold = sick_sensitivity; + + try { + + /* Attempt to set the new configuration */ + _setSickConfig(sick_device_config); + + } + + /* Handle any config exceptions */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a timeout exception */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle anything else */ + catch(...) { + std::cerr << "SickLMS2xx::SetSickSensitivity: Unknown exception!!!" << std::endl; + throw; + } + + } + else { + std::cerr << "\tSickLMS2xx::SetSickSensitivity - Sick is already operating at this sensitivity level! (skipping write)" << std::endl; + } + + } + + /** + * \brief Sets the Sick LMS sensitivity level + * \param sick_sensitivity Desired sensitivity level + */ + void SickLMS2xx::SetSickPeakThreshold( const sick_lms_2xx_peak_threshold_t sick_peak_threshold ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::SetSickPeakThreshold: Sick LMS is not initialized!"); + } + + /* Ensure the command is supported by the given Sick model */ + if (!_isSickLMS200() && !_isSickLMS220()) { + throw SickConfigException("SickLMS2xx::SetSickPeakThreshold: This command is not supported by this Sick model!"); + } + + /* Ensure this is a valid sick sensitivity value*/ + if (!_validSickPeakThreshold(sick_peak_threshold)) { + throw SickConfigException("SickLMS2xx::SetSickPeakThreshold: Undefined peak threshold!"); + } + + /* Make sure the write is necessary */ + if (sick_peak_threshold != _sick_device_config.sick_peak_threshold) { + + /* Setup a local copy of the config */ + sick_lms_2xx_device_config_t sick_device_config; + + /* Copy the configuration locally */ + sick_device_config = _sick_device_config; + + /* Set the units value */ + sick_device_config.sick_peak_threshold = sick_peak_threshold; + + try { + + /* Attempt to set the new configuration */ + _setSickConfig(sick_device_config); + + } + + /* Handle any config exceptions */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a timeout exception */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle anything else */ + catch(...) { + std::cerr << "SickLMS2xx::SetSickPeakThreshold: Unknown exception!!!" << std::endl; + throw; + } + + } + else { + std::cerr << "\tSickLMS2xx::SetSickPeakThreshold - Sick is already operating w/ given threshold! (skipping write)" << std::endl; + } + + } + + /** + * \brief Gets the current Sick LMS 2xx sensitivity level + * \return Sensitivity level (sick_lms_2xx_sensitivity_t) + */ + sick_lms_2xx_sensitivity_t SickLMS2xx::GetSickSensitivity( ) const throw( SickConfigException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickSensitivity: Sick LMS is not initialized!"); + } + + /* Make sure sensitivity is something that is defined for this model */ + if(!_isSickLMS211() && !_isSickLMS221() && !_isSickLMS291()) { + std::cerr << "Sensitivity is undefined for model: " << SickTypeToString(GetSickType()) << " (returning \"Unknown\")" << std::endl; + return SICK_SENSITIVITY_UNKNOWN; + } + + /* If its supported than return the actual value */ + return (sick_lms_2xx_sensitivity_t)_sick_device_config.sick_peak_threshold; //If the device is 211/221/291 then this value is sensitivity + + } + + /** + * \brief Gets the current Sick LMS 2xx sensitivity level + * \return Sensitivity level (sick_lms_2xx_sensitivity_t) + */ + sick_lms_2xx_peak_threshold_t SickLMS2xx::GetSickPeakThreshold( ) const throw( SickConfigException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickPeakThreshold: Sick LMS is not initialized!"); + } + + /* Make sure sensitivity is something that is defined for this model */ + if(!_isSickLMS200() && !_isSickLMS220()) { + std::cerr << "Peak threshold is undefined for model: " << SickTypeToString(GetSickType()) << " (returning \"Unknown\")" << std::endl; + return SICK_PEAK_THRESHOLD_UNKNOWN; + } + + /* If its supported than return the actual value */ + return (sick_lms_2xx_peak_threshold_t)_sick_device_config.sick_peak_threshold; //If the device is 211/221/291 then this value is sensitivity + + } + + /** + * \brief Sets the measuring mode for the device + * \param sick_measuring_mode Desired measuring mode + */ + void SickLMS2xx::SetSickMeasuringMode( const sick_lms_2xx_measuring_mode_t sick_measuring_mode ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::SetSickMeasuringUnits: Sick LMS is not initialized!"); + } + + /* Ensure this is a valid sick sensitivity value*/ + if (!_validSickMeasuringMode(sick_measuring_mode)) { + throw SickConfigException("SickLMS2xx::SetSickMeasuringMode: Undefined measuring mode!"); + } + + /* Make sure the write is necessary */ + if (sick_measuring_mode != _sick_device_config.sick_measuring_mode) { + + /* Setup a local copy of the config */ + sick_lms_2xx_device_config_t sick_device_config; + + /* Copy the configuration locally */ + sick_device_config = _sick_device_config; + + /* Set the units value */ + sick_device_config.sick_measuring_mode = sick_measuring_mode; + + try { + + /* Attempt to set the new configuration */ + _setSickConfig(sick_device_config); + + } + + /* Handle any config exceptions */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a timeout exception */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle anything else */ + catch(...) { + std::cerr << "SickLMS2xx::SetSickMeasuringMode: Unknown exception!!!" << std::endl; + throw; + } + + } + else { + std::cerr << "\tSickLMS2xx::SetSickMeasuringMode - Sick is already operating w/ this measuring mode! (skipping write)" << std::endl; + } + + } + + /** + * \brief Gets the current Sick LMS 2xx measuring mode + * \return Measuring mode (sick_lms_2xx_measuring_mode_t) + */ + sick_lms_2xx_measuring_mode_t SickLMS2xx::GetSickMeasuringMode( ) const throw( SickConfigException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickMeasuringMode: Sick LMS is not initialized!"); + } + + /* Return the determined measuring mode */ + return (sick_lms_2xx_measuring_mode_t)_sick_operating_status.sick_measuring_mode; + + } + + /** + * \brief Gets the current Sick LMS 2xx operating mode + * \return Operating mode (sick_lms_2xx_operating_mode_t) + */ + sick_lms_2xx_operating_mode_t SickLMS2xx::GetSickOperatingMode( ) const throw( SickConfigException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickScanAngle: Sick LMS is not initialized!"); + } + + /* Return the current operating mode of the device */ + return (sick_lms_2xx_operating_mode_t)_sick_operating_status.sick_operating_mode; + + } + + /** + * \brief Sets the availability level of the device + * \param sick_availability_level Desired availability of the Sick LMS + */ + void SickLMS2xx::SetSickAvailability( const uint8_t sick_availability_flags ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::SetSickAvailabilityFlags: Sick LMS is not initialized!"); + } + + /* Ensure this is a valid sick sensitivity value*/ + if ( sick_availability_flags > 7 ) { + throw SickConfigException("SickLMS2xx::SetSickAvailabilityFlags: Invalid availability!"); + } + + /* Setup a local copy of the config */ + sick_lms_2xx_device_config_t sick_device_config; + + /* Copy the configuration locally */ + sick_device_config = _sick_device_config; + + /* Maintain the higher level bits */ + sick_device_config.sick_availability_level &= 0xF8; + + /* Set the new availability flags */ + sick_device_config.sick_availability_level |= sick_availability_flags; + + /* Make sure the write is necessary */ + if (sick_device_config.sick_availability_level != _sick_device_config.sick_availability_level) { + + try { + + /* Attempt to set the new configuration */ + _setSickConfig(sick_device_config); + + } + + /* Handle any config exceptions */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a timeout exception */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle anything else */ + catch(...) { + std::cerr << "SickLMS2xx::SetSickAvailabilityFlags: Unknown exception!!!" << std::endl; + throw; + } + + } + else { + std::cerr << "\tSickLMS2xx::SetSickAvailability - Device is already operating w/ given availability. (skipping write)" << std::endl; + } + + } + + /** + * \brief Gets the current Sick LMS 2xx availability level flags + * \return Sick LMS 2xx Availability level flags + */ + uint8_t SickLMS2xx::GetSickAvailability( ) const throw( SickConfigException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickAvailabilityFlags: Sick LMS is not initialized!"); + } + + /* Return the availability flags */ + return _sick_device_config.sick_availability_level; + + } + + /*! + * \brief Sets the variant of the Sick LMS 2xx (scan angle and scan resolution) + * \param scan_angle The desired scan angle of the Sick LMS 2xx + * \param scan_resolution The desired angular resolution of the Sick LMS 2xx + */ + void SickLMS2xx::SetSickVariant( const sick_lms_2xx_scan_angle_t scan_angle, const sick_lms_2xx_scan_resolution_t scan_resolution ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::SetSickVariant: Sick LMS is not initialized!"); + } + + /* A sanity check to make sure that the command is supported */ + if (_sick_type == SICK_LMS_TYPE_211_S14 || _sick_type == SICK_LMS_TYPE_221_S14 ||_sick_type == SICK_LMS_TYPE_291_S14) { + throw SickConfigException("SickLMS2xx::SetSickVariant: Command not supported on this model!"); + } + + /* Ensure the given scan angle is defined */ + if (!_validSickScanAngle(scan_angle)) { + throw SickConfigException("SickLMS2xx::SetSickVariant: Undefined scan angle!"); + } + + /* Ensure the given scan resolution is defined */ + if (!_validSickScanResolution(scan_resolution)) { + throw SickConfigException("SickLMS2xx::SetSickMeasuringUnits: Undefined scan resolution!"); + } + + SickLMS2xxMessage message, response; + uint8_t payload_buffer[SickLMS2xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + payload_buffer[0] = 0x3B; // Command to set sick variant + + /* Map the scan angle */ + switch(scan_angle) { + case SICK_SCAN_ANGLE_100: + payload_buffer[1] = 0x64; + break; + case SICK_SCAN_ANGLE_180: + payload_buffer[1] = 0xB4; + break; + default: + throw SickConfigException("SickLMS2xx::SetSickVariant: Given scan angle is invalid!"); + } + + /* Map the resolution */ + switch(scan_resolution) { + case SICK_SCAN_RESOLUTION_100: + payload_buffer[3] = 0x64; + break; + case SICK_SCAN_RESOLUTION_50: + payload_buffer[3] = 0x32; + break; + case SICK_SCAN_RESOLUTION_25: + payload_buffer[3] = 0x19; + break; + default: + throw SickConfigException("SickLMS2xx::SetSickVariant: Given scan resolution is invalid!"); + } + + /* Build the request message */ + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,5); + + try { + + /* + * Set the device to request measured mode + * + * NOTE: This is done since the Sick stops sending + * data if the variant is reset midstream. + */ + _setSickOpModeMonitorRequestValues(); + + /* Send the variant request and get a reply */ + _sendMessageAndGetReply(message,response,DEFAULT_SICK_LMS_2XX_SICK_MESSAGE_TIMEOUT,DEFAULT_SICK_LMS_2XX_NUM_TRIES); + + } + + /* Handle a config exception */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a timeout exception */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle anything else */ + catch(...) { + std::cerr << "SickLMS2xx::SetSickVariant: Unknown exception!!!" << std::endl; + throw; + } + + /* Extract the payload length */ + response.GetPayload(payload_buffer); + + /* Check if the configuration was successful */ + if(payload_buffer[1] != 0x01) { + throw SickConfigException("SickLMS2xx::SetSickVariant: Configuration was unsuccessful!"); + } + + /* Update the scan angle of the device */ + memcpy(&_sick_operating_status.sick_scan_angle,&payload_buffer[2],2); + _sick_operating_status.sick_scan_angle = + sick_lms_2xx_to_host_byte_order(_sick_operating_status.sick_scan_angle); + + /* Update the angular resolution of the device */ + memcpy(&_sick_operating_status.sick_scan_resolution,&payload_buffer[4],2); + _sick_operating_status.sick_scan_resolution = + sick_lms_2xx_to_host_byte_order(_sick_operating_status.sick_scan_resolution); + + } + + /** + * \brief Returns the most recent measured values obtained by the Sick LMS 2xx + * \param *measurement_values Destination buffer for holding the current round of measured values + * \param &num_measurement_values Number of values stored in measurement_values + * \param *sick_field_a_values Stores the Field A values associated with the given scan (Default: NULL => Not wanted) + * \param *sick_field_b_values Stores the Field B values associated with the given scan (Default: NULL => Not wanted) + * \param *sick_field_c_values Stores the Field C values associated with the given scan (Default: NULL => Not wanted) + * \param *sick_telegram_index The telegram index assigned to the message (modulo: 256) (Default: NULL => Not wanted) + * \param *sick_real_time_scan_index The real time scan index for the latest message (module 256) (Default: NULL => Not wanted) + * + * NOTE: Calling this function will return either range or reflectivity measurements + * depending upon the current measuring mode of the device. + * + * NOTE: Real-time scan indices must be enabled by setting the corresponding availability + * of the Sick LMS 2xx for this value to be populated. + */ + void SickLMS2xx::GetSickScan( unsigned int * const measurement_values, + unsigned int & num_measurement_values, + unsigned int * const sick_field_a_values, + unsigned int * const sick_field_b_values, + unsigned int * const sick_field_c_values, + unsigned int * const sick_telegram_index, + unsigned int * const sick_real_time_scan_index ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickScan: Sick LMS is not initialized!"); + } + + /* Declare message objects */ + SickLMS2xxMessage response; + + /* Declare some useful variables and a buffer */ + uint8_t payload_buffer[SickLMS2xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + try { + + /* Restore original operating mode */ + _setSickOpModeMonitorStreamValues(); + + /* Receive a data frame from the stream. */ + _recvMessage(response,DEFAULT_SICK_LMS_2XX_SICK_MESSAGE_TIMEOUT); + + /* Check that our payload has the proper command byte of 0xB0 */ + if(response.GetCommandCode() != 0xB0) { + throw SickIOException("SickLMS2xx::GetSickScan: Unexpected message!"); + } + + /* Acquire the payload buffer and length*/ + response.GetPayload(payload_buffer); + + /* Define a local scan profile object */ + sick_lms_2xx_scan_profile_b0_t sick_scan_profile; + + /* Initialize the profile */ + memset(&sick_scan_profile,0,sizeof(sick_lms_2xx_scan_profile_b0_t)); + + /* Parse the message payload */ + _parseSickScanProfileB0(&payload_buffer[1],sick_scan_profile); + + /* Return the request values! */ + num_measurement_values = sick_scan_profile.sick_num_measurements; + + for (unsigned int i = 0; i < num_measurement_values; i++) { + + /* Copy the measurement value */ + measurement_values[i] = sick_scan_profile.sick_measurements[i]; + + /* If requested, copy field A values */ + if(sick_field_a_values) { + sick_field_a_values[i] = sick_scan_profile.sick_field_a_values[i]; + } + + /* If requested, copy field B values */ + if(sick_field_b_values) { + sick_field_b_values[i] = sick_scan_profile.sick_field_b_values[i]; + } + + /* If requested, copy field C values */ + if(sick_field_c_values) { + sick_field_c_values[i] = sick_scan_profile.sick_field_c_values[i]; + } + + } + + /* If requested, copy the real time scan index */ + if(sick_real_time_scan_index) { + *sick_real_time_scan_index = sick_scan_profile.sick_real_time_scan_index; + } + + /* If requested, copy the telegram index */ + if(sick_telegram_index) { + *sick_telegram_index = sick_scan_profile.sick_telegram_index; + } + + } + + /* Handle any config exceptions */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a timeout exception */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle anything else */ + catch(...) { + std::cerr << "SickLMS2xx::GetSickScan: Unknown exception!!!" << std::endl; + throw; + } + + } + + /** + * \brief Acquires both range and reflectivity values from the Sick LMS 211/221/291-S14 (LMS-FAST) + * \param *range_values The buffer in which range measurements will be stored + * \param *reflect_values The buffer in which reflectivity measurements will be stored + * \param reflect_subrange_start_index The starting index of the desired measured reflectivity subrange + * \param relfect_subrange_stop_index The stopping index of the desired measured relfectivity subrange + * \param &num_range_measurements The number of range measurements stored in range_values + * \param &num_reflectivity_measurements The number of reflectivity measurements stored in reflect_values + * \param *sick_field_a_values Stores the Field A values associated with the given scan (Default: NULL => Not wanted) + * \param *sick_field_b_values Stores the Field B values associated with the given scan (Default: NULL => Not wanted) + * \param *sick_field_c_values Stores the Field C values associated with the given scan (Default: NULL => Not wanted) + * \param *sick_telegram_index The telegram index assigned to the message (modulo: 256) (Default: NULL => Not wanted) + * \param *sick_real_time_scan_index The real time scan index for the latest message (module 256) (Default: NULL => Not wanted) + * + * NOTE: Real-time scan indices must be enabled by setting the corresponding availability + * of the Sick LMS 2xx for this value to be populated. + */ + void SickLMS2xx::GetSickScan( unsigned int * const range_values, + unsigned int * const reflect_values, + unsigned int & num_range_measurements, + unsigned int & num_reflect_measurements, + unsigned int * const sick_field_a_values, + unsigned int * const sick_field_b_values, + unsigned int * const sick_field_c_values, + unsigned int * const sick_telegram_index, + unsigned int * const sick_real_time_scan_index ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickScan: Sick LMS is not initialized!"); + } + + /* Declare message objects */ + SickLMS2xxMessage response; + + /* Declare some useful variables and a buffer */ + uint8_t payload_buffer[SickLMS2xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + try { + + /* Restore original operating mode */ + _setSickOpModeMonitorStreamRangeAndReflectivity(); + + /* Receive a data frame from the stream. */ + _recvMessage(response,DEFAULT_SICK_LMS_2XX_SICK_MESSAGE_TIMEOUT); + + /* Check that our payload has the proper command byte of 0xB0 */ + if(response.GetCommandCode() != 0xC4) { + throw SickIOException("SickLMS2xx::GetSickScan: Unexpected message!"); + } + + /* Acquire the payload buffer and length*/ + response.GetPayload(payload_buffer); + + /* Define a local scan profile object */ + sick_lms_2xx_scan_profile_c4_t sick_scan_profile; + + /* Initialize the profile */ + memset(&sick_scan_profile,0,sizeof(sick_lms_2xx_scan_profile_c4_t)); + + /* Parse the message payload */ + _parseSickScanProfileC4(&payload_buffer[1],sick_scan_profile); + + /* Return the requested values! */ + num_range_measurements = sick_scan_profile.sick_num_range_measurements; + num_reflect_measurements = sick_scan_profile.sick_num_reflect_measurements; + + for (unsigned int i = 0; i < sick_scan_profile.sick_num_range_measurements; i++) { + + /* Copy the measurement value */ + range_values[i] = sick_scan_profile.sick_range_measurements[i]; + + /* If requested, copy field A values */ + if(sick_field_a_values) { + sick_field_a_values[i] = sick_scan_profile.sick_field_a_values[i]; + } + + /* If requested, copy field B values */ + if(sick_field_b_values) { + sick_field_b_values[i] = sick_scan_profile.sick_field_b_values[i]; + } + + /* If requested, copy field C values */ + if(sick_field_c_values) { + sick_field_c_values[i] = sick_scan_profile.sick_field_c_values[i]; + } + + } + + /* Copy the reflectivity measurements */ + for( unsigned int i = 0; i < num_reflect_measurements; i++) { + reflect_values[i] = sick_scan_profile.sick_reflect_measurements[i]; + } + + /* If requested, copy the telegram index */ + if(sick_telegram_index) { + *sick_telegram_index = sick_scan_profile.sick_telegram_index; + } + + /* If requested, copy the real time scan index */ + if(sick_real_time_scan_index) { + *sick_real_time_scan_index = sick_scan_profile.sick_real_time_scan_index; + } + + } + + /* Handle any config exceptions */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a timeout exception */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle anything else */ + catch(...) { + std::cerr << "SickLMS2xx::GetSickScan: Unknown exception!!!" << std::endl; + throw; + } + + } + + /** + * \brief Returns the most recent measured values from the corresponding subrange + * \param sick_subrange_start_index The starting index of the desired subrange (See below for example) + * \param sick_subrange_stop_index The stopping index of the desired subrange (See below for example) + * \param *measurement_values Destination buffer for holding the current round of measured value + * \param &num_measurement_values Number of values stored in measurement_values + * \param *sick_field_a_values Stores the Field A values associated with the given scan (Default: NULL => Not wanted) + * \param *sick_field_b_values Stores the Field B values associated with the given scan (Default: NULL => Not wanted) + * \param *sick_field_c_values Stores the Field C values associated with the given scan (Default: NULL => Not wanted) + * \param *sick_telegram_index The telegram index assigned to the message (modulo: 256) (Default: NULL => Not wanted) + * \param *sick_real_time_scan_index The real time scan index for the latest message (module 256) (Default: NULL => Not wanted)* + * + * NOTE: Calling this function will return either range or reflectivity measurements + * depending upon the current measuring mode of the device. + * + * NOTE: Real-time scan indices must be enabled by setting the corresponding availability + * of the Sick LMS 2xx for this value to be populated. + * + * EXAMPLE: Using a 180/0.5 Sick LMS variant, a subrange over the scan area [0,10.5] would + * correspond to setting the index arguments as follows: sick_subrange_start = 1, + * sick_subrange_stop = 22 + */ + void SickLMS2xx::GetSickScanSubrange( const uint16_t sick_subrange_start_index, + const uint16_t sick_subrange_stop_index, + unsigned int * const measurement_values, + unsigned int & num_measurement_values, + unsigned int * const sick_field_a_values, + unsigned int * const sick_field_b_values, + unsigned int * const sick_field_c_values, + unsigned int * const sick_telegram_index, + unsigned int * const sick_real_time_scan_index ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickScanSubrange: Sick LMS is not initialized!"); + } + + /* Declare message object */ + SickLMS2xxMessage response; + + /* Declare some useful variables and a buffer */ + uint8_t payload_buffer[SickLMS2xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + try { + + /* Restore original operating mode */ + _setSickOpModeMonitorStreamValuesSubrange(sick_subrange_start_index,sick_subrange_stop_index); + + /* Receive a data frame from the stream. */ + _recvMessage(response,DEFAULT_SICK_LMS_2XX_SICK_MESSAGE_TIMEOUT); + + /* Check that our payload has the proper command byte of 0xB0 */ + if(response.GetCommandCode() != 0xB7) { + throw SickIOException("SickLMS2xx::GetSickScanSubrange: Unexpected message!"); + } + + /* Acquire the payload buffer and length*/ + response.GetPayload(payload_buffer); + + /* Define a local scan profile object */ + sick_lms_2xx_scan_profile_b7_t sick_scan_profile; + + /* Initialize the profile */ + memset(&sick_scan_profile,0,sizeof(sick_lms_2xx_scan_profile_b7_t)); + + /* Parse the message payload */ + _parseSickScanProfileB7(&payload_buffer[1],sick_scan_profile); + + /* Return the request values! */ + num_measurement_values = sick_scan_profile.sick_num_measurements; + + for (unsigned int i = 0; i < num_measurement_values; i++) { + + /* Copy the measurement value */ + measurement_values[i] = sick_scan_profile.sick_measurements[i]; + + /* If requested, copy field A values */ + if(sick_field_a_values) { + sick_field_a_values[i] = sick_scan_profile.sick_field_a_values[i]; + } + + /* If requested, copy field B values */ + if(sick_field_b_values) { + sick_field_b_values[i] = sick_scan_profile.sick_field_b_values[i]; + } + + /* If requested, copy field C values */ + if(sick_field_c_values) { + sick_field_c_values[i] = sick_scan_profile.sick_field_c_values[i]; + } + + } + + /* If requested, copy the real time scan index */ + if(sick_real_time_scan_index) { + *sick_real_time_scan_index = sick_scan_profile.sick_real_time_scan_index; + } + + /* If requested, copy the telegram index */ + if(sick_telegram_index) { + *sick_telegram_index = sick_scan_profile.sick_telegram_index; + } + + } + + /* Handle any config exceptions */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a timeout exception */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle anything else */ + catch(...) { + std::cerr << "SickLMS2xx::GetSickScanSubrange: Unknown exception!!!" << std::endl; + throw; + } + + } + + /** + * \brief Returns the most recent partial scan obtained by Sick LMS 2xx + * \param *measurement_values Destination buffer for holding the current round of measured value + * \param &num_measurement_values Number of values stored in measurement_values + * \param *sick_partial_scan_index Partial scan index associated w/ returned values (0 = 0.00 deg, 1 = 0.25 deg, 2 = 0.50 deg, 3 = 0.75 deg) + * \param *sick_field_a_values Stores the Field A values associated with the given scan (Default: NULL => Not wanted) + * \param *sick_field_b_values Stores the Field B values associated with the given scan (Default: NULL => Not wanted) + * \param *sick_field_c_values Stores the Field C values associated with the given scan (Default: NULL => Not wanted) + * \param *sick_telegram_index The telegram index assigned to the message (modulo: 256) (Default: NULL => Not wanted) + * \param *sick_real_time_scan_index The real time scan index for the latest message (module 256) (Default: NULL => Not wanted) + * + * NOTE: This function will set the device to interlaced mode. + * + * NOTE: The current angular resolution defines the minimum step size in the partial + * scan sequence. To obtain a high resolution partial scan you must set the + * Sick LMS 2xx variant to use a 0.25 degrees scan resolution. + * + * NOTE: Calling this function will return either range or reflectivity measurements + * depending upon the current measuring mode of the device. + * + * NOTE: Real-time scan indices must be enabled by setting the corresponding availability + * of the Sick LMS 2xx for this value to be populated. + */ + void SickLMS2xx::GetSickPartialScan( unsigned int * const measurement_values, + unsigned int & num_measurement_values, + unsigned int & partial_scan_index, + unsigned int * const sick_field_a_values, + unsigned int * const sick_field_b_values, + unsigned int * const sick_field_c_values, + unsigned int * const sick_telegram_index, + unsigned int * const sick_real_time_scan_index ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickPartialScan: Sick LMS is not initialized!"); + } + + /* Declare message objects */ + SickLMS2xxMessage response; + + /* Declare some useful variables and a buffer */ + uint8_t payload_buffer[SickLMS2xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + try { + + /* Restore original operating mode */ + _setSickOpModeMonitorStreamValuesFromPartialScan(); + + /* Receive a data frame from the stream. */ + _recvMessage(response,DEFAULT_SICK_LMS_2XX_SICK_MESSAGE_TIMEOUT); + + /* Check that our payload has the proper command byte of 0xB0 */ + if(response.GetCommandCode() != 0xB0) { + throw SickIOException("SickLMS2xx::GetSickPartialScan: Unexpected message!"); + } + + /* Acquire the payload buffer and length*/ + response.GetPayload(payload_buffer); + + /* Define a local scan profile object */ + sick_lms_2xx_scan_profile_b0_t sick_scan_profile; + + /* Initialize the profile */ + memset(&sick_scan_profile,0,sizeof(sick_lms_2xx_scan_profile_b0_t)); + + /* Parse the message payload */ + _parseSickScanProfileB0(&payload_buffer[1],sick_scan_profile); + + /* Return the request values! */ + num_measurement_values = sick_scan_profile.sick_num_measurements; + + /* Assign the partial scan index */ + partial_scan_index = sick_scan_profile.sick_partial_scan_index; + + for (unsigned int i = 0; i < num_measurement_values; i++) { + + /* Copy the measurement value */ + measurement_values[i] = sick_scan_profile.sick_measurements[i]; + + /* If requested, copy field A values */ + if(sick_field_a_values) { + sick_field_a_values[i] = sick_scan_profile.sick_field_a_values[i]; + } + + /* If requested, copy field B values */ + if(sick_field_b_values) { + sick_field_b_values[i] = sick_scan_profile.sick_field_b_values[i]; + } + + /* If requested, copy field C values */ + if(sick_field_c_values) { + sick_field_c_values[i] = sick_scan_profile.sick_field_c_values[i]; + } + + } + + /* If requested, copy the real time scan index */ + if(sick_real_time_scan_index) { + *sick_real_time_scan_index = sick_scan_profile.sick_real_time_scan_index; + } + + /* If requested, copy the telegram index */ + if(sick_telegram_index) { + *sick_telegram_index = sick_scan_profile.sick_telegram_index; + } + + } + + /* Handle any config exceptions */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a timeout exception */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle anything else */ + catch(...) { + std::cerr << "SickLMS2xx::GetSickPartialScan: Unknown exception!!!" << std::endl; + throw; + } + + } + + /** + * \brief Returns the most recent mean measured values from the Sick LMS 2xx. + * \param sick_sample_size Number of scans to consider in computing the mean measured values (NOTE: 2 <= sick_sample_size <= 250) + * \param *measurement_values Destination buffer for holding the current round of measured value + * \param &num_measurement_values Number of values stored in measurement_values + * \param *sick_telegram_index The telegram index assigned to the message (modulo: 256) (Default: NULL => Not wanted) + * \param *sick_real_time_scan_index The real time scan index for the latest message (module 256) (Default: NULL => Not wanted) + * + * NOTE: Calling this function will return either range or reflectivity measurements + * depending upon the current measuring mode of the device. + * + * NOTE: Real-time scan indices must be enabled by setting the corresponding availability + * of the Sick LMS 2xx for this value to be populated. + */ + void SickLMS2xx::GetSickMeanValues( const uint8_t sick_sample_size, + unsigned int * const measurement_values, + unsigned int & num_measurement_values, + unsigned int * const sick_telegram_index, + unsigned int * const sick_real_time_scan_index ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickMeanValues: Sick LMS is not initialized!"); + } + + /* Declare message objects */ + SickLMS2xxMessage response; + + /* Declare some useful variables and a buffer */ + uint8_t payload_buffer[SickLMS2xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + try { + + /* Restore original operating mode */ + _setSickOpModeMonitorStreamMeanValues(sick_sample_size); + + /* Receive a data frame from the stream. (NOTE: Can take 10+ seconds for a reply) */ + _recvMessage(response,DEFAULT_SICK_LMS_2XX_SICK_MEAN_VALUES_MESSAGE_TIMEOUT); + + /* Check that our payload has the proper command byte of 0xB0 */ + if(response.GetCommandCode() != 0xB6) { + throw SickIOException("SickLMS2xx::GetSickMeanValues: Unexpected message!"); + } + + /* Acquire the payload buffer and length*/ + response.GetPayload(payload_buffer); + + /* Define a local scan profile object */ + sick_lms_2xx_scan_profile_b6_t sick_scan_profile; + + /* Initialize the profile */ + memset(&sick_scan_profile,0,sizeof(sick_lms_2xx_scan_profile_b6_t)); + + /* Parse the message payload */ + _parseSickScanProfileB6(&payload_buffer[1],sick_scan_profile); + + /* Return the request values! */ + num_measurement_values = sick_scan_profile.sick_num_measurements; + + for (unsigned int i = 0; i < num_measurement_values; i++) { + /* Copy the measurement value */ + measurement_values[i] = sick_scan_profile.sick_measurements[i]; + } + + /* If requested, copy the real time scan index */ + if(sick_real_time_scan_index) { + *sick_real_time_scan_index = sick_scan_profile.sick_real_time_scan_index; + } + + /* If requested, copy the telegram index */ + if(sick_telegram_index) { + *sick_telegram_index = sick_scan_profile.sick_telegram_index; + } + + } + + /* Handle any config exceptions */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a timeout exception */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle anything else */ + catch(...) { + std::cerr << "SickLMS2xx::GetSickMeanValues: Unknown exception!!!" << std::endl; + throw; + } + + } + + /** + * \brief Returns the most recent mean measured values from the specified subrange + * \param sick_sample_size Number of consecutive scans used to compute the mean values + * \param sick_subrange_start_index The starting index of the desired subrange (See below for example) + * \param sick_subrange_stop_index The stopping index of the desired subrange (See below for example) + * \param *measurement_values Destination buffer for holding the current round of measured value + * \param &num_measurement_values Number of values stored in measurement_values + * \param *sick_telegram_index The telegram index assigned to the message (modulo: 256) (Default: NULL => Not wanted) + * \param *sick_real_time_scan_index The real time scan index for the latest message (module 256) (Default: NULL => Not wanted) + * + * NOTE: Calling this function will return either range or reflectivity measurements + * depending upon the current measuring mode of the device. + * + * NOTE: Real-time scan indices must be enabled by setting the corresponding availability + * of the Sick LMS 2xx for this value to be populated. + * + * EXAMPLE: Using a 180/0.5 Sick LMS variant, a subrange over the scan area [0,10.5] would + * correspond to setting the index arguments as follows: sick_subrange_start = 1, + * sick_subrange_stop = 22 + */ + void SickLMS2xx::GetSickMeanValuesSubrange( const uint8_t sick_sample_size, + const uint16_t sick_subrange_start_index, + const uint16_t sick_subrange_stop_index, + unsigned int * const measurement_values, + unsigned int & num_measurement_values, + unsigned int * const sick_telegram_index, + unsigned int * const sick_real_time_scan_index ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickMeanValuesSubrange: Sick LMS is not initialized!"); + } + + /* Declare message objects */ + SickLMS2xxMessage response; + + /* Declare some useful variables and a buffer */ + uint8_t payload_buffer[SickLMS2xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + try { + + /* Restore original operating mode */ + _setSickOpModeMonitorStreamMeanValuesSubrange(sick_sample_size,sick_subrange_start_index,sick_subrange_stop_index); + + /* Receive a data frame from the stream. */ + _recvMessage(response,DEFAULT_SICK_LMS_2XX_SICK_MEAN_VALUES_MESSAGE_TIMEOUT); + + /* Check that our payload has the proper command byte of 0xB0 */ + if(response.GetCommandCode() != 0xBF) { + throw SickIOException("SickLMS2xx::GetSickMeanValuesSubrange: Unexpected message!"); + } + + /* Acquire the payload buffer and length*/ + response.GetPayload(payload_buffer); + + /* Define a local scan profile object */ + sick_lms_2xx_scan_profile_bf_t sick_scan_profile; + + /* Initialize the profile */ + memset(&sick_scan_profile,0,sizeof(sick_lms_2xx_scan_profile_bf_t)); + + /* Parse the message payload */ + _parseSickScanProfileBF(&payload_buffer[1],sick_scan_profile); + + /* Return the request values! */ + num_measurement_values = sick_scan_profile.sick_num_measurements; + + for (unsigned int i = 0; i < num_measurement_values; i++) { + + /* Copy the measurement value */ + measurement_values[i] = sick_scan_profile.sick_measurements[i]; + + } + + /* If requested, copy the real time scan index */ + if(sick_real_time_scan_index) { + *sick_real_time_scan_index = sick_scan_profile.sick_real_time_scan_index; + } + + /* If requested, copy the telegram index */ + if(sick_telegram_index) { + *sick_telegram_index = sick_scan_profile.sick_telegram_index; + } + + } + + /* Handle any config exceptions */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Handle a timeout exception */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Handle any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle anything else */ + catch(...) { + std::cerr << "SickLMS2xx::GetMeanValuesSubrange: Unknown exception!!!" << std::endl; + throw; + } + + } + + /** + * \brief Acquire the Sick LMS 2xx status + * \return The status of the device + * + * NOTE: This method also updated the local view of all other information + * returned with a status request. + */ + sick_lms_2xx_status_t SickLMS2xx::GetSickStatus( ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::GetSickStatus: Sick LMS is not initialized!"); + } + + try { + + /* Refresh the status info! */ + _getSickStatus(); + + } + + /* Catch any timeout exceptions */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Catch any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Catch any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Catch anything else */ + catch(...) { + std::cerr << "SickLMS2xx::GetSickStatus: Unknown exception!" << std::endl; + throw; + } + + /* Return the latest Sick status */ + return (sick_lms_2xx_status_t)_sick_operating_status.sick_device_status; + } + + /** + * \brief Indicates whether the device is an LMS Fast + */ + bool SickLMS2xx::IsSickLMS2xxFast() const throw(SickConfigException) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::IsSickLMS2xxFast: Sick LMS is not initialized!"); + } + + return (_sick_type == SICK_LMS_TYPE_211_S14 || + _sick_type == SICK_LMS_TYPE_221_S14 || + _sick_type == SICK_LMS_TYPE_291_S14); + + } + + /** + * \brief Reset the Sick LMS 2xx active field values + * NOTE: Considered successful if the LMS ready message is received. + */ + void SickLMS2xx::ResetSick( ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) { + + /* Ensure the device is initialized */ + if (!_sick_initialized) { + throw SickConfigException("SickLMS2xx::ResetSick: Sick LMS is not initialized!"); + } + + SickLMS2xxMessage message,response; + uint8_t payload[SickLMS2xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Construct the reset command */ + payload[0] = 0x10; // Request field reset + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload,1); + + std::cout << "\tResetting the device..." << std::endl; + std::cout << "\tWaiting for Power on message..." << std::endl; + + try { + + /* Send the reset command and wait for the reply */ + _sendMessageAndGetReply(message,response,0x91,(unsigned int)60e6,DEFAULT_SICK_LMS_2XX_NUM_TRIES); + + std::cout << "\t\tPower on message received!" << std::endl; + std::cout << "\tWaiting for LMS Ready message..." << std::endl; + + /* Set terminal baud to the detected rate to get the LMS ready message */ + _setTerminalBaud(_baudToSickBaud(DEFAULT_SICK_LMS_2XX_SICK_BAUD)); + + /* Receive the LMS ready message after power on */ + _recvMessage(response,(unsigned int)30e6); + + /* Verify the response */ + if(response.GetCommandCode() != 0x90) { + std::cerr << "SickLMS2xx::ResetSick: Unexpected reply! (assuming device has been reset!)" << std::endl; + } else { + std::cout << "\t\tLMS Ready message received!" << std::endl; + } + std::cout << std::endl; + + /* Reinitialize and sync the device */ + Initialize(_desired_session_baud); + + } + + /* Catch any timeout exceptions */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Catch any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Catch any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Catch anything else */ + catch(...) { + std::cerr << "SickLMS2xx::ResetSick: Unknown exception!!!" << std::endl; + throw; + } + + std::cout << "\tRe-initialization sucessful. LMS is ready to go!" << std::endl; + + } + + /** + * \brief Acquire the Sick LMS's status as a printable string + * \return The Sick LMS status as a well-formatted string + */ + std::string SickLMS2xx::GetSickStatusAsString( ) const { + + std::stringstream str_stream; + + str_stream << "\t=============== Sick LMS Status ===============" << std::endl; + + /* If Sick is initialized then print the status! */ + if (_sick_initialized) { + + str_stream << "\tVariant: " << _sickVariantToString(_sick_operating_status.sick_variant) << std::endl; + str_stream << "\tSensor Status: " << SickStatusToString((sick_lms_2xx_status_t)_sick_operating_status.sick_device_status) << std::endl; + str_stream << "\tScan Angle: " << GetSickScanAngle() << " (deg)" << std::endl; + str_stream << "\tScan Resolution: " << GetSickScanResolution() << " (deg)" << std::endl; + str_stream << "\tOperating Mode: " << SickOperatingModeToString(GetSickOperatingMode()) << std::endl; + str_stream << "\tMeasuring Mode: " << SickMeasuringModeToString(GetSickMeasuringMode()) << std::endl; + str_stream << "\tMeasuring Units: " << SickMeasuringUnitsToString(GetSickMeasuringUnits()) << std::endl; + + } + else { + + str_stream << "\t Unknown (Device is not initialized)" << std::endl; + + } + + str_stream << "\t===============================================" << std::endl; + + return str_stream.str(); + } + + /** + * \brief Acquire the Sick LMS's operating params as a printable string + * \return The Sick LMS operating params as a well-formatted string + */ + std::string SickLMS2xx::GetSickSoftwareVersionAsString( ) const { + + std::stringstream str_stream; + + str_stream << "\t============== Sick LMS Software ==============" << std::endl; + + if (_sick_initialized) { + + str_stream << "\tSystem Software: " << std::string((char *)_sick_software_status.sick_system_software_version) << std::endl; + str_stream << "\tSystem Boot PROM Software: " << std::string((char *)_sick_software_status.sick_prom_software_version) << std::endl; + + } + else { + + str_stream << "\t Unknown (Device is not initialized)" << std::endl; + + } + + str_stream << "\t===============================================" << std::endl; + + return str_stream.str(); + } + + /** + * \brief Acquire the Sick LMS's config as a printable string + * \return The Sick LMS config as a well-formatted string + */ + std::string SickLMS2xx::GetSickConfigAsString( ) const { + + std::stringstream str_stream; + + str_stream<< "\t=============== Sick LMS Config ===============" << std::endl; + + if (_sick_initialized) { + + str_stream << "\tBlanking Value: " << _sick_device_config.sick_blanking << std::endl; + + if(_isSickLMS211() || _isSickLMS221() || _isSickLMS291()) { + str_stream << "\tSensitivity: " << SickSensitivityToString(GetSickSensitivity()) << std::endl; + } + else { + str_stream << "\tPeak Thresh: " << SickPeakThresholdToString((sick_lms_2xx_peak_threshold_t)_sick_device_config.sick_peak_threshold) << std::endl; + str_stream << "\tStop Thresh: " << (unsigned int)_sick_device_config.sick_stop_threshold << std::endl; + } + + str_stream << "\tAvailability: " << _sickAvailabilityToString(_sick_device_config.sick_availability_level) << std::endl; + str_stream << "\tMeasuring Mode: " << SickMeasuringModeToString((sick_lms_2xx_measuring_mode_t)_sick_device_config.sick_measuring_mode) << std::endl; + str_stream << "\tMeasuring Units: " << SickMeasuringUnitsToString((sick_lms_2xx_measuring_units_t)_sick_device_config.sick_measuring_units) << std::endl; + str_stream << "\tTemporary Field: " << _sickTemporaryFieldToString(_sick_device_config.sick_temporary_field) << std::endl; + str_stream << "\tSubtractive Fields: " << _sickSubtractiveFieldsToString(_sick_device_config.sick_subtractive_fields) << std::endl; + str_stream << "\tMultiple Evaluation: " << (unsigned int)_sick_device_config.sick_multiple_evaluation << std::endl; + str_stream << "\tSuppressed Objects Multiple Evaluation: " << (unsigned int)_sick_device_config.sick_multiple_evaluation_suppressed_objects << std::endl; + str_stream << "\tDazzling Multiple Evaluation: " << (unsigned int)_sick_device_config.sick_dazzling_multiple_evaluation << std::endl; + str_stream << "\tRestart Mode: " << _sickRestartToString(_sick_device_config.sick_restart) << std::endl; + str_stream << "\tRestart Time: " << (unsigned int)_sick_device_config.sick_restart_time << std::endl; + str_stream << "\tFields B,C Restart Time: " << (unsigned int)_sick_device_config.sick_fields_b_c_restart_times << std::endl; + str_stream << "\tContour Function A: " << _sickContourFunctionToString(_sick_device_config.sick_contour_a_reference) << std::endl; + str_stream << "\tContour Function B: " << _sickContourFunctionToString(_sick_device_config.sick_contour_b_reference) << std::endl; + str_stream << "\tContour Function C: " << _sickContourFunctionToString(_sick_device_config.sick_contour_c_reference) << std::endl; + str_stream << "\tPixel Oriented Evaluation: " << (unsigned int)_sick_device_config.sick_pixel_oriented_evaluation << std::endl; + str_stream << "\tSingle Measured Value Eval. Mode: " << (unsigned int)_sick_device_config.sick_single_measured_value_evaluation_mode << std::endl; + + } + else { + + str_stream << "\t Unknown (Device is not initialized)" << std::endl; + + } + + str_stream << "\t===============================================" << std::endl; + + return str_stream.str(); + } + + /** + * \brief Prints ths status of the Sick LMS 2xx unit + */ + void SickLMS2xx::PrintSickStatus() const { + std::cout << GetSickStatusAsString() << std::endl; + } + + /** + * \brief Prints out relevant software versioning information + */ + void SickLMS2xx::PrintSickSoftwareVersion() const { + std::cout << GetSickSoftwareVersionAsString() << std::endl; + } + + /** + * \brief Prints out the Sick LMS configurations parameters + */ + void SickLMS2xx::PrintSickConfig() const { + std::cout << GetSickConfigAsString() << std::endl; + } + + /** + * \brief Converts the Sick LMS type to a corresponding string + * \param sick_type The device type + * \return Sick LMS type as a string + */ + std::string SickLMS2xx::SickTypeToString( const sick_lms_2xx_type_t sick_type ) { + + switch(sick_type) { + case SICK_LMS_TYPE_200_30106: + return "Sick LMS 200-30106"; + case SICK_LMS_TYPE_211_30106: + return "Sick LMS 211-30106"; + case SICK_LMS_TYPE_211_30206: + return "Sick LMS 211-30206"; + case SICK_LMS_TYPE_211_S07: + return "Sick LMS 211-S07"; + case SICK_LMS_TYPE_211_S14: + return "Sick LMS 211-S14"; + case SICK_LMS_TYPE_211_S15: + return "Sick LMS 211-S15"; + case SICK_LMS_TYPE_211_S19: + return "Sick LMS 211-S19"; + case SICK_LMS_TYPE_211_S20: + return "Sick LMS 211-S20"; + case SICK_LMS_TYPE_220_30106: + return "Sick LMS 220-30106"; + case SICK_LMS_TYPE_221_30106: + return "Sick LMS 221-30106"; + case SICK_LMS_TYPE_221_30206: + return "Sick LMS 221-30206"; + case SICK_LMS_TYPE_221_S07: + return "Sick LMS 221-S07"; + case SICK_LMS_TYPE_221_S14: + return "Sick LMS 221-S14"; + case SICK_LMS_TYPE_221_S15: + return "Sick LMS 221-S15"; + case SICK_LMS_TYPE_221_S16: + return "Sick LMS 221-S16"; + case SICK_LMS_TYPE_221_S19: + return "Sick LMS 221-S19"; + case SICK_LMS_TYPE_221_S20: + return "Sick LMS 221-S20"; + case SICK_LMS_TYPE_291_S05: + return "Sick LMS 291-S05"; + case SICK_LMS_TYPE_291_S14: + return "Sick LMS 291-S14"; + case SICK_LMS_TYPE_291_S15: + return "Sick LMS 291-S15"; + default: + return "Unknown!"; + } + + } + + /** + * \brief Converts integer to corresponding Sick LMS scan angle + * \param scan_angle_int Scan angle (FOV) as an integer (e.g. 90,100,180) + */ + sick_lms_2xx_scan_angle_t SickLMS2xx::IntToSickScanAngle( const int scan_angle_int ) { + + switch(scan_angle_int) { + case 90: + return SICK_SCAN_ANGLE_90; + case 100: + return SICK_SCAN_ANGLE_100; + case 180: + return SICK_SCAN_ANGLE_180; + default: + return SICK_SCAN_ANGLE_UNKNOWN; + } + + } + + /** + * \brief Converts integer to corresponding Sick LMS scan resolution + * \param scan_resolution_int Scan resolution as an integer (e.g. 25,50,100) + */ + sick_lms_2xx_scan_resolution_t SickLMS2xx::IntToSickScanResolution( const int scan_resolution_int ) { + + switch(scan_resolution_int) { + case 25: + return SICK_SCAN_RESOLUTION_25; + case 50: + return SICK_SCAN_RESOLUTION_50; + case 100: + return SICK_SCAN_RESOLUTION_100; + default: + return SICK_SCAN_RESOLUTION_UNKNOWN; + } + + } + + /** + * \brief Converts double to corresponding Sick LMS scan resolution + * \param scan_resolution_double Scan resolution as a double (e.g. 0.25,0.5,1.0) + */ + sick_lms_2xx_scan_resolution_t SickLMS2xx::DoubleToSickScanResolution( const double scan_resolution_double ) { + return IntToSickScanResolution((const int)(scan_resolution_double*100)); + } + + /** + * \brief Converts Sick LMS baud to a corresponding string + * \param baud_rate The baud rate to be represented as a string + * \return The string representation of the baud rate + */ + std::string SickLMS2xx::SickBaudToString( const sick_lms_2xx_baud_t baud_rate ) { + + switch(baud_rate) { + case SICK_BAUD_9600: + return "9600bps"; + case SICK_BAUD_19200: + return "19200bps"; + case SICK_BAUD_38400: + return "38400bps"; + case SICK_BAUD_500K: + return "500Kbps"; + default: + return "Unknown!"; + } + + } + + /** + * \brief Converts integer to corresponding Sick LMS baud + * \param baud_str Baud rate as integer (e.g. 9600,19200,38400,500000) + */ + sick_lms_2xx_baud_t SickLMS2xx::IntToSickBaud( const int baud_int ) { + + switch(baud_int) { + case 9600: + return SICK_BAUD_9600; + case 19200: + return SICK_BAUD_19200; + case 38400: + return SICK_BAUD_38400; + case 500000: + return SICK_BAUD_500K; + default: + return SICK_BAUD_UNKNOWN; + } + + } + + /** + * \brief Converts string to corresponding Sick LMS baud + * \param baud_str Baud rate as string (e.g. "9600","19200","38400","500000") + */ + sick_lms_2xx_baud_t SickLMS2xx::StringToSickBaud( const std::string baud_str ) { + + int baud_int; + std::istringstream input_stream(baud_str); + input_stream >> baud_int; + + return IntToSickBaud(baud_int); + + } + + /** + * \brief Converts the Sick LMS 2xx status code to a string + * \param sick_status The device status + * \return A string corresponding to the given status code + */ + std::string SickLMS2xx::SickStatusToString( const sick_lms_2xx_status_t sick_status ) { + + /* Return a string */ + if(sick_status != SICK_STATUS_OK) { + return "Error (possibly fatal)"; + } + return "OK!"; + + } + + /** + * \brief Converts the Sick measuring mode to a corresponding string + * \param sick_measuring_mode The Sick measuring mode + * \return The corresponding string + */ + std::string SickLMS2xx::SickMeasuringModeToString( const sick_lms_2xx_measuring_mode_t sick_measuring_mode ) { + + switch(sick_measuring_mode) { + case SICK_MS_MODE_8_OR_80_FA_FB_DAZZLE: + return "8m/80m; fields A,B,Dazzle"; + case SICK_MS_MODE_8_OR_80_REFLECTOR: + return "8m/80m; 3 reflector bits"; + case SICK_MS_MODE_8_OR_80_FA_FB_FC: + return "8m/80m; fields A,B,C"; + case SICK_MS_MODE_16_REFLECTOR: + return "16m; 4 reflector bits"; + case SICK_MS_MODE_16_FA_FB: + return "16m; fields A & B"; + case SICK_MS_MODE_32_REFLECTOR: + return "32m; 2 reflector bits"; + case SICK_MS_MODE_32_FA: + return "32m; field A"; + case SICK_MS_MODE_32_IMMEDIATE: + return "32m; immediate"; + case SICK_MS_MODE_REFLECTIVITY: + return "Reflectivity"; + default: + return "Unknown"; + } + } + + /** + * \brief Converts the Sick operating mode to a corresponding string + * \param sick_operating_mode The Sick operating mode + * \return The corresponding string + */ + std::string SickLMS2xx::SickOperatingModeToString( const sick_lms_2xx_operating_mode_t sick_operating_mode ) { + + switch(sick_operating_mode) { + case SICK_OP_MODE_INSTALLATION: + return "Installation Mode"; + case SICK_OP_MODE_DIAGNOSTIC: + return "Diagnostic Mode"; + case SICK_OP_MODE_MONITOR_STREAM_MIN_VALUE_FOR_EACH_SEGMENT: + return "Stream mim measured values for each segment"; + case SICK_OP_MODE_MONITOR_TRIGGER_MIN_VALUE_ON_OBJECT: + return "Min measured value for each segment when object detected"; + case SICK_OP_MODE_MONITOR_STREAM_MIN_VERT_DIST_TO_OBJECT: + return "Min vertical distance"; + case SICK_OP_MODE_MONITOR_TRIGGER_MIN_VERT_DIST_TO_OBJECT: + return "Min vertical distance when object detected"; + case SICK_OP_MODE_MONITOR_STREAM_VALUES: + return "Stream all measured values"; + case SICK_OP_MODE_MONITOR_REQUEST_VALUES: + return "Request measured values"; + case SICK_OP_MODE_MONITOR_STREAM_MEAN_VALUES: + return "Stream mean measured values"; + case SICK_OP_MODE_MONITOR_STREAM_VALUES_SUBRANGE: + return "Stream measured value subrange"; + case SICK_OP_MODE_MONITOR_STREAM_MEAN_VALUES_SUBRANGE: + return "Stream mean measured value subrange"; + case SICK_OP_MODE_MONITOR_STREAM_VALUES_WITH_FIELDS: + return "Stream measured and field values"; + case SICK_OP_MODE_MONITOR_STREAM_VALUES_FROM_PARTIAL_SCAN: + return "Stream measured values from partial scan"; + case SICK_OP_MODE_MONITOR_STREAM_RANGE_AND_REFLECT_FROM_PARTIAL_SCAN: + return "Stream range w/ reflectivity from partial scan"; + case SICK_OP_MODE_MONITOR_STREAM_MIN_VALUES_FOR_EACH_SEGMENT_SUBRANGE: + return "Stream min measured values for each segment over a subrange"; + case SICK_OP_MODE_MONITOR_NAVIGATION: + return "Output navigation data records"; + case SICK_OP_MODE_MONITOR_STREAM_RANGE_AND_REFLECT: + return "Stream range w/ reflectivity values"; + default: + return "Unknown!"; + }; + + } + + /** + * \brief Converts Sick LMS 2xx sensitivity level to a corresponding string + * \param sick_sensitivity Sick sensitivity level + * \return The corresponding string + */ + std::string SickLMS2xx::SickSensitivityToString( const sick_lms_2xx_sensitivity_t sick_sensitivity ) { + + switch(sick_sensitivity) { + case SICK_SENSITIVITY_STANDARD: + return "Standard (~30m @ 10% reflectivity)"; + case SICK_SENSITIVITY_MEDIUM: + return "Medium (~25m @ 10% reflectivity)"; + case SICK_SENSITIVITY_LOW: + return "Low (~20m @ 10% relfectivity)"; + case SICK_SENSITIVITY_HIGH: + return "High (~42m @ 10% reflectivity)"; + default: + return "Unknown!"; + } + + } + + /** + * \brief Converts Sick LMS 2xx peak threshold to a corresponding string + * \param sick_peak_threshold Sick sensitivity level + * \return The corresponding string + */ + std::string SickLMS2xx::SickPeakThresholdToString( const sick_lms_2xx_peak_threshold_t sick_peak_threshold ) { + + switch(sick_peak_threshold) { + case SICK_PEAK_THRESHOLD_DETECTION_WITH_NO_BLACK_EXTENSION: + return "Peak detection, no black extension"; + case SICK_PEAK_THRESHOLD_DETECTION_WITH_BLACK_EXTENSION: + return "Peak detection w/ black extension"; + case SICK_PEAK_THRESHOLD_NO_DETECTION_WITH_NO_BLACK_EXTENSION: + return "No peak detection, no black extension"; + case SICK_PEAK_THRESHOLD_NO_DETECTION_WITH_BLACK_EXTENSION: + return "No peak detection w/ black extension"; + default: + return "Unknown!"; + } + + } + + /** + * \brief Converts the Sick LMS measurement units to a corresponding string + * \param sick_units The measuring units + * \return The corresponding string + */ + std::string SickLMS2xx::SickMeasuringUnitsToString( const sick_lms_2xx_measuring_units_t sick_units ) { + + /* Return the proper string */ + switch(sick_units) { + case SICK_MEASURING_UNITS_CM: + return "Centimeters (cm)"; + case SICK_MEASURING_UNITS_MM: + return "Millimeters (mm)"; + default: + return "Unknown!"; + } + + } + + /** + * \brief Attempts to open a I/O stream using the device path given at object instantiation. + */ + void SickLMS2xx::_setupConnection() throw ( SickIOException, SickThreadException ) { + SickLMS2xx::_setupConnection(0); + } + + /** + * \brief Attempts to open a I/O stream using the device path given at object instantiation + * \param delay Delay to wait for SICK to power on. (In seconds) + */ + void SickLMS2xx::_setupConnection( const uint32_t delay ) throw ( SickIOException, SickThreadException ) { + + try { + + /* Open the device */ + if((_sick_fd = open(_sick_device_path.c_str(), O_RDWR | O_NOCTTY | O_NDELAY)) < 0) { + throw SickIOException("SickLMS2xx::_setupConnection: - Unable to open serial port"); + } + + // Sleep to allow the SICK to power on for some applications + sleep(delay); + + /* Backup the original term settings */ + if(tcgetattr(_sick_fd,&_old_term) < 0) { + throw SickIOException("SickLMS2xx::_setupConnection: tcgetattr() failed!"); + } + + /* Set the host terminal baud rate to the new speed */ + _setTerminalBaud(_baudToSickBaud(DEFAULT_SICK_LMS_2XX_SICK_BAUD)); + + } + + /* Handle any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle unknown exceptions */ + catch(...) { + std::cerr << "SickLMS2xx::_setupConnection: Unknown exception!" << std::endl; + throw; + } + + } + + /** + * \brief Closes the data connection associated with the device + */ + void SickLMS2xx::_teardownConnection( ) throw( SickIOException ) { + + /* Check whether device was initialized */ + if(!_sick_initialized) { + return; + } + + /* Restore old terminal settings */ + if (tcsetattr(_sick_fd,TCSANOW,&_old_term) < 0) { + throw SickIOException("SickLMS2xx::_teardownConnection: tcsetattr() failed!"); + } + + /* Actually close the device */ + if(close(_sick_fd) != 0) { + throw SickIOException("SickLMS2xx::_teardownConnection: close() failed!"); + } + + } + + /** + * \brief Flushes terminal I/O buffers + */ + void SickLMS2xx::_flushTerminalBuffer( ) throw ( SickThreadException ) { + + try { + + /* Acquire access to the data stream */ + _sick_buffer_monitor->AcquireDataStream(); + + /* Nobody is reading a message, so safely flush! */ + if (tcflush(_sick_fd,TCIOFLUSH) != 0) { + throw SickThreadException("SickLMS2xx::_flushTerminalBuffer: tcflush() failed!"); + } + + /* Attempt to release the data stream */ + _sick_buffer_monitor->ReleaseDataStream(); + + } + + /* Handle thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* A sanity check */ + catch(...) { + std::cerr << "SickLMS2xx::_flushTerminalBuffer: Unknown exception!" << std::endl; + throw; + } + + } + + /** + * \brief Sends a message and searches for the corresponding reply + * \param &send_message The message to be sent to the Sick LMS 2xx unit + * \param &recv_message The expected message reply from the Sick LMS + * \param timeout_value The epoch to wait before considering a sent frame lost (in usecs) + * \param num_tries The number of times to try and transmit the message + * before quitting + * + * NOTE: Uses the 0x80 response code rule for looking for the response message + */ + void SickLMS2xx::_sendMessageAndGetReply( const SickLMS2xxMessage &send_message, + SickLMS2xxMessage &recv_message, + const unsigned int timeout_value, + const unsigned int num_tries ) throw( SickIOException, SickThreadException, SickTimeoutException ) { + + uint8_t sick_reply_code = send_message.GetCommandCode() + 0x80; + + try { + + /* Send a message and get reply using a reply code */ + _sendMessageAndGetReply(send_message,recv_message,sick_reply_code,timeout_value,num_tries); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout) { + /* For now just rethrow it */ + throw; + } + + /* Handle a thread exception */ + catch (SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_error) { + std::cerr << sick_io_error.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS2xx::_sendMessageAndGetReply: Unknown exception!!!" << std::endl; + throw; + } + + } + + /** + * \brief Sends a message and searches for the reply with given reply code + * \param &send_message The message to be sent to the Sick LMS 2xx unit + * \param &recv_message The expected message reply from the Sick LMS + * \param reply_code The reply code associated with the expected messgage + * \param timeout_value The epoch to wait before considering a sent frame lost (in usecs) + * \param num_tries The number of times to send the message in the event the LMS fails to reply + */ + void SickLMS2xx::_sendMessageAndGetReply( const SickLMS2xxMessage &send_message, + SickLMS2xxMessage &recv_message, + const uint8_t reply_code, + const unsigned int timeout_value, + const unsigned int num_tries ) throw( SickIOException, SickThreadException, SickTimeoutException ) { + + try { + + /* Attempt to flush the terminal buffer */ + _flushTerminalBuffer(); + + /* Send a message and get reply using parent's method */ + SickLIDAR< SickLMS2xxBufferMonitor, SickLMS2xxMessage >::_sendMessageAndGetReply(send_message,recv_message,&reply_code,1,DEFAULT_SICK_LMS_2XX_BYTE_INTERVAL,timeout_value,num_tries); + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout) { + throw; + } + + /* Handle a thread exception */ + catch (SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_error) { + std::cerr << sick_io_error.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLMS2xx::_sendMessageAndGetReply: Unknown exception!!!" << std::endl; + throw; + } + + } + + /** + * \brief Sets the baud rate for the current communication session + * \param baud_rate The desired baud rate + */ + void SickLMS2xx::_setSessionBaud(const sick_lms_2xx_baud_t baud_rate) throw ( SickIOException, SickThreadException, SickTimeoutException ){ + + SickLMS2xxMessage message, response; + + uint8_t payload[SickLMS2xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + + /* Another sanity check */ + if(baud_rate == SICK_BAUD_UNKNOWN) { + throw SickIOException("SickLMS2xx::_setSessionBaud: Undefined baud rate!"); + } + + /* Construct the command telegram */ + payload[0] = 0x20; + payload[1] = baud_rate; + + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload,2); + + try { + + /* Send the status request and get a reply */ + _sendMessageAndGetReply(message,response,DEFAULT_SICK_LMS_2XX_SICK_MESSAGE_TIMEOUT,DEFAULT_SICK_LMS_2XX_NUM_TRIES); + + /* Set the host terminal baud rate to the new speed */ + _setTerminalBaud(baud_rate); + + /* Sick likes a sleep here */ + usleep(250000); + + } + + /* Catch a timeout */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Catch any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Catch any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Catch anything else */ + catch(...) { + std::cerr << "SickLMS2xx::_getSickErrors: Unknown exception!!!" << std::endl; + throw; + } + + } + + /** + * \brief Attempts to detect whether the LMS is operating at the given baud rate + * \param baud_rate The baud rate to use when "pinging" the Sick LMS 2xx + */ + bool SickLMS2xx::_testSickBaud(const sick_lms_2xx_baud_t baud_rate) throw( SickIOException, SickThreadException ) { + + try { + + /* Another sanity check */ + if(baud_rate == SICK_BAUD_UNKNOWN) { + throw SickIOException("SickLMS2xx::_testBaudRate: Undefined baud rate!"); + } + + /* Attempt to get status information at the current baud */ + std::cout << "\t\tChecking " << SickBaudToString(baud_rate) << "..." << std::endl; + + /* Set the host terminal baud rate to the test speed */ + _setTerminalBaud(baud_rate); + + try { + + /* Check to see if the Sick replies! */ + _getSickErrors(); + + } + + /* Catch a timeout exception */ + catch(SickTimeoutException &sick_timeout_exception) { + /* This means that the current baud rate timed out! */ + return false; + } + + /* Catch anything else and throw it away */ + catch(...) { + std::cerr << "SickLMS2xx::_testBaudRate: Unknown exception!" << std::endl; + throw; + } + + } + + /* Handle any IO exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Handle thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* A safety net */ + catch(...) { + std::cerr << "SickLMS2xx::_testBaudRate: Unknown exception!!!" << std::endl; + throw; + } + + /* Success! */ + return true; + + } + + /** + * \brief Sets the local terminal baud rate + * \param baud_rate The desired terminal baud rate + */ + void SickLMS2xx::_setTerminalBaud( const sick_lms_2xx_baud_t baud_rate ) throw( SickIOException, SickThreadException ) { + + struct termios term; + +#ifdef HAVE_LINUX_SERIAL_H + struct serial_struct serial; +#endif + + try { + + /* If seeting baud to 500k */ + if (baud_rate == SICK_BAUD_500K) { + +#ifdef HAVE_LINUX_SERIAL_H + + /* Get serial attributes */ + if(ioctl(_sick_fd,TIOCGSERIAL,&serial) < 0) { + throw SickIOException("SickLMS2xx::_setTerminalBaud: ioctl() failed!"); + } + + /* Set the custom devisor */ + serial.flags |= ASYNC_SPD_CUST; + serial.custom_divisor = 48; // for FTDI USB/serial converter divisor is 240/5 + + /* Set the new attibute values */ + if(ioctl(_sick_fd,TIOCSSERIAL,&serial) < 0) { + throw SickIOException("SickLMS2xx::_setTerminalBaud: ioctl() failed!"); + } + +#else + throw SickIOException("SickLMS2xx::_setTerminalBaud - 500K baud is only supported under Linux!"); +#endif + + } + +#ifdef HAVE_LINUX_SERIAL_H + + else { /* Using a standard baud rate */ + + /* We let the next few errors slide in case USB adapter is being used */ + if(ioctl(_sick_fd,TIOCGSERIAL,&serial) < 0) { + std::cerr << "SickLMS2xx::_setTermSpeed: ioctl() failed while trying to get serial port info!" << std::endl; + std::cerr << "\tNOTE: This is normal when connected via USB!" < 250) { + throw SickConfigException("SickLMS2xx::_setSickOpModeMonitorStreamMeanValues: Invalid sample size!"); + } + + std::cout << "\tRequesting mean value data stream (sample size = " << (int)sample_size << ")..." << std::endl; + + try { + + /* Attempt to switch modes */ + _switchSickOperatingMode(SICK_OP_MODE_MONITOR_STREAM_MEAN_VALUES,&sample_size); + + } + + /* Catch any config exceptions */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Catch any timeout exceptions */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Catch any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Catch any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Catch anything else */ + catch(...) { + std::cerr << "SickLMS2xx::_setSickOpModeStreamRangeFromPartialScan: Unknown exception!!!" << std::endl; + throw; + } + + /* Assign the new operating mode */ + _sick_operating_status.sick_operating_mode = SICK_OP_MODE_MONITOR_STREAM_MEAN_VALUES; + + /* Buffer the current sample size! */ + _sick_mean_value_sample_size = sample_size; + + /* Reset these parameters */ + _sick_values_subrange_start_index = _sick_values_subrange_stop_index = 0; + + std::cout << "\t\tData stream started!" << std::endl; + + } + + } + + /** + * \brief Sets the device to monitor mode and tells it to send a measured value subrange + * \param subrange_start_index The starting index of the desired subrange + * \param subrange_stop_index The stopping index of the desired subrange + */ + void SickLMS2xx::_setSickOpModeMonitorStreamValuesSubrange( const uint16_t subrange_start_index, const uint16_t subrange_stop_index ) + throw( SickConfigException, SickIOException, SickThreadException, SickTimeoutException) { + + /* Check if mode should be changed */ + if (_sick_operating_status.sick_operating_mode != SICK_OP_MODE_MONITOR_STREAM_VALUES_SUBRANGE || + _sick_values_subrange_start_index != subrange_start_index || + _sick_values_subrange_stop_index != subrange_stop_index ) { + + /* Compute the maximum subregion bound */ + unsigned int max_subrange_stop_index = (unsigned int)((_sick_operating_status.sick_scan_angle*100)/_sick_operating_status.sick_scan_resolution + 1) ; + + /* Ensure the subregion is properly defined for the given variant */ + if(subrange_start_index > subrange_stop_index || subrange_start_index == 0 || subrange_stop_index > max_subrange_stop_index) { + throw SickConfigException("SickLMS2xx::_setSickOpMonitorStreamValuesSubrange: Invalid subregion bounds!"); + } + + /* Setup a few buffers */ + uint8_t mode_params[4] = {0}; + uint16_t temp_buffer = 0; + + /* Assign the subrange start index */ + temp_buffer = host_to_sick_lms_2xx_byte_order(subrange_start_index); + memcpy(mode_params,&temp_buffer,2); + + /* Assign the subrange stop index */ + temp_buffer = host_to_sick_lms_2xx_byte_order(subrange_stop_index); + memcpy(&mode_params[2],&temp_buffer,2); + + std::cout << "\tRequesting measured value stream... (subrange = [" << subrange_start_index << "," << subrange_stop_index << "])" << std::endl; + + try { + + /* Attempt to switch modes */ + _switchSickOperatingMode(SICK_OP_MODE_MONITOR_STREAM_VALUES_SUBRANGE,mode_params); + + } + + /* Catch any config exceptions */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Catch any timeout exceptions */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Catch any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Catch any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Catch anything else */ + catch(...) { + std::cerr << "SickLMS2xx::_setSickOpModeInstallation: Unknown exception!!!" << std::endl; + throw; + } + + /* Assign the new operating mode */ + _sick_operating_status.sick_operating_mode = SICK_OP_MODE_MONITOR_STREAM_VALUES_SUBRANGE; + + /* Reset this parameter */ + _sick_mean_value_sample_size = 0; + + /* Buffer the starting/stopping indices */ + _sick_values_subrange_start_index = subrange_start_index; + _sick_values_subrange_stop_index = subrange_stop_index; + + std::cout << "\t\tData stream started!" << std::endl; + + } + + } + + /** + * \brief Sets the device to monitor mode and tells it to send a mean value subrange + * \param sample_size The number of scans to consider in computing the mean measured values + * \param subrange_start_index The starting index of the desired subrange + * \param subrange_stop_index The stopping index of the desired subrange + */ + void SickLMS2xx::_setSickOpModeMonitorStreamMeanValuesSubrange( const uint16_t sample_size, const uint16_t subrange_start_index, const uint16_t subrange_stop_index ) + throw( SickConfigException, SickIOException, SickThreadException, SickTimeoutException) { + + /* Check if mode should be changed */ + if (_sick_operating_status.sick_operating_mode != SICK_OP_MODE_MONITOR_STREAM_MEAN_VALUES_SUBRANGE || + _sick_values_subrange_start_index != subrange_start_index || + _sick_values_subrange_stop_index != subrange_stop_index || + _sick_mean_value_sample_size != sample_size ) { + + /* Make sure the sample size is legit */ + if(sample_size < 2 || sample_size > 250) { + throw SickConfigException("SickLMS2xx::_setSickOpModeMonitorStreamMeanValuesSubrange: Invalid sample size!"); + } + + /* Compute the maximum subregion bound */ + unsigned int max_subrange_stop_index = (unsigned int)((_sick_operating_status.sick_scan_angle*100)/_sick_operating_status.sick_scan_resolution + 1) ; + + /* Ensure the subregion is properly defined for the given variant */ + if(subrange_start_index > subrange_stop_index || subrange_start_index == 0 || subrange_stop_index > max_subrange_stop_index) { + throw SickConfigException("SickLMS2xx::_setSickOpMonitorStreamMeanValuesSubrange: Invalid subregion bounds!"); + } + + /* Setup a few buffers */ + uint8_t mode_params[5] = {0}; + uint16_t temp_buffer = 0; + + /* Assign the sample size */ + mode_params[0] = sample_size; + + /* Assign the subrange start index */ + temp_buffer = host_to_sick_lms_2xx_byte_order(subrange_start_index); + memcpy(&mode_params[1],&temp_buffer,2); + + /* Assign the subrange stop index */ + temp_buffer = host_to_sick_lms_2xx_byte_order(subrange_stop_index); + memcpy(&mode_params[3],&temp_buffer,2); + + std::cout << "\tRequesting mean value stream... (subrange = [" << subrange_start_index << "," << subrange_stop_index << "])" << std::endl; + + try { + + /* Attempt to switch modes */ + _switchSickOperatingMode(SICK_OP_MODE_MONITOR_STREAM_MEAN_VALUES_SUBRANGE,mode_params); + + } + + /* Catch any config exceptions */ + catch(SickConfigException &sick_config_exception) { + std::cerr << sick_config_exception.what() << std::endl; + throw; + } + + /* Catch any timeout exceptions */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Catch any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Catch any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Catch anything else */ + catch(...) { + std::cerr << "SickLMS2xx::_setSickOpModeInstallation: Unknown exception!!!" << std::endl; + throw; + } + + /* Assign the new operating mode */ + _sick_operating_status.sick_operating_mode = SICK_OP_MODE_MONITOR_STREAM_MEAN_VALUES_SUBRANGE; + + /* Buffer the sample size */ + _sick_mean_value_sample_size = sample_size; + + /* Buffer the starting/stopping indices */ + _sick_values_subrange_start_index = subrange_start_index; + _sick_values_subrange_stop_index = subrange_stop_index; + + std::cout << "\t\tData stream started!" << std::endl; + + } + + } + + /** + * \brief Attempts to switch the operating mode of the Sick LMS 2xx + * \param sick_mode The desired operating mode + * \param mode_params Additional parameters required to set the new operating mode + */ + void SickLMS2xx::_switchSickOperatingMode( const uint8_t sick_mode, const uint8_t * const mode_params ) + throw( SickConfigException, SickIOException, SickThreadException, SickTimeoutException) { + + SickLMS2xxMessage message,response; + + uint8_t payload_buffer[SickLMS2xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + uint16_t num_partial_scans = 0; + + /* Construct the correct switch mode packet */ + payload_buffer[0] = 0x20; + payload_buffer[1] = sick_mode; + + switch(sick_mode) { + + case SICK_OP_MODE_INSTALLATION: + + /* Make sure the params are defined */ + if(mode_params == NULL) { + throw SickConfigException("SickLMS2xx::_switchSickOperatingMode - Requested mode requires parameters!"); + } + + memcpy(&payload_buffer[2],mode_params,8); //Copy password + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,10); + break; + + case SICK_OP_MODE_DIAGNOSTIC: + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,2); + break; + + case SICK_OP_MODE_MONITOR_STREAM_MIN_VALUE_FOR_EACH_SEGMENT: + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,2); + break; + + case SICK_OP_MODE_MONITOR_TRIGGER_MIN_VALUE_ON_OBJECT: + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,2); + break; + + case SICK_OP_MODE_MONITOR_STREAM_MIN_VERT_DIST_TO_OBJECT: + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,2); + break; + + case SICK_OP_MODE_MONITOR_TRIGGER_MIN_VERT_DIST_TO_OBJECT: + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,2); + break; + + case SICK_OP_MODE_MONITOR_STREAM_VALUES: + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,2); + break; + + case SICK_OP_MODE_MONITOR_REQUEST_VALUES: + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,2); + break; + + case SICK_OP_MODE_MONITOR_STREAM_MEAN_VALUES: + + /* Make sure the params are defined */ + if(mode_params == NULL) { + throw SickConfigException("SickLMS2xx::_switchSickOperatingMode - Requested mode requires parameters!"); + } + + payload_buffer[2] = *mode_params; + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,3); + break; + + case SICK_OP_MODE_MONITOR_STREAM_VALUES_SUBRANGE: + + /* Make sure the params are defined */ + if(mode_params == NULL) { + throw SickConfigException("SickLMS2xx::_switchSickOperatingMode - Requested mode requires parameters!"); + } + + memcpy(&payload_buffer[2],mode_params,2); //Begin range + memcpy(&payload_buffer[4],&mode_params[2],2); //End range + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,6); + break; + + case SICK_OP_MODE_MONITOR_STREAM_MEAN_VALUES_SUBRANGE: + + /* Make sure the params are defined */ + if(mode_params == NULL) { + throw SickConfigException("SickLMS2xx::_switchSickOperatingMode - Requested mode requires parameters!"); + } + + payload_buffer[2] = mode_params[0]; //Sample size + memcpy(&payload_buffer[3],&mode_params[1],2); //Begin mean range + memcpy(&payload_buffer[5],&mode_params[3],2); //End mean range + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,7); + break; + + case SICK_OP_MODE_MONITOR_STREAM_VALUES_WITH_FIELDS: + + /* Make sure the params are defined */ + if(mode_params == NULL) { + throw SickConfigException("SickLMS2xx::_switchSickOperatingMode - Requested mode requires parameters!"); + } + + memcpy(&payload_buffer[2],mode_params,2); //Start + memcpy(&payload_buffer[4],&mode_params[2],2); //End + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,6); + break; + + case SICK_OP_MODE_MONITOR_STREAM_VALUES_FROM_PARTIAL_SCAN: + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,2); + break; + + case SICK_OP_MODE_MONITOR_STREAM_RANGE_AND_REFLECT_FROM_PARTIAL_SCAN: + + /* Make sure the params are defined */ + if(mode_params == NULL) { + throw SickConfigException("SickLMS2xx::_switchSickOperatingMode - Requested mode requires parameters!"); + } + + /* Get the number of partial scans (between 1 and 5) */ + memcpy(&num_partial_scans,mode_params,2); + + /* Setup the command packet */ + memcpy(&payload_buffer[2],mode_params,num_partial_scans*4+2); + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,num_partial_scans*4+4); + break; + + case SICK_OP_MODE_MONITOR_STREAM_MIN_VALUES_FOR_EACH_SEGMENT_SUBRANGE: + + /* Make sure the params are defined */ + if(mode_params == NULL) { + throw SickConfigException("SickLMS2xx::_switchSickOperatingMode - Requested mode requires parameters!"); + } + + /* Get the number of partial scans (between 1 and 5) */ + memcpy(&num_partial_scans,mode_params,2); + + /* Setup the command packet */ + memcpy(&payload_buffer[2],mode_params,num_partial_scans*4+2); + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,num_partial_scans*4+4); + break; + + case SICK_OP_MODE_MONITOR_NAVIGATION: + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,2); + break; + + case SICK_OP_MODE_MONITOR_STREAM_RANGE_AND_REFLECT: + + /* Make sure the params are defined */ + if(mode_params == NULL) { + throw SickConfigException("SickLMS2xx::_switchSickOperatingMode - Requested mode requires parameters!"); + } + + memcpy(&payload_buffer[2],mode_params,2); //Start + memcpy(&payload_buffer[4],&mode_params[2],2); //End + message.BuildMessage(DEFAULT_SICK_LMS_2XX_SICK_ADDRESS,payload_buffer,6); + break; + + case SICK_OP_MODE_UNKNOWN: + //Let this case go straight to default + + default: + throw SickConfigException("SickLMS2xx::_switchSickOperatingMode: Unrecognized operating mode!"); + } + + try { + + /* Attempt to send the message and get the reply */ + _sendMessageAndGetReply(message,response,DEFAULT_SICK_LMS_2XX_SICK_SWITCH_MODE_TIMEOUT,DEFAULT_SICK_LMS_2XX_NUM_TRIES); + + } + + /* Catch any timeout exceptions */ + catch(SickTimeoutException &sick_timeout_exception) { + std::cerr << sick_timeout_exception.what() << std::endl; + throw; + } + + /* Catch any I/O exceptions */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + throw; + } + + /* Catch any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Catch anything else */ + catch(...) { + std::cerr << "SickLMS2xx::_switchSickOperatingMode: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the buffer */ + memset(payload_buffer,0,sizeof(payload_buffer)); + + /* Obtain the response payload */ + response.GetPayload(payload_buffer); + + /* Make sure the reply was expected */ + if(payload_buffer[1] != 0x00) { + throw SickConfigException("SickLMS2xx::_switchSickOperatingMode: configuration request failed!"); + } + + } + + /** + * \brief Parses a byte sequence into a scan profile corresponding to message B0 + * \param *src_buffer The byte sequence to be parsed + * \param &sick_scan_profile The returned scan profile for the current round of measurements + */ + void SickLMS2xx::_parseSickScanProfileB0( const uint8_t * const src_buffer, sick_lms_2xx_scan_profile_b0_t &sick_scan_profile ) const { + + /* Read block A, the number of measurments */ + sick_scan_profile.sick_num_measurements = src_buffer[0] + 256*(src_buffer[1] & 0x03); + + /* Check whether this is a partial scan */ + sick_scan_profile.sick_partial_scan_index = ((src_buffer[1] & 0x18) >> 3); + + /* Extract the measurements and Field values (if there are any) */ + _extractSickMeasurementValues(&src_buffer[2], + sick_scan_profile.sick_num_measurements, + sick_scan_profile.sick_measurements, + sick_scan_profile.sick_field_a_values, + sick_scan_profile.sick_field_b_values, + sick_scan_profile.sick_field_c_values); + + /* If the Sick is pulling real-time indices then pull them too */ + unsigned int data_offset = 2 + 2*sick_scan_profile.sick_num_measurements; + if (_returningRealTimeIndices()) { + sick_scan_profile.sick_real_time_scan_index = src_buffer[data_offset]; + data_offset++; + } + + /* Buffer the Sick telegram index */ + sick_scan_profile.sick_telegram_index = src_buffer[data_offset]; + + } + + /** + * \brief Parses a byte sequence into a scan profile corresponding to message B6 + * \param *src_buffer The byte sequence to be parsed + * \param &sick_scan_profile The returned scan profile for the current round of mean measurements + */ + void SickLMS2xx::_parseSickScanProfileB6( const uint8_t * const src_buffer, sick_lms_2xx_scan_profile_b6_t &sick_scan_profile ) const { + + /* Read Block A, the sample size used in computing the mean return */ + sick_scan_profile.sick_sample_size = src_buffer[0]; + + /* Read Block B, the number of measured values sent */ + sick_scan_profile.sick_num_measurements = src_buffer[1] + 256*(src_buffer[2] & 0x03); + + /* Read Block C, extract the range measurements and Field values (if there are any) */ + _extractSickMeasurementValues(&src_buffer[3], + sick_scan_profile.sick_num_measurements, + sick_scan_profile.sick_measurements); + + /* Read Block D, if the Sick is pulling real-time indices then pull them too */ + unsigned int data_offset = 3 + 2*sick_scan_profile.sick_num_measurements; + if (_returningRealTimeIndices()) { + sick_scan_profile.sick_real_time_scan_index = src_buffer[data_offset]; + data_offset++; + } + + /* Read Block E, buffer the Sick telegram index */ + sick_scan_profile.sick_telegram_index = src_buffer[data_offset]; + + } + + /** + * \brief Parses a byte sequence into a scan profile corresponding to message B7 + * \param *src_buffer The byte sequence to be parsed + * \param &sick_scan_profile The returned scan profile for the current round of mean measurements + */ + void SickLMS2xx::_parseSickScanProfileB7( const uint8_t * const src_buffer, sick_lms_2xx_scan_profile_b7_t &sick_scan_profile ) const { + + /* Read Block A, Sick LMS measured value subrange start index */ + sick_scan_profile.sick_subrange_start_index = src_buffer[0] + 256*src_buffer[1]; + + /* Read Block B, Sick LMS measured value subrange stop index */ + sick_scan_profile.sick_subrange_stop_index = src_buffer[2] + 256*src_buffer[3]; + + /* Read block C, the number of measurements */ + sick_scan_profile.sick_num_measurements = src_buffer[4] + 256*(src_buffer[5] & 0x03); + + /* Acquire the partial scan index (also in Block C) */ + sick_scan_profile.sick_partial_scan_index = ((src_buffer[5] & 0x18) >> 3); + + /* Read Block D, extract the range measurements and Field values (if there are any) */ + _extractSickMeasurementValues(&src_buffer[6], + sick_scan_profile.sick_num_measurements, + sick_scan_profile.sick_measurements, + sick_scan_profile.sick_field_a_values, + sick_scan_profile.sick_field_b_values, + sick_scan_profile.sick_field_c_values); + + /* Read Block E, if the Sick is pulling real-time indices then pull them too */ + unsigned int data_offset = 6 + 2*sick_scan_profile.sick_num_measurements; + if (_returningRealTimeIndices()) { + sick_scan_profile.sick_real_time_scan_index = src_buffer[data_offset]; + data_offset++; + } + + /* Read Block F, buffer the Sick telegram index */ + sick_scan_profile.sick_telegram_index = src_buffer[data_offset]; + + } + + /** + * \brief Parses a byte sequence into a scan profile corresponding to message B6 + * \param *src_buffer The byte sequence to be parsed + * \param &sick_scan_profile The returned scan profile for the current round of mean measurements + */ + void SickLMS2xx::_parseSickScanProfileBF( const uint8_t * const src_buffer, sick_lms_2xx_scan_profile_bf_t &sick_scan_profile ) const { + + /* Read Block A, the sample size used in computing the mean return */ + sick_scan_profile.sick_sample_size = src_buffer[0]; + + /* Read Block B, Sick LMS measured value subrange start index */ + sick_scan_profile.sick_subrange_start_index = src_buffer[1] + 256*src_buffer[2]; + + /* Read Block C, Sick LMS measured value subrange stop index */ + sick_scan_profile.sick_subrange_stop_index = src_buffer[3] + 256*src_buffer[4]; + + /* Read Block D, the number of measured values sent */ + sick_scan_profile.sick_num_measurements = src_buffer[5] + 256*(src_buffer[6] & 0x3F); + + /* Read Block E, extract the mean measurements */ + _extractSickMeasurementValues(&src_buffer[7], + sick_scan_profile.sick_num_measurements, + sick_scan_profile.sick_measurements); + + /* Read Block D, if the Sick is pulling real-time indices then pull them too */ + unsigned int data_offset = 7 + 2*sick_scan_profile.sick_num_measurements; + if (_returningRealTimeIndices()) { + sick_scan_profile.sick_real_time_scan_index = src_buffer[data_offset]; + data_offset++; + } + + /* Read Block E, buffer the Sick telegram index */ + sick_scan_profile.sick_telegram_index = src_buffer[data_offset]; + + } + + /** + * \brief Parses a byte sequence into a scan profile corresponding to message C4 + * \param *src_buffer The byte sequence to be parsed + * \param &sick_scan_profile The returned scan profile for the current round of measurements + */ + void SickLMS2xx::_parseSickScanProfileC4( const uint8_t * const src_buffer, sick_lms_2xx_scan_profile_c4_t &sick_scan_profile ) const { + + /* Read block A - the number of range measurments. We need the low two bits + * of the most significant byte. */ + sick_scan_profile.sick_num_range_measurements = src_buffer[0] + 256*(src_buffer[1] & 0x03); + + /* Read Block B - Extract the range measurements and Field values (if there are any) */ + _extractSickMeasurementValues(&src_buffer[2], + sick_scan_profile.sick_num_range_measurements, + sick_scan_profile.sick_range_measurements, + sick_scan_profile.sick_field_a_values, + sick_scan_profile.sick_field_b_values, + sick_scan_profile.sick_field_c_values); + + /* Read Block D - Extract the number of range measurements */ + unsigned int data_offset = 2 + 2*sick_scan_profile.sick_num_range_measurements; + sick_scan_profile.sick_num_reflect_measurements = src_buffer[data_offset] + 256*(src_buffer[data_offset+1] & 0x03); + data_offset += 2; + + /* Read Block E - Extract the reflectivity value subrange start index */ + sick_scan_profile.sick_reflect_subrange_start_index = src_buffer[data_offset] + 256*src_buffer[data_offset+1]; + data_offset += 2; + + /* Read Block F - Extract the reflectivity value subrange stop index */ + sick_scan_profile.sick_reflect_subrange_stop_index = src_buffer[data_offset] + 256*src_buffer[data_offset+1]; + data_offset += 2; + + /* Read blocks G...H. Mask out the reflectivity values and store in provided buffer. */ + for(unsigned int i=0; i < sick_scan_profile.sick_num_reflect_measurements; i++,data_offset++) { + sick_scan_profile.sick_reflect_measurements[i] = src_buffer[data_offset]; + } + + /* Read Block I - real-time scan indices */ + if (_returningRealTimeIndices()) { + sick_scan_profile.sick_real_time_scan_index = src_buffer[data_offset]; + data_offset++; + } + + /* Read Block J - the telegram scan index */ + sick_scan_profile.sick_telegram_index = src_buffer[data_offset]; + + } + + /** + * \brief Parses a byte sequence into a Sick config structure + * \param *src_buffer The byte sequence to be parsed + * \param &sick_device_config The device configuration + */ + void SickLMS2xx::_parseSickConfigProfile( const uint8_t * const src_buffer, sick_lms_2xx_device_config_t &sick_device_config ) const { + + /* Buffer Block A */ + memcpy(&sick_device_config.sick_blanking,&src_buffer[0],2); + sick_device_config.sick_blanking = sick_lms_2xx_to_host_byte_order(sick_device_config.sick_blanking); + + /* Buffer Block B */ + sick_device_config.sick_peak_threshold = src_buffer[3]; // NOTE: This value represent sensitivity for LMS 211/221/291 + sick_device_config.sick_stop_threshold = src_buffer[2]; // NOTE: This value will be 0 for LMS 211/221/291 + + /* Buffer Block C */ + sick_device_config.sick_availability_level = src_buffer[4]; + + /* Buffer Block D */ + sick_device_config.sick_measuring_mode = src_buffer[5]; + + /* Buffer Block E */ + sick_device_config.sick_measuring_units = src_buffer[6]; + + /* Buffer Block F */ + sick_device_config.sick_temporary_field = src_buffer[7]; + + /* Buffer Block G */ + sick_device_config.sick_subtractive_fields = src_buffer[8]; + + /* Buffer Block H */ + sick_device_config.sick_multiple_evaluation = src_buffer[9]; + + /* Buffer Block I */ + sick_device_config.sick_restart = src_buffer[10]; + + /* Buffer Block J */ + sick_device_config.sick_restart_time = src_buffer[11]; + + /* Buffer Block K */ + sick_device_config.sick_multiple_evaluation_suppressed_objects = src_buffer[12]; + + /* Buffer Block L */ + sick_device_config.sick_contour_a_reference = src_buffer[13]; + + /* Buffer Block M */ + sick_device_config.sick_contour_a_positive_tolerance_band = src_buffer[14]; + + /* Buffer Block N */ + sick_device_config.sick_contour_a_negative_tolerance_band = src_buffer[15]; + + /* Buffer Block O */ + sick_device_config.sick_contour_a_start_angle = src_buffer[16]; + + /* Buffer Block P */ + sick_device_config.sick_contour_a_stop_angle = src_buffer[17]; + + /* Buffer Block Q */ + sick_device_config.sick_contour_b_reference = src_buffer[18]; + + /* Buffer Block R */ + sick_device_config.sick_contour_b_positive_tolerance_band = src_buffer[19]; + + /* Buffer Block S */ + sick_device_config.sick_contour_b_negative_tolerance_band = src_buffer[20]; + + /* Buffer Block T */ + sick_device_config.sick_contour_b_start_angle = src_buffer[21]; + + /* Buffer Block U */ + sick_device_config.sick_contour_b_stop_angle = src_buffer[22]; + + /* Buffer Block V */ + sick_device_config.sick_contour_c_reference = src_buffer[23]; + + /* Buffer Block W */ + sick_device_config.sick_contour_c_positive_tolerance_band = src_buffer[24]; + + /* Buffer Block X */ + sick_device_config.sick_contour_c_negative_tolerance_band = src_buffer[25]; + + /* Buffer Block Y */ + sick_device_config.sick_contour_c_start_angle = src_buffer[26]; + + /* Buffer Block Z */ + sick_device_config.sick_contour_c_stop_angle = src_buffer[27]; + + /* Buffer Block A1 */ + sick_device_config.sick_pixel_oriented_evaluation = src_buffer[28]; + + /* Buffer Block A2 */ + sick_device_config.sick_single_measured_value_evaluation_mode = src_buffer[29]; + + /* Buffer Block A3 */ + memcpy(&sick_device_config.sick_fields_b_c_restart_times,&src_buffer[30],2); + sick_device_config.sick_fields_b_c_restart_times = + sick_lms_2xx_to_host_byte_order(sick_device_config.sick_fields_b_c_restart_times); + + /* Buffer Block A4 */ + memcpy(&sick_device_config.sick_dazzling_multiple_evaluation,&src_buffer[32],2); + sick_device_config.sick_dazzling_multiple_evaluation = + sick_lms_2xx_to_host_byte_order(sick_device_config.sick_dazzling_multiple_evaluation); + + } + + /** + * \brief Extracts the measured values (w/ flags) that were returned by the device. + * \param *byte_sequence The byte sequence holding the current measured values + * \param num_measurements The number of measurements given in the byte sequence + * \param *measured_values A buffer to hold the extracted measured values + * \param *field_a_values Stores the Field A values associated with the given measurements (Default: NULL => Not wanted) + * \param *field_b_values Stores the Field B values associated with the given measurements (Default: NULL => Not wanted) + * \param *field_c_values Stores the Field C values associated with the given measurements (Default: NULL => Not wanted) + */ + void SickLMS2xx::_extractSickMeasurementValues( const uint8_t * const byte_sequence, const uint16_t num_measurements, uint16_t * const measured_values, + uint8_t * const field_a_values, uint8_t * const field_b_values, uint8_t * const field_c_values ) const { + + /* Parse the byte sequence and fill the return buffer with range measurements... */ + switch(_sick_device_config.sick_measuring_mode) { + case SICK_MS_MODE_8_OR_80_FA_FB_DAZZLE: + { + + /* Extract the range and Field values */ + for(unsigned int i = 0; i < num_measurements; i++) { + measured_values[i] = byte_sequence[i*2] + 256*(byte_sequence[i*2+1] & 0x1F); + + if(field_a_values) { + field_a_values[i] = byte_sequence[i*2+1] & 0x20; + } + + if(field_b_values) { + field_b_values[i] = byte_sequence[i*2+1] & 0x40; + } + + if(field_c_values) { + field_c_values[i] = byte_sequence[i*2+1] & 0x80; + } + + } + + break; + } + case SICK_MS_MODE_8_OR_80_REFLECTOR: + { + + /* Extract the range and Field A */ + for(unsigned int i = 0; i < num_measurements; i++) { + measured_values[i] = byte_sequence[i*2] + 256*(byte_sequence[i*2+1] & 0x1F); + + if(field_a_values) { + field_a_values[i] = byte_sequence[i*2+1] & 0xE0; + } + + } + + break; + } + case SICK_MS_MODE_8_OR_80_FA_FB_FC: + { + + /* Extract the range and Fields A,B and C */ + for(unsigned int i = 0; i < num_measurements; i++) { + measured_values[i] = byte_sequence[i*2] + 256*(byte_sequence[i*2+1] & 0x1F); + + if(field_a_values) { + field_a_values[i] = byte_sequence[i*2+1] & 0x20; + } + + if(field_b_values) { + field_b_values[i] = byte_sequence[i*2+1] & 0x40; + } + + if(field_c_values) { + field_c_values[i] = byte_sequence[i*2+1] & 0x80; + } + + } + + break; + } + case SICK_MS_MODE_16_REFLECTOR: + { + + /* Extract the range and reflector values */ + for(unsigned int i = 0; i < num_measurements; i++) { + measured_values[i] = byte_sequence[i*2] + 256*(byte_sequence[i*2+1] & 0x3F); + + if (field_a_values) { + field_a_values[i] = byte_sequence[i*2+1] & 0xC0; + } + + } + + break; + } + case SICK_MS_MODE_16_FA_FB: + { + + /* Extract the range and Fields A and B values */ + for(unsigned int i = 0; i < num_measurements; i++) { + measured_values[i] = byte_sequence[i*2] + 256*(byte_sequence[i*2+1] & 0x3F); + + if(field_a_values) { + field_a_values[i] = byte_sequence[i*2+1] & 0x40; + } + + if(field_b_values) { + field_b_values[i] = byte_sequence[i*2+1] & 0x80; + } + + } + + break; + } + case SICK_MS_MODE_32_REFLECTOR: + { + + /* Extract the range and reflector values */ + for(unsigned int i = 0; i < num_measurements; i++) { + measured_values[i] = byte_sequence[i*2] + 256*(byte_sequence[i*2+1] & 0x7F); + + if(field_a_values) { + field_a_values[i] = byte_sequence[i*2+1] & 0x80; + } + + } + + break; + } + case SICK_MS_MODE_32_FA: + { + + /* Extract the range and Field A values */ + for(unsigned int i = 0; i < num_measurements; i++) { + measured_values[i] = byte_sequence[i*2] + 256*(byte_sequence[i*2+1] & 0x7F); + + if(field_a_values) { + field_a_values[i] = byte_sequence[i*2+1] & 0x80; + } + + } + + break; + } + case SICK_MS_MODE_32_IMMEDIATE: + { + + /* Extract the range measurements (no flags for this mode */ + for(unsigned int i = 0; i < num_measurements; i++) { + measured_values[i] = byte_sequence[i*2] + 256*(byte_sequence[i*2+1]); + } + + break; + } + case SICK_MS_MODE_REFLECTIVITY: + { + + /* Extract the reflectivity values */ + for(unsigned int i = 0; i < num_measurements; i++) { + measured_values[i] = byte_sequence[i*2] + 256*(byte_sequence[i*2+1]); + } + + break; + } + default: + break; + } + + } + + /** + * \brief Indicates whether the given measuring units are valid/defined + * \param sick_units The units in question + */ + bool SickLMS2xx::_validSickMeasuringUnits( const sick_lms_2xx_measuring_units_t sick_units ) const { + + /* Check the given units value */ + if (sick_units != SICK_MEASURING_UNITS_CM && sick_units != SICK_MEASURING_UNITS_MM) { + return false; + } + + /* Valid */ + return true; + } + + /** + * \brief Indicates whether the Sick is an LMS 200 + * \return True if the device is a Sick LMS 200, False otherwise + */ + bool SickLMS2xx::_isSickLMS200( ) const { + + /* Check the given Sick type value */ + switch(_sick_type) { + case SICK_LMS_TYPE_200_30106: + return true; + default: + return false; + } + + } + + /** + * \brief Indicates whether the Sick is an LMS 211 + * \return True if the device is a Sick LMS 211, False otherwise + */ + bool SickLMS2xx::_isSickLMS211( ) const { + + /* Check the given Sick type value */ + switch(_sick_type) { + case SICK_LMS_TYPE_211_30106: + return true; + case SICK_LMS_TYPE_211_30206: + return true; + case SICK_LMS_TYPE_211_S07: + return true; + case SICK_LMS_TYPE_211_S14: + return true; + case SICK_LMS_TYPE_211_S15: + return true; + case SICK_LMS_TYPE_211_S19: + return true; + case SICK_LMS_TYPE_211_S20: + return true; + default: + return false; + } + + } + + /** + * \brief Indicates whether the Sick is an LMS 220 + * \return True if the device is a Sick LMS 220, False otherwise + */ + bool SickLMS2xx::_isSickLMS220( ) const { + + /* Check the given Sick type value */ + switch(_sick_type) { + case SICK_LMS_TYPE_220_30106: + return true; + default: + return false; + } + + } + + /** + * \brief Indicates whether the Sick is an LMS 221 + * \return True if the device is a Sick LMS 221, False otherwise + */ + bool SickLMS2xx::_isSickLMS221( ) const { + + /* Check the given Sick type value */ + switch(_sick_type) { + case SICK_LMS_TYPE_221_30106: + return true; + case SICK_LMS_TYPE_221_30206: + return true; + case SICK_LMS_TYPE_221_S07: + return true; + case SICK_LMS_TYPE_221_S14: + return true; + case SICK_LMS_TYPE_221_S15: + return true; + case SICK_LMS_TYPE_221_S16: + return true; + case SICK_LMS_TYPE_221_S19: + return true; + case SICK_LMS_TYPE_221_S20: + return true; + default: + return false; + } + + } + + /** + * \brief Indicates whether the Sick is an LMS 291 + * \return True if the device is a Sick LMS 291, False otherwise + */ + bool SickLMS2xx::_isSickLMS291( ) const { + + /* Check the given Sick type value */ + switch(_sick_type) { + case SICK_LMS_TYPE_291_S05: + return true; + case SICK_LMS_TYPE_291_S14: + return true; + case SICK_LMS_TYPE_291_S15: + return true; + default: + return false; + } + + } + + /** + * \brief Indicates whether the Sick type is unknown + * \return True if the device is unknown, False otherwise + */ + bool SickLMS2xx::_isSickUnknown( ) const { + return _sick_type == SICK_LMS_TYPE_UNKNOWN; + } + + /** + * \brief Indicates whether the given scan angle is defined + * \param sick_scan_angle The scan angle in question + */ + bool SickLMS2xx::_validSickScanAngle( const sick_lms_2xx_scan_angle_t sick_scan_angle ) const { + + /* Check the given Sick scan angle */ + if (sick_scan_angle != SICK_SCAN_ANGLE_90 && + sick_scan_angle != SICK_SCAN_ANGLE_100 && + sick_scan_angle != SICK_SCAN_ANGLE_180 ) { + + return false; + } + + /* Valid */ + return true; + } + + /** + * \brief Indicates whether the given scan resolution is defined + * \param sick_scan_resolution The scan resolution in question + */ + bool SickLMS2xx::_validSickScanResolution( const sick_lms_2xx_scan_resolution_t sick_scan_resolution ) const { + + /* Check the given Sick scan resolution value */ + if (sick_scan_resolution != SICK_SCAN_RESOLUTION_25 && + sick_scan_resolution != SICK_SCAN_RESOLUTION_50 && + sick_scan_resolution != SICK_SCAN_RESOLUTION_100 ) { + + return false; + } + + /* Valid */ + return true; + } + + /** + * \brief Indicates whether the given sensitivity is defined + * \param sick_sensitivity The sick sensitivity in question + */ + bool SickLMS2xx::_validSickSensitivity( const sick_lms_2xx_sensitivity_t sick_sensitivity ) const { + + /* Check the given Sick sensitivity value */ + if (sick_sensitivity != SICK_SENSITIVITY_STANDARD && + sick_sensitivity != SICK_SENSITIVITY_MEDIUM && + sick_sensitivity != SICK_SENSITIVITY_LOW && + sick_sensitivity != SICK_SENSITIVITY_HIGH ) { + + return false; + } + + /* Valid */ + return true; + } + + /** + * \brief Indicates whether the given peak threshold is valid + * \param sick_peak_threshold Peak threshold definition for Sick LMS 2xx + */ + bool SickLMS2xx::_validSickPeakThreshold( const sick_lms_2xx_peak_threshold_t sick_peak_threshold ) const { + + /* Check the given Sick scan angle */ + if (sick_peak_threshold != SICK_PEAK_THRESHOLD_DETECTION_WITH_NO_BLACK_EXTENSION && + sick_peak_threshold != SICK_PEAK_THRESHOLD_DETECTION_WITH_BLACK_EXTENSION && + sick_peak_threshold != SICK_PEAK_THRESHOLD_NO_DETECTION_WITH_NO_BLACK_EXTENSION && + sick_peak_threshold != SICK_PEAK_THRESHOLD_NO_DETECTION_WITH_BLACK_EXTENSION) { + + return false; + } + + /* Valid */ + return true; + } + + /** + * \brief Indicates whether the given measuring mode is defined + * \param sick_measuring_mode The sick measuring mode in question + */ + bool SickLMS2xx::_validSickMeasuringMode( const sick_lms_2xx_measuring_mode_t sick_measuring_mode ) const { + + /* Check the given measuring mode */ + if (sick_measuring_mode != SICK_MS_MODE_8_OR_80_FA_FB_DAZZLE && + sick_measuring_mode != SICK_MS_MODE_8_OR_80_REFLECTOR && + sick_measuring_mode != SICK_MS_MODE_8_OR_80_FA_FB_FC && + sick_measuring_mode != SICK_MS_MODE_16_REFLECTOR && + sick_measuring_mode != SICK_MS_MODE_16_FA_FB && + sick_measuring_mode != SICK_MS_MODE_32_REFLECTOR && + sick_measuring_mode != SICK_MS_MODE_32_FA && + sick_measuring_mode != SICK_MS_MODE_32_IMMEDIATE && + sick_measuring_mode != SICK_MS_MODE_REFLECTIVITY ) { + + return false; + } + + /* Valid */ + return true; + } + + /** + * \brief Converts a termios baud to an equivalent Sick baud + * \param baud_rate The baud rate to be converted to a Sick LMS baud + * \return The Sick LMS 2xx equivalent of the given baud rate + */ + sick_lms_2xx_baud_t SickLMS2xx::_baudToSickBaud( const int baud_rate ) const { + + switch(baud_rate) { + case B9600: + return SICK_BAUD_9600; + case B19200: + return SICK_BAUD_19200; + case B38400: + return SICK_BAUD_38400; + case B500000: + return SICK_BAUD_500K; + default: + std::cerr << "Unexpected baud rate!" << std::endl; + return SICK_BAUD_9600; + } + + } + + /** + * \brief Converts given restart level to a corresponding string + * \param availability_flags The availability level of the Sick LMS 2xx + * \return The corresponding string + */ + std::string SickLMS2xx::_sickAvailabilityToString( const uint8_t availability_flags ) const { + + /* Check if availability is specified */ + if (availability_flags == 0) { + return "Default (Unspecified)"; + } + + std::string availability_str; + + /* Check if set to highest possible availability */ + if (0x01 & availability_flags) { + availability_str += "Highest"; + } + + /* Check for real-time indices */ + if (0x02 & availability_flags) { + + /* Check whether to add a spacer */ + if (availability_str.length() > 0) { + availability_str += ", "; + } + + availability_str += "Real-time indices"; + } + + /* Check for real-time indices */ + if (0x04 & availability_flags) { + + /* Check whether to add a spacer */ + if (availability_str.length() > 0) { + availability_str += ", "; + } + + availability_str += "No effect dazzle"; + } + + /* Return the string */ + return availability_str; + + } + + /** + * \brief Converts restart code to a corresponding string + * \param restart_code Restart code + * \return The corresponding string + */ + std::string SickLMS2xx::_sickRestartToString( const uint8_t restart_code ) const { + + std::string restart_str; + + /* Identify restart mode */ + switch(restart_code) { + case 0x00: + restart_str += "Restart when button actuated"; + break; + case 0x01: + restart_str += "Restart after set time"; + break; + case 0x02: + restart_str += "No restart block"; + break; + case 0x03: + restart_str += "Button switches field set, restart after set time"; + break; + case 0x04: + restart_str += "Button switches field set, no restart block"; + break; + case 0x05: + restart_str += "LMS2xx operates as a slave, restart after set time"; + break; + case 0x06: + restart_str += "LMS2xx operates as a slave, immediate restart"; + break; + default: + restart_str += "Unknown!"; + } + + /* Return the restart code */ + return restart_str; + + } + + /** + * \brief Converts Sick LMS temporary field code to a corresponding string + * \param temp_field_code The temporary field code + * \return The corresponding string + */ + std::string SickLMS2xx::_sickTemporaryFieldToString( const uint8_t temp_field_code ) const { + + switch(temp_field_code) { + case 0: + return "Not used"; + case 1: + return "Belongs to field set no. 1"; + case 2: + return "Belongs to field set no. 2"; + default: + return "Unknown!"; + } + + } + + /** + * \brief Converts Sick LMS subtractive fields code to a corresponding string + * \param subt_field_code The subtractive fields code + * \return The corresponding string + */ + std::string SickLMS2xx::_sickSubtractiveFieldsToString( const uint8_t subt_field_code ) const { + + switch(subt_field_code) { + case 0: + return "Not active"; + case 1: + return "Active"; + default: + return "Unknown!"; + } + + } + + /*! + * \brief Converts Sick LMS contour function code to a corresponding string + * \param contour_function_code The subtractive fields code + * \return The corresponding string + */ + std::string SickLMS2xx::_sickContourFunctionToString( const uint8_t contour_function_code ) const { + + switch(contour_function_code) { + case 0: + return "Not active"; + default: { + + /* For converting an int to string */ + std::ostringstream output_str; + + /* Indicate its active and include min object size */ + output_str << "Active, Min object size: " << (int)contour_function_code << " (cm)"; + return output_str.str(); + + } + } + + } + + /** + * \brief Converts the Sick LMS variant to a corresponding string + * \param sick_variant The Sick LMS variant + * \return The corresponding string + */ + std::string SickLMS2xx::_sickVariantToString( const unsigned int sick_variant ) const { + + /* Return the correct string */ + if(sick_variant == SICK_LMS_VARIANT_2XX_TYPE_6) { + return "Standard device (LMS2xx,type 6)"; + } + else if (sick_variant == SICK_LMS_VARIANT_SPECIAL) { + return "Special device (LMS211-/221-S19/-S20)"; + } + else { + return "Unknown"; + } + + } + +} //namespace SickToolbox diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/SickLMS2xxBufferMonitor.cc b/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/SickLMS2xxBufferMonitor.cc new file mode 100644 index 0000000..a710af1 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/SickLMS2xxBufferMonitor.cc @@ -0,0 +1,133 @@ +/*! + * \file SickLMS2xxBufferMonitor.cc + * \brief Implements a class for monitoring the receive + * buffer when interfacing w/ a Sick LMS 2xx LIDAR. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +/* Auto-generated header */ +#include + +/* Implementation dependencies */ +#include +#include + +#include +#include +#include +#include +#include + +/* Associate the namespace */ +namespace SickToolbox { + + /** + * \brief A standard constructor + */ + SickLMS2xxBufferMonitor::SickLMS2xxBufferMonitor( ) : SickBufferMonitor(this) { } + + /** + * \brief Acquires the next message from the SickLMS2xx byte stream + * \param &sick_message The returned message object + */ + void SickLMS2xxBufferMonitor::GetNextMessageFromDataStream( SickLMS2xxMessage &sick_message ) throw( SickIOException ) { + + uint8_t search_buffer[2] = {0}; + uint8_t payload_length_buffer[2] = {0}; + uint8_t payload_buffer[SickLMS2xxMessage::MESSAGE_PAYLOAD_MAX_LENGTH] = {0}; + uint8_t checksum_buffer[2] = {0}; + uint16_t payload_length, checksum; + + try { + + /* Drain the I/O buffers! */ + if (tcdrain(_sick_fd) != 0) { + throw SickIOException("SickLMS2xxBufferMonitor::GetNextMessageFromDataStream: tcdrain failed!"); + } + + /* Read until we get a valid message header */ + unsigned int bytes_searched = 0; + while(search_buffer[0] != 0x02 || search_buffer[1] != DEFAULT_SICK_LMS_2XX_HOST_ADDRESS) { + + /* Slide the search window */ + search_buffer[0] = search_buffer[1]; + + /* Attempt to read in another byte */ + _readBytes(&search_buffer[1],1,DEFAULT_SICK_LMS_2XX_SICK_BYTE_TIMEOUT); + + /* Header should be no more than max message length + header length bytes away */ + if (bytes_searched > SickLMS2xxMessage::MESSAGE_MAX_LENGTH + SickLMS2xxMessage::MESSAGE_HEADER_LENGTH) { + throw SickTimeoutException("SickLMS2xxBufferMonitor::GetNextMessageFromDataStream: header timeout!"); + } + + /* Increment the number of bytes searched */ + bytes_searched++; + + } + + /* Read until we receive the payload length or we timeout */ + _readBytes(payload_length_buffer,2,DEFAULT_SICK_LMS_2XX_SICK_BYTE_TIMEOUT); + + /* Extract the payload length */ + memcpy(&payload_length,payload_length_buffer,2); + payload_length = sick_lms_2xx_to_host_byte_order(payload_length); + + /* Make sure the payload length is legitimate, otherwise disregard */ + if (payload_length <= SickLMS2xxMessage::MESSAGE_MAX_LENGTH) { + + /* Read until we receive the payload or we timeout */ + _readBytes(payload_buffer,payload_length,DEFAULT_SICK_LMS_2XX_SICK_BYTE_TIMEOUT); + + /* Read until we receive the checksum or we timeout */ + _readBytes(checksum_buffer,2,DEFAULT_SICK_LMS_2XX_SICK_BYTE_TIMEOUT); + + /* Copy into uint16_t so it can be used */ + memcpy(&checksum,checksum_buffer,2); + checksum = sick_lms_2xx_to_host_byte_order(checksum); + + /* Build a frame and compute the crc */ + sick_message.BuildMessage(DEFAULT_SICK_LMS_2XX_HOST_ADDRESS,payload_buffer,payload_length); + + /* See if the checksums match */ + if(sick_message.GetChecksum() != checksum) { + throw SickBadChecksumException("SickLMS2xx::GetNextMessageFromDataStream: CRC16 failed!"); + } + + } + + } + + catch(SickTimeoutException &sick_timeout_exception) { /* This is ok! */ } + + /* Handle a bad checksum! */ + catch(SickBadChecksumException &sick_checksum_exception) { + sick_message.Clear(); // Clear the message container + } + + /* Handle any serious IO exceptions */ + catch(SickIOException &sick_io_exception) { + throw; + } + + /* A sanity check */ + catch (...) { + throw; + } + + } + + /** + * \brief A standard destructor + */ + SickLMS2xxBufferMonitor::~SickLMS2xxBufferMonitor( ) { } + +} /* namespace SickToolbox */ diff --git a/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/SickLMS2xxMessage.cc b/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/SickLMS2xxMessage.cc new file mode 100644 index 0000000..3106c02 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/drivers/lms2xx/sicklms2xx/SickLMS2xxMessage.cc @@ -0,0 +1,181 @@ +/*! + * \file SickLMS2xxMessage.cc + * \brief Implementation of class SickFrame. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +/* Auto-generated header */ +#include + +/* Implementation dependencies */ +#include +#include + +#include +#include + +/* Associate the namespace */ +namespace SickToolbox { + + /*! + * \brief A default constructor + */ + SickLMS2xxMessage::SickLMS2xxMessage( ) { + + /* Initialize the object */ + Clear(); + } + + /*! + * \brief A constructor for building a message from the given parameter values + * \param dest_address The source address of the message + * \param payload_buffer The payload of the message as an array of bytes (including the command code) + * \param payload_length The length of the payload array in bytes + */ + SickLMS2xxMessage::SickLMS2xxMessage( const uint8_t dest_address, const uint8_t * const payload_buffer, const unsigned int payload_length ) : + SickMessage< SICK_LMS_2XX_MSG_HEADER_LEN, SICK_LMS_2XX_MSG_PAYLOAD_MAX_LEN, SICK_LMS_2XX_MSG_TRAILER_LEN >() { + + /* Build the message */ + BuildMessage(dest_address,payload_buffer,payload_length); + } + + /*! + * \brief A constructor for parsing a byte sequence into a message object + * \param message_buffer A well-formed message to be parsed into the class' fields + */ + SickLMS2xxMessage::SickLMS2xxMessage( uint8_t * const message_buffer ) : + SickMessage< SICK_LMS_2XX_MSG_HEADER_LEN, SICK_LMS_2XX_MSG_PAYLOAD_MAX_LEN, SICK_LMS_2XX_MSG_TRAILER_LEN >() { + + /* Parse the byte sequence into a message object */ + ParseMessage(message_buffer); + } + + /*! + * \brief Consructs a message object from given parameter values + * \param dest_address The destination address of the frame + * \param *payload_buffer The payload for the frame as an array of bytes (including the command code) + * \param payload_length The length of the payload array in bytes + */ + void SickLMS2xxMessage::BuildMessage( const uint8_t dest_address, const uint8_t * const payload_buffer, + const unsigned int payload_length ) { + + /* Call the parent method! + * NOTE: The parent method resets the object and assigns _message_length, _payload_length, + * _populated and copies the payload into the message buffer at the correct position + */ + SickMessage< SICK_LMS_2XX_MSG_HEADER_LEN, SICK_LMS_2XX_MSG_PAYLOAD_MAX_LEN, SICK_LMS_2XX_MSG_TRAILER_LEN > + ::BuildMessage(payload_buffer,payload_length); + + /* + * Set the message header! + */ + _message_buffer[0] = 0x02; // Start of transmission (stx) + _message_buffer[1] = dest_address; // Sick LMS address + + /* Include the payload length in the header */ + uint16_t payload_length_16 = host_to_sick_lms_2xx_byte_order((uint16_t)_payload_length); + memcpy(&_message_buffer[2],&payload_length_16,2); + + /* + * Set the message trailer! + */ + _checksum = host_to_sick_lms_2xx_byte_order(_computeCRC(_message_buffer,_payload_length+4)); + memcpy(&_message_buffer[_payload_length+4],&_checksum,2); + + } + + /*! + * \brief Parses a sequence of bytes into a well-formed message + * \param *message_buffer The buffer containing the source message + */ + void SickLMS2xxMessage::ParseMessage( const uint8_t * const message_buffer ) { + + /* Call the parent method! + * NOTE: This method resets the object and assigns _populated as true + */ + SickMessage< SICK_LMS_2XX_MSG_HEADER_LEN, SICK_LMS_2XX_MSG_PAYLOAD_MAX_LEN, SICK_LMS_2XX_MSG_TRAILER_LEN > + ::ParseMessage(message_buffer); + + /* Extract the payload length */ + uint16_t payload_length_16 = 0; + memcpy(&payload_length_16,&message_buffer[2],2); + _payload_length = (unsigned int)sick_lms_2xx_to_host_byte_order(payload_length_16); + + /* Compute the total message length */ + _message_length = MESSAGE_HEADER_LENGTH + MESSAGE_TRAILER_LENGTH + _payload_length; + + /* Copy the give message into the buffer */ + memcpy(_message_buffer, message_buffer,_message_length); + + /* Extract the checksum from the frame */ + memcpy(&_checksum,&_message_buffer[_payload_length+MESSAGE_HEADER_LENGTH],2); + _checksum = sick_lms_2xx_to_host_byte_order(_checksum); + + } + + /*! + * \brief Reset all internal fields and buffers associated with the object. + */ + void SickLMS2xxMessage::Clear( ) { + + /* Call the parent method and clear out class' protected members */ + SickMessage< SICK_LMS_2XX_MSG_HEADER_LEN, SICK_LMS_2XX_MSG_PAYLOAD_MAX_LEN, SICK_LMS_2XX_MSG_TRAILER_LEN >::Clear(); + + /* Reset the class' additional fields */ + _checksum = 0; + + } + + /*! + * \brief Print the message contents. + */ + void SickLMS2xxMessage::Print( ) const { + + std::cout.setf(std::ios::hex,std::ios::basefield); + std::cout << "Checksum: " << (unsigned int) GetChecksum() << std::endl; + std::cout << "Dest. Addr.: " << (unsigned int) GetDestAddress() << std::endl; + std::cout << "Command Code: " << (unsigned int) GetCommandCode() << std::endl; + std::cout << std::flush; + + /* Call parent's print function */ + SickMessage< SICK_LMS_2XX_MSG_HEADER_LEN, SICK_LMS_2XX_MSG_PAYLOAD_MAX_LEN, SICK_LMS_2XX_MSG_TRAILER_LEN >::Print(); + } + + /*! + * \brief Computes the CRC16 of the given data buffer + * \param data An array of bytes whose checksum to compute + * \param len The length of the data array + * \return CRC16 computed over given data buffer + */ + uint16_t SickLMS2xxMessage::_computeCRC( uint8_t * data, unsigned int data_length ) const { + + uint16_t uCrc16; + uint8_t abData[2]; + uCrc16 = abData[0] = 0; + while (data_length-- ) { + abData[1] = abData[0]; + abData[0] = *data++; + if(uCrc16 & 0x8000) { + uCrc16 = (uCrc16 & 0x7fff) << 1; + uCrc16 ^= CRC16_GEN_POL; + } + else { + uCrc16 <<= 1; + } + uCrc16 ^= MKSHORT(abData[0],abData[1]); + } + return uCrc16; + } + + SickLMS2xxMessage::~SickLMS2xxMessage( ) { } + +} /* namespace SickToolbox */ diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/Doxyfile b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/Doxyfile new file mode 100644 index 0000000..5ba2cb8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/Doxyfile @@ -0,0 +1,1227 @@ +# Doxyfile 1.4.4 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project +# +# All text after a hash (#) is considered a comment and will be ignored +# The format is: +# TAG = value [value, ...] +# For lists items can also be appended using: +# TAG += value [value, ...] +# Values that contain spaces should be placed between quotes (" ") + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- + +# The PROJECT_NAME tag is a single word (or a sequence of words surrounded +# by quotes) that should identify the project. + +PROJECT_NAME = ld_config + +# The PROJECT_NUMBER tag can be used to enter a project or revision number. +# This could be handy for archiving the generated documentation or +# if some version control system is used. + +PROJECT_NUMBER = + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) +# base path where the generated documentation will be put. +# If a relative path is entered, it will be relative to the location +# where doxygen was started. If left blank the current directory will be used. + +OUTPUT_DIRECTORY = doc + +# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create +# 4096 sub-directories (in 2 levels) under the output directory of each output +# format and will distribute the generated files over these directories. +# Enabling this option can be useful when feeding doxygen a huge amount of +# source files, where putting all generated files in the same directory would +# otherwise cause performance problems for the file system. + +CREATE_SUBDIRS = NO + +# The OUTPUT_LANGUAGE tag is used to specify the language in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all constant output in the proper language. +# The default language is English, other supported languages are: +# Brazilian, Catalan, Chinese, Chinese-Traditional, Croatian, Czech, Danish, +# Dutch, Finnish, French, German, Greek, Hungarian, Italian, Japanese, +# Japanese-en (Japanese with English messages), Korean, Korean-en, Norwegian, +# Polish, Portuguese, Romanian, Russian, Serbian, Slovak, Slovene, Spanish, +# Swedish, and Ukrainian. + +OUTPUT_LANGUAGE = English + +# This tag can be used to specify the encoding used in the generated output. +# The encoding is not always determined by the language that is chosen, +# but also whether or not the output is meant for Windows or non-Windows users. +# In case there is a difference, setting the USE_WINDOWS_ENCODING tag to YES +# forces the Windows encoding (this is the default for the Windows binary), +# whereas setting the tag to NO uses a Unix-style encoding (the default for +# all platforms other than Windows). + +USE_WINDOWS_ENCODING = NO + +# If the BRIEF_MEMBER_DESC tag is set to YES (the default) Doxygen will +# include brief member descriptions after the members that are listed in +# the file and class documentation (similar to JavaDoc). +# Set to NO to disable this. + +BRIEF_MEMBER_DESC = YES + +# If the REPEAT_BRIEF tag is set to YES (the default) Doxygen will prepend +# the brief description of a member or function before the detailed description. +# Note: if both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the +# brief descriptions will be completely suppressed. + +REPEAT_BRIEF = YES + +# This tag implements a quasi-intelligent brief description abbreviator +# that is used to form the text in various listings. Each string +# in this list, if found as the leading text of the brief description, will be +# stripped from the text and the result after processing the whole list, is +# used as the annotated text. Otherwise, the brief description is used as-is. +# If left blank, the following values are used ("$name" is automatically +# replaced with the name of the entity): "The $name class" "The $name widget" +# "The $name file" "is" "provides" "specifies" "contains" +# "represents" "a" "an" "the" + +ABBREVIATE_BRIEF = + +# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then +# Doxygen will generate a detailed section even if there is only a brief +# description. + +ALWAYS_DETAILED_SEC = NO + +# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all +# inherited members of a class in the documentation of that class as if those +# members were ordinary class members. Constructors, destructors and assignment +# operators of the base classes will not be shown. + +INLINE_INHERITED_MEMB = NO + +# If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full +# path before files name in the file list and in the header files. If set +# to NO the shortest path that makes the file name unique will be used. + +FULL_PATH_NAMES = YES + +# If the FULL_PATH_NAMES tag is set to YES then the STRIP_FROM_PATH tag +# can be used to strip a user-defined part of the path. Stripping is +# only done if one of the specified strings matches the left-hand part of +# the path. The tag can be used to show relative paths in the file list. +# If left blank the directory from which doxygen is run is used as the +# path to strip. + +STRIP_FROM_PATH = src + +# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of +# the path mentioned in the documentation of a class, which tells +# the reader which header file to include in order to use a class. +# If left blank only the name of the header file containing the class +# definition is used. Otherwise one should specify the include paths that +# are normally passed to the compiler using the -I flag. + +STRIP_FROM_INC_PATH = include + +# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter +# (but less readable) file names. This can be useful is your file systems +# doesn't support long names like on DOS, Mac, or CD-ROM. + +SHORT_NAMES = NO + +# If the JAVADOC_AUTOBRIEF tag is set to YES then Doxygen +# will interpret the first line (until the first dot) of a JavaDoc-style +# comment as the brief description. If set to NO, the JavaDoc +# comments will behave just like the Qt-style comments (thus requiring an +# explicit @brief command for a brief description. + +JAVADOC_AUTOBRIEF = YES + +# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make Doxygen +# treat a multi-line C++ special comment block (i.e. a block of //! or /// +# comments) as a brief description. This used to be the default behaviour. +# The new default is to treat a multi-line C++ comment block as a detailed +# description. Set this tag to YES if you prefer the old behaviour instead. + +MULTILINE_CPP_IS_BRIEF = NO + +# If the DETAILS_AT_TOP tag is set to YES then Doxygen +# will output the detailed description near the top, like JavaDoc. +# If set to NO, the detailed description appears after the member +# documentation. + +DETAILS_AT_TOP = NO + +# If the INHERIT_DOCS tag is set to YES (the default) then an undocumented +# member inherits the documentation from any documented member that it +# re-implements. + +INHERIT_DOCS = YES + +# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC +# tag is set to YES, then doxygen will reuse the documentation of the first +# member in the group (if any) for the other members of the group. By default +# all members of a group must be documented explicitly. + +DISTRIBUTE_GROUP_DOC = NO + +# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce +# a new page for each member. If set to NO, the documentation of a member will +# be part of the file/class/namespace that contains it. + +SEPARATE_MEMBER_PAGES = NO + +# The TAB_SIZE tag can be used to set the number of spaces in a tab. +# Doxygen uses this value to replace tabs by spaces in code fragments. + +TAB_SIZE = 8 + +# This tag can be used to specify a number of aliases that acts +# as commands in the documentation. An alias has the form "name=value". +# For example adding "sideeffect=\par Side Effects:\n" will allow you to +# put the command \sideeffect (or @sideeffect) in the documentation, which +# will result in a user-defined paragraph with heading "Side Effects:". +# You can put \n's in the value part of an alias to insert newlines. + +ALIASES = + +# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C +# sources only. Doxygen will then generate output that is more tailored for C. +# For instance, some of the names that are used will be different. The list +# of all members will be omitted, etc. + +OPTIMIZE_OUTPUT_FOR_C = NO + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java sources +# only. Doxygen will then generate output that is more tailored for Java. +# For instance, namespaces will be presented as packages, qualified scopes +# will look different, etc. + +OPTIMIZE_OUTPUT_JAVA = NO + +# Set the SUBGROUPING tag to YES (the default) to allow class member groups of +# the same type (for instance a group of public functions) to be put as a +# subgroup of that type (e.g. under the Public Functions section). Set it to +# NO to prevent subgrouping. Alternatively, this can be done per class using +# the \nosubgrouping command. + +SUBGROUPING = YES + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in +# documentation are documented, even if no documentation was available. +# Private class members and static file members will be hidden unless +# the EXTRACT_PRIVATE and EXTRACT_STATIC tags are set to YES + +EXTRACT_ALL = NO + +# If the EXTRACT_PRIVATE tag is set to YES all private members of a class +# will be included in the documentation. + +EXTRACT_PRIVATE = NO + +# If the EXTRACT_STATIC tag is set to YES all static members of a file +# will be included in the documentation. + +EXTRACT_STATIC = NO + +# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) +# defined locally in source files will be included in the documentation. +# If set to NO only classes defined in header files are included. + +EXTRACT_LOCAL_CLASSES = YES + +# This flag is only useful for Objective-C code. When set to YES local +# methods, which are defined in the implementation section but not in +# the interface are included in the documentation. +# If set to NO (the default) only methods in the interface are included. + +EXTRACT_LOCAL_METHODS = NO + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, Doxygen will hide all +# undocumented members of documented classes, files or namespaces. +# If set to NO (the default) these members will be included in the +# various overviews, but no documentation section is generated. +# This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_MEMBERS = NO + +# If the HIDE_UNDOC_CLASSES tag is set to YES, Doxygen will hide all +# undocumented classes that are normally visible in the class hierarchy. +# If set to NO (the default) these classes will be included in the various +# overviews. This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_CLASSES = NO + +# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, Doxygen will hide all +# friend (class|struct|union) declarations. +# If set to NO (the default) these declarations will be included in the +# documentation. + +HIDE_FRIEND_COMPOUNDS = NO + +# If the HIDE_IN_BODY_DOCS tag is set to YES, Doxygen will hide any +# documentation blocks found inside the body of a function. +# If set to NO (the default) these blocks will be appended to the +# function's detailed documentation block. + +HIDE_IN_BODY_DOCS = NO + +# The INTERNAL_DOCS tag determines if documentation +# that is typed after a \internal command is included. If the tag is set +# to NO (the default) then the documentation will be excluded. +# Set it to YES to include the internal documentation. + +INTERNAL_DOCS = NO + +# If the CASE_SENSE_NAMES tag is set to NO then Doxygen will only generate +# file names in lower-case letters. If set to YES upper-case letters are also +# allowed. This is useful if you have classes or files whose names only differ +# in case and if your file system supports case sensitive file names. Windows +# and Mac users are advised to set this option to NO. + +CASE_SENSE_NAMES = YES + +# If the HIDE_SCOPE_NAMES tag is set to NO (the default) then Doxygen +# will show members with their full class and namespace scopes in the +# documentation. If set to YES the scope will be hidden. + +HIDE_SCOPE_NAMES = NO + +# If the SHOW_INCLUDE_FILES tag is set to YES (the default) then Doxygen +# will put a list of the files that are included by a file in the documentation +# of that file. + +SHOW_INCLUDE_FILES = YES + +# If the INLINE_INFO tag is set to YES (the default) then a tag [inline] +# is inserted in the documentation for inline members. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES (the default) then doxygen +# will sort the (detailed) documentation of file and class members +# alphabetically by member name. If set to NO the members will appear in +# declaration order. + +SORT_MEMBER_DOCS = YES + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the +# brief documentation of file, namespace and class members alphabetically +# by member name. If set to NO (the default) the members will appear in +# declaration order. + +SORT_BRIEF_DOCS = NO + +# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be +# sorted by fully-qualified names, including namespaces. If set to +# NO (the default), the class list will be sorted only by class name, +# not including the namespace part. +# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. +# Note: This option applies only to the class list, not to the +# alphabetical list. + +SORT_BY_SCOPE_NAME = NO + +# The GENERATE_TODOLIST tag can be used to enable (YES) or +# disable (NO) the todo list. This list is created by putting \todo +# commands in the documentation. + +GENERATE_TODOLIST = YES + +# The GENERATE_TESTLIST tag can be used to enable (YES) or +# disable (NO) the test list. This list is created by putting \test +# commands in the documentation. + +GENERATE_TESTLIST = YES + +# The GENERATE_BUGLIST tag can be used to enable (YES) or +# disable (NO) the bug list. This list is created by putting \bug +# commands in the documentation. + +GENERATE_BUGLIST = YES + +# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or +# disable (NO) the deprecated list. This list is created by putting +# \deprecated commands in the documentation. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional +# documentation sections, marked by \if sectionname ... \endif. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines +# the initial value of a variable or define consists of for it to appear in +# the documentation. If the initializer consists of more lines than specified +# here it will be hidden. Use a value of 0 to hide initializers completely. +# The appearance of the initializer of individual variables and defines in the +# documentation can be controlled using \showinitializer or \hideinitializer +# command in the documentation regardless of this setting. + +MAX_INITIALIZER_LINES = 30 + +# Set the SHOW_USED_FILES tag to NO to disable the list of files generated +# at the bottom of the documentation of classes and structs. If set to YES the +# list will mention the files that were used to generate the documentation. + +SHOW_USED_FILES = YES + +# If the sources in your project are distributed over multiple directories +# then setting the SHOW_DIRECTORIES tag to YES will show the directory hierarchy +# in the documentation. The default is YES. + +SHOW_DIRECTORIES = YES + +# The FILE_VERSION_FILTER tag can be used to specify a program or script that +# doxygen should invoke to get the current version for each file (typically from the +# version control system). Doxygen will invoke the program by executing (via +# popen()) the command , where is the value of +# the FILE_VERSION_FILTER tag, and is the name of an input file +# provided by doxygen. Whatever the progam writes to standard output +# is used as the file version. See the manual for examples. + +FILE_VERSION_FILTER = + +#--------------------------------------------------------------------------- +# configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated +# by doxygen. Possible values are YES and NO. If left blank NO is used. + +QUIET = NO + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated by doxygen. Possible values are YES and NO. If left blank +# NO is used. + +WARNINGS = YES + +# If WARN_IF_UNDOCUMENTED is set to YES, then doxygen will generate warnings +# for undocumented members. If EXTRACT_ALL is set to YES then this flag will +# automatically be disabled. + +WARN_IF_UNDOCUMENTED = YES + +# If WARN_IF_DOC_ERROR is set to YES, doxygen will generate warnings for +# potential errors in the documentation, such as not documenting some +# parameters in a documented function, or documenting parameters that +# don't exist or using markup commands wrongly. + +WARN_IF_DOC_ERROR = YES + +# This WARN_NO_PARAMDOC option can be abled to get warnings for +# functions that are documented, but have no documentation for their parameters +# or return value. If set to NO (the default) doxygen will only warn about +# wrong or incomplete parameter documentation, but not about the absence of +# documentation. + +WARN_NO_PARAMDOC = NO + +# The WARN_FORMAT tag determines the format of the warning messages that +# doxygen can produce. The string should contain the $file, $line, and $text +# tags, which will be replaced by the file and line number from which the +# warning originated and the warning text. Optionally the format may contain +# $version, which will be replaced by the version of the file (if it could +# be obtained via FILE_VERSION_FILTER) + +WARN_FORMAT = "$file:$line: $text" + +# The WARN_LOGFILE tag can be used to specify a file to which warning +# and error messages should be written. If left blank the output is written +# to stderr. + +WARN_LOGFILE = + +#--------------------------------------------------------------------------- +# configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag can be used to specify the files and/or directories that contain +# documented source files. You may enter file names like "myfile.cpp" or +# directories like "/usr/src/myproject". Separate the files or directories +# with spaces. + +INPUT = src + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank the following patterns are tested: +# *.c *.cc *.cxx *.cpp *.c++ *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh *.hxx +# *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm + +FILE_PATTERNS = + +# The RECURSIVE tag can be used to turn specify whether or not subdirectories +# should be searched for input files as well. Possible values are YES and NO. +# If left blank NO is used. + +RECURSIVE = YES + +# The EXCLUDE tag can be used to specify files and/or directories that should +# excluded from the INPUT source files. This way you can easily exclude a +# subdirectory from a directory tree whose root is specified with the INPUT tag. + +EXCLUDE = + +# The EXCLUDE_SYMLINKS tag can be used select whether or not files or +# directories that are symbolic links (a Unix filesystem feature) are excluded +# from the input. + +EXCLUDE_SYMLINKS = NO + +# If the value of the INPUT tag contains directories, you can use the +# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude +# certain files from those directories. Note that the wildcards are matched +# against the file with absolute path, so to exclude all test directories +# for example use the pattern */test/* + +EXCLUDE_PATTERNS = + +# The EXAMPLE_PATH tag can be used to specify one or more files or +# directories that contain example code fragments that are included (see +# the \include command). + +EXAMPLE_PATH = + +# If the value of the EXAMPLE_PATH tag contains directories, you can use the +# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank all files are included. + +EXAMPLE_PATTERNS = + +# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be +# searched for input files to be used with the \include or \dontinclude +# commands irrespective of the value of the RECURSIVE tag. +# Possible values are YES and NO. If left blank NO is used. + +EXAMPLE_RECURSIVE = NO + +# The IMAGE_PATH tag can be used to specify one or more files or +# directories that contain image that are included in the documentation (see +# the \image command). + +IMAGE_PATH = + +# The INPUT_FILTER tag can be used to specify a program that doxygen should +# invoke to filter for each input file. Doxygen will invoke the filter program +# by executing (via popen()) the command , where +# is the value of the INPUT_FILTER tag, and is the name of an +# input file. Doxygen will then use the output that the filter program writes +# to standard output. If FILTER_PATTERNS is specified, this tag will be +# ignored. + +INPUT_FILTER = + +# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern +# basis. Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. The filters are a list of the form: +# pattern=filter (like *.cpp=my_cpp_filter). See INPUT_FILTER for further +# info on how filters are used. If FILTER_PATTERNS is empty, INPUT_FILTER +# is applied to all files. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER) will be used to filter the input files when producing source +# files to browse (i.e. when SOURCE_BROWSER is set to YES). + +FILTER_SOURCE_FILES = NO + +#--------------------------------------------------------------------------- +# configuration options related to source browsing +#--------------------------------------------------------------------------- + +# If the SOURCE_BROWSER tag is set to YES then a list of source files will +# be generated. Documented entities will be cross-referenced with these sources. +# Note: To get rid of all source code in the generated output, make sure also +# VERBATIM_HEADERS is set to NO. + +SOURCE_BROWSER = NO + +# Setting the INLINE_SOURCES tag to YES will include the body +# of functions and classes directly in the documentation. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES (the default) will instruct +# doxygen to hide any special comment blocks from generated source code +# fragments. Normal C and C++ comments will always remain visible. + +STRIP_CODE_COMMENTS = YES + +# If the REFERENCED_BY_RELATION tag is set to YES (the default) +# then for each documented function all documented +# functions referencing it will be listed. + +REFERENCED_BY_RELATION = YES + +# If the REFERENCES_RELATION tag is set to YES (the default) +# then for each documented function all documented entities +# called/used by that function will be listed. + +REFERENCES_RELATION = YES + +# If the USE_HTAGS tag is set to YES then the references to source code +# will point to the HTML generated by the htags(1) tool instead of doxygen +# built-in source browser. The htags tool is part of GNU's global source +# tagging system (see http://www.gnu.org/software/global/global.html). You +# will need version 4.8.6 or higher. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set to YES (the default) then Doxygen +# will generate a verbatim copy of the header file for each class for +# which an include is specified. Set to NO to disable this. + +VERBATIM_HEADERS = YES + +#--------------------------------------------------------------------------- +# configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index +# of all compounds will be generated. Enable this if the project +# contains a lot of classes, structs, unions or interfaces. + +ALPHABETICAL_INDEX = NO + +# If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then +# the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns +# in which this list will be split (can be a number in the range [1..20]) + +COLS_IN_ALPHA_INDEX = 5 + +# In case all classes in a project start with a common prefix, all +# classes will be put under the same header in the alphabetical index. +# The IGNORE_PREFIX tag can be used to specify one or more prefixes that +# should be ignored while generating the index headers. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES (the default) Doxygen will +# generate HTML output. + +GENERATE_HTML = YES + +# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `html' will be used as the default path. + +HTML_OUTPUT = html + +# The HTML_FILE_EXTENSION tag can be used to specify the file extension for +# each generated HTML page (for example: .htm,.php,.asp). If it is left blank +# doxygen will generate files with .html extension. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a personal HTML header for +# each generated HTML page. If it is left blank doxygen will generate a +# standard header. + +HTML_HEADER = doxygen-html-header + +# The HTML_FOOTER tag can be used to specify a personal HTML footer for +# each generated HTML page. If it is left blank doxygen will generate a +# standard footer. + +HTML_FOOTER = + +# The HTML_STYLESHEET tag can be used to specify a user-defined cascading +# style sheet that is used by each HTML page. It can be used to +# fine-tune the look of the HTML output. If the tag is left blank doxygen +# will generate a default style sheet. Note that doxygen will try to copy +# the style sheet file to the HTML output directory, so don't put your own +# stylesheet in the HTML output directory as well, or it will be erased! + +HTML_STYLESHEET = + +# If the HTML_ALIGN_MEMBERS tag is set to YES, the members of classes, +# files or namespaces will be aligned in HTML using tables. If set to +# NO a bullet list will be used. + +HTML_ALIGN_MEMBERS = YES + +# If the GENERATE_HTMLHELP tag is set to YES, additional index files +# will be generated that can be used as input for tools like the +# Microsoft HTML help workshop to generate a compressed HTML help file (.chm) +# of the generated HTML documentation. + +GENERATE_HTMLHELP = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_FILE tag can +# be used to specify the file name of the resulting .chm file. You +# can add a path in front of the file if the result should not be +# written to the html output directory. + +CHM_FILE = + +# If the GENERATE_HTMLHELP tag is set to YES, the HHC_LOCATION tag can +# be used to specify the location (absolute path including file name) of +# the HTML help compiler (hhc.exe). If non-empty doxygen will try to run +# the HTML help compiler on the generated index.hhp. + +HHC_LOCATION = + +# If the GENERATE_HTMLHELP tag is set to YES, the GENERATE_CHI flag +# controls if a separate .chi index file is generated (YES) or that +# it should be included in the master .chm file (NO). + +GENERATE_CHI = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the BINARY_TOC flag +# controls whether a binary table of contents is generated (YES) or a +# normal table of contents (NO) in the .chm file. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members +# to the contents of the HTML help documentation and to the tree view. + +TOC_EXPAND = NO + +# The DISABLE_INDEX tag can be used to turn on/off the condensed index at +# top of each HTML page. The value NO (the default) enables the index and +# the value YES disables it. + +DISABLE_INDEX = NO + +# This tag can be used to set the number of enum values (range [1..20]) +# that doxygen will group on one line in the generated HTML documentation. + +ENUM_VALUES_PER_LINE = 4 + +# If the GENERATE_TREEVIEW tag is set to YES, a side panel will be +# generated containing a tree-like index structure (just like the one that +# is generated for HTML Help). For this to work a browser that supports +# JavaScript, DHTML, CSS and frames is required (for instance Mozilla 1.0+, +# Netscape 6.0+, Internet explorer 5.0+, or Konqueror). Windows users are +# probably better off using the HTML help feature. + +GENERATE_TREEVIEW = NO + +# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be +# used to set the initial width (in pixels) of the frame in which the tree +# is shown. + +TREEVIEW_WIDTH = 250 + +#--------------------------------------------------------------------------- +# configuration options related to the LaTeX output +#--------------------------------------------------------------------------- + +# If the GENERATE_LATEX tag is set to YES (the default) Doxygen will +# generate Latex output. +GENERATE_LATEX = NO + +# The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `latex' will be used as the default path. + +LATEX_OUTPUT = latex + +# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be +# invoked. If left blank `latex' will be used as the default command name. + +LATEX_CMD_NAME = latex + +# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to +# generate index for LaTeX. If left blank `makeindex' will be used as the +# default command name. + +MAKEINDEX_CMD_NAME = makeindex + +# If the COMPACT_LATEX tag is set to YES Doxygen generates more compact +# LaTeX documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_LATEX = NO + +# The PAPER_TYPE tag can be used to set the paper type that is used +# by the printer. Possible values are: a4, a4wide, letter, legal and +# executive. If left blank a4wide will be used. + +PAPER_TYPE = a4wide + +# The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX +# packages that should be included in the LaTeX output. + +EXTRA_PACKAGES = + +# The LATEX_HEADER tag can be used to specify a personal LaTeX header for +# the generated latex document. The header should contain everything until +# the first chapter. If it is left blank doxygen will generate a +# standard header. Notice: only use this tag if you know what you are doing! + +LATEX_HEADER = + +# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated +# is prepared for conversion to pdf (using ps2pdf). The pdf file will +# contain links (just like the HTML output) instead of page references +# This makes the output suitable for online browsing using a pdf viewer. + +PDF_HYPERLINKS = YES + +# If the USE_PDFLATEX tag is set to YES, pdflatex will be used instead of +# plain latex in the generated Makefile. Set this option to YES to get a +# higher quality PDF documentation. + +USE_PDFLATEX = YES + +# If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\batchmode. +# command to the generated LaTeX files. This will instruct LaTeX to keep +# running if errors occur, instead of asking the user for help. +# This option is also used when generating formulas in HTML. + +LATEX_BATCHMODE = NO + +# If LATEX_HIDE_INDICES is set to YES then doxygen will not +# include the index chapters (such as File Index, Compound Index, etc.) +# in the output. + +LATEX_HIDE_INDICES = NO + +#--------------------------------------------------------------------------- +# configuration options related to the RTF output +#--------------------------------------------------------------------------- + +# If the GENERATE_RTF tag is set to YES Doxygen will generate RTF output +# The RTF output is optimized for Word 97 and may not look very pretty with +# other RTF readers or editors. + +GENERATE_RTF = NO + +# The RTF_OUTPUT tag is used to specify where the RTF docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `rtf' will be used as the default path. + +RTF_OUTPUT = rtf + +# If the COMPACT_RTF tag is set to YES Doxygen generates more compact +# RTF documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_RTF = NO + +# If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated +# will contain hyperlink fields. The RTF file will +# contain links (just like the HTML output) instead of page references. +# This makes the output suitable for online browsing using WORD or other +# programs which support those fields. +# Note: wordpad (write) and others do not support links. + +RTF_HYPERLINKS = NO + +# Load stylesheet definitions from file. Syntax is similar to doxygen's +# config file, i.e. a series of assignments. You only have to provide +# replacements, missing definitions are set to their default value. + +RTF_STYLESHEET_FILE = + +# Set optional variables used in the generation of an rtf document. +# Syntax is similar to doxygen's config file. + +RTF_EXTENSIONS_FILE = + +#--------------------------------------------------------------------------- +# configuration options related to the man page output +#--------------------------------------------------------------------------- + +# If the GENERATE_MAN tag is set to YES (the default) Doxygen will +# generate man pages + +GENERATE_MAN = NO + +# The MAN_OUTPUT tag is used to specify where the man pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `man' will be used as the default path. + +MAN_OUTPUT = man + +# The MAN_EXTENSION tag determines the extension that is added to +# the generated man pages (default is the subroutine's section .3) + +MAN_EXTENSION = .3 + +# If the MAN_LINKS tag is set to YES and Doxygen generates man output, +# then it will generate one additional man file for each entity +# documented in the real man page(s). These additional files +# only source the real man page, but without them the man command +# would be unable to find the correct page. The default is NO. + +MAN_LINKS = NO + +#--------------------------------------------------------------------------- +# configuration options related to the XML output +#--------------------------------------------------------------------------- + +# If the GENERATE_XML tag is set to YES Doxygen will +# generate an XML file that captures the structure of +# the code including all documentation. + +GENERATE_XML = NO + +# The XML_OUTPUT tag is used to specify where the XML pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `xml' will be used as the default path. + +XML_OUTPUT = xml + +# The XML_SCHEMA tag can be used to specify an XML schema, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_SCHEMA = + +# The XML_DTD tag can be used to specify an XML DTD, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_DTD = + +# If the XML_PROGRAMLISTING tag is set to YES Doxygen will +# dump the program listings (including syntax highlighting +# and cross-referencing information) to the XML output. Note that +# enabling this will significantly increase the size of the XML output. + +XML_PROGRAMLISTING = YES + +#--------------------------------------------------------------------------- +# configuration options for the AutoGen Definitions output +#--------------------------------------------------------------------------- + +# If the GENERATE_AUTOGEN_DEF tag is set to YES Doxygen will +# generate an AutoGen Definitions (see autogen.sf.net) file +# that captures the structure of the code including all +# documentation. Note that this feature is still experimental +# and incomplete at the moment. + +GENERATE_AUTOGEN_DEF = NO + +#--------------------------------------------------------------------------- +# configuration options related to the Perl module output +#--------------------------------------------------------------------------- + +# If the GENERATE_PERLMOD tag is set to YES Doxygen will +# generate a Perl module file that captures the structure of +# the code including all documentation. Note that this +# feature is still experimental and incomplete at the +# moment. + +GENERATE_PERLMOD = NO + +# If the PERLMOD_LATEX tag is set to YES Doxygen will generate +# the necessary Makefile rules, Perl scripts and LaTeX code to be able +# to generate PDF and DVI output from the Perl module output. + +PERLMOD_LATEX = NO + +# If the PERLMOD_PRETTY tag is set to YES the Perl module output will be +# nicely formatted so it can be parsed by a human reader. This is useful +# if you want to understand what is going on. On the other hand, if this +# tag is set to NO the size of the Perl module output will be much smaller +# and Perl will parse it just the same. + +PERLMOD_PRETTY = YES + +# The names of the make variables in the generated doxyrules.make file +# are prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX. +# This is useful so different doxyrules.make files included by the same +# Makefile don't overwrite each other's variables. + +PERLMOD_MAKEVAR_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the preprocessor +#--------------------------------------------------------------------------- + +# If the ENABLE_PREPROCESSING tag is set to YES (the default) Doxygen will +# evaluate all C-preprocessor directives found in the sources and include +# files. + +ENABLE_PREPROCESSING = YES + +# If the MACRO_EXPANSION tag is set to YES Doxygen will expand all macro +# names in the source code. If set to NO (the default) only conditional +# compilation will be performed. Macro expansion can be done in a controlled +# way by setting EXPAND_ONLY_PREDEF to YES. + +MACRO_EXPANSION = NO + +# If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES +# then the macro expansion is limited to the macros specified with the +# PREDEFINED and EXPAND_AS_PREDEFINED tags. + +EXPAND_ONLY_PREDEF = NO + +# If the SEARCH_INCLUDES tag is set to YES (the default) the includes files +# in the INCLUDE_PATH (see below) will be search if a #include is found. + +SEARCH_INCLUDES = YES + +# The INCLUDE_PATH tag can be used to specify one or more directories that +# contain include files that are not input files but should be processed by +# the preprocessor. + +INCLUDE_PATH = + +# You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard +# patterns (like *.h and *.hpp) to filter out the header-files in the +# directories. If left blank, the patterns specified with FILE_PATTERNS will +# be used. + +INCLUDE_FILE_PATTERNS = + +# The PREDEFINED tag can be used to specify one or more macro names that +# are defined before the preprocessor is started (similar to the -D option of +# gcc). The argument of the tag is a list of macros of the form: name +# or name=definition (no spaces). If the definition and the = are +# omitted =1 is assumed. To prevent a macro definition from being +# undefined via #undef or recursively expanded use the := operator +# instead of the = operator. + +PREDEFINED = + +# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then +# this tag can be used to specify a list of macro names that should be expanded. +# The macro definition that is found in the sources will be used. +# Use the PREDEFINED tag if you want to use a different macro definition. + +EXPAND_AS_DEFINED = + +# If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then +# doxygen's preprocessor will remove all function-like macros that are alone +# on a line, have an all uppercase name, and do not end with a semicolon. Such +# function macros are typically used for boiler-plate code, and will confuse +# the parser if not removed. + +SKIP_FUNCTION_MACROS = YES + +#--------------------------------------------------------------------------- +# Configuration::additions related to external references +#--------------------------------------------------------------------------- + +# The TAGFILES option can be used to specify one or more tagfiles. +# Optionally an initial location of the external documentation +# can be added for each tagfile. The format of a tag file without +# this location is as follows: +# TAGFILES = file1 file2 ... +# Adding location for the tag files is done as follows: +# TAGFILES = file1=loc1 "file2 = loc2" ... +# where "loc1" and "loc2" can be relative or absolute paths or +# URLs. If a location is present for each tag, the installdox tool +# does not have to be run to correct the links. +# Note that each tag file must have a unique name +# (where the name does NOT include the path) +# If a tag file is not located in the directory in which doxygen +# is run, you must also specify the path to the tagfile here. + +TAGFILES = + +# When a file name is specified after GENERATE_TAGFILE, doxygen will create +# a tag file that is based on the input files it reads. + +GENERATE_TAGFILE = + +# If the ALLEXTERNALS tag is set to YES all external classes will be listed +# in the class index. If set to NO only the inherited external classes +# will be listed. + +ALLEXTERNALS = NO + +# If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed +# in the modules index. If set to NO, only the current project's groups will +# be listed. + +EXTERNAL_GROUPS = YES + +# The PERL_PATH should be the absolute path and name of the perl script +# interpreter (i.e. the result of `which perl'). + +PERL_PATH = /usr/bin/perl + +#--------------------------------------------------------------------------- +# Configuration options related to the dot tool +#--------------------------------------------------------------------------- + +# If the CLASS_DIAGRAMS tag is set to YES (the default) Doxygen will +# generate a inheritance diagram (in HTML, RTF and LaTeX) for classes with base +# or super classes. Setting the tag to NO turns the diagrams off. Note that +# this option is superseded by the HAVE_DOT option below. This is only a +# fallback. It is recommended to install and use dot, since it yields more +# powerful graphs. + +CLASS_DIAGRAMS = YES + +# If set to YES, the inheritance and collaboration graphs will hide +# inheritance and usage relations if the target is undocumented +# or is not a class. + +HIDE_UNDOC_RELATIONS = YES + +# If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is +# available from the path. This tool is part of Graphviz, a graph visualization +# toolkit from AT&T and Lucent Bell Labs. The other options in this section +# have no effect if this option is set to NO (the default) + +HAVE_DOT = YES + +# If the CLASS_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect inheritance relations. Setting this tag to YES will force the +# the CLASS_DIAGRAMS tag to NO. + +CLASS_GRAPH = YES + +# If the COLLABORATION_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect implementation dependencies (inheritance, containment, and +# class references variables) of the class with other documented classes. + +COLLABORATION_GRAPH = YES + +# If the GROUP_GRAPHS and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for groups, showing the direct groups dependencies + +GROUP_GRAPHS = YES + +# If the UML_LOOK tag is set to YES doxygen will generate inheritance and +# collaboration diagrams in a style similar to the OMG's Unified Modeling +# Language. + +UML_LOOK = NO + +# If set to YES, the inheritance and collaboration graphs will show the +# relations between templates and their instances. + +TEMPLATE_RELATIONS = NO + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDE_GRAPH, and HAVE_DOT +# tags are set to YES then doxygen will generate a graph for each documented +# file showing the direct and indirect include dependencies of the file with +# other documented files. + +INCLUDE_GRAPH = YES + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDED_BY_GRAPH, and +# HAVE_DOT tags are set to YES then doxygen will generate a graph for each +# documented header file showing the documented files that directly or +# indirectly include this file. + +INCLUDED_BY_GRAPH = YES + +# If the CALL_GRAPH and HAVE_DOT tags are set to YES then doxygen will +# generate a call dependency graph for every global function or class method. +# Note that enabling this option will significantly increase the time of a run. +# So in most cases it will be better to enable call graphs for selected +# functions only using the \callgraph command. + +CALL_GRAPH = NO + +# If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen +# will graphical hierarchy of all classes instead of a textual one. + +GRAPHICAL_HIERARCHY = YES + +# If the DIRECTORY_GRAPH, SHOW_DIRECTORIES and HAVE_DOT tags are set to YES +# then doxygen will show the dependencies a directory has on other directories +# in a graphical way. The dependency relations are determined by the #include +# relations between the files in the directories. + +DIRECTORY_GRAPH = YES + +# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images +# generated by dot. Possible values are png, jpg, or gif +# If left blank png will be used. + +DOT_IMAGE_FORMAT = png + +# The tag DOT_PATH can be used to specify the path where the dot tool can be +# found. If left blank, it is assumed the dot tool can be found in the path. + +DOT_PATH = + +# The DOTFILE_DIRS tag can be used to specify one or more directories that +# contain dot files that are included in the documentation (see the +# \dotfile command). + +DOTFILE_DIRS = + +# The MAX_DOT_GRAPH_WIDTH tag can be used to set the maximum allowed width +# (in pixels) of the graphs generated by dot. If a graph becomes larger than +# this value, doxygen will try to truncate the graph, so that it fits within +# the specified constraint. Beware that most browsers cannot cope with very +# large images. + +MAX_DOT_GRAPH_WIDTH = 1024 + +# The MAX_DOT_GRAPH_HEIGHT tag can be used to set the maximum allows height +# (in pixels) of the graphs generated by dot. If a graph becomes larger than +# this value, doxygen will try to truncate the graph, so that it fits within +# the specified constraint. Beware that most browsers cannot cope with very +# large images. + +MAX_DOT_GRAPH_HEIGHT = 1024 + +# The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the +# graphs generated by dot. A depth value of 3 means that only nodes reachable +# from the root by following a path via at most 3 edges will be shown. Nodes +# that lay further from the root node will be omitted. Note that setting this +# option to 1 or 2 may greatly reduce the computation time needed for large +# code bases. Also note that a graph may be further truncated if the graph's +# image dimensions are not sufficient to fit the graph (see MAX_DOT_GRAPH_WIDTH +# and MAX_DOT_GRAPH_HEIGHT). If 0 is used for the depth value (the default), +# the graph is not depth-constrained. + +MAX_DOT_GRAPH_DEPTH = 0 + +# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent +# background. This is disabled by default, which results in a white background. +# Warning: Depending on the platform used, enabling this option may lead to +# badly anti-aliased labels on the edges of a graph (i.e. they become hard to +# read). + +DOT_TRANSPARENT = NO + +# Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output +# files in one run (i.e. multiple -o and -T options on the command line). This +# makes dot run faster, but since only newer versions of dot (>1.8.10) +# support this, this feature is disabled by default. + +DOT_MULTI_TARGETS = YES + +# If the GENERATE_LEGEND tag is set to YES (the default) Doxygen will +# generate a legend page explaining the meaning of the various boxes and +# arrows in the dot generated graphs. + +GENERATE_LEGEND = YES + +# If the DOT_CLEANUP tag is set to YES (the default) Doxygen will +# remove the intermediate dot files that are used to generate +# the various graphs. + +DOT_CLEANUP = YES + +#--------------------------------------------------------------------------- +# Configuration::additions related to the search engine +#--------------------------------------------------------------------------- + +# The SEARCHENGINE tag specifies whether or not a search engine should be +# used. If set to NO the values of all tags below this one will be ignored. + +SEARCHENGINE = NO diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/conf/sickld.conf b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/conf/sickld.conf new file mode 100644 index 0000000..453863a --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/conf/sickld.conf @@ -0,0 +1,21 @@ +############################################################### +# +# The Sick LIDAR Matlab/C++ Toolbox +# +# File: sickld.conf +# Auth: Jason Derenick and Thomas Miller at Lehigh University +# Cont: derenick(at)lehigh(dot)edu +# Date: 20 July 2007 +# +# Desc: Sample config file for ld_config utility. +# +############################################################### + +# Define the Sick LD motor speed (Hz) +SICK_LD_MOTOR_SPEED = 10 + +# Define the Sick LD scan res. (angle step) in degrees +SICK_LD_SCAN_RESOLUTION = 0.5 + +# Define the active scan areas for the device +SICK_LD_SCAN_AREAS = [90 270] [315 45] diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/doxygen-html-header b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/doxygen-html-header new file mode 100644 index 0000000..c773c29 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/doxygen-html-header @@ -0,0 +1,3 @@ + + + diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/.deps/ConfigFile.Po b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/.deps/ConfigFile.Po new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/.deps/ConfigFile.Po @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/.deps/main.Po b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/.deps/main.Po new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/.deps/main.Po @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/ConfigFile.cpp b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/ConfigFile.cpp new file mode 100644 index 0000000..f041064 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/ConfigFile.cpp @@ -0,0 +1,142 @@ +// ConfigFile.cpp + +#include "ConfigFile.h" + +using std::string; + +ConfigFile::ConfigFile( string filename, string delimiter, + string comment, string sentry ) + : myDelimiter(delimiter), myComment(comment), mySentry(sentry) +{ + // Construct a ConfigFile, getting keys and values from given file + + std::ifstream in( filename.c_str() ); + + if( !in ) throw file_not_found( filename ); + + in >> (*this); +} + + +ConfigFile::ConfigFile() + : myDelimiter( string(1,'=') ), myComment( string(1,'#') ) +{ + // Construct a ConfigFile without a file; empty +} + + +void ConfigFile::remove( const string& key ) +{ + // Remove key and its value + myContents.erase( myContents.find( key ) ); + return; +} + + +bool ConfigFile::keyExists( const string& key ) const +{ + // Indicate whether key is found + mapci p = myContents.find( key ); + return ( p != myContents.end() ); +} + + +/* static */ +void ConfigFile::trim( string& s ) +{ + // Remove leading and trailing whitespace + static const char whitespace[] = " \n\t\v\r\f"; + s.erase( 0, s.find_first_not_of(whitespace) ); + s.erase( s.find_last_not_of(whitespace) + 1U ); +} + + +std::ostream& operator<<( std::ostream& os, const ConfigFile& cf ) +{ + // Save a ConfigFile to os + for( ConfigFile::mapci p = cf.myContents.begin(); + p != cf.myContents.end(); + ++p ) + { + os << p->first << " " << cf.myDelimiter << " "; + os << p->second << std::endl; + } + return os; +} + + +std::istream& operator>>( std::istream& is, ConfigFile& cf ) +{ + // Load a ConfigFile from is + // Read in keys and values, keeping internal whitespace + typedef string::size_type pos; + const string& delim = cf.myDelimiter; // separator + const string& comm = cf.myComment; // comment + const string& sentry = cf.mySentry; // end of file sentry + const pos skip = delim.length(); // length of separator + + string nextline = ""; // might need to read ahead to see where value ends + + while( is || nextline.length() > 0 ) + { + // Read an entire line at a time + string line; + if( nextline.length() > 0 ) + { + line = nextline; // we read ahead; use it now + nextline = ""; + } + else + { + std::getline( is, line ); + } + + // Ignore comments + line = line.substr( 0, line.find(comm) ); + + // Check for end of file sentry + if( sentry != "" && line.find(sentry) != string::npos ) return is; + + // Parse the line if it contains a delimiter + pos delimPos = line.find( delim ); + if( delimPos < string::npos ) + { + // Extract the key + string key = line.substr( 0, delimPos ); + line.replace( 0, delimPos+skip, "" ); + + // See if value continues on the next line + // Stop at blank line, next line with a key, end of stream, + // or end of file sentry + bool terminate = false; + while( !terminate && is ) + { + std::getline( is, nextline ); + terminate = true; + + string nlcopy = nextline; + ConfigFile::trim(nlcopy); + if( nlcopy == "" ) continue; + + nextline = nextline.substr( 0, nextline.find(comm) ); + if( nextline.find(delim) != string::npos ) + continue; + if( sentry != "" && nextline.find(sentry) != string::npos ) + continue; + + nlcopy = nextline; + ConfigFile::trim(nlcopy); + if( nlcopy != "" ) line += "\n"; + line += nextline; + terminate = false; + } + + // Store key and value + ConfigFile::trim(key); + ConfigFile::trim(line); + cf.myContents[key] = line; // overwrites if key is repeated + } + } + + return is; +} diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/ConfigFile.h b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/ConfigFile.h new file mode 100644 index 0000000..c2f0024 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/ConfigFile.h @@ -0,0 +1,253 @@ +// ConfigFile.h +// Class for reading named values from configuration files +// Richard J. Wagner v2.1 24 May 2004 wagnerr@umich.edu + +// Copyright (c) 2004 Richard J. Wagner +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to +// deal in the Software without restriction, including without limitation the +// rights to use, copy, modify, merge, publish, distribute, sublicense, and/or +// sell copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING +// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS +// IN THE SOFTWARE. + +// Typical usage +// ------------- +// +// Given a configuration file "settings.inp": +// atoms = 25 +// length = 8.0 # nanometers +// name = Reece Surcher +// +// Named values are read in various ways, with or without default values: +// ConfigFile config( "settings.inp" ); +// int atoms = config.read( "atoms" ); +// double length = config.read( "length", 10.0 ); +// string author, title; +// config.readInto( author, "name" ); +// config.readInto( title, "title", string("Untitled") ); +// +// See file example.cpp for more examples. + +#ifndef CONFIGFILE_H +#define CONFIGFILE_H + +#include +#include +#include +#include +#include + +using std::string; + +class ConfigFile { +// Data +protected: + string myDelimiter; // separator between key and value + string myComment; // separator between value and comments + string mySentry; // optional string to signal end of file + std::map myContents; // extracted keys and values + + typedef std::map::iterator mapi; + typedef std::map::const_iterator mapci; + +// Methods +public: + ConfigFile( string filename, + string delimiter = "=", + string comment = "#", + string sentry = "EndConfigFile" ); + ConfigFile(); + + // Search for key and read value or optional default value + template T read( const string& key ) const; // call as read + template T read( const string& key, const T& value ) const; + template bool readInto( T& var, const string& key ) const; + template + bool readInto( T& var, const string& key, const T& value ) const; + + // Modify keys and values + template void add( string key, const T& value ); + void remove( const string& key ); + + // Check whether key exists in configuration + bool keyExists( const string& key ) const; + + // Check or change configuration syntax + string getDelimiter() const { return myDelimiter; } + string getComment() const { return myComment; } + string getSentry() const { return mySentry; } + string setDelimiter( const string& s ) + { string old = myDelimiter; myDelimiter = s; return old; } + string setComment( const string& s ) + { string old = myComment; myComment = s; return old; } + + // Write or read configuration + friend std::ostream& operator<<( std::ostream& os, const ConfigFile& cf ); + friend std::istream& operator>>( std::istream& is, ConfigFile& cf ); + +protected: + template static string T_as_string( const T& t ); + template static T string_as_T( const string& s ); + static void trim( string& s ); + + +// Exception types +public: + struct file_not_found { + string filename; + file_not_found( const string& filename_ = string() ) + : filename(filename_) {} }; + struct key_not_found { // thrown only by T read(key) variant of read() + string key; + key_not_found( const string& key_ = string() ) + : key(key_) {} }; +}; + + +/* static */ +template +string ConfigFile::T_as_string( const T& t ) +{ + // Convert from a T to a string + // Type T must support << operator + std::ostringstream ost; + ost << t; + return ost.str(); +} + + +/* static */ +template +T ConfigFile::string_as_T( const string& s ) +{ + // Convert from a string to a T + // Type T must support >> operator + T t; + std::istringstream ist(s); + ist >> t; + return t; +} + + +/* static */ +template<> +inline string ConfigFile::string_as_T( const string& s ) +{ + // Convert from a string to a string + // In other words, do nothing + return s; +} + + +/* static */ +template<> +inline bool ConfigFile::string_as_T( const string& s ) +{ + // Convert from a string to a bool + // Interpret "false", "F", "no", "n", "0" as false + // Interpret "true", "T", "yes", "y", "1", "-1", or anything else as true + bool b = true; + string sup = s; + for( string::iterator p = sup.begin(); p != sup.end(); ++p ) + *p = toupper(*p); // make string all caps + if( sup==string("FALSE") || sup==string("F") || + sup==string("NO") || sup==string("N") || + sup==string("0") || sup==string("NONE") ) + b = false; + return b; +} + + +template +T ConfigFile::read( const string& key ) const +{ + // Read the value corresponding to key + mapci p = myContents.find(key); + if( p == myContents.end() ) throw key_not_found(key); + return string_as_T( p->second ); +} + + +template +T ConfigFile::read( const string& key, const T& value ) const +{ + // Return the value corresponding to key or given default value + // if key is not found + mapci p = myContents.find(key); + if( p == myContents.end() ) return value; + return string_as_T( p->second ); +} + + +template +bool ConfigFile::readInto( T& var, const string& key ) const +{ + // Get the value corresponding to key and store in var + // Return true if key is found + // Otherwise leave var untouched + mapci p = myContents.find(key); + bool found = ( p != myContents.end() ); + if( found ) var = string_as_T( p->second ); + return found; +} + + +template +bool ConfigFile::readInto( T& var, const string& key, const T& value ) const +{ + // Get the value corresponding to key and store in var + // Return true if key is found + // Otherwise set var to given default + mapci p = myContents.find(key); + bool found = ( p != myContents.end() ); + if( found ) + var = string_as_T( p->second ); + else + var = value; + return found; +} + + +template +void ConfigFile::add( string key, const T& value ) +{ + // Add a key with given value + string v = T_as_string( value ); + trim(key); + trim(v); + myContents[key] = v; + return; +} + +#endif // CONFIGFILE_H + +// Release notes: +// v1.0 21 May 1999 +// + First release +// + Template read() access only through non-member readConfigFile() +// + ConfigurationFileBool is only built-in helper class +// +// v2.0 3 May 2002 +// + Shortened name from ConfigurationFile to ConfigFile +// + Implemented template member functions +// + Changed default comment separator from % to # +// + Enabled reading of multiple-line values +// +// v2.1 24 May 2004 +// + Made template specializations inline to avoid compiler-dependent linkage +// + Allowed comments within multiple-line values +// + Enabled blank line termination for multiple-line values +// + Added optional sentry to detect end of configuration file +// + Rewrote messy trimWhitespace() function as elegant trim() diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/main.cc b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/main.cc new file mode 100644 index 0000000..4fd2151 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_config/src/main.cc @@ -0,0 +1,430 @@ +/*! + * \file main.cc + * \brief A simple configuration utility for Sick LD LIDARs. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * ConfigFile was written by Richard J. Wagner + * Download at http://www-personal.umich.edu/~wagnerr/ChE.html + * + * LDConfig is a simple utility to make configuring the SICK LD-LRS + * easier. By editing the configuration file, one can set up the LD-LRS + * in different configurations, without mucking about in source code. + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#include +#include +#include +#include +#include +#include +#include "ConfigFile.h" + +#define INVALID_OPTION_STRING " Invalid option!!! :o(" +#define PROMPT_STRING "ld?> " + +/* Config file parameters */ +#define CONFIG_OPT_MOTOR_SPD_STR "SICK_LD_MOTOR_SPEED" +#define CONFIG_OPT_SCAN_AREA_STR "SICK_LD_SCAN_AREAS" +#define CONFIG_OPT_SCAN_RES_STR "SICK_LD_SCAN_RESOLUTION" + +using namespace std; +using namespace SickToolbox; + +/** + * \fn sigintHandler + * \brief Callback for SIGINT interrupt. Used for uninitialization. + * \param signal Signal ID + */ +void sigintHandler(int signal); + +/** + * \fn getUserOption + * \brief A utility function for capturing input from the user + * \param is_null_input Indicates whether the user entered null input + * \return User option as an integer + */ +int getUserOption(bool &is_null_input); + +/** + * \fn getFilename + * \brief Prompts the user for config filename + * \return Configuration file path + */ +string getFilename(); + +/** + * \fn setConfig + * \brief Attempts to set the desired config via the driver. + * Parses configuration file as well. + */ +void setConfig(); + +/** + * \fn printConfig + * \brief Prints the current Sick status/config + */ +void printConfig(); + +/** + * \fn parseScanAreasStr + * \brief Parses the scan areas input string. + * \param start_angs Array of angles to begin a sector + * \param stop_angs Array of angles to end a sector + * \param areas String of sectors (e.g. "[0 10.75] [40.5 60.0] [85 100]") + * \param num_pairs Number of angle pairs found + * \return true on success, false otherwise + * + * pre: all parameters != NULL + * post: start_angs and stop_angs hold num_pairs values; + * 0 < num_pairs < SickLD::SICK_MAX_NUM_MEASURING_SECTORS + * + * This function separates the scan areas found in the config file + * into two arrays - one with angles that the scan areas begin at, + * and another with the angles that the scan areas end at. Uses + * setAngle() + */ +bool parseScanAreasStr(string& scan_areas_str, double *start_angs, double *stop_angs, int& num_sectors); + +/** + * \fn parseNumStr + * \param entry String to be converted to a number + * \param num Variable to receive converted string + * \return true on success, false otherwise + * + * Parses entry string into a double, and saves it in num. + */ +bool parseNumStr(const string& entry, double& num); + +/* A pointer to the current driver instance */ +SickLD *sick_ld = NULL; + +int main(int argc, char* argv[]) +{ + + string sick_ip_addr(DEFAULT_SICK_IP_ADDRESS); // IP address of the Sick LD unit + + /* Check the num args */ + if(argc > 2 || (argc == 2 && strcasecmp(argv[1],"--help") == 0)) { + cerr << "Usage: ld_config [SICK IP ADDRESS]" << endl + << "Ex. ld_config 192.168.1.11" << endl; + return -1; + } + + /* Assign the IP address */ + if(argc == 2) { + sick_ip_addr = argv[1]; + } + + /* Instantiate the SickLD driver */ + sick_ld = new SickLD(sick_ip_addr); + + cout << endl; + cout << "The Sick LIDAR C++/Matlab Toolbox " << endl; + cout << "Sick LD Config Utility " << endl; + cout << endl; + + /* Initialize the Sick LD */ + try { + sick_ld->Initialize(); + } + + catch(...) { + cerr << "Initialize failed! Are you using the correct IP address?" << endl; + return -1; + } + + /* Register the signal handler */ + signal(SIGINT,sigintHandler); + + do { + + cout << "Enter your choice: (Ctrl-c to exit)" << endl; + cout << " [1] Set new configuration"<< endl; + cout << " [2] Show current settings"<< endl; + cout << PROMPT_STRING; + + bool is_null_input; + switch(getUserOption(is_null_input)) { + + case 1: + setConfig(); + break; + case 2: + printConfig(); + break; + default: + if(!is_null_input) { + cerr << INVALID_OPTION_STRING << endl; + } + + } + + cout << endl; + + } while(true); + + /* Success */ + return 0; + +} + +/** + * Handles the SIGINT signal + */ +void sigintHandler(int signal) { + + cout << endl; + cout << "Quitting..." << endl; + + /* Unitialize the device */ + try { + + sick_ld->Uninitialize(); + delete sick_ld; + + } + + catch(...) { + cerr << "Uninitialize failed!" << endl; + exit(-1); + } + + cout << endl; + cout << "Thanks for using the Sick LIDAR Matlab/C++ Toolbox!" << endl; + cout << "Bye Bye :o)" << endl; + + exit(0); + +} + +/** + * Reads user input string and returns numeric representation. + */ +int getUserOption(bool &is_null_input) { + + string user_input_str; + getline(cin,user_input_str); + + // Check whether its null input + is_null_input = true; + if (user_input_str.length() > 0) { + is_null_input = false; + } + + int int_val = 0; + istringstream input_stream(user_input_str); + input_stream >> int_val; + + return int_val; + +} + +/** + * Prompts the user for the filename + */ +string getFilename() { + + string filename; + + cout << "config file: "; + getline(cin,filename); + + return filename; + +} + +/** + * Parses config file and loads new configuration + */ +void setConfig() { + + int motor_spd; + int num_sectors; + double scan_res; + double start_angs[SickLD::SICK_MAX_NUM_MEASURING_SECTORS] = {0}; + double stop_angs[SickLD::SICK_MAX_NUM_MEASURING_SECTORS] = {0}; + string scan_areas_str; + + ConfigFile sick_config_file; // Extracts values from config file + string config_path; + + /* Prompt the user for the filename */ + config_path = getFilename(); + + /* Instantiate the parser */ + if(ifstream(config_path.c_str())) { + sick_config_file = ConfigFile(config_path); + } + else { + cerr << "Invalid filename!" << endl; + return; + } + + /* Use the ConfigFile class to extract the various parameters for + * the sick configuration. + * + * NOTE: The third parameter specifies the value to use, if the second + * parameter is not found in the file. + */ + if(!sick_config_file.readInto(motor_spd,CONFIG_OPT_MOTOR_SPD_STR)) { + cerr << "ERROR: Invalid config file - " << CONFIG_OPT_MOTOR_SPD_STR << " needs to be specified!" << endl; + return; + } + + if(!sick_config_file.readInto(scan_res,CONFIG_OPT_SCAN_RES_STR)) { + cerr << "ERROR: Invalid config file - " << CONFIG_OPT_SCAN_RES_STR << " needs to be specified!" << endl; + return; + } + + if(!sick_config_file.readInto(scan_areas_str,CONFIG_OPT_SCAN_AREA_STR)) { + cerr << "ERROR: Invalid config file - " << CONFIG_OPT_SCAN_AREA_STR << " needs to be specified!" << endl; + return; + } + + /* Extract the start/stop pairs and angle res for the scanning sectors */ + if (!parseScanAreasStr(scan_areas_str,start_angs,stop_angs,num_sectors)) { + cerr << "ERROR: Parser failed to extract scan areas!" << endl; + return; + } + + /* Set the global parameters - we pass them all at once to ensure a feasible config */ + cout << endl << "\tAttempting to configure the Sick LD..." << endl; + + try { + sick_ld->SetSickGlobalParamsAndScanAreas(motor_spd,scan_res,start_angs,stop_angs,num_sectors); + } + + catch(SickConfigException &sick_config_exception) { + cerr << "ERROR: Couldn't set requested configuration!" << endl; + return; + } + + catch(...) { + exit(-1); + } + + cout << "\t\tConfiguration Successfull!!!" << endl; + +} + +/** + * Print the current Sick LD configuration + */ +void printConfig() { + + cout << endl; + sick_ld->PrintSickStatus(); + sick_ld->PrintSickIdentity(); + sick_ld->PrintSickGlobalConfig(); + sick_ld->PrintSickEthernetConfig(); + sick_ld->PrintSickSectorConfig(); + +} + +/** + * Parses scan areas string in order extract desired sector configuration + */ +bool parseScanAreasStr(string& areas, double * start_angs, double * stop_angs, int& num_pairs) { + + unsigned long i; // number of sectors found so far + unsigned int start_pos = 0; // starting position of a sector in 'areas' + unsigned int end_pos = 0; // ending position of a sector in 'areas' + unsigned int split = 0; // position of the delimiter inside a sector + string pair; // a string of 'areas' that contains one start and one stop angle + + /* Get the beginning and end of the first scan sector */ + start_pos = areas.find('[',start_pos); // Find the next [, starting at start_pos + end_pos = areas.find(']',start_pos); + + /* Keep getting sectors until we either run out of open + * brackets or we exceed the number of allowed sectors + */ + for(i=0; (start_pos != (unsigned int)string::npos) && (i <= SickLD::SICK_MAX_NUM_MEASURING_SECTORS); i++) { + + pair = areas.substr(start_pos+1,end_pos-(start_pos+1)); + + /* Eliminate any padding before first value */ + try { + pair = pair.substr(pair.find_first_not_of(' ')); + } + + catch(...) { + cerr << "ERROR: There was an problem parsing your scan areas! Check your config file." << endl; + return false; + } + + split = pair.find(' '); + + /* Catch a lack of ' ' inside the sector definition; + * alternative is to let it fail at pair.substr(split) + */ + if(split == (unsigned int)string::npos) { + cerr << "ERROR: Invalid sector definition." << endl; + return false; + } + + /* Get the number from the beginning to the delimiter */ + if(!parseNumStr(pair.substr(0,split),start_angs[i])) { + cerr << "ERROR: Invalid start angle found." << endl; + return false; + } + + /* Get the number from the delimiter to the end */ + if(!parseNumStr(pair.substr(split),stop_angs[i])) { + cerr << "ERROR: Invalid stop angle found." << endl; + return false; + } + + start_pos = end_pos; // Shift to the end of the current sector + + /* Try to find another sector */ + start_pos = areas.find("[", start_pos); + end_pos = areas.find("]", start_pos); + + } + + num_pairs = i; + + /* Check if we broke out because of too many loops */ + if(num_pairs > SickLD::SICK_MAX_NUM_MEASURING_SECTORS) { + cerr << "ERROR: Too many scan areas found (max " << SickLD::SICK_MAX_NUM_MEASURING_SECTORS << ")" << endl; + return false; + } + + /* Or, we might not have even entered the loop */ + if(num_pairs == 0) { + cerr << "ERROR: No scan areas found! Check brackets in your config file." << endl; + return false; + } + + /* Success! */ + return true; + +} + +/** + * Parses entry string into a double, and saves it in num. + */ +bool parseNumStr(const string& entry, double& num) +{ + + string num_str = entry.substr(entry.find_first_not_of(' ')); + istringstream input_stream(num_str.c_str()); + if(!(input_stream >> num)) { + cerr << "ERROR: Invalid angle value: " + num_str << endl; + return false; + } + + /* Success! */ + return true; + +} diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_more_config/src/.deps/main.Po b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_more_config/src/.deps/main.Po new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_more_config/src/.deps/main.Po @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_more_config/src/main.cc b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_more_config/src/main.cc new file mode 100644 index 0000000..fea4e7b --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_more_config/src/main.cc @@ -0,0 +1,113 @@ + +/*! + * \file main.cc + * \brief Illustrates a variety of ways to configure the flash + * parameters on the Sick LD device as well as how to set + * the unit's clock. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#include +#include +#include +#include + +using namespace std; +using namespace SickToolbox; + +int main (int argc, char *argv[]) { + + /* A string for the IP address */ + string sick_ip_addr(DEFAULT_SICK_IP_ADDRESS); + + /* Check the num of args */ + if(argc > 2 || (argc == 2 && strcasecmp(argv[1],"--help") == 0)) { + cerr << "Usage: ld_more_config [SICK IP ADDRESS]" << endl + << "Ex. ld_more_config 192.168.1.11" << endl; + return -1; + } + + /* Assign the IP address */ + if(argc == 2) { + sick_ip_addr = argv[1]; + } + + /* Define the object */ + SickLD sick_ld(sick_ip_addr); + + /* + * Initialize the Sick LD + */ + try { + sick_ld.Initialize(); + } + + catch(...) { + cerr << "Initialize failed! Are you using the correct IP address?" << endl; + return -1; + } + + try { + + /* Assign absolute and then relative time */ + //uint16_t new_sick_time = 0; + //sick_ld.SetSickTimeAbsolute(1500,new_sick_time); + //cout << "\tNew sick time: " << new_sick_time << endl; + //sick_ld.SetSickTimeRelative(-500,new_sick_time); + //cout << "\tNew sick time: " << new_sick_time << endl; + + /* Configure the Sick LD sensor ID */ + //sick_ld.PrintSickGlobalConfig(); + //sick_ld.SetSickSensorID(16); + //sick_ld.PrintSickGlobalConfig(); + + /* Configure the sick motor speed */ + //sick_ld.PrintSickGlobalConfig(); + //sick_ld.SetSickMotorSpeed(10); + //sick_ld.PrintSickGlobalConfig(); + + /* Configure the sick scan resolution */ + //sick_ld.PrintSickGlobalConfig(); + //sick_ld.SetSickScanResolution(0.5); + //sick_ld.PrintSickGlobalConfig(); + + /* Configure all the global parameters */ + //double start_angle = 45; + //double stop_angle = 315; + //sick_ld.PrintSickGlobalConfig(); + //sick_ld.PrintSickSectorConfig(); + //sick_ld.SetSickGlobalParamsAndScanAreas(10,0.5,&start_angle,&stop_angle,1); + //sick_ld.PrintSickGlobalConfig(); + //sick_ld.PrintSickSectorConfig(); + + } + + catch(...) { + cerr << "An error occurred!" << endl; + } + + /* + * Uninitialize the device + */ + try { + sick_ld.Uninitialize(); + } + + catch(...) { + cerr << "Uninitialize failed!" << endl; + return -1; + } + + /* Success! */ + return 0; + +} diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_multi_sector/src/.deps/main.Po b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_multi_sector/src/.deps/main.Po new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_multi_sector/src/.deps/main.Po @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_multi_sector/src/main.cc b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_multi_sector/src/main.cc new file mode 100644 index 0000000..9865b2e --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_multi_sector/src/main.cc @@ -0,0 +1,124 @@ +/*! + * \file main.cc + * \brief Illustrates how to work with the Sick LD + * using multiple scan areas/sectors. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#include +#include +#include +#include + +/* Define the number of active sectors */ +#define NUM_ACTIVE_SECTORS (3) + +using namespace std; +using namespace SickToolbox; + +int main (int argc, char *argv[]) { + + /* A string for the IP address */ + string sick_ip_addr(DEFAULT_SICK_IP_ADDRESS); + + /* Check the num of args */ + if(argc > 2 || (argc == 2 && strcasecmp(argv[1],"--help") == 0)) { + cerr << "Usage: ld_multi_sector [SICK IP ADDRESS]" << endl + << "Ex. ld_multi_sector 192.168.1.11" << endl; + return -1; + } + + /* Assign the IP address */ + if(argc == 2) { + sick_ip_addr = argv[1]; + } + + /* Define the temporal scan area (3 active sectors/scan areas) + * NOTE: This scan configuration will persist until the power + * is cycled or until it is reset w/ different params. + */ + double sector_start_angs[NUM_ACTIVE_SECTORS] = {45,270,345}; + double sector_stop_angs[NUM_ACTIVE_SECTORS] = {90,315,15}; + + /* Define the destination buffers */ + double range_values[SickLD::SICK_MAX_NUM_MEASUREMENTS] = {0}; + unsigned int reflect_values[SickLD::SICK_MAX_NUM_MEASUREMENTS] = {0}; + + /* Some buffer for additional info we can get from the Sick LD */ + unsigned int num_values[NUM_ACTIVE_SECTORS] = {0}; + unsigned int data_offsets[NUM_ACTIVE_SECTORS] = {0}; + unsigned int sector_ids[NUM_ACTIVE_SECTORS] = {0}; + + /* Define the object */ + SickLD sick_ld(sick_ip_addr); + + /* Initialize the Sick LD */ + try { + sick_ld.Initialize(); + } + + catch(...) { + cerr << "Initialize failed! Are you using the correct IP address?" << endl; + return -1; + } + + try { + + /* Set the temporary scan areas */ + sick_ld.SetSickTempScanAreas(sector_start_angs,sector_stop_angs,NUM_ACTIVE_SECTORS); + + /* Print the sector configuration */ + sick_ld.PrintSickSectorConfig(); + + /* Request some measurements */ + for (unsigned int i = 0; i < 10; i++) { + + /* Acquire the most recent range and reflectivity (echo amplitude) values */ + sick_ld.GetSickMeasurements(range_values,reflect_values,num_values,sector_ids,data_offsets); + + /* Print out some data for each sector */ + for (unsigned int i = 0; i < NUM_ACTIVE_SECTORS; i++) { + + cout << "\t[Sector ID: " << sector_ids[i] + << ", Num Meas: " << num_values[i] + << ", 1st Range Val: " << range_values[data_offsets[i]] + << ", 1st Reflect Val: " << reflect_values[data_offsets[i]] + << "]" << endl; + + } + cout << endl; + + } + + } + + /* Catch any exception! */ + catch(...) { + cerr << "An error occurred!" << endl; + } + + /* + * Uninitialize the device + */ + try { + sick_ld.Uninitialize(); + } + + catch(...) { + cerr << "Uninitialize failed!" << endl; + return -1; + } + + /* Success !*/ + return 0; + +} diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_single_sector/src/.deps/main.Po b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_single_sector/src/.deps/main.Po new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_single_sector/src/.deps/main.Po @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_single_sector/src/main.cc b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_single_sector/src/main.cc new file mode 100644 index 0000000..8edc7f0 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/ld/ld_single_sector/src/main.cc @@ -0,0 +1,105 @@ +/*! + * \file main.cc + * \brief A simple application illustrating the use of + * the Sick LD C++ driver using a single sector. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#include +#include +#include +#include + +/* Use the namespace */ +using namespace std; +using namespace SickToolbox; + +int main (int argc, char *argv[]) { + + /* A string for the IP address */ + string sick_ip_addr(DEFAULT_SICK_IP_ADDRESS); + + /* Check the num of args */ + if(argc > 2 || (argc == 2 && strcasecmp(argv[1],"--help") == 0)) { + cerr << "Usage: ld_single_sector [SICK IP ADDRESS]" << endl + << "Ex. ld_single_sector 192.168.1.11" << endl; + return -1; + } + + /* Assign the IP address */ + if(argc == 2) { + sick_ip_addr = argv[1]; + } + + /* Define the data buffers */ + double values[SickLD::SICK_MAX_NUM_MEASUREMENTS] = {0}; + unsigned int num_values = 0; + + /* Define the bounds for a single sector */ + double sector_start_ang = 90; + double sector_stop_ang = 270; + + /* Define the object */ + SickLD sick_ld(sick_ip_addr); + + /* + * Initialize the Sick LD + */ + try { + sick_ld.Initialize(); + } + + catch(...) { + cerr << "Initialize failed! Are you using the correct IP address?" << endl; + return -1; + } + + try { + + /* Set the desired sector configuration */ + sick_ld.SetSickTempScanAreas(§or_start_ang,§or_stop_ang,1); + + /* Print the sector configuration */ + sick_ld.PrintSickSectorConfig(); + + /* Acquire some range measurements */ + for (unsigned int i = 0; i < 10; i++) { + + /* Here we only want the range values so the second arg is NULL */ + sick_ld.GetSickMeasurements(values,NULL,&num_values); + cout << "\t Num. Values: " << num_values << endl; + + } + + } + + /* Catch any exceptions */ + catch(...) { + cerr << "An error occurred!" << endl; + } + + /* + * Uninitialize the device + */ + try { + sick_ld.Uninitialize(); + } + + catch(...) { + cerr << "Uninitialize failed!" << endl; + return -1; + } + + /* Success !*/ + return 0; + +} diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms1xx/lms1xx_simple_app/src/.deps/main.Po b/sitl_config/ugv/sicktoolbox/c++/examples/lms1xx/lms1xx_simple_app/src/.deps/main.Po new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms1xx/lms1xx_simple_app/src/.deps/main.Po @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms1xx/lms1xx_simple_app/src/main.cc b/sitl_config/ugv/sicktoolbox/c++/examples/lms1xx/lms1xx_simple_app/src/main.cc new file mode 100644 index 0000000..6c1ca51 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms1xx/lms1xx_simple_app/src/main.cc @@ -0,0 +1,94 @@ +/*! + * \file main.cc + * \brief A simple application using the Sick LMS 1xx driver. + * + * Code by Jason C. Derenick and Christopher R. Mansley. + * Contact jasonder(at)seas(dot)upenn(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2009, Jason C. Derenick and Christopher R. Mansley + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#include +#include +#include +#include + +using namespace std; +using namespace SickToolbox; + +int main(int argc, char* argv[]) +{ + + /* + * Instantiate an instance + */ + SickLMS1xx sick_lms_1xx; + + /* + * Initialize the Sick LMS 2xx + */ + try { + sick_lms_1xx.Initialize(); + } + + catch(...) { + cerr << "Initialize failed! Are you using the correct IP address?" << endl; + return -1; + } + + try { + unsigned int status = 1; + unsigned int num_measurements = 0; + unsigned int range_1_vals[SickLMS1xx::SICK_LMS_1XX_MAX_NUM_MEASUREMENTS]; + unsigned int range_2_vals[SickLMS1xx::SICK_LMS_1XX_MAX_NUM_MEASUREMENTS]; + //sick_lms_1xx.SetSickScanFreqAndRes(SickLMS1xx::SICK_LMS_1XX_SCAN_FREQ_25, + //SickLMS1xx::SICK_LMS_1XX_SCAN_RES_25); + //sick_lms_1xx.SetSickScanDataFormat(SickLMS1xx::SICK_LMS_1XX_DIST_DOUBLE_PULSE, + // SickLMS1xx::SICK_LMS_1XX_REFLECT_NONE); + sick_lms_1xx.SetSickScanDataFormat(SickLMS1xx::SICK_LMS_1XX_SCAN_FORMAT_DIST_DOUBLE_PULSE_REFLECT_16BIT); + for (int i = 0; i < 1000; i++) { + sick_lms_1xx.GetSickMeasurements(range_1_vals,range_2_vals,range_1_vals,range_2_vals,num_measurements,&status); + std::cout << i << ": " << num_measurements << " " << status << std::endl; + } + } + + catch(SickConfigException sick_exception) { + std::cout << sick_exception.what() << std::endl; + } + + catch(SickIOException sick_exception) { + std::cout << sick_exception.what() << std::endl; + } + + catch(SickTimeoutException sick_exception) { + std::cout << sick_exception.what() << std::endl; + } + + catch(...) { + cerr << "An Error Occurred!" << endl; + return -1; + } + + + /* + * Uninitialize the device + */ + try { + sick_lms_1xx.Uninitialize(); + } + + catch(...) { + cerr << "Uninitialize failed!" << endl; + return -1; + } + + /* Success! */ + return 0; + +} + diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_config/README b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_config/README new file mode 100644 index 0000000..31bf922 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_config/README @@ -0,0 +1,14 @@ +================================================= +Sick LIDAR Matlab/C++ Toolbox +================================================= + +Example: lms_config +Note: This example is COMPATIBLE w/ ALL Sick 2xx LIDAR units! :o) + +Desc: This example provides a simple shell-like configuration + utility for working w/ Sick LMS 2xx LIDARs. It can be + used for setting measuring units, measuring mode, and + sensitivity. It can also display the current LMS config. + +Example call (from build dir): ./lms_config /dev/ttyUSB0 9600 + diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_config/src/.deps/main.Po b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_config/src/.deps/main.Po new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_config/src/.deps/main.Po @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_config/src/main.cc b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_config/src/main.cc new file mode 100644 index 0000000..36a1f28 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_config/src/main.cc @@ -0,0 +1,627 @@ +/*! + * \file main.cc + * \brief A simple config utility for Sick LMS 2xx LIDARs. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +/* Implementation dependencies */ +#include +#include +#include +#include +#include +#include +#include + +#define INVALID_OPTION_STRING " Invalid option!!! :o(" +#define PROMPT_STRING "lms2xx?> " + +using namespace std; +using namespace SickToolbox; + +/** + * \fn sigintHandler + * \brief Callback for SIGINT interrupt. Used for uninitialization. + * \param signal Signal ID + */ +void sigintHandler(int signal); + +/** + * \fn strToInt + * \brief Utility function for converting string to int + * \param input_str Input string to convert + */ +int strToInt(string input_str); + +/** + * \fn getUserOption + * \brief Utility function for grabbing user input + * \param is_null_input Output parameter indicating whether + * user entered NULL input + */ +int getUserOption(bool &is_null_input); + +/** + * \fn writeToEEPROM + * \brief Confirms the user actually wants to perform write + */ +bool writeToEEPROM(); + +/** + * \fn setMeasuringUnits + * \brief Prompts the user and sets the desired measuring + * units via the driver interface. + */ +void setMeasuringUnits(); + +/** + * \fn setMeasuringMode + * \brief Prompts the user and sets the desired measuring + * mode via the driver interface. + */ +void setMeasuringMode(); + +/** + * \fn setAvailabilityLevel + * \brief Prompts the user and sets the desired availability + * level via the driver interface. + */ +void setAvailabilityLevel(); + +/** + * \fn setSensitivityLevel + * \brief Prompts the user and sets the desired sensitivity + * level via the driver interface. + */ +void setSensitivityLevel(); + +/* A pointer to the Sick obj */ +SickLMS2xx *sick_lms_2xx = NULL; + +int main(int argc, char * argv[]) { + + string device_str; // Device path of the Sick LMS 2xx + SickLMS2xx::sick_lms_2xx_baud_t desired_baud = SickLMS2xx::SICK_BAUD_38400; + + /* Check for a device path. If it's not present, print a usage statement. */ + if ((argc != 2 && argc != 3) || (argc == 2 && strcasecmp(argv[1],"--help") == 0)) { + cout << "Usage: lms2xx_config PATH [BAUD RATE]" << endl + << "Ex: lms2xx_config /dev/ttyUSB0 9600" << endl; + return -1; + } + + /* Only device path is given */ + if (argc == 2) { + device_str = argv[1]; + } + + /* Device path and baud are given */ + if (argc == 3) { + device_str = argv[1]; + if ((desired_baud = SickLMS2xx::StringToSickBaud(argv[2])) == SickLMS2xx::SICK_BAUD_UNKNOWN) { + cerr << "Invalid baud value! Valid values are: 9600, 19200, 38400, and 500000" << endl; + return -1; + } + } + + /* Instantiate the SickLMS2xx class with the device path string. */ + sick_lms_2xx = new SickLMS2xx(device_str); + + cout << endl; + cout << "The Sick LIDAR C++/Matlab Toolbox " << endl; + cout << "Sick LMS 2xx Config Utility " << endl; + + /* Initialize the device */ + try { + sick_lms_2xx->Initialize(desired_baud); + } + + catch(...) { + cerr << "Initialize failed! Are you using the correct device path?" << endl; + return -1; + } + + /* Register the signal handler */ + signal(SIGINT,sigintHandler); + + cout << "NOTE - Configuring the Sick LMS - REQUIRES - writing to the device's EEPROM." << endl; + cout << " The number of times this can be done is finite (a few thousand)." << endl; + cout << " Thus, you should configure sparingly." << endl; + cout << endl; + + do { + + cout << "Enter your choice: (Ctrl-c to exit)" << endl; + cout << " [1] Set measuring units"<< endl; + cout << " [2] Set measuring mode"<< endl; + cout << " [3] Set availability level" << endl; + cout << " [4] Set sensitivity level" << endl; + cout << " [5] Show detailed configuration" << endl; + cout << PROMPT_STRING; + + bool is_null_input; + switch(getUserOption(is_null_input)) { + + case 1: + setMeasuringUnits(); + break; + case 2: + setMeasuringMode(); + break; + case 3: + setAvailabilityLevel(); + break; + case 4: + setSensitivityLevel(); + break; + case 5: + sick_lms_2xx->PrintSickConfig(); + break; + default: + if (!is_null_input) { + cerr << INVALID_OPTION_STRING << endl; + } + } + + cout << endl; + + } while(true); + + /* Success! */ + return 0; + +} + +/** + * Handle the SIGINT signal + */ +void sigintHandler( int signal ) { + + cout << endl; + cout << "Quitting..." << endl; + + /* Unitialize the device */ + try { + + sick_lms_2xx->Uninitialize(); + delete sick_lms_2xx; + + } + + catch(...) { + cerr << "Uninitialize failed!" << endl; + exit(-1); + } + + cout << endl; + cout << "Thanks for using the Sick LIDAR Matlab/C++ Toolbox!" << endl; + cout << "Bye Bye :o)" << endl; + + exit(0); + +} + +/** + * Converts ascii string to an integer + */ +int strToInt( string input_str ) { + int int_val; + istringstream input_stream(input_str); + input_stream >> int_val; + return int_val; +} + +/** + * Reads in user input string and returns numeric + * representation + */ +int getUserOption( bool &is_null_input ) { + + string user_input_str; + getline(cin,user_input_str); + + // Check whether its null input + is_null_input = true; + if (user_input_str.length() > 0) { + is_null_input = false; + } + + return strToInt(user_input_str); + +} + +/** + * Prompts the user to confirm requested operation + */ +bool writeToEEPROM( ) { + + string user_input_str; + + do { + + cout << "This will attempt to write to EEPROM. Continue [y/n]? "; + getline(cin,user_input_str); + + // Check whether its null input + if (user_input_str == "Y" || user_input_str == "y") { + return true; + } + else if (user_input_str == "N" || user_input_str == "n") { + return false; + } + else { + cerr << "Please answer [y/n]!" << endl; + } + + } while (true); + +} + +/** + * Sets the measuring units of the device + */ +void setMeasuringUnits() { + + bool keep_running = true; + + do { + + cout << endl; + cout << "Select the desired units:" << endl; + cout << " [1] Centimeters (cm)"<< endl; + cout << " [2] Millimeters (mm)"<< endl; + cout << " [3] Back to main"<< endl; + cout << PROMPT_STRING; + + try { + + bool is_null_input; + switch(getUserOption(is_null_input)) { + + case 1: + if (writeToEEPROM()) { + cout << " Setting Sick LMS units to (cm)" << endl; + sick_lms_2xx->SetSickMeasuringUnits(SickLMS2xx::SICK_MEASURING_UNITS_CM); + cout << " Done!" << endl; + } + break; + case 2: + if (writeToEEPROM()) { + cout << " Setting Sick LMS units to (mm)" << endl; + sick_lms_2xx->SetSickMeasuringUnits(SickLMS2xx::SICK_MEASURING_UNITS_MM); + cout << " Done!" << endl; + } + break; + case 3: + keep_running = !keep_running; + break; + default: + if (!is_null_input) { + cerr << INVALID_OPTION_STRING << endl; + } + } + + } + + catch( SickException &sick_exception ) { + cerr << "A Sick exception occurred!" << endl; + exit(-1); + } + + catch(...) { + cerr << "An unknown exception occurred!" << endl; + exit(-1); + } + + } while (keep_running); + +} + +/** + * Sets the measuring mode of the device + */ +void setMeasuringMode() { + + bool keep_running = true; + + do { + + cout << endl; + cout << "Select the desired measuring mode (see telegram listing for descriptions):" << endl; + cout << " [1] Measurement range 8m/80m; field A, field B, and dazzle" << endl; + cout << " [2] Measurement range 8m/80m; reflector bits in 8 levels" << endl; + cout << " [3] Measurement range 8m/80m; field A, field B and field C" << endl; + cout << " [4] Measurement range 16m/theoretically 160m; reflector bits in 4 levels" << endl; + cout << " [5] Measurement range 16m/theoretically 160m; field A and field B" << endl; + cout << " [6] Measurement range 32m/theoretically 320m; reflector bits in 2 levels" << endl; + cout << " [7] Measurement range 32m/theoretically 320m; field A" << endl; + cout << " [8] Measurement range 32m/theoretically 320m; Immediate" << endl; + cout << " [9] Reflectivity/Intensity values" << endl; + cout << " [10] Back to main" << endl; + cout << PROMPT_STRING; + + try { + + bool is_null_input; + switch(getUserOption(is_null_input)) { + + case 1: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Meas. Mode to: Measurement range 8m/80m; field A, field B, and dazzle" << endl; + sick_lms_2xx->SetSickMeasuringMode(SickLMS2xx::SICK_MS_MODE_8_OR_80_FA_FB_DAZZLE); + cout << " Done!" << endl; + } + break; + case 2: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Meas. Mode to: Measurement range 8m/80m; reflector bits in 8 levels" << endl; + sick_lms_2xx->SetSickMeasuringMode(SickLMS2xx::SICK_MS_MODE_8_OR_80_REFLECTOR); + cout << " Done!" << endl; + } + break; + case 3: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Meas. Mode to: Measurement range 8m/80m; field A, field B and field C" << endl; + sick_lms_2xx->SetSickMeasuringMode(SickLMS2xx::SICK_MS_MODE_8_OR_80_FA_FB_FC); + cout << " Done!" << endl; + } + break; + case 4: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Meas. Mode to: Measurement range 16m/theoretically 160m; reflector bits in 4 levels" << endl; + sick_lms_2xx->SetSickMeasuringMode(SickLMS2xx::SICK_MS_MODE_16_REFLECTOR); + cout << " Done!" << endl; + } + break; + case 5: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Meas. Mode to: Measurement range 16m/theoretically 160m; field A and field B" << endl; + sick_lms_2xx->SetSickMeasuringMode(SickLMS2xx::SICK_MS_MODE_16_FA_FB); + cout << " Done!" << endl; + } + break; + case 6: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Meas. Mode to: Measurement range 32m/theoretically 320m; reflector bit in 2 levels" << endl; + sick_lms_2xx->SetSickMeasuringMode(SickLMS2xx::SICK_MS_MODE_32_REFLECTOR); + cout << " Done!" << endl; + } + break; + case 7: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Meas. Mode to: Measurement range 32m/theoretically 320m; field A" << endl; + sick_lms_2xx->SetSickMeasuringMode(SickLMS2xx::SICK_MS_MODE_32_FA); + cout << " Done!" << endl; + } + break; + case 8: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Meas. Mode to: Measurement range 32m/theoretically 320m; Immediate" << endl; + sick_lms_2xx->SetSickMeasuringMode(SickLMS2xx::SICK_MS_MODE_32_IMMEDIATE); + cout << " Done!" << endl; + } + break; + case 9: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Meas. Mode to: Reflectivity/Intensity" << endl; + sick_lms_2xx->SetSickMeasuringMode(SickLMS2xx::SICK_MS_MODE_REFLECTIVITY); + cout << " Done!" << endl; + } + break; + case 10: + keep_running = !keep_running; + break; + default: + if (!is_null_input) { + cerr << INVALID_OPTION_STRING << endl; + } + } + + } + + catch( SickException &sick_exception ) { + cerr << "A Sick exception occurred!" << endl; + exit(-1); + } + + catch(...) { + cerr << "An unknown exception occurred!" << endl; + exit(-1); + } + + } while (keep_running); + +} + +/** + * Sets the measuring mode of the device + */ +void setAvailabilityLevel() { + + bool keep_running = true; + + do { + + cout << endl; + cout << "Select the desired availability (see telegram listing for descriptions):" << endl; + cout << " [1] Restore to factory default" << endl; + cout << " [2] High" << endl; + cout << " [3] High w/ Real-time indices" << endl; + cout << " [4] High w/ No effect dazzle" << endl; + cout << " [5] High w/ Real-time indices and No effect dazzle" << endl; + cout << " [6] Real-time indices" << endl; + cout << " [7] Real-time indices w/ No effect dazzle" << endl; + cout << " [8] No effect dazzle" << endl; + cout << " [9] Back to main" << endl; + cout << PROMPT_STRING; + + try { + + bool is_null_input; + switch(getUserOption(is_null_input)) { + + case 1: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Availability to: Factory settings" << endl; + sick_lms_2xx->SetSickAvailability(); + cout << " Done!" << endl; + } + break; + case 2: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Availability to: High" << endl; + sick_lms_2xx->SetSickAvailability(SickLMS2xx::SICK_FLAG_AVAILABILITY_HIGH); + cout << " Done!" << endl; + } + break; + case 3: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Availability to: High w/ Real-time indices" << endl; + sick_lms_2xx->SetSickAvailability(SickLMS2xx::SICK_FLAG_AVAILABILITY_HIGH | SickLMS2xx::SICK_FLAG_AVAILABILITY_REAL_TIME_INDICES); + cout << " Done!" << endl; + } + break; + case 4: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Availability to: High w/ No effect dazzle" << endl; + sick_lms_2xx->SetSickAvailability(SickLMS2xx::SICK_FLAG_AVAILABILITY_HIGH | SickLMS2xx::SICK_FLAG_AVAILABILITY_DAZZLE_NO_EFFECT); + cout << " Done!" << endl; + } + break; + case 5: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Availability to: High w/ Real-time indices and No effect dazzle" << endl; + sick_lms_2xx->SetSickAvailability(SickLMS2xx::SICK_FLAG_AVAILABILITY_HIGH | SickLMS2xx::SICK_FLAG_AVAILABILITY_REAL_TIME_INDICES | SickLMS2xx::SICK_FLAG_AVAILABILITY_DAZZLE_NO_EFFECT); + cout << " Done!" << endl; + } + break; + case 6: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Availability to: Real-time indices" << endl; + sick_lms_2xx->SetSickAvailability(SickLMS2xx::SICK_FLAG_AVAILABILITY_REAL_TIME_INDICES); + cout << " Done!" << endl; + } + break; + case 7: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Availability to: Real-time indices w/ No effect dazzle" << endl; + sick_lms_2xx->SetSickAvailability(SickLMS2xx::SICK_FLAG_AVAILABILITY_REAL_TIME_INDICES | SickLMS2xx::SICK_FLAG_AVAILABILITY_DAZZLE_NO_EFFECT); + cout << " Done!" << endl; + } + break; + case 8: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Availability to: No effect dazzle" << endl; + sick_lms_2xx->SetSickAvailability(SickLMS2xx::SICK_FLAG_AVAILABILITY_DAZZLE_NO_EFFECT); + cout << " Done!" << endl; + } + break; + case 9: + keep_running = !keep_running; + break; + default: + if (!is_null_input) { + cerr << INVALID_OPTION_STRING << endl; + } + } + + } + + catch( SickException &sick_exception ) { + cerr << "A Sick exception occurred!" << endl; + exit(-1); + } + + catch(...) { + cerr << "An unknown exception occurred!" << endl; + exit(-1); + } + + } while (keep_running); + +} + +/** + * Sets the Sick LMS sensitivity level + */ +void setSensitivityLevel() { + + bool keep_running = true; + + do { + + cout << endl; + cout << "Select the desired sensitivity level:" << endl; + cout << " [1] High (42m @ 10% reflectivity)"<< endl; + cout << " [2] Standard (30m @ 10% reflectivity, factory setting)"<< endl; + cout << " [3] Medium (25m @ 10% reflectivity)"<< endl; + cout << " [4] Low (20m @ 10% reflectivity)"<< endl; + cout << " [5] Back to main"<< endl; + cout << PROMPT_STRING; + + try { + + bool is_null_input; + switch(getUserOption(is_null_input)) { + + case 1: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Sensitivity to: High" << endl; + sick_lms_2xx->SetSickSensitivity(SickLMS2xx::SICK_SENSITIVITY_HIGH); + cout << " Done!" << endl; + } + break; + case 2: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Sensitivity to: Standard (Factory setting)" << endl; + sick_lms_2xx->SetSickSensitivity(); + cout << " Done!" << endl; + } + break; + case 3: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Sensitivity to: Medium" << endl; + sick_lms_2xx->SetSickSensitivity(SickLMS2xx::SICK_SENSITIVITY_MEDIUM); + cout << " Done!" << endl; + } + break; + case 4: + if (writeToEEPROM()) { + cout << " Setting Sick LMS Sensitivity to: Low" << endl; + sick_lms_2xx->SetSickSensitivity(SickLMS2xx::SICK_SENSITIVITY_LOW); + cout << " Done!" << endl; + } + break; + case 5: + keep_running = !keep_running; + break; + default: + if (!is_null_input) { + cerr << INVALID_OPTION_STRING << endl; + } + } + + } + + catch( SickException &sick_exception ) { + cerr << "A Sick exception occurred!" << endl; + exit(-1); + } + + catch(...) { + cerr << "An unknown exception occurred!" << endl; + exit(-1); + } + + } while (keep_running); + +} diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_mean_values/README b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_mean_values/README new file mode 100644 index 0000000..780f865 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_mean_values/README @@ -0,0 +1,11 @@ +================================================= +Sick LIDAR Matlab/C++ Toolbox +================================================= + +Example: lms_mean_values +Note: This example is COMPATIBLE w/ ALL Sick 2xx LIDAR units! :o) + +Desc: This example illustrates grabbing mean values from the Sick LMS. + +Example call (from build dir): ./lms_mean_values /dev/ttyUSB0 9600 + diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_mean_values/src/.deps/main.Po b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_mean_values/src/.deps/main.Po new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_mean_values/src/.deps/main.Po @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_mean_values/src/main.cc b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_mean_values/src/main.cc new file mode 100644 index 0000000..a003605 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_mean_values/src/main.cc @@ -0,0 +1,114 @@ +/*! + * \file main.cc + * \brief A simple example illustrating how to acquire + * mean values from the Sick LMS 2xx. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#include +#include +#include +#include + +using namespace std; +using namespace SickToolbox; + +int main(int argc, char* argv[]) +{ + + string device_str; + SickLMS2xx::sick_lms_2xx_baud_t desired_baud = SickLMS2xx::SICK_BAUD_38400; + + unsigned int values[SickLMS2xx::SICK_MAX_NUM_MEASUREMENTS] = {0}; // Uses macro defined in SickLMS2xx.hh + unsigned int num_values; // Holds the number of measurements returned + + /* Check for a device path. If it's not present, print a usage statement. */ + if ((argc != 2 && argc != 3) || (argc == 2 && strcasecmp(argv[1],"--help") == 0)) { + cout << "Usage: lms2xx_mean_values PATH [BAUD RATE]" << endl + << "Ex: lms2xx_mean_values /dev/ttyUSB0 9600" << endl; + return -1; + } + + /* Only device path is given */ + if (argc == 2) { + device_str = argv[1]; + } + + /* Device path and baud are given */ + if (argc == 3) { + device_str = argv[1]; + if ((desired_baud = SickLMS2xx::StringToSickBaud(argv[2])) == SickLMS2xx::SICK_BAUD_UNKNOWN) { + cerr << "Invalid baud value! Valid values are: 9600, 19200, 38400, and 500000" << endl; + return -1; + } + } + + /* + * Instantiate an instance + */ + SickLMS2xx sick_lms_2xx(device_str); + + /* + * Initialize the Sick LMS 2xx + */ + try { + sick_lms_2xx.Initialize(desired_baud); + } + + catch(...) { + cerr << "Initialize failed! Are you using the correct device path?" << endl; + return -1; + } + + /* + * Acquire a few scans from the Sick LMS + */ + try { + + for (unsigned int i=0; i < 10; i++) { + + /* + * The first argument is an input to the driver + * telling it the number of raw scans over which + * the Sick should average. (i.e. here, the Sick + * will average over 5 scans before returning + * the resulting mean values) + */ + sick_lms_2xx.GetSickMeanValues(5,values,num_values); + cout << "\t Num. Values: " << num_values << endl; + + } + + } + + /* Catch anything else and exit */ + catch(...) { + cerr << "An error occurred!" << endl; + } + + /* + * Uninitialize the device + */ + try { + sick_lms_2xx.Uninitialize(); + } + + catch(...) { + cerr << "Uninitialize failed!" << endl; + return -1; + } + + /* Success! */ + return 0; + +} + diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_partial_scan/README b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_partial_scan/README new file mode 100644 index 0000000..3528b96 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_partial_scan/README @@ -0,0 +1,12 @@ +================================================= +Sick LIDAR Matlab/C++ Toolbox +================================================= + +Example: lms_partial_scan +Note: This example is NOT COMPATIBLE w/ LMS {211,221,291}-S14 LIDARs! + +Desc: This example illustrates grabbing partial scans using the + Sick LMS driver. + +Example call (from build dir): ./lms_partial_scan /dev/ttyUSB0 9600 + diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_partial_scan/src/.deps/main.Po b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_partial_scan/src/.deps/main.Po new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_partial_scan/src/.deps/main.Po @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_partial_scan/src/main.cc b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_partial_scan/src/main.cc new file mode 100644 index 0000000..9fe6feb --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_partial_scan/src/main.cc @@ -0,0 +1,140 @@ +/*! + * \file main.cc + * \brief Illustrates how to acquire partial scans + * from the Sick LMS as well as telegram indices. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#include +#include +#include +#include +#include + +using namespace std; +using namespace SickToolbox; + +int main(int argc, char* argv[]) { + + string device_str; + SickLMS2xx::sick_lms_2xx_baud_t desired_baud = SickLMS2xx::SICK_BAUD_38400; + + unsigned int values[SickLMS2xx::SICK_MAX_NUM_MEASUREMENTS] = {0}; // Uses macro defined in SickLMS2xx.hh + unsigned int num_values = 0; // Holds the number of measurements returned + unsigned int scan_idx = 0; // Holds the idx for the returned partial scan + unsigned int telegram_idx = 0; // Holds the idx of the telegram associated w/ scan + + /* Check for a device path. If it's not present, print a usage statement. */ + if ((argc != 2 && argc != 3) || (argc == 2 && strcasecmp(argv[1],"--help") == 0)) { + cout << "Usage: lms2xx_partial_scan PATH [BAUD RATE]" << endl + << "Ex: lms2xx_partial_scan /dev/ttyUSB0 9600" << endl; + return -1; + } + + /* Only device path is given */ + if (argc == 2) { + device_str = argv[1]; + } + + /* Device path and baud are given */ + if (argc == 3) { + device_str = argv[1]; + if ((desired_baud = SickLMS2xx::StringToSickBaud(argv[2])) == SickLMS2xx::SICK_BAUD_UNKNOWN) { + cerr << "Invalid baud value! Valid values are: 9600, 19200, 38400, and 500000" << endl; + return -1; + } + } + + /* + * Instantiate an instance + */ + SickLMS2xx sick_lms_2xx(device_str); + + /* + * Initialize the Sick LMS 2xx + */ + try { + sick_lms_2xx.Initialize(desired_baud); + } + + catch(...) { + cerr << "Initialize failed! Are you using the correct device path?" << endl; + return -1; + } + + /* + * Ensure real-time indices are set + */ + if (sick_lms_2xx.GetSickAvailability() & SickLMS2xx::SICK_FLAG_AVAILABILITY_REAL_TIME_INDICES) { + + try { + + /* + * Set the device variant to 100/0.25 + * + * NOTE: Setting the variant this way ensures that the + * partial scans will start at angles that are a + * multiple of 0.25 deg. + * + */ + sick_lms_2xx.SetSickVariant(SickLMS2xx::SICK_SCAN_ANGLE_100,SickLMS2xx::SICK_SCAN_RESOLUTION_25); + + /* + * Acquire some partial scans from Sick + */ + for (unsigned int i=0; i < 12; i++) { + + /* + * NOTE: Notice that here we are also obtaining the telegram idx. In a + * proper implementation, this value would be used to ensure the + * temporal consistency (acting as a sequence number) of the newly + * obtained partial scan. Here we simply just print it out. + * + * Also, we don't want Field A,B, or C outputs... so we pass in + * NULL for these params. + */ + sick_lms_2xx.GetSickPartialScan(values,num_values,scan_idx,NULL,NULL,NULL,&telegram_idx); + cout << "\t Start angle: " << setw(4) << 0.25*scan_idx << ", Num. Values: " << num_values << ", Msg Idx: " << telegram_idx << endl; + + } + + } + + /* Catch anything else and exit */ + catch(...) { + cerr << "An error occurred!" << endl; + } + + } + + else { + cout << "Please set the Sick LMS to an availability w/ real-time indices..." << endl; + cout << "Hint: Use the lms_config utility/example! :o)"<< endl; + } + + /* + * Uninitialize the device + */ + try { + sick_lms_2xx.Uninitialize(); + } + + catch(...) { + cerr << "Uninitialize failed!" << endl; + return -1; + } + + /* Success! */ + return 0; + +} + diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_real_time_indices/README b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_real_time_indices/README new file mode 100644 index 0000000..8ff0e16 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_real_time_indices/README @@ -0,0 +1,12 @@ +================================================= +Sick LIDAR Matlab/C++ Toolbox +================================================= + +Example: lms_real_time_indices +Note: This example is COMPATIBLE w/ ALL Sick 2xx LIDAR units! :o) + +Desc: This example provides a simple program template for grabbing + data as well as real-time indices from a Sick LMS 2xx LIDAR. + +Example call (from build dir): ./lms_real_time_indices /dev/ttyUSB0 9600 + diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_real_time_indices/src/.deps/main.Po b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_real_time_indices/src/.deps/main.Po new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_real_time_indices/src/.deps/main.Po @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_real_time_indices/src/main.cc b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_real_time_indices/src/main.cc new file mode 100644 index 0000000..c94d446 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_real_time_indices/src/main.cc @@ -0,0 +1,125 @@ +/*! + * \file main.cc + * \brief Illustrates how to use the Sick Toolbox C++ interface + * to acquire scan data along with real-time indices from + * a Sick LMS 2xx. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#include +#include +#include +#include + +using namespace std; +using namespace SickToolbox; + +int main(int argc, char* argv[]) +{ + + string device_str; + SickLMS2xx::sick_lms_2xx_baud_t desired_baud = SickLMS2xx::SICK_BAUD_38400; + + unsigned int values[SickLMS2xx::SICK_MAX_NUM_MEASUREMENTS] = {0}; // Uses macro defined in SickLMS2xx.hh + unsigned int num_values = 0; // Holds the number of measurements returned + unsigned int telegram_idx = 0; + unsigned int real_time_idx = 0; + + /* Check for a device path. If it's not present, print a usage statement. */ + if ((argc != 2 && argc != 3) || (argc == 2 && strcasecmp(argv[1],"--help") == 0)) { + cout << "Usage: lms2xx_real_time_indices PATH [BAUD RATE]" << endl + << "Ex: lms2xx_real_time_indices /dev/ttyUSB0 9600" << endl; + return -1; + } + + /* Only device path is given */ + if (argc == 2) { + device_str = argv[1]; + } + + /* Device path and baud are given */ + if (argc == 3) { + device_str = argv[1]; + if ((desired_baud = SickLMS2xx::StringToSickBaud(argv[2])) == SickLMS2xx::SICK_BAUD_UNKNOWN) { + cerr << "Invalid baud value! Valid values are: 9600, 19200, 38400, and 500000" << endl; + return -1; + } + } + + /* + * Instantiate an instance + */ + SickLMS2xx sick_lms_2xx(device_str); + + /* + * Initialize the Sick LMS 2xx + */ + try { + sick_lms_2xx.Initialize(desired_baud); + } + + catch(...) { + cerr << "Initialize failed! Are you using the correct device path?" << endl; + return -1; + } + + /* + * Ensure real-time indices are enabled + */ + if (sick_lms_2xx.GetSickAvailability() & SickLMS2xx::SICK_FLAG_AVAILABILITY_REAL_TIME_INDICES) { + + try { + + /* + * Acquire a few scans from the Sick LMS + */ + for (unsigned int i=0; i < 10; i++) { + + /* We don't want Fields A,B, or C, so we pass NULL */ + sick_lms_2xx.GetSickScan(values,num_values,NULL,NULL,NULL,&telegram_idx,&real_time_idx); + cout << "\t Num. Values: " << num_values << ", Msg Idx: " << telegram_idx + << ", Real-time Idx: " << real_time_idx << endl; + + } + + } + + /* Catch anything else and exit */ + catch(...) { + cerr << "An error occurred!" << endl; + return -1; + } + + } + + else { + cout << "Please set the Sick LMS to an availability w/ real-time indices..." << endl; + cout << "Hint: Use the lms_config utility/example! :o)"<< endl; + } + + /* + * Uninitialize the device + */ + try { + sick_lms_2xx.Uninitialize(); + } + + catch(...) { + cerr << "Uninitialize failed!" << endl; + return -1; + } + + /* Success! */ + return 0; + +} + diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_set_variant/README b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_set_variant/README new file mode 100644 index 0000000..465d1e5 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_set_variant/README @@ -0,0 +1,12 @@ +================================================= +Sick LIDAR Matlab/C++ Toolbox +================================================= + +Example: lms_set_variant +Note: This example is NOT COMPATIBLE w/ LMS {211,221,291}-S14 LIDARs! + +Desc: This example illustrates the proper way to switch the Sick LMS + variant (i.e. the Sick's FOV and scan resolution). + +Example call (from build dir): ./lms_set_variant /dev/ttyUSB0 9600 + diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_set_variant/src/.deps/main.Po b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_set_variant/src/.deps/main.Po new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_set_variant/src/.deps/main.Po @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_set_variant/src/main.cc b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_set_variant/src/main.cc new file mode 100644 index 0000000..7c9af5a --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_set_variant/src/main.cc @@ -0,0 +1,155 @@ +/*! + * \file main.cc + * \brief Illustrates how to set the device variant and then + * acquire measured values + * + * Note: This example WILL NOT WORK for LMS 211-S14, 221-S14, + * 291-S14 models as they do not support variant switching. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +/* Implementation dependencies */ +#include +#include +#include +#include + +/* Use the namespace */ +using namespace std; +using namespace SickToolbox; + +int main(int argc, char * argv[]) { + + string device_str; + SickLMS2xx::sick_lms_2xx_baud_t desired_baud = SickLMS2xx::SICK_BAUD_38400; + + /* Check for a device path. If it's not present, print a usage statement. */ + if ((argc != 2 && argc != 3) || (argc == 2 && strcasecmp(argv[1],"--help") == 0)) { + cout << "Usage: lms2xx_set_variant PATH [BAUD RATE]" << endl + << "Ex: lms2xx_set_variant /dev/ttyUSB0 9600" << endl; + return -1; + } + + /* Only device path is given */ + if (argc == 2) { + device_str = argv[1]; + } + + /* Device path and baud are given */ + if (argc == 3) { + device_str = argv[1]; + if ((desired_baud = SickLMS2xx::StringToSickBaud(argv[2])) == SickLMS2xx::SICK_BAUD_UNKNOWN) { + cerr << "Invalid baud value! Valid values are: 9600, 19200, 38400, and 500000" << endl; + return -1; + } + } + + /* Instantiate the SickLMS2xx class with the device path string. */ + SickLMS2xx sick_lms_2xx(device_str); + + /* Define some buffers to hold the returned measurements */ + unsigned int values[SickLMS2xx::SICK_MAX_NUM_MEASUREMENTS] = {0}; + unsigned int num_values = 0; + + /* + * Initialize the Sick LMS 2xx + */ + try { + sick_lms_2xx.Initialize(desired_baud); + } + + catch(...) { + cerr << "Initialize failed! Are you using the correct device path?" << endl; + return -1; + } + + /* + * Check whether device is LMS Fast + */ + if (!sick_lms_2xx.IsSickLMS2xxFast()) { + + try { + + /* + * Set the device variant to 100/0.25 + * + * NOTE: If an invalid variant definition is + * given a SickConfigException will be + * thrown stating so. + * + */ + cout << "\tSetting variant to 100/0.25" << std::endl << flush; + sick_lms_2xx.SetSickVariant(SickLMS2xx::SICK_SCAN_ANGLE_100,SickLMS2xx::SICK_SCAN_RESOLUTION_25); + + /* + * Acquire some measurements from Sick LMS 2xx using 100/0.25 + */ + cout << "\tAcquiring some measurements..." << endl; + for(unsigned int i = 0; i < 10; i++) { + + /* Acquire the most recent scan from the Sick */ + sick_lms_2xx.GetSickScan(values,num_values); + + /* Display the number of measurements */ + cout << "\t Num. Values: " << num_values << endl; + + } + + /* + * Set the device variant to 180/0.5 + */ + cout << std::endl << "\tSetting variant to 180/0.50" << endl; + sick_lms_2xx.SetSickVariant(SickLMS2xx::SICK_SCAN_ANGLE_180,SickLMS2xx::SICK_SCAN_RESOLUTION_50); + + /* + * Acquire some measurements from Sick LMS 2xx using 180/0.50 + */ + cout << "\tAcquiring some measurements..." << endl; + for(unsigned int i = 0; i < 10; i++) { + + /* Acquire the most recent scan from the Sick */ + sick_lms_2xx.GetSickScan(values,num_values); + + /* Display the number of measured values */ + cout << "\t Num. Values: " << num_values << endl; + + } + + } + + catch(...) { + cerr << "An error occurred!" << endl; + } + + } + + else { + cerr << "Oops... Your Sick is an LMS Fast!" << endl; + cerr << "It doesn't support the variant command." << endl; + } + + /* + * Uninitialize the device + */ + try { + sick_lms_2xx.Uninitialize(); + } + + catch(...) { + cerr << "Uninitialize failed!" << endl; + return -1; + } + + /* Success! */ + return 0; + +} diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_simple_app/README b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_simple_app/README new file mode 100644 index 0000000..a58aaa0 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_simple_app/README @@ -0,0 +1,13 @@ +================================================= +Sick LIDAR Matlab/C++ Toolbox +================================================= + +Example: lms_simple_app +Note: This example is COMPATIBLE w/ ALL Sick 2xx LIDAR units! :o) + +Desc: This example provides a simple program template for grabbing + data from a Sick LMS 2xx LIDAR. It illustrates the simplest + use of the Sick LIDAR Toolkit w/ C++. + +Example call (from build dir): ./lms_simple_app /dev/ttyUSB0 9600 + diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_simple_app/src/.deps/main.Po b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_simple_app/src/.deps/main.Po new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_simple_app/src/.deps/main.Po @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_simple_app/src/main.cc b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_simple_app/src/main.cc new file mode 100644 index 0000000..4ee2fbe --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_simple_app/src/main.cc @@ -0,0 +1,104 @@ +/*! + * \file main.cc + * \brief A simple application using the Sick LMS 2xx driver. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#include +#include +#include +#include + +using namespace std; +using namespace SickToolbox; + +int main(int argc, char* argv[]) +{ + + string device_str; + SickLMS2xx::sick_lms_2xx_baud_t desired_baud = SickLMS2xx::SICK_BAUD_38400; + + unsigned int values[SickLMS2xx::SICK_MAX_NUM_MEASUREMENTS] = {0}; // Uses macro defined in SickLMS2xx.hh + unsigned int num_values = 0; // Holds the number of measurements returned + + /* Check for a device path. If it's not present, print a usage statement. */ + if ((argc != 2 && argc != 3) || (argc == 2 && strcasecmp(argv[1],"--help") == 0)) { + cout << "Usage: lms2xx_simple_app PATH [BAUD RATE]" << endl + << "Ex: lms2xx_simple_app /dev/ttyUSB0 9600" << endl; + return -1; + } + + /* Only device path is given */ + if (argc == 2) { + device_str = argv[1]; + } + + /* Device path and baud are given */ + if (argc == 3) { + device_str = argv[1]; + if ((desired_baud = SickLMS2xx::StringToSickBaud(argv[2])) == SickLMS2xx::SICK_BAUD_UNKNOWN) { + cerr << "Invalid baud value! Valid values are: 9600, 19200, 38400, and 500000" << endl; + return -1; + } + } + + /* + * Instantiate an instance + */ + SickLMS2xx sick_lms_2xx(device_str); + + /* + * Initialize the Sick LMS 2xx + */ + try { + sick_lms_2xx.Initialize(desired_baud); + } + + catch(...) { + cerr << "Initialize failed! Are you using the correct device path?" << endl; + return -1; + } + + /* + * Acquire a few scans from the Sick LMS + */ + try { + + for (unsigned int i=0; i < 10; i++) { + sick_lms_2xx.GetSickScan(values,num_values); + cout << "\t Num. Values: " << num_values << endl; + } + + } + + /* Catch anything else and exit */ + catch(...) { + cerr << "An error occurred!" << endl; + } + + /* + * Uninitialize the device + */ + try { + sick_lms_2xx.Uninitialize(); + } + + catch(...) { + cerr << "Uninitialize failed!" << endl; + return -1; + } + + /* Success! */ + return 0; + +} + diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_stream_range_and_reflect/README b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_stream_range_and_reflect/README new file mode 100644 index 0000000..62ba5c1 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_stream_range_and_reflect/README @@ -0,0 +1,12 @@ +================================================= +Sick LIDAR Matlab/C++ Toolbox +================================================= + +Example: lms_stream_range_and_reflect +Note: This example is COMPATIBLE w/ ONLY Sick 291-S14 (LMS FAST) LIDAR units! + +Desc: This example provides a simple program template for streaming + range and reflectivity data from a Sick LMS 291-S14 LIDAR. + +Example call (from build dir): ./lms_stream_range_and_reflect /dev/ttyUSB0 9600 + diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_stream_range_and_reflect/src/.deps/main.Po b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_stream_range_and_reflect/src/.deps/main.Po new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_stream_range_and_reflect/src/.deps/main.Po @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_stream_range_and_reflect/src/main.cc b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_stream_range_and_reflect/src/main.cc new file mode 100644 index 0000000..ce29638 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_stream_range_and_reflect/src/main.cc @@ -0,0 +1,117 @@ +/*! + * \file main.cc + * \brief A simple program illustrating how to stream range + * and reflectivity returns from a Sick LMS 291-S14. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#include +#include +#include +#include + +using namespace std; +using namespace SickToolbox; + +int main(int argc, char* argv[]) { + + string device_str; + SickLMS2xx::sick_lms_2xx_baud_t desired_baud = SickLMS2xx::SICK_BAUD_38400; + + unsigned int num_range_values; + unsigned int num_reflect_values; + unsigned int range_values[SickLMS2xx::SICK_MAX_NUM_MEASUREMENTS] = {0}; + unsigned int reflect_values[SickLMS2xx::SICK_MAX_NUM_MEASUREMENTS] = {0}; + + /* Check for a device path. If it's not present, print a usage statement. */ + if ((argc != 2 && argc != 3) || (argc == 2 && strcasecmp(argv[1],"--help") == 0)) { + cout << "Usage: lms2xx_stream_range_and_reflect PATH [BAUD RATE]" << endl + << "Ex: lms2xx_stream_range_and_reflect /dev/ttyUSB0 9600" << endl; + return -1; + } + + /* Only device path is given */ + if (argc == 2) { + device_str = argv[1]; + } + + /* Device path and baud are given */ + if (argc == 3) { + device_str = argv[1]; + if ((desired_baud = SickLMS2xx::StringToSickBaud(argv[2])) == SickLMS2xx::SICK_BAUD_UNKNOWN) { + cerr << "Invalid baud value! Valid values are: 9600, 19200, 38400, and 500000" << endl; + return -1; + } + } + + /* + * Instantiate driver instance + */ + SickLMS2xx sick_lms_2xx(device_str); + + /* + * Initialize the Sick LMS 2xx + */ + try { + sick_lms_2xx.Initialize(desired_baud); + } + + catch(...) { + cerr << "Initialize failed! Are you using the correct device path?" << endl; + return -1; + } + + /* + * Ensure it is an LMS Fast model + */ + if (sick_lms_2xx.IsSickLMS2xxFast()) { + + /* + * Grab range and reflectivity data from the Sick LMS Fast + */ + try { + + for (unsigned int i=0; i < 10; i++) { + sick_lms_2xx.GetSickScan(range_values,reflect_values,num_range_values,num_reflect_values); + cout << "Num. Range Vals: " << num_range_values << " Num. Reflect Vals: " << num_reflect_values << endl; + } + + } + + catch (...) { + cerr << "An error occurred!" << endl; + } + + } + + else { + cerr << "Oops... Your Sick is NOT an LMS Fast!" << endl; + cerr << "It doesn't support this kind of stream." << endl; + } + + /* + * Uninitialize the device + */ + try { + sick_lms_2xx.Uninitialize(); + } + + catch(...) { + cerr << "Uninitialize failed!" << endl; + return -1; + } + + /* Success! */ + return 0; + +} + diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_subrange/README b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_subrange/README new file mode 100644 index 0000000..dc4d8d3 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_subrange/README @@ -0,0 +1,12 @@ +================================================= +Sick LIDAR Matlab/C++ Toolbox +================================================= + +Example: lms_subrange +Note: This example is COMPATIBLE w/ ALL Sick 2xx LIDAR units! :o) + +Desc: This example illustrates how to acquire a scan subrange from + the Sick LMS. + +Example call (from build dir): ./lms_subrange /dev/ttyUSB0 9600 + diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_subrange/src/.deps/main.Po b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_subrange/src/.deps/main.Po new file mode 100644 index 0000000..9ce06a8 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_subrange/src/.deps/main.Po @@ -0,0 +1 @@ +# dummy diff --git a/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_subrange/src/main.cc b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_subrange/src/main.cc new file mode 100644 index 0000000..99ac49b --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/c++/examples/lms2xx/lms2xx_subrange/src/main.cc @@ -0,0 +1,109 @@ +/*! + * \file main.cc + * \brief A simple program illustrating how to acquire a scan + * subrange from a Sick LMS 2xx. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#include +#include +#include +#include + +using namespace std; +using namespace SickToolbox; + +int main(int argc, char* argv[]) +{ + + string device_str; + SickLMS2xx::sick_lms_2xx_baud_t desired_baud = SickLMS2xx::SICK_BAUD_38400; + + unsigned int values[SickLMS2xx::SICK_MAX_NUM_MEASUREMENTS] = {0}; // Uses macro defined in SickLMS2xx.hh + unsigned int num_values; // Holds the number of measurements returned + + /* Check for a device path. If it's not present, print a usage statement. */ + if ((argc != 2 && argc != 3) || (strcasecmp(argv[1],"--help") == 0)) { + cout << "Usage: lms2xx_subrange PATH [BAUD RATE]" << endl + << "Ex: lms2xx_subrange /dev/ttyUSB0 9600" << endl; + return -1; + } + + /* Only device path is given */ + if (argc == 2) { + device_str = argv[1]; + } + + /* Device path and baud are given */ + if (argc == 3) { + device_str = argv[1]; + if ((desired_baud = SickLMS2xx::StringToSickBaud(argv[2])) == SickLMS2xx::SICK_BAUD_UNKNOWN) { + cerr << "Invalid baud value! Valid values are: 9600, 19200, 38400, and 500000" << endl; + return -1; + } + } + + /* + * Instantiate an instance + */ + SickLMS2xx sick_lms_2xx(device_str); + + /* + * Initialize the Sick LMS 2xx + */ + try { + sick_lms_2xx.Initialize(desired_baud); + } + + catch(...) { + cerr << "Initialize failed! Are you using the correct device path?" << endl; + return -1; + } + + try { + + /* + * Acquire a few scans from the Sick LMS + */ + for (unsigned int i=0; i < 10; i++) { + + /* + * Acquire the first ten measurements of a scan from the Sick + */ + sick_lms_2xx.GetSickScanSubrange(1,10,values,num_values); + cout << "\t Num. Values: " << num_values << endl; + + } + + } + + catch(...) { + cerr << "An error occurred!" << endl; + } + + /* + * Uninitialize the device + */ + try { + sick_lms_2xx.Uninitialize(); + } + + catch(...) { + cerr << "Uninitialize failed!" << endl; + return -1; + } + + /* Success! */ + return 0; + +} + diff --git a/sitl_config/ugv/sicktoolbox/doxygen.cfg b/sitl_config/ugv/sicktoolbox/doxygen.cfg new file mode 100644 index 0000000..023bc37 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/doxygen.cfg @@ -0,0 +1,241 @@ +# Doxygen 1.5.1 + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- +PROJECT_NAME = $(PROJECT)-$(VERSION) +PROJECT_NUMBER = +OUTPUT_DIRECTORY = $(DOCDIR) +CREATE_SUBDIRS = NO +OUTPUT_LANGUAGE = English +USE_WINDOWS_ENCODING = NO +BRIEF_MEMBER_DESC = YES +REPEAT_BRIEF = YES +ABBREVIATE_BRIEF = +ALWAYS_DETAILED_SEC = NO +INLINE_INHERITED_MEMB = NO +FULL_PATH_NAMES = YES +STRIP_FROM_PATH = $(SRCDIR) +STRIP_FROM_INC_PATH = $(SRCDIR) +SHORT_NAMES = YES +JAVADOC_AUTOBRIEF = NO +MULTILINE_CPP_IS_BRIEF = NO +DETAILS_AT_TOP = NO +INHERIT_DOCS = YES +SEPARATE_MEMBER_PAGES = NO +TAB_SIZE = 8 +ALIASES = +OPTIMIZE_OUTPUT_FOR_C = NO +OPTIMIZE_OUTPUT_JAVA = NO +BUILTIN_STL_SUPPORT = NO +DISTRIBUTE_GROUP_DOC = NO +SUBGROUPING = YES + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- +EXTRACT_ALL = YES +EXTRACT_PRIVATE = NO +EXTRACT_STATIC = NO +EXTRACT_LOCAL_CLASSES = YES +EXTRACT_LOCAL_METHODS = NO +HIDE_UNDOC_MEMBERS = NO +HIDE_UNDOC_CLASSES = NO +HIDE_FRIEND_COMPOUNDS = NO +HIDE_IN_BODY_DOCS = NO +INTERNAL_DOCS = NO +CASE_SENSE_NAMES = YES +HIDE_SCOPE_NAMES = NO +SHOW_INCLUDE_FILES = YES +INLINE_INFO = YES +SORT_MEMBER_DOCS = YES +SORT_BRIEF_DOCS = NO +SORT_BY_SCOPE_NAME = NO +GENERATE_TODOLIST = YES +GENERATE_TESTLIST = YES +GENERATE_BUGLIST = YES +GENERATE_DEPRECATEDLIST= YES +ENABLED_SECTIONS = +MAX_INITIALIZER_LINES = 30 +SHOW_USED_FILES = YES +SHOW_DIRECTORIES = NO +FILE_VERSION_FILTER = + +#--------------------------------------------------------------------------- +# configuration options related to warning and progress messages +#--------------------------------------------------------------------------- +QUIET = NO +WARNINGS = YES +WARN_IF_UNDOCUMENTED = YES +WARN_IF_DOC_ERROR = YES +WARN_NO_PARAMDOC = NO +WARN_FORMAT = "$file:$line: $text" +WARN_LOGFILE = + +#--------------------------------------------------------------------------- +# configuration options related to the input files +#--------------------------------------------------------------------------- +INPUT = $(SRCDIR) +FILE_PATTERNS = *.cc *.hh +RECURSIVE = YES +EXCLUDE = $(SRCDIR)/c++/examples +EXCLUDE_SYMLINKS = NO +EXCLUDE_PATTERNS = +EXAMPLE_PATH = +EXAMPLE_PATTERNS = +EXAMPLE_RECURSIVE = NO +IMAGE_PATH = +INPUT_FILTER = +FILTER_PATTERNS = +FILTER_SOURCE_FILES = NO + +#--------------------------------------------------------------------------- +# configuration options related to source browsing +#--------------------------------------------------------------------------- +SOURCE_BROWSER = NO +INLINE_SOURCES = NO +STRIP_CODE_COMMENTS = NO +REFERENCED_BY_RELATION = YES +REFERENCES_RELATION = YES +REFERENCES_LINK_SOURCE = YES +USE_HTAGS = NO +VERBATIM_HEADERS = YES + +#--------------------------------------------------------------------------- +# configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- +ALPHABETICAL_INDEX = YES +COLS_IN_ALPHA_INDEX = 5 +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# configuration options related to the HTML output +#--------------------------------------------------------------------------- +GENERATE_HTML = $(GENERATE_HTML) +HTML_OUTPUT = html +HTML_FILE_EXTENSION = .html +HTML_HEADER = +HTML_FOOTER = +HTML_STYLESHEET = +HTML_ALIGN_MEMBERS = YES +GENERATE_HTMLHELP = $(GENERATE_CHM) +CHM_FILE = ../$(PROJECT).chm +HHC_LOCATION = $(HHC_PATH) +GENERATE_CHI = $(GENERATE_CHI) +BINARY_TOC = NO +TOC_EXPAND = NO +DISABLE_INDEX = NO +ENUM_VALUES_PER_LINE = 4 +GENERATE_TREEVIEW = YES +TREEVIEW_WIDTH = 250 + +#--------------------------------------------------------------------------- +# configuration options related to the LaTeX output +#--------------------------------------------------------------------------- +GENERATE_LATEX = $(GENERATE_LATEX) +LATEX_OUTPUT = latex +LATEX_CMD_NAME = latex +MAKEINDEX_CMD_NAME = makeindex +COMPACT_LATEX = NO +PAPER_TYPE = $(PAPER_SIZE) +EXTRA_PACKAGES = +LATEX_HEADER = +PDF_HYPERLINKS = NO +USE_PDFLATEX = NO +LATEX_BATCHMODE = YES +LATEX_HIDE_INDICES = NO + +#--------------------------------------------------------------------------- +# configuration options related to the RTF output +#--------------------------------------------------------------------------- +GENERATE_RTF = $(GENERATE_RTF) +RTF_OUTPUT = rtf +COMPACT_RTF = NO +RTF_HYPERLINKS = NO +RTF_STYLESHEET_FILE = +RTF_EXTENSIONS_FILE = + +#--------------------------------------------------------------------------- +# configuration options related to the man page output +#--------------------------------------------------------------------------- +GENERATE_MAN = $(GENERATE_MAN) +MAN_OUTPUT = man +MAN_EXTENSION = .1 +MAN_LINKS = NO + +#--------------------------------------------------------------------------- +# configuration options related to the XML output +#--------------------------------------------------------------------------- +GENERATE_XML = $(GENERATE_XML) +XML_OUTPUT = xml +XML_SCHEMA = +XML_DTD = +XML_PROGRAMLISTING = YES + +#--------------------------------------------------------------------------- +# configuration options for the AutoGen Definitions output +#--------------------------------------------------------------------------- +GENERATE_AUTOGEN_DEF = NO + +#--------------------------------------------------------------------------- +# configuration options related to the Perl module output +#--------------------------------------------------------------------------- +GENERATE_PERLMOD = NO +PERLMOD_LATEX = NO +PERLMOD_PRETTY = YES +PERLMOD_MAKEVAR_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the preprocessor +#--------------------------------------------------------------------------- +ENABLE_PREPROCESSING = YES +MACRO_EXPANSION = NO +EXPAND_ONLY_PREDEF = NO +SEARCH_INCLUDES = YES +INCLUDE_PATH = +INCLUDE_FILE_PATTERNS = +PREDEFINED = +EXPAND_AS_DEFINED = +SKIP_FUNCTION_MACROS = YES + +#--------------------------------------------------------------------------- +# Configuration::additions related to external references +#--------------------------------------------------------------------------- +TAGFILES = +GENERATE_TAGFILE = $(DOCDIR)/$(PROJECT).tag +ALLEXTERNALS = NO +EXTERNAL_GROUPS = YES +PERL_PATH = $(PERL_PATH) + +#--------------------------------------------------------------------------- +# Configuration options related to the dot tool +#--------------------------------------------------------------------------- +CLASS_DIAGRAMS = YES +HIDE_UNDOC_RELATIONS = YES +HAVE_DOT = $(HAVE_DOT) +CLASS_GRAPH = YES +COLLABORATION_GRAPH = YES +GROUP_GRAPHS = YES +UML_LOOK = NO +TEMPLATE_RELATIONS = NO +INCLUDE_GRAPH = YES +INCLUDED_BY_GRAPH = YES +CALL_GRAPH = NO +CALLER_GRAPH = NO +GRAPHICAL_HIERARCHY = YES +DIRECTORY_GRAPH = YES +DOT_IMAGE_FORMAT = png +DOT_PATH = $(DOT_PATH) +DOTFILE_DIRS = +MAX_DOT_GRAPH_WIDTH = 1024 +MAX_DOT_GRAPH_HEIGHT = 1024 +MAX_DOT_GRAPH_DEPTH = 0 +DOT_TRANSPARENT = NO +DOT_MULTI_TARGETS = NO +GENERATE_LEGEND = YES +DOT_CLEANUP = YES + +#--------------------------------------------------------------------------- +# Configuration::additions related to the search engine +#--------------------------------------------------------------------------- +SEARCHENGINE = NO diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickBufferMonitor.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickBufferMonitor.hh new file mode 100644 index 0000000..b2ec539 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickBufferMonitor.hh @@ -0,0 +1,471 @@ +/*! + * \file SickBufferMonitor.hh + * \brief Defines an abstract class for interfacing with a Sick LIDAR. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#ifndef SICK_BUFFER_MONITOR +#define SICK_BUFFER_MONITOR + +/* Dependencies */ +#include +#include +#include +#include "SickException.hh" + +/* Associate the namespace */ +namespace SickToolbox { + + /** + * \class SickBufferMonitor + */ + template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + class SickBufferMonitor { + + public: + + /** A standard constructor */ + SickBufferMonitor( SICK_MONITOR_CLASS * const monitor_instance ) throw( SickThreadException ); + + /** A method for setting the target data stream */ + void SetDataStream( const unsigned int sick_fd ) throw( SickThreadException ); + + /** Start the buffer monitor for the device */ + void StartMonitor( const unsigned int sick_fd ) throw( SickThreadException ); + + /** Acquire the most recent message buffered by the monitor */ + bool GetNextMessageFromMonitor( SICK_MSG_CLASS &sick_message ) throw( SickThreadException ); + + /** Stop the buffer monitor for the device */ + void StopMonitor( ) throw( SickThreadException ); + + /** Locks access to the data stream */ + void AcquireDataStream( ) throw( SickThreadException ); + + /** Acquire the next message from raw byte stream */ + void GetNextMessageFromDataStream( SICK_MSG_CLASS &sick_message ); + + /** Unlock access to the data stream */ + void ReleaseDataStream( ) throw( SickThreadException ); + + /** A standard destructor */ + ~SickBufferMonitor( ) throw( SickThreadException ); + + protected: + + /** Sick data stream file descriptor */ + unsigned int _sick_fd; + + /** Reads n bytes into the destination buffer */ + void _readBytes( uint8_t * const dest_buffer, const int num_bytes_to_read, const unsigned int timeout_value = 0 ) const throw ( SickTimeoutException, SickIOException ); + + private: + + /** The current monitor instance */ + SICK_MONITOR_CLASS *_sick_monitor_instance; + + /** A flag to indicate the monitor should continue running */ + bool _continue_grabbing; + + /** Buffer monitor thread ID */ + pthread_t _monitor_thread_id; + + /** A mutex for guarding the message container */ + pthread_mutex_t _container_mutex; + + /** A mutex for locking the data stream */ + pthread_mutex_t _stream_mutex; + + /** A container to hold the most recent message */ + SICK_MSG_CLASS _recv_msg_container; + + /** Locks access to the message container */ + void _acquireMessageContainer( ) throw( SickThreadException ); + + /** Unlocks access to the message container */ + void _releaseMessageContainer( ) throw( SickThreadException ); + + /** Entry point for the monitor thread */ + static void * _bufferMonitorThread( void * thread_args ); + + }; + + /** + * \brief Primary constructor + * \param device_instance A pointer to the current driver instance + */ + template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::SickBufferMonitor( SICK_MONITOR_CLASS * const monitor_instance ) throw( SickThreadException ) : + _sick_monitor_instance(monitor_instance), _continue_grabbing(true), _monitor_thread_id(0) { + + /* Initialize the shared message buffer mutex */ + if (pthread_mutex_init(&_container_mutex,NULL) != 0) { + throw SickThreadException("SickBufferMonitor::SickBufferMonitor: pthread_mutex_init() failed!"); + } + + /* Initialize the shared data stream mutex */ + if (pthread_mutex_init(&_stream_mutex,NULL) != 0) { + throw SickThreadException("SickBufferMonitor::SickBufferMonitor: pthread_mutex_init() failed!"); + } + + } + + /** + * \brief A method for setting/changing the current data stream + * \param sick_fd The data stream file descriptor + */ + template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::SetDataStream( const unsigned int sick_fd ) throw ( SickThreadException ) { + + try { + + /* Attempt to acquire the data stream */ + AcquireDataStream(); + + /* Assign the data stream fd */ + _sick_fd = sick_fd; + + /* Attempt to release the data stream */ + ReleaseDataStream(); + + } + + /* Handle thread exception */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + } + + /* A safety net */ + catch(...) { + std::cerr << "SickBufferMonitor::SetDataStream: Unknown exception!" << std::endl; + throw; + } + + } + + /** + * \brief Creates and starts the buffer monitor thread + * \return True upon success, False otherwise + */ + template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::StartMonitor( const unsigned int sick_fd ) throw ( SickThreadException ) { + + /* Assign the fd associated with the data stream */ + _sick_fd = sick_fd; + + /* Start the buffer monitor */ + if (pthread_create(&_monitor_thread_id,NULL,SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_bufferMonitorThread,_sick_monitor_instance) != 0) { + throw SickThreadException("SickBufferMonitor::StartMonitor: pthread_create() failed!"); + } + + /* Set the flag to continue grabbing data */ + _continue_grabbing = true; + + } + + /** + * \brief Checks the message container for the next available Sick message + * \param &sick_message The message object that is to be populated with the results + * \return True if the current contents were acquired, false otherwise + */ + template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + bool SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::GetNextMessageFromMonitor( SICK_MSG_CLASS &sick_message ) throw( SickThreadException ) { + + bool acquired_message = false; + + try { + + /* Acquire a lock on the message buffer */ + _acquireMessageContainer(); + + /* Check whether the object is populated */ + if (_recv_msg_container.IsPopulated()) { + + /* Copy the shared message */ + sick_message = _recv_msg_container; + _recv_msg_container.Clear(); + + /* Set the flag indicating success */ + acquired_message = true; + } + + /* Release message container */ + _releaseMessageContainer(); + + } + + /* Handle a thread exception */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle an unknown exception */ + catch(...) { + std::cerr << "SickBufferMonitor::CheckMessageContainer: Unknown exception!" << std::endl; + throw; + } + + /* Return the flag */ + return acquired_message; + } + + /** + * \brief Cancels the buffer monitor thread + * \return True if the thread was properly canceled, false otherwise + */ + template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::StopMonitor( ) throw ( SickThreadException ) { + + try { + + /* Return results from the thread */ + void *monitor_result = NULL; + + /* Tell the thread to quit working */ + AcquireDataStream(); + _continue_grabbing = false; + ReleaseDataStream(); + + /* Wait for the buffer monitor to exit */ + if (pthread_join(_monitor_thread_id,&monitor_result) != 0) { + throw SickThreadException("SickBufferMonitor::StopMonitor: pthread_join() failed!"); + } + + } + + /* Handle thread exception */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + } + + /* A safety net */ + catch(...) { + std::cerr << "SickBufferMonitor::StopMonitor: Unknown exception!" << std::endl; + throw; + } + + } + + /** + * \brief Acquires a lock on the data stream + */ + template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::AcquireDataStream( ) throw( SickThreadException ) { + + /* Attempt to lock the stream mutex */ + if (pthread_mutex_lock(&_stream_mutex) != 0) { + throw SickThreadException("SickBufferMonitor::AcquireDataStream: pthread_mutex_lock() failed!"); + } + + } + + /** + * \brief Releases a lock on the data stream + */ + template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::ReleaseDataStream( ) throw( SickThreadException ) { + + /* Attempt to lock the stream mutex */ + if (pthread_mutex_unlock(&_stream_mutex) != 0) { + throw SickThreadException("SickBufferMonitor::ReleaseDataStream: pthread_mutex_unlock() failed!"); + } + + } + + /** + * \brief The destructor (kills the mutex) + */ + template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::~SickBufferMonitor( ) throw( SickThreadException ) { + + /* Destroy the message container mutex */ + if (pthread_mutex_destroy(&_container_mutex) != 0) { + throw SickThreadException("SickBufferMonitor::~SickBufferMonitor: pthread_mutex_destroy() failed!"); + } + + /* Destroy the data stream container mutex */ + if (pthread_mutex_destroy(&_stream_mutex) != 0) { + throw SickThreadException("SickBufferMonitor::~SickBufferMonitor: pthread_mutex_destroy() failed!"); + } + + } + + /** + * \brief Locks access to the message container + */ + template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_acquireMessageContainer( ) throw( SickThreadException ) { + + /* Lock the mutex */ + if (pthread_mutex_lock(&_container_mutex) != 0) { + throw SickThreadException("SickBufferMonitor::_acquireMessageContainer: pthread_mutex_lock() failed!"); + } + + } + + /** + * \brief Unlocks access to the message container + */ + template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_releaseMessageContainer( ) throw( SickThreadException ) { + + /* Unlock the mutex */ + if (pthread_mutex_unlock(&_container_mutex) != 0) { + throw SickThreadException("SickBufferMonitor::_releaseMessageContainer: pthread_mutex_unlock() failed!"); + } + + } + + /** + * \brief Attempt to read a certain number of bytes from the stream + * \param *dest_buffer A pointer to the destination buffer + * \param num_bytes_to_read The number of bytes to read into the buffer + * \param timeout_value The number of microseconds allowed between subsequent bytes in a message + * \return True if the number of requested bytes were successfully read + */ + template< class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_readBytes( uint8_t * const dest_buffer, const int num_bytes_to_read, const unsigned int timeout_value ) const + throw ( SickTimeoutException, SickIOException ) { + + /* Some helpful variables */ + int num_bytes_read = 0; + int total_num_bytes_read = 0; + int num_active_files = 0; + + struct timeval timeout_val; // This structure will be used for setting our timeout values + fd_set file_desc_set; // File descriptor set for monitoring I/O + + /* Attempt to fetch the bytes */ + while ( total_num_bytes_read < num_bytes_to_read ) { + + /* Initialize and set the file descriptor set for select */ + FD_ZERO(&file_desc_set); + FD_SET(_sick_fd,&file_desc_set); + + /* Setup the timeout structure */ + memset(&timeout_val,0,sizeof(timeout_val)); // Initialize the buffer + timeout_val.tv_usec = timeout_value; // Wait for specified time before throwing a timeout + + /* Wait for the OS to tell us that data is waiting! */ + num_active_files = select(getdtablesize(),&file_desc_set,0,0,(timeout_value > 0) ? &timeout_val : 0); + + /* Figure out what to do based on the output of select */ + if (num_active_files > 0) { + + /* A file is ready for reading! + * + * NOTE: The following conditional is just a sanity check. Since + * the file descriptor set only contains the sick device fd, + * it likely unnecessary to use FD_ISSET + */ + if (FD_ISSET(_sick_fd,&file_desc_set)) { + + /* Read a single byte from the stream! */ + num_bytes_read = read(_sick_fd,&dest_buffer[total_num_bytes_read],1); + + /* Decide what to do based on the output of read */ + if (num_bytes_read > 0) { //Update the number of bytes read so far + total_num_bytes_read += num_bytes_read; + } + else { + /* If this happens, something is wrong */ + throw SickIOException("SickBufferMonitor::_readBytes: read() failed!"); + } + + } + + } + else if (num_active_files == 0) { + + /* A timeout has occurred! */ + throw SickTimeoutException("SickBufferMonitor::_readBytes: select() timeout!"); + + } + else { + + /* An error has occurred! */ + throw SickIOException("SickBufferMonitor::_readBytes: select() failed!"); + + } + + } + + } + + /** + * \brief The monitor thread + * \param *args The thread arguments + */ + template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void * SickBufferMonitor< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_bufferMonitorThread( void * thread_args ) { + + /* Declare a Sick LD receive object */ + SICK_MSG_CLASS curr_message; + + /* Acquire the Sick device instance */ + SICK_MONITOR_CLASS *buffer_monitor = (SICK_MONITOR_CLASS *)thread_args; + + /* The main thread control loop */ + for (;;) { + + try { + + /* Reset the sick message object */ + curr_message.Clear(); + + /* Acquire the most recent message */ + buffer_monitor->AcquireDataStream(); + + if (!buffer_monitor->_continue_grabbing) { // should the thread continue grabbing + buffer_monitor->ReleaseDataStream(); + break; + } + + buffer_monitor->GetNextMessageFromDataStream(curr_message); + buffer_monitor->ReleaseDataStream(); + + /* Update message container contents */ + buffer_monitor->_acquireMessageContainer(); + buffer_monitor->_recv_msg_container = curr_message; + buffer_monitor->_releaseMessageContainer(); + + } + + /* Make sure there wasn't a serious error reading from the buffer */ + catch(SickIOException &sick_io_exception) { + std::cerr << sick_io_exception.what() << std::endl; + } + + /* Catch any thread exceptions */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + } + + /* A failsafe */ + catch(...) { + std::cerr << "SickBufferMonitor::_bufferMonitorThread: Unknown exception!" << std::endl; + } + + /* sleep a bit! */ + usleep(1000); + + } + + /* Thread is done */ + return NULL; + + } + +} /* namespace SickToolbox */ + +#endif /* SICK_BUFFER_MONITOR */ diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickConfig.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickConfig.hh new file mode 100644 index 0000000..ac4436c --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickConfig.hh @@ -0,0 +1,186 @@ +/* c++/drivers/base/src/SickConfig.hh. Generated from SickConfig.hh.in by configure. */ +/* c++/drivers/base/src/SickConfig.hh.in. Generated from configure.ac by autoheader. */ + +/* Define if building universal (internal helper macro) */ +/* #undef AC_APPLE_UNIVERSAL_BUILD */ + +/* Define to 1 if you have the header file. */ +#define HAVE_ARPA_INET_H 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_DLFCN_H 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_FCNTL_H 1 + +/* Define to 1 if you have the `gettimeofday' function. */ +#define HAVE_GETTIMEOFDAY 1 + +/* Define if you have gnuplot */ +/* #undef HAVE_GNUPLOT */ + +/* Define to 1 if you have the header file. */ +#define HAVE_INTTYPES_H 1 + +/* Define if you have linux/serial.h */ +#define HAVE_LINUX_SERIAL_H 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_MEMORY_H 1 + +/* Define to 1 if you have the `memset' function. */ +#define HAVE_MEMSET 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_NETINET_IN_H 1 + +/* Define if you have POSIX threads libraries and header files. */ +#define HAVE_PTHREAD 1 + +/* Define to 1 if you have the `select' function. */ +#define HAVE_SELECT 1 + +/* Define to 1 if you have the `socket' function. */ +#define HAVE_SOCKET 1 + +/* Define to 1 if stdbool.h conforms to C99. */ +#define HAVE_STDBOOL_H 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_STDINT_H 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_STDLIB_H 1 + +/* Define to 1 if you have the `strcasecmp' function. */ +#define HAVE_STRCASECMP 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_STRINGS_H 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_STRING_H 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_SYS_IOCTL_H 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_SYS_SELECT_H 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_SYS_SOCKET_H 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_SYS_STAT_H 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_SYS_TIME_H 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_SYS_TYPES_H 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_TERMIOS_H 1 + +/* Define to 1 if you have the header file. */ +#define HAVE_UNISTD_H 1 + +/* Define to 1 if the system has the type `_Bool'. */ +#define HAVE__BOOL 1 + +/* Define to the sub-directory in which libtool stores uninstalled libraries. + */ +#define LT_OBJDIR ".libs/" + +/* Name of package */ +#define PACKAGE "sicktoolbox" + +/* Define to the address where bug reports for this package should be sent. */ +#define PACKAGE_BUGREPORT "jasonder@seas.upenn.edu" + +/* Define to the full name of this package. */ +#define PACKAGE_NAME "SickToolbox" + +/* Define to the full name and version of this package. */ +#define PACKAGE_STRING "SickToolbox 1.1" + +/* Define to the one symbol short name of this package. */ +#define PACKAGE_TARNAME "sicktoolbox" + +/* Define to the home page for this package. */ +#define PACKAGE_URL "" + +/* Define to the version of this package. */ +#define PACKAGE_VERSION "1.1" + +/* Define to necessary symbol if this constant uses a non-standard name on + your system. */ +/* #undef PTHREAD_CREATE_JOINABLE */ + +/* Define as the return type of signal handlers (`int' or `void'). */ +#define RETSIGTYPE void + +/* Define to the type of arg 1 for `select'. */ +#define SELECT_TYPE_ARG1 int + +/* Define to the type of args 2, 3 and 4 for `select'. */ +#define SELECT_TYPE_ARG234 (fd_set *) + +/* Define to the type of arg 5 for `select'. */ +#define SELECT_TYPE_ARG5 (struct timeval *) + +/* Define to 1 if you have the ANSI C header files. */ +#define STDC_HEADERS 1 + +/* Define to 1 if you can safely include both and . */ +#define TIME_WITH_SYS_TIME 1 + +/* Version number of package */ +#define VERSION "1.1" + +/* Define WORDS_BIGENDIAN to 1 if your processor stores words with the most + significant byte first (like Motorola and SPARC, unlike Intel). */ +#if defined AC_APPLE_UNIVERSAL_BUILD +# if defined __BIG_ENDIAN__ +# define WORDS_BIGENDIAN 1 +# endif +#else +# ifndef WORDS_BIGENDIAN +/* # undef WORDS_BIGENDIAN */ +# endif +#endif + +/* Define for Solaris 2.5.1 so the uint32_t typedef from , + , or is not used. If the typedef were allowed, the + #define below would cause a syntax error. */ +/* #undef _UINT32_T */ + +/* Define for Solaris 2.5.1 so the uint8_t typedef from , + , or is not used. If the typedef were allowed, the + #define below would cause a syntax error. */ +/* #undef _UINT8_T */ + +/* Define to empty if `const' does not conform to ANSI C. */ +/* #undef const */ + +/* Define to `__inline__' or `__inline' if that's what the C compiler + calls it, or to nothing if 'inline' is not supported under any name. */ +#ifndef __cplusplus +/* #undef inline */ +#endif + +/* Define to the type of a signed integer type of width exactly 16 bits if + such a type exists and the standard includes do not define it. */ +/* #undef int16_t */ + +/* Define to the type of an unsigned integer type of width exactly 16 bits if + such a type exists and the standard includes do not define it. */ +/* #undef uint16_t */ + +/* Define to the type of an unsigned integer type of width exactly 32 bits if + such a type exists and the standard includes do not define it. */ +/* #undef uint32_t */ + +/* Define to the type of an unsigned integer type of width exactly 8 bits if + such a type exists and the standard includes do not define it. */ +/* #undef uint8_t */ diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickException.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickException.hh new file mode 100644 index 0000000..c4efda2 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickException.hh @@ -0,0 +1,244 @@ +/*! + * \file SickException.hh + * \brief Contains some simple exception classes. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#ifndef SICK_EXCEPTION +#define SICK_EXCEPTION + +/* Definition dependencies */ +#include +#include + +/* Associate the namespace */ +namespace SickToolbox { + + /** \class SickException + * \brief Provides a base exception class from + * which to derive other Sick exceptions + */ + class SickException : std::exception { + + public: + + /** + * \brief A standard constructor + * \param general_str A descriptive "general" string + */ + SickException( const std::string general_str ) { + _detailed_msg = general_str; + } + + /** + * \brief A standard constructor + * \param general_str A descriptive "general" string + * \param detailed_str A more detailed description + */ + SickException( const std::string general_str, const std::string detailed_str ) { + _detailed_msg = general_str + " " + detailed_str; + } + + /** + * \brief From the standard exception library + */ + virtual const char* what( ) const throw() { + return _detailed_msg.c_str(); + } + + /** + * \brief A destructor + */ + ~SickException() throw() {} + + private: + + /** The string identifier */ + std::string _detailed_msg; + + }; + + /** + * \class SickTimeoutException + * \brief Makes handling timeouts much easier + */ + class SickTimeoutException : public SickException { + + public: + + /** + * \brief A constructor + */ + SickTimeoutException() : + SickException("A Timeout Occurred!") { } + + /** + * \brief A constructor + * \param detailed_str A more detailed description + */ + SickTimeoutException( const std::string detailed_str ) : + SickException("A Timeout Occurred -",detailed_str) { } + + /** + * \brief A destructor + */ + ~SickTimeoutException() throw() { } + + }; + + /** + * \class SickIOException + * \brief Thrown instance where the driver can't + * read,write,drain,flush,... the buffers + */ + class SickIOException : public SickException { + + public: + + /** + * \brief A constructor + */ + SickIOException() : + SickException("ERROR: I/O exception!") { } + + /** + * \brief Another constructor + * \param detailed_str A more detailed description + */ + SickIOException( const std::string detailed_str ) : + SickException("ERROR: I/O exception -",detailed_str) { } + + /** + * \brief A destructor + */ + ~SickIOException() throw() { } + + }; + + /** + * \class SickBadChecksumException + * \brief Thrown when a received message has an + * invalid checksum + */ + class SickBadChecksumException : public SickException { + + public: + + /** + * \brief A constructor + */ + SickBadChecksumException() : + SickException("ERROR: Bad Checksum!") { } + + /** + * \brief Another constructor + * \param detailed_str A more detailed description + */ + SickBadChecksumException( const std::string detailed_str ) : + SickException("ERROR: Bad Checksum -",detailed_str) { } + + /** + * \brief A destructor + */ + ~SickBadChecksumException() throw() { } + + }; + + /** + * \class SickThreadException + * \brief Thrown when error occurs during thread + * initialization, and uninitialization + */ + class SickThreadException : public SickException { + + public: + + /** + * \brief A constructor + */ + SickThreadException() : + SickException("ERROR: Sick thread exception!") { } + + /** + * \brief Another constructor + * \param detailed_str A more detailed description + */ + SickThreadException( const std::string detailed_str ) : + SickException("ERROR: Sick thread exception -",detailed_str) { } + + /** + * \brief A destructor + */ + ~SickThreadException() throw() { } + + }; + + /** + * \class SickConfigException + * \brief Thrown when the driver detects (or the Sick reports) + * an invalid config + */ + class SickConfigException : public SickException { + + public: + + /** + * \brief A constructor + */ + SickConfigException() : + SickException("ERROR: Config exception!") { } + + /** + * \brief Another constructor + * \param detailed_str A more detailed description + */ + SickConfigException( const std::string detailed_str ) : + SickException("ERROR: Config exception -",detailed_str) { } + + /** + * \brief A destructor + */ + ~SickConfigException() throw() { } + + }; + + /** + * \class SickErrorException + * \brief Thrown when Sick returns an error code + * or an unexpected response. + */ + class SickErrorException : public SickException { + + public: + + /** + * \brief A constructor + */ + SickErrorException() : + SickException("ERROR: Sick returned error code!") { }; + + /** + * \brief Another constructor + * \param detailed_str A more detailed description + */ + SickErrorException( const std::string detailed_str ) : + SickException("ERROR: Sick error -", detailed_str) { } + + /** + * \brief A destructor + */ + ~SickErrorException() throw() { } + + }; +} /* namespace SickToolbox */ + +#endif /* SICK_EXCEPTION */ diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLD.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLD.hh new file mode 100644 index 0000000..72c0102 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLD.hh @@ -0,0 +1,805 @@ +/*! + * \file SickLD.hh + * \brief Defines the SickLD class for working with the + * Sick LD-OEM/LD-LRS long range LIDARs. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#ifndef SICK_LD_HH +#define SICK_LD_HH + +/* Macros */ +#define DEFAULT_SICK_IP_ADDRESS "192.168.1.10" ///< Default Sick LD INet 4 address +#define DEFAULT_SICK_TCP_PORT (49152) ///< Default TCP port +#define DEFAULT_SICK_MESSAGE_TIMEOUT (unsigned int)(5e6) ///< The max time to wait for a message reply (usecs) +#define DEFAULT_SICK_CONNECT_TIMEOUT (unsigned int)(1e6) ///< The max time to wait before considering a connection attempt as failed (usecs) +#define DEFAULT_SICK_NUM_SCAN_PROFILES (0) ///< Setting this value to 0 will tell the Sick LD to stream measurements when measurement data is requested (NOTE: A profile is a single scans worth of range measurements) +#define DEFAULT_SICK_SIGNAL_SET (0) ///< Default Sick signal configuration + +/** + * \def SWAP_VALUES(x,y,t) + * \brief A simple macro for swapping two values. + */ +#define SWAP_VALUES(x,y,t) (t=x,x=y,y=t); + +/* Definition dependencies */ +#include +#include +#include +#include + +#include "SickLIDAR.hh" +#include "SickLDBufferMonitor.hh" +#include "SickLDMessage.hh" +#include "SickException.hh" + +/** + * \namespace SickToolbox + * \brief Encapsulates the Sick LIDAR Matlab/C++ toolbox + */ +namespace SickToolbox { + + /** + * \class SickLD + * \brief Provides a simple driver interface for working with the + * Sick LD-OEM/Sick LD-LRS long-range models via Ethernet. + */ + class SickLD : public SickLIDAR< SickLDBufferMonitor, SickLDMessage > { + + public: + + /* Some constants for the developer/end-user */ + static const uint16_t SICK_MAX_NUM_MEASUREMENTS = 2881; ///< Maximum number of measurements per sector + static const uint16_t SICK_MAX_NUM_SECTORS = 8; ///< Maximum number of scan sectors (NOTE: This value must be even) + static const uint16_t SICK_MAX_NUM_MEASURING_SECTORS = 4; ///< Maximum number of active/measuring scan sectors + static const uint16_t SICK_MAX_SCAN_AREA = 360; ///< Maximum area that can be covered in a single scan (deg) + static const uint16_t SICK_MIN_MOTOR_SPEED = 5; ///< Minimum motor speed in Hz + static const uint16_t SICK_MAX_MOTOR_SPEED = 20; ///< Maximum motor speed in Hz + static const uint16_t SICK_MIN_VALID_SENSOR_ID = 1; ///< The lowest value the Sick will accept as a Sensor ID + static const uint16_t SICK_MAX_VALID_SENSOR_ID = 254; ///< The largest value the Sick will accept as a Sensor ID + static const uint16_t SICK_MAX_MEAN_PULSE_FREQUENCY = 10800; ///< Max mean pulse frequence of the current device configuration (in Hz) (see page 22 of the operator's manual) + static const uint16_t SICK_MAX_PULSE_FREQUENCY = 14400; ///< Max pulse frequency of the device (in Hz) (see page 22 of the operator's manual) + static const uint16_t SICK_NUM_TICKS_PER_MOTOR_REV = 5760; ///< Odometer ticks per revolution of the Sick LD scan head + static constexpr double SICK_MAX_SCAN_ANGULAR_RESOLUTION = 0.125; ///< Minimum valid separation between laser pulses in active scan ares (deg) + static constexpr double SICK_DEGREES_PER_MOTOR_STEP = 0.0625; ///< Each odometer tick is equivalent to rotating the scan head this many degrees + + /* Sick LD sensor modes of operation */ + static const uint8_t SICK_SENSOR_MODE_IDLE = 0x01; ///< The Sick LD is powered but idle + static const uint8_t SICK_SENSOR_MODE_ROTATE = 0x02; ///< The Sick LD prism is rotating, but laser is off + static const uint8_t SICK_SENSOR_MODE_MEASURE = 0x03; ///< The Sick LD prism is rotating, and the laser is on + static const uint8_t SICK_SENSOR_MODE_ERROR = 0x04; ///< The Sick LD is in error mode + static const uint8_t SICK_SENSOR_MODE_UNKNOWN = 0xFF; ///< The Sick LD is in an unknown state + + /* Sick LD motor modes */ + static const uint8_t SICK_MOTOR_MODE_OK = 0x00; ///< Motor is functioning properly + static const uint8_t SICK_MOTOR_MODE_SPIN_TOO_HIGH = 0x09; ///< Motor spin too low (i.e. rotational velocity too low) + static const uint8_t SICK_MOTOR_MODE_SPIN_TOO_LOW = 0x04; ///< Motor spin too high (i.e. rotational velocity too fast) + static const uint8_t SICK_MOTOR_MODE_ERROR = 0x0B; ///< Motor stops or coder error + static const uint8_t SICK_MOTOR_MODE_UNKNOWN = 0xFF; ///< Motor is in an unknown state + + /* Sick LD service codes */ + static const uint8_t SICK_STAT_SERV_CODE = 0x01; ///< Status service code + static const uint8_t SICK_CONF_SERV_CODE = 0x02; ///< Configuration service code + static const uint8_t SICK_MEAS_SERV_CODE = 0x03; ///< Measurement service code + static const uint8_t SICK_WORK_SERV_CODE = 0x04; ///< Working service code + static const uint8_t SICK_ROUT_SERV_CODE = 0x06; ///< Routing service code + static const uint8_t SICK_FILE_SERV_CODE = 0x07; ///< File service code + static const uint8_t SICK_MONR_SERV_CODE = 0x08; ///< Monitor service code + + /* Sick LD status services (service code 0x01) */ + static const uint8_t SICK_STAT_SERV_GET_ID = 0x01; ///< Request the Sick LD ID + static const uint8_t SICK_STAT_SERV_GET_STATUS = 0x02; ///< Request status information + static const uint8_t SICK_STAT_SERV_GET_SIGNAL = 0x04; ///< Reads the value of the switch and LED port + static const uint8_t SICK_STAT_SERV_SET_SIGNAL = 0x05; ///< Sets the switches and LEDs + static const uint8_t SICK_STAT_SERV_LD_REGISTER_APPLICATION = 0x06; ///< Registers the ID data for the application firmware + + /* Sick LD status service GET_IDENTIFICATION request codes */ + static const uint8_t SICK_STAT_SERV_GET_ID_SENSOR_PART_NUM = 0x00; ///< Request the sensor's part number + static const uint8_t SICK_STAT_SERV_GET_ID_SENSOR_NAME = 0x01; ///< Request the sensor's name + static const uint8_t SICK_STAT_SERV_GET_ID_SENSOR_VERSION = 0x02; ///< Request the sensor's version + static const uint8_t SICK_STAT_SERV_GET_ID_SENSOR_SERIAL_NUM = 0x03; ///< Request the sensor's serial number + static const uint8_t SICK_STAT_SERV_GET_ID_SENSOR_EDM_SERIAL_NUM = 0x04; ///< Request the edm??? serial number + static const uint8_t SICK_STAT_SERV_GET_ID_FIRMWARE_PART_NUM = 0x10; ///< Requess the firmware's part number + static const uint8_t SICK_STAT_SERV_GET_ID_FIRMWARE_NAME = 0x11; ///< Request the firmware's name + static const uint8_t SICK_STAT_SERV_GET_ID_FIRMWARE_VERSION = 0x12; ///< Request the firmware's version + static const uint8_t SICK_STAT_SERV_GET_ID_APP_PART_NUM = 0x20; ///< Request the application part number + static const uint8_t SICK_STAT_SERV_GET_ID_APP_NAME = 0x21; ///< Request the application name + static const uint8_t SICK_STAT_SERV_GET_ID_APP_VERSION = 0x22; ///< Request the application version + + /* Sick LD configuration services (service code 0x02) */ + static const uint8_t SICK_CONF_SERV_SET_CONFIGURATION = 0x01; ///< Set the Sick LD configuration + static const uint8_t SICK_CONF_SERV_GET_CONFIGURATION = 0x02; ///< Read the Sick LD configuration information + static const uint8_t SICK_CONF_SERV_SET_TIME_ABSOLUTE = 0x03; ///< Set the internal clock to a timestamp value + static const uint8_t SICK_CONF_SERV_SET_TIME_RELATIVE = 0x04; ///< Correct the internal clock by some value + static const uint8_t SICK_CONF_SERV_GET_SYNC_CLOCK = 0x05; ///< Read the internal time of the LD-OEM/LD-LRS + static const uint8_t SICK_CONF_SERV_SET_FILTER = 0x09; ///< Set the filter configuration + static const uint8_t SICK_CONF_SERV_SET_FUNCTION = 0x0A; ///< Assigns a measurement function to an angle range + static const uint8_t SICK_CONF_SERV_GET_FUNCTION = 0x0B; ///< Returns the configuration of the given sector + + /* Sick LD configuration filter codes */ + static const uint8_t SICK_CONF_SERV_SET_FILTER_NEARFIELD = 0x01; ///< Code for identifying filter type: nearfield suppression + + /* Sick LD nearfield suppression configuration codes */ + static const uint8_t SICK_CONF_SERV_SET_FILTER_NEARFIELD_OFF = 0x00; ///< Used to set nearfield suppression off + static const uint8_t SICK_CONF_SERV_SET_FILTER_NEARFIELD_ON = 0x01; ///< Used to set nearfield suppression on + + /* Sick LD measurement services (service code 0x03) */ + static const uint8_t SICK_MEAS_SERV_GET_PROFILE = 0x01; ///< Requests n profiles of a defined format + static const uint8_t SICK_MEAS_SERV_CANCEL_PROFILE = 0x02; ///< Stops profile output + + /* Sick LD working services (service code 0x04) */ + static const uint8_t SICK_WORK_SERV_RESET = 0x01; ///< Sick LD enters a reset sequence + static const uint8_t SICK_WORK_SERV_TRANS_IDLE = 0x02; ///< Sick LD enters IDLE mode (motor stops and laser is turned off) + static const uint8_t SICK_WORK_SERV_TRANS_ROTATE = 0x03; ///< Sick LD enters ROTATE mode (motor starts and rotates with a specified speed in Hz, laser is off) + static const uint8_t SICK_WORK_SERV_TRANS_MEASURE = 0x04; ///< Sick LD enters MEASURE mode (laser starts with next revolution) + + /* Sick LD working service DO_RESET request codes */ + static const uint8_t SICK_WORK_SERV_RESET_INIT_CPU = 0x00; ///< Sick LD does a complete reset (Reinitializes the CPU) + static const uint8_t SICK_WORK_SERV_RESET_KEEP_CPU = 0x01; ///< Sick LD does a partial reset (CPU is not reinitialized) + static const uint8_t SICK_WORK_SERV_RESET_HALT_APP = 0x02; ///< Sick LD does a minimal reset (Application is halted and device enters IDLE state) + + /* Sick LD working service TRANS_MEASURE return codes */ + static const uint8_t SICK_WORK_SERV_TRANS_MEASURE_RET_OK = 0x00; ///< Sick LD is ready to stream/obtain scan profiles + static const uint8_t SICK_WORK_SERV_TRANS_MEASURE_RET_ERR_MAX_PULSE = 0x01; ///< Sick LD reports config yields a max laser pulse frequency that is too high + static const uint8_t SICK_WORK_SERV_TRANS_MEASURE_RET_ERR_MEAN_PULSE = 0x02; ///< Sick LD reports config yields a max mean pulse frequency that is too high + static const uint8_t SICK_WORK_SERV_TRANS_MEASURE_RET_ERR_SECT_BORDER = 0x03; ///< Sick LD reports sector borders are not configured correctly + static const uint8_t SICK_WORK_SERV_TRANS_MEASURE_RET_ERR_SECT_BORDER_MULT = 0x04; ///< Sick LD reports sector borders are not a multiple of the step angle + + /* Sick LD interface routing services (service code 0x06) */ + static const uint8_t SICK_ROUT_SERV_COM_ATTACH = 0x01; ///< Attach a master (host) communications interface + static const uint8_t SICK_ROUT_SERV_COM_DETACH = 0x02; ///< Detach a master (host) communications interface + static const uint8_t SICK_ROUT_SERV_COM_INITIALIZE = 0x03; ///< Initialize the interface (Note: using this may not be necessary for some interfaces, e.g. Ethernet) + static const uint8_t SICK_ROUT_SERV_COM_OUTPUT = 0x04; ///< Output data to the interface + static const uint8_t SICK_ROUT_SERV_COM_DATA = 0x05; ///< Forward data received on specified interface to master interface + + /* Sick LD file services (service code 0x07) */ + static const uint8_t SICK_FILE_SERV_DIR = 0x01; ///< List the stored files in flash memory + static const uint8_t SICK_FILE_SERV_SAVE = 0x02; ///< Saves the data into flash memory + static const uint8_t SICK_FILE_SERV_LOAD = 0x03; ///< Recalls a file from the flash + static const uint8_t SICK_FILE_SERV_DELETE = 0x04; ///< Deletes a file from the flash + + /* Sick LD monitor services (service code 0x08) */ + static const uint8_t SICK_MONR_SERV_MONITOR_RUN = 0x01; ///< Enable/disable monitor services + static const uint8_t SICK_MONR_SERV_MONITOR_PROFILE_LOG = 0x02; ///< Enable/disable profile logging + + /* Sick LD configuration keys */ + static const uint8_t SICK_CONF_KEY_RS232_RS422 = 0x01; ///< Key for configuring RS-232/RS-422 + static const uint8_t SICK_CONF_KEY_CAN = 0x02; ///< Key for configuring CAN + static const uint8_t SICK_CONF_KEY_ETHERNET = 0x05; ///< Key for configuring Ethernet + static const uint8_t SICK_CONF_KEY_GLOBAL = 0x10; ///< Key for global configuration + + /* Sick LD sector configuration codes */ + static const uint8_t SICK_CONF_SECTOR_NOT_INITIALIZED = 0x00; ///< Sector is uninitialized + static const uint8_t SICK_CONF_SECTOR_NO_MEASUREMENT = 0x01; ///< Sector has no measurements + static const uint8_t SICK_CONF_SECTOR_RESERVED = 0x02; ///< Sector is reserved by Sick LD + static const uint8_t SICK_CONF_SECTOR_NORMAL_MEASUREMENT = 0x03; ///< Sector is returning measurements + static const uint8_t SICK_CONF_SECTOR_REFERENCE_MEASUREMENT = 0x04; ///< Sector can be used as reference measurement + + /* Sick LD profile formats */ + static const uint16_t SICK_SCAN_PROFILE_RANGE = 0x39FF; ///< Request sector scan data w/o any echo data + /* + * SICK_SCAN_PROFILE_RANGE format (0x39FF) interpretation: + * (See page 32 of telegram listing for fieldname definitions) + * + * Field Name | Send + * -------------------- + * PROFILESENT | YES + * PROFILECOUNT | YES + * LAYERNUM | YES + * SECTORNUM | YES + * DIRSTEP | YES + * POINTNUM | YES + * TSTART | YES + * STARTDIR | YES + * DISTANCE-n | YES + * DIRECTION-n | NO + * ECHO-n | NO + * TEND | YES + * ENDDIR | YES + * SENSTAT | YES + */ + + /* Sick LD profile formats */ + static const uint16_t SICK_SCAN_PROFILE_RANGE_AND_ECHO = 0x3DFF; ///< Request sector scan data w/ echo data + /* + * SICK_SCAN_PROFILE_RANGE format (0x3DFF) interpretation: + * (See page 32 of telegram listing for fieldname definitions) + * + * Field Name | Send + * -------------------- + * PROFILESENT | YES + * PROFILECOUNT | YES + * LAYERNUM | YES + * SECTORNUM | YES + * DIRSTEP | YES + * POINTNUM | YES + * TSTART | YES + * STARTDIR | YES + * DISTANCE-n | YES + * DIRECTION-n | NO + * ECHO-n | YES + * TEND | YES + * ENDDIR | YES + * SENSTAT | YES + */ + + /* Masks for working with the Sick LD signals + * + * NOTE: Although the Sick LD manual defines the flag + * values for red and green LEDs the operation + * of these LEDs are reserved. So they can't + * be set by the device driver. + */ + static const uint8_t SICK_SIGNAL_LED_YELLOW_A = 0x01; ///< Mask for first yellow LED + static const uint8_t SICK_SIGNAL_LED_YELLOW_B = 0x02; ///< Mask for second yellow LED + static const uint8_t SICK_SIGNAL_LED_GREEN = 0x04; ///< Mask for green LED + static const uint8_t SICK_SIGNAL_LED_RED = 0x08; ///< Mask for red LED + static const uint8_t SICK_SIGNAL_SWITCH_0 = 0x10; ///< Mask for signal switch 0 + static const uint8_t SICK_SIGNAL_SWITCH_1 = 0x20; ///< Mask for signal switch 1 + static const uint8_t SICK_SIGNAL_SWITCH_2 = 0x40; ///< Mask for signal switch 2 + static const uint8_t SICK_SIGNAL_SWITCH_3 = 0x80; ///< Mask for signal switch 3 + + /** + * \struct sick_ld_config_global_tag + * \brief A structure to aggregate the data used to configure the + * Sick LD global parameter values. + */ + /** + * \typedef sick_ld_config_global_t + * \brief Adopt c-style convention + */ + typedef struct sick_ld_config_global_tag { + uint16_t sick_sensor_id; ///< The single word sensor ID for the Sick unit + uint16_t sick_motor_speed; ///< Nominal motor speed value: 0x0005 to 0x0014 (5 to 20) + double sick_angle_step; ///< Difference between two laser pulse positions in 1/16th deg. (NOTE: this value must be a divisor of 5760 and be greater than 1) + } sick_ld_config_global_t; + + /** + * \struct sick_ld_config_ethernet_tag + * \brief A structure to aggregate the data used to configure + * the Sick LD unit for Ethernet. + * + * \todo Eventually add similar config structures for the other protocols. + */ + /** + * \typedef sick_ld_config_ethernet_t + * \brief Adopt c-style convention + */ + typedef struct sick_ld_config_ethernet_tag { + uint16_t sick_ip_address[4]; ///< IP address in numerical form w/ leftmost part at sick_ip_address[0] + uint16_t sick_subnet_mask[4]; ///< Subnet mask for the network to which the Sick LD is assigned + uint16_t sick_gateway_ip_address[4]; ///< The address of the local gateway + uint16_t sick_node_id; ///< Single word address of the Sick LD + uint16_t sick_transparent_tcp_port; ///< The TCP/IP transparent port associated with the Sick LD + } sick_ld_config_ethernet_t; + + /** + * \struct sick_ld_config_sector_tag + * \brief A structure to aggregate data used to define the + * Sick LD's sector configuration. + */ + /** + * \typedef sick_ld_config_sector_t + * \brief Adopt c-style convention + */ + typedef struct sick_ld_config_sector_tag { + uint8_t sick_num_active_sectors; ///< Number of active sectors (sectors that are actually being scanned) + uint8_t sick_num_initialized_sectors; ///< Number of sectors configured w/ a function other than "not initialized" + uint8_t sick_active_sector_ids[SICK_MAX_NUM_SECTORS]; ///< IDs of all active sectors + uint8_t sick_sector_functions[SICK_MAX_NUM_SECTORS]; ///< Function values associated w/ each of the Sick LD's sectors + double sick_sector_start_angles[SICK_MAX_NUM_SECTORS]; ///< Start angles for each initialized sector (deg) + double sick_sector_stop_angles[SICK_MAX_NUM_SECTORS]; ///< Stop angles for each sector (deg) + } sick_ld_config_sector_t; + + /** + * \struct sick_ld_identity_tag + * \brief A structure to aggregate the fields that collectively + * define the identity of a Sick LD unit. + */ + /** + * \typedef sick_ld_identity_t + * \brief Adopt c-style convention + */ + typedef struct sick_ld_identity_tag { + std::string sick_part_number; ///< The Sick LD's part number + std::string sick_name; ///< The name assigned to the Sick + std::string sick_version; ///< The Sick LD's version number + std::string sick_serial_number; ///< The Sick LD's serial number + std::string sick_edm_serial_number; ///< The Sick LD's edm??? serial number + std::string sick_firmware_part_number; ///< The Sick LD's firmware part number + std::string sick_firmware_name; ///< The Sick LD's firmware name + std::string sick_firmware_version; ///< The Sick LD's firmware version + std::string sick_application_software_part_number; ///< The Sick LD's app. software part number + std::string sick_application_software_name; ///< The Sick LD's app. software name + std::string sick_application_software_version; ///< The Sick LD's app. software version + } sick_ld_identity_t; + + /** + * \struct sick_ld_sector_data_tag + * \brief A structure to aggregate the fields that collectively + * define a sector in the scan area of the Sick LD unit. + */ + /** + * \typedef sick_ld_sector_data_t + * \brief Adopt c-style convention + */ + typedef struct sick_ld_sector_data_tag { + unsigned int sector_num; ///< The sector number in the scan area + unsigned int num_data_points; ///< The number of data points in the scan area + unsigned int timestamp_start; ///< The timestamp (in ms) corresponding to the time the first measurement in the sector was taken + unsigned int timestamp_stop; ///< The timestamp (in ms) corresponding to the time the last measurement in the sector was taken + unsigned int echo_values[SICK_MAX_NUM_MEASUREMENTS]; ///< The corresponding echo/reflectivity values + double angle_step; ///< The angle step used for the given sector (this should be the same for all sectors) + double angle_start; ///< The angle at which the first measurement in the sector was acquired + double angle_stop; ///< The angle at which the last measurement in the sector was acquired + double range_values[SICK_MAX_NUM_MEASUREMENTS]; ///< The corresponding range values (NOTE: The size of this array is intended to be large enough to accomodate various sector configs.) + double scan_angles[SICK_MAX_NUM_MEASUREMENTS]; ///< The scan angles corresponding to the respective measurements + } sick_ld_sector_data_t; + + /** + * \struct sick_ld_scan_profile_tag + * \brief A structure to aggregate the fields that collectively + * define the profile of a single scan acquired from the + * Sick LD unit. + */ + /** + * \typedef sick_ld_scan_profile_t + * \brief Adopt c-style convention + */ + typedef struct sick_ld_scan_profile_tag { + unsigned int profile_number; ///< The number of profiles sent to the host (i.e. the current profile number) + unsigned int profile_counter; ///< The number of profiles gathered by the Sick LD + unsigned int layer_num; ///< The layer number associated with a scan (this will always be 0) + unsigned int sensor_status; ///< The status of the Sick LD sensor + unsigned int motor_status; ///< The status of the Sick LD motor + unsigned int num_sectors; ///< The number of sectors returned in the profile + sick_ld_sector_data_t sector_data[SICK_MAX_NUM_SECTORS]; ///< The sectors associated with the scan profile + } sick_ld_scan_profile_t; + + /** Primary constructor */ + SickLD( const std::string sick_ip_address = DEFAULT_SICK_IP_ADDRESS, + const uint16_t sick_tcp_port = DEFAULT_SICK_TCP_PORT ); + + /** Initializes the Sick LD unit (use scan areas defined in flash) */ + void Initialize( ) throw( SickIOException, SickThreadException, SickTimeoutException, SickErrorException ); + + /** Gets the sensor and motor mode of the unit */ + void GetSickStatus( unsigned int &sick_sensor_mode, unsigned int &sick_motor_mode ) + throw( SickIOException, SickTimeoutException ); + + /** Sets the temporal scan configuration (until power is cycled) */ + void SetSickTempScanAreas( const double * active_sector_start_angles, const double * const active_sector_stop_angles, + const unsigned int num_active_sectors ) + throw( SickTimeoutException, SickIOException, SickConfigException ); + + /** Sets the internal clock of the Sick LD unit */ + void SetSickTimeAbsolute( const uint16_t absolute_clock_time, uint16_t &new_sick_clock_time ) + throw( SickErrorException, SickTimeoutException, SickIOException, SickConfigException ); + + /** Sets the internal clock of the Sick LD using the relative given time value */ + void SetSickTimeRelative( const int16_t time_delta, uint16_t &new_sick_clock_time ) + throw( SickErrorException, SickTimeoutException, SickIOException, SickConfigException ); + + /** Gets the internal clock time of the Sick LD unit */ + void GetSickTime( uint16_t &sick_time ) + throw( SickIOException, SickTimeoutException, SickErrorException ); + + /** Sets the signal LEDs and switches */ + void SetSickSignals( const uint8_t sick_signal_flags = DEFAULT_SICK_SIGNAL_SET ) + throw( SickIOException, SickTimeoutException, SickErrorException ); + + /** Query the Sick for its current signal settings */ + void GetSickSignals( uint8_t &sick_signal_flags ) throw( SickIOException, SickTimeoutException ); + + /** Enables nearfield suppressive filtering (in flash) */ + void EnableNearfieldSuppression( ) throw( SickErrorException, SickTimeoutException, SickIOException ); + + /** Disables nearfield suppressive filtering (in flash) */ + void DisableNearfieldSuppression( ) throw( SickErrorException, SickTimeoutException, SickIOException ); + + /** Acquires measurements and related data for all active sectors */ + void GetSickMeasurements( double * const range_measurements, + unsigned int * const echo_measurements = NULL, + unsigned int * const num_measurements = NULL, + unsigned int * const sector_ids = NULL, + unsigned int * const sector_data_offsets = NULL, + double * const sector_step_angles = NULL, + double * const sector_start_angles = NULL, + double * const sector_stop_angles = NULL, + unsigned int * const sector_start_timestamps = NULL, + unsigned int * const sector_stop_timestamps = NULL ) + throw( SickErrorException, SickIOException, SickTimeoutException, SickConfigException ); + + /** Attempts to set a new senor ID for the device (in flash) */ + void SetSickSensorID( const unsigned int sick_sensor_id ) + throw( SickErrorException, SickTimeoutException, SickIOException ); + + /** Attempts to set a new motor speed for the device (in flash) */ + void SetSickMotorSpeed( const unsigned int sick_motor_speed ) + throw( SickErrorException, SickTimeoutException, SickIOException ); + + /** Attempts to set a new scan resolution for the device (in flash) */ + void SetSickScanResolution( const double sick_step_angle ) + throw( SickTimeoutException, SickIOException, SickConfigException ); + + /** Attempts to set the global params and the active scan sectors for the device (in flash) */ + void SetSickGlobalParamsAndScanAreas( const unsigned int sick_motor_speed, + const double sick_step_angle, + const double * const active_sector_start_angles, + const double * const active_sector_stop_angles, + const unsigned int num_active_sectors ) + throw( SickTimeoutException, SickIOException, SickConfigException, SickErrorException ); + + /** Attempts to set the active scan sectors for the device (in flash) */ + void SetSickScanAreas( const double * const active_sector_start_angles, + const double * const active_sector_stop_angles, + const unsigned int num_active_sectors ) + throw( SickTimeoutException, SickIOException, SickConfigException, SickErrorException ); + + /** Resets the Sick LD using the given reset level */ + void ResetSick( const unsigned int reset_level = SICK_WORK_SERV_RESET_INIT_CPU ) + throw( SickErrorException, SickTimeoutException, SickIOException, SickConfigException ); + + /** Returns the number of active/measuring sectors */ + unsigned int GetSickNumActiveSectors( ) const; + + /** Acquire the Sick LD's sensor ID */ + unsigned int GetSickSensorID( ) const; + + /** Acquire the Sick LD's current motor speed in Hz */ + unsigned int GetSickMotorSpeed( ) const; + + /** Acquire the Sick LD's current scan resolution */ + double GetSickScanResolution( ) const; + + /** Acquire the current IP address of the Sick */ + std::string GetSickIPAddress( ) const; + + /** Acquire the subnet mask for the Sick */ + std::string GetSickSubnetMask( ) const; + + /** Acquire the IP address of the Sick gateway */ + std::string GetSickGatewayIPAddress( ) const; + + /** Acquire the Sick LD's part number */ + std::string GetSickPartNumber( ) const; + + /** Acquire the Sick LD's name */ + std::string GetSickName( ) const; + + /** Acquire the Sick LD's version number */ + std::string GetSickVersion( ) const; + + /** Acquire the Sick LD's serial number */ + std::string GetSickSerialNumber( ) const; + + /** Acquire the Sick LD's EDM serial number */ + std::string GetSickEDMSerialNumber( ) const; + + /** Acquire the Sick LD's firmware part number */ + std::string GetSickFirmwarePartNumber( ) const; + + /** Acquire the Sick LD's firmware number */ + std::string GetSickFirmwareName( ) const; + + /** Acquire the Sick LD's firmware version */ + std::string GetSickFirmwareVersion( ) const; + + /** Acquire the Sick LD's application software part number */ + std::string GetSickAppSoftwarePartNumber( ) const; + + /** Acquire the Sick LD's application software name */ + std::string GetSickAppSoftwareName( ) const; + + /** Acquire the Sick LD's application software version number */ + std::string GetSickAppSoftwareVersionNumber( ) const; + + /** Acquire the Sick LD's status as a printable string */ + std::string GetSickStatusAsString() const; + + /** Acquire the Sick LD's identity as a printable string */ + std::string GetSickIdentityAsString() const; + + /** Acquire the Sick LD's global config as a printable string */ + std::string GetSickGlobalConfigAsString() const; + + /** Acquire the Sick LD's Ethernet config as a printable string */ + std::string GetSickEthernetConfigAsString() const; + + /** Acquire the Sick LD's sector config as a printable string */ + std::string GetSickSectorConfigAsString() const; + + /** Acquire the total scan area (in degrees) being scanned by the Sick LD */ + double GetSickScanArea( ) const; + + /** Prints the Sick LD's status information */ + void PrintSickStatus( ) const; + + /** Prints the Sick LD's identity information */ + void PrintSickIdentity( ) const; + + /** Prints the global configuration parameter values */ + void PrintSickGlobalConfig( ) const; + + /** Prints the Ethernet configuration parameter values */ + void PrintSickEthernetConfig( ) const; + + /** Prints the Sick Sector configuration */ + void PrintSickSectorConfig( ) const; + + /** Uninitializes the Sick LD unit */ + void Uninitialize( ) throw( SickIOException, SickTimeoutException, SickErrorException, SickThreadException ); + + /** Destructor */ + ~SickLD(); + + private: + + /** The Sick LD IP address */ + std::string _sick_ip_address; + + /** The Sick LD TCP port number */ + uint16_t _sick_tcp_port; + + /** Sick LD socket structure */ + unsigned int _socket; + + /** Sick LD socket address structure */ + struct sockaddr_in _sick_inet_address_info; + + /** The current sensor mode */ + uint8_t _sick_sensor_mode; + + /** The mode of the motor */ + uint8_t _sick_motor_mode; + + /** Indicates whether the Sick LD is currently streaming range data */ + bool _sick_streaming_range_data; + + /** Indicates whether the Sick LD is currently streaming range and echo data */ + bool _sick_streaming_range_and_echo_data; + + /** The identity structure for the Sick */ + sick_ld_identity_t _sick_identity; + + /** The current global configuration for the unit */ + sick_ld_config_global_t _sick_global_config; + + /** The current Ethernet configuration for the unit */ + sick_ld_config_ethernet_t _sick_ethernet_config; + + /** The current sector configuration for the unit */ + sick_ld_config_sector_t _sick_sector_config; + + /** Setup the connection parameters and establish TCP connection! */ + void _setupConnection( ) throw( SickIOException, SickTimeoutException ); + + /** Synchronizes the driver state with the Sick LD (used for initialization) */ + void _syncDriverWithSick( ) throw( SickIOException, SickTimeoutException, SickErrorException ); + + /** Set the function for a particular scan secto */ + void _setSickSectorFunction( const uint8_t sector_number, const uint8_t sector_function, + const double sector_angle_stop, const bool write_to_flash = false ) + throw( SickErrorException, SickTimeoutException, SickIOException, SickConfigException ); + + /** Acquires the given Sector's function (i.e. current config) */ + void _getSickSectorFunction( const uint8_t sector_num, uint8_t §or_function, double §or_stop_angle ) + throw( SickErrorException, SickTimeoutException, SickIOException ); + + /** Sets the Sick LD to IDLE mode */ + void _setSickSensorModeToIdle( ) throw( SickErrorException, SickTimeoutException, SickIOException ); + + /** Sets the Sick LD to ROTATE mode */ + void _setSickSensorModeToRotate( ) throw( SickErrorException, SickTimeoutException, SickIOException ); + + /** Sets the Sick LD to MEASURE mode */ + void _setSickSensorModeToMeasure( ) throw( SickErrorException, SickTimeoutException, SickIOException ); + + /** Sets the Sick LD's sensor mode to IDLE (laser off, motor off) */ + void _setSickSensorMode( const uint8_t new_sick_sensor_mode ) + throw( SickErrorException, SickTimeoutException, SickIOException ); + + /** Requests n range measurement profiles from the Sick LD */ + void _getSickScanProfiles( const uint16_t profile_format, const uint16_t num_profiles = DEFAULT_SICK_NUM_SCAN_PROFILES ) + throw( SickErrorException, SickTimeoutException, SickIOException, SickConfigException ); + + /** Parses a sequence of bytes and populates the profile_data struct w/ the results */ + void _parseScanProfile( uint8_t * const src_buffer, sick_ld_scan_profile_t &profile_data ) const; + + /** Cancels the active data stream */ + void _cancelSickScanProfiles( ) throw( SickErrorException, SickTimeoutException, SickIOException ); + + /** Turns nearfield suppression on/off */ + void _setSickFilter( const uint8_t suppress_code ) + throw( SickErrorException, SickTimeoutException, SickIOException ); + + /** Stores an image of the Sick LD's identity locally */ + void _getSickIdentity( ) throw( SickTimeoutException, SickIOException ); + + /** Query the Sick for its sensor and motor status */ + void _getSickStatus( ) throw( SickTimeoutException, SickIOException ); + + /** Sets the Sick LD's global configuration (in flash) */ + void _setSickGlobalConfig( const uint8_t sick_sensor_id, const uint8_t sick_motor_speed, const double sick_angle_step ) + throw( SickErrorException, SickTimeoutException, SickIOException ); + + /** Query the Sick for its global configuration parameters */ + void _getSickGlobalConfig( ) throw( SickErrorException, SickTimeoutException, SickIOException ); + + /** Query the Sick for its Ethernet configuration parameters */ + void _getSickEthernetConfig( ) throw( SickErrorException, SickTimeoutException, SickIOException ); + + /** Acquires the configuration (function and stop angle) for each sector */ + void _getSickSectorConfig( ) throw( SickErrorException, SickTimeoutException, SickIOException ); + + /** Query the Sick for ID information */ + void _getIdentificationString( const uint8_t id_request_code, std::string &id_return_string ) + throw( SickTimeoutException, SickIOException ); + + /** Query the Sick for its sensor part number */ + void _getSensorPartNumber( ) throw( SickTimeoutException, SickIOException ); + + /** Query the Sick for its assigned name */ + void _getSensorName( ) throw( SickTimeoutException, SickIOException ); + + /** Query the Sick for its version number */ + void _getSensorVersion( ) throw( SickTimeoutException, SickIOException ); + + /** Query the Sick for its serial number */ + void _getSensorSerialNumber( ) throw( SickTimeoutException, SickIOException ); + + /** Query the Sick for its EDM unit's serial number */ + void _getSensorEDMSerialNumber( ) throw( SickTimeoutException, SickIOException ); + + /** Query the Sick for the part number of its firmware */ + void _getFirmwarePartNumber( ) throw( SickTimeoutException, SickIOException ); + + /** Query the Sick for the name of its firmware */ + void _getFirmwareName( ) throw( SickTimeoutException, SickIOException ); + + /** Query the Sick for the version of the firmware */ + void _getFirmwareVersion( ) throw( SickTimeoutException, SickIOException ); + + /** Query the part number of the application software */ + void _getApplicationSoftwarePartNumber( ) throw( SickTimeoutException, SickIOException ); + + /** Query the Sick for the application name */ + void _getApplicationSoftwareName( ) throw( SickTimeoutException, SickIOException ); + + /** Query the Sick for the application software version */ + void _getApplicationSoftwareVersion( ) throw( SickTimeoutException, SickIOException ); + + /** Allows setting the global parameters and scan area definition (in flash) */ + void _setSickGlobalParamsAndScanAreas( const unsigned int sick_motor_speed, const double sick_step_angle, + const double * const active_sector_start_angles, + const double * const active_sector_stop_angles, + const unsigned int num_active_sectors ) + throw( SickTimeoutException, SickIOException, SickConfigException, SickErrorException ); + + /** Allows setting a temporary (until a device reset) sector configuration on the device */ + void _setSickTemporaryScanAreas( const double * const active_sector_start_angles, + const double * const active_sector_stop_angles, + const unsigned int num_active_sectors ) + throw( SickTimeoutException, SickIOException, SickConfigException ); + + /** Sets the sick sector configuration */ + void _setSickSectorConfig( const unsigned int * const sector_functions, const double * const sector_stop_angles, + const unsigned int num_sectors, const bool write_to_flash = false ) + throw( SickErrorException, SickTimeoutException, SickIOException, SickConfigException ); + + /** Sets the signals for the device */ + void _setSickSignals( const uint8_t sick_signal_flags = DEFAULT_SICK_SIGNAL_SET ) + throw( SickIOException, SickTimeoutException, SickErrorException ); + + /** Send a message, get the reply from the Sick LD and check it */ + void _sendMessageAndGetReply( const SickLDMessage &send_message, SickLDMessage &recv_message, + const unsigned int timeout_value = DEFAULT_SICK_MESSAGE_TIMEOUT ) + throw( SickIOException, SickTimeoutException ); + + /** Flushed the TCP receive buffer */ + void _flushTCPRecvBuffer( ) throw ( SickIOException, SickThreadException ); + + /** Teardown the connection to the Sick LD */ + void _teardownConnection( ) throw( SickIOException ); + + /** Generates a device-ready sector set given only an active sector spec. */ + void _generateSickSectorConfig( const double * const active_sector_start_angles, + const double * const active_sector_stop_angles, + const unsigned int num_active_sectors, + const double sick_step_angle, + unsigned int * const sector_functions, + double * const sector_stop_angles, + unsigned int &num_sectors ) const; + + /** Converts odometry ticks to an equivalent angle */ + double _ticksToAngle( const uint16_t ticks ) const; + + /** Converts angle to an equivalent representation in odometer ticks */ + uint16_t _angleToTicks( const double angle ) const; + + /** Computes the mean pulse frequency for the given config */ + double _computeMeanPulseFrequency( const double active_scan_area, const double curr_motor_speed, + const double curr_angular_resolution ) const; + + /** Computes the total pulse frequency for the given config */ + double _computeMaxPulseFrequency( const double total_scan_area, const double curr_motor_speed, + const double curr_angular_resolution ) const; + + /** Indicates whether a given sensor ID is valid for the device */ + bool _validSickSensorID( const unsigned int sick_sensor_id ) const; + + /** Indicates whether a given motor speed is valid for the device */ + bool _validSickMotorSpeed( const unsigned int sick_motor_speed ) const; + + /** Indicates whether a given motor speed is valid for the device */ + bool _validSickScanResolution( const double sick_step_angle, const double * const active_sector_start_angles, + const double * const active_sector_stop_angles, const unsigned int num_active_sectors ) const; + + /** Indicates whether the given configuration yields a valid max and mean pulse frequency */ + bool _validPulseFrequency( const unsigned int sick_motor_speed, const double sick_step_angle ) const; + + /** Indicates whether the given configuration yields a valid max and mean pulse frequency */ + bool _validPulseFrequency( const unsigned int sick_motor_speed, const double sick_step_angle, + const double * const active_sector_start_angles, + const double * const active_sector_stop_angles, + const unsigned int num_active_sectors ) const; + + /** Returns the scanning area for the device given the current sector configuration */ + double _computeScanArea( const double sick_step_angle, const double * const sector_start_angles, + const double * const sector_stop_angles, const unsigned int num_sectors ) const; + + /** Reorders given sector angle sets */ + void _sortScanAreas( double * const sector_start_angles, double * const sector_stop_angles, + const unsigned int num_sectors ) const; + + /** Checks the given sector arguments for overlapping regions yielding an invalid configuration */ + bool _validActiveSectors( const double * const sector_start_angles, const double * const sector_stop_angles, + const unsigned int num_active_sectors ) const; + + /** Indicates whether the supplied profile format is currently supported by the driver */ + bool _supportedScanProfileFormat( const uint16_t profile_format ) const; + + /** Prints data corresponding to a single scan sector (data obtained using GET_PROFILE) */ + void _printSectorProfileData( const sick_ld_sector_data_t §or_data ) const; + + /** Prints the data corresponding to the given scan profile (for debugging purposes) */ + void _printSickScanProfile( const sick_ld_scan_profile_t profile_data, const bool print_sector_data = true ) const; + + /** Returns the corresponding work service subcode required to transition the Sick LD to the given sensor mode. */ + uint8_t _sickSensorModeToWorkServiceSubcode( const uint8_t sick_sensor_mode ) const; + + /** Converts _sick_sensor_mode to a representative string */ + std::string _sickSensorModeToString( const uint8_t sick_sensor_mode ) const; + + /** Converts _sick_motor_mode to a representative string */ + std::string _sickMotorModeToString( const uint8_t sick_motor_mode ) const; + + /** Converts the specified trans measurement mode return value to a string */ + std::string _sickTransMeasureReturnToString( const uint8_t return_value ) const; + + /** Converts the specified reset level to a representative string */ + std::string _sickResetLevelToString( const uint16_t reset_level ) const; + + /** Converts Sick LD sector configuration word to a representative string */ + std::string _sickSectorFunctionToString( const uint16_t sick_sector_function ) const; + + /** Converts a given scan profile format to a string for friendlier output */ + std::string _sickProfileFormatToString( const uint16_t profile_format ) const; + + /** Prints the initialization footer */ + void _printInitFooter( ) const; + + }; + +} //namespace SickToolbox + +#endif /* SICK_LD_HH */ diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLDBufferMonitor.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLDBufferMonitor.hh new file mode 100644 index 0000000..c86fdee --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLDBufferMonitor.hh @@ -0,0 +1,50 @@ +/*! + * \file SickLDBufferMonitor.hh + * \brief Defines a class for monitoring the receive + * buffer when interfacing w/ a Sick LMS LIDAR. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#ifndef SICK_LD_BUFFER_MONITOR_HH +#define SICK_LD_BUFFER_MONITOR_HH + +#define DEFAULT_SICK_BYTE_TIMEOUT (35000) ///< Max allowable time between consecutive bytes + +/* Definition dependencies */ +#include "SickLDMessage.hh" +#include "SickBufferMonitor.hh" +#include "SickException.hh" + +/* Associate the namespace */ +namespace SickToolbox { + + /*! + * \brief A class for monitoring the receive buffer when interfacing with a Sick LD LIDAR + */ + class SickLDBufferMonitor : public SickBufferMonitor< SickLDBufferMonitor, SickLDMessage > { + + public: + + /** A standard constructor */ + SickLDBufferMonitor( ); + + /** A method for extracting a single message from the stream */ + void GetNextMessageFromDataStream( SickLDMessage &sick_message ) throw( SickIOException ); + + /** A standard destructor */ + ~SickLDBufferMonitor( ); + + }; + +} /* namespace SickToolbox */ + +#endif /* SICK_LD_BUFFER_MONITOR_HH */ diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLDMessage.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLDMessage.hh new file mode 100644 index 0000000..43a482a --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLDMessage.hh @@ -0,0 +1,80 @@ +/*! + * \file SickLDMessage.hh + * \brief Defines the class SickLDMessage. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#ifndef SICK_LD_MESSAGE_HH +#define SICK_LD_MESSAGE_HH + +/* Definition dependencies */ +#include +#include +#include "SickMessage.hh" + +#define SICK_LD_MSG_HEADER_LEN (8) ///< Sick LD message header length in bytes +#define SICK_LD_MSG_PAYLOAD_MAX_LEN (5816) ///< Sick LD maximum payload length +#define SICK_LD_MSG_TRAILER_LEN (1) ///< Sick LD length of the message trailer + +/* Associate the namespace */ +namespace SickToolbox { + + /** + * \class SickLDMessage + * \brief A class to represent all messages sent to and from the Sick LD unit. + */ + class SickLDMessage : public SickMessage< SICK_LD_MSG_HEADER_LEN, SICK_LD_MSG_PAYLOAD_MAX_LEN, SICK_LD_MSG_TRAILER_LEN > { + + public: + + /** A standard constructor */ + SickLDMessage( ); + + /** Constructs a packet by using BuildMessage */ + SickLDMessage( const uint8_t * const payload_buffer, const unsigned int payload_length ); + + /** Constructs a packet using ParseMessage() */ + SickLDMessage( const uint8_t * const message_buffer ); + + /** Construct a well-formed raw packet */ + void BuildMessage( const uint8_t * const payload_buffer, const unsigned int payload_length ); + + /** Populates fields from a (well-formed) raw packet */ + void ParseMessage( const uint8_t * const message_buffer ); + + /** Get the length of the service code associated with the message */ + uint8_t GetServiceCode( ) const { return _message_buffer[8]; } + + /** Get the service sub-code associated with the message */ + uint8_t GetServiceSubcode( ) const { return _message_buffer[9]; } + + /** Get the checksum for the packet */ + uint8_t GetChecksum( ) const { return _message_buffer[_message_length-1]; } + + /** A debugging function that prints the contents of the frame. */ + void Print( ) const; + + /** Destructor */ + ~SickLDMessage( ); + + private: + + /** Computes the checksum of the frame. + * NOTE: Uses XOR of single bytes over packet payload data. + */ + uint8_t _computeXOR( const uint8_t * const data, const uint32_t length ); + + }; + +} /* namespace SickToolbox */ + +#endif /* SICK_LD_MESSAGE_HH */ diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLDUtility.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLDUtility.hh new file mode 100644 index 0000000..e971a1b --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLDUtility.hh @@ -0,0 +1,120 @@ +/*! + * \file SickLDUtility.hh + * \brief Defines simple utility functions for working with the Sick LD. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +/* Auto-generated header */ +#include "SickConfig.hh" + +/** + * \def REVERSE_BYTE_ORDER_16 + * \brief Reverses the byte order of the given 16 bit unsigned integer + */ +#define REVERSE_BYTE_ORDER_16( y ) ( ( ( y & 0x00FF ) << 8 ) | ( ( y & 0xFF00 ) >> 8 ) ) + +/** + * \def REVERSE_BYTE_ORDER_32 + * \brief Reverses the byte order of the given 32 bit unsigned integer + */ +#define REVERSE_BYTE_ORDER_32( y ) ( ( ( y & 0x000000FF ) << 24 ) | ( ( y & 0x0000FF00 ) << 8 ) | ( ( y & 0x00FF0000 ) >> 8 ) | ( ( y & 0xFF000000 ) >> 24 ) ) + +/* Associate the namespace */ +namespace SickToolbox { + +#ifndef WORDS_BIGENDIAN + +/* NOTE: The following functions are necessary since the Sick LD doesn't adopt the + * convention of converting from network byte order. + */ + +/** + * \brief Converts host byte order (little-endian) to Sick LD byte order (big-endian) + * \param value The 2-byte value to convert to big-endian + * \return Value in Sick LD byte order (big-endian) + */ +inline uint16_t host_to_sick_ld_byte_order( uint16_t value ) { + return REVERSE_BYTE_ORDER_16(value); +} + +/** + * \brief Converts host byte order (little-endian) to Sick LD byte order (big-endian) + * \param value The 4-byte value to convert to big-endian + * \return Value in Sick LD byte order (big-endian) + */ +inline uint32_t host_to_sick_ld_byte_order( uint32_t value ) { + return REVERSE_BYTE_ORDER_32(value); +} + +/** + * \brief Converts Sick LD byte order (big-endian) to host byte order (little-endian) + * \param value The 2-byte value to convert to little-endian + * \return Value in host byte order (little-endian) + */ +inline uint16_t sick_ld_to_host_byte_order( uint16_t value ) { + return REVERSE_BYTE_ORDER_16(value); +} + +/** + * \brief Converts Sick LD byte order (big-endian) to host byte order (little-endian) + * \param value The 4-byte value to convert to little-endian + * \return Value in host byte order (little-endian) + */ +inline uint32_t sick_ld_to_host_byte_order( uint32_t value ) { + return REVERSE_BYTE_ORDER_32(value); +} + +#else // The host has a big-endian architecture + +/** + * \brief Converts host byte order (big-endian) to Sick LD byte order (big-endian) + * \param value The 2-byte value to convert to big-endian + * \return Value in Sick LD byte order (big-endian) + */ +inline uint16_t host_to_sick_ld_byte_order( uint16_t value ) { + return value; +} + +/** + * \brief Converts host byte order (big-endian) to Sick LD byte order (big-endian) + * \param value The 4-byte value to convert to big-endian + * \return Value in Sick LD byte order (big-endian) + */ +inline uint32_t host_to_sick_ld_byte_order( uint32_t value ) { + return value; +} + +/** + * \brief Converts Sick LD byte order (big-endian) to host byte order (big-endian) + * \param value The 2-byte value to convert to big-endian + * \return Value in host byte order (big-endian) + */ +inline uint16_t sick_ld_to_host_byte_order( uint16_t value ) { + return value; +} + +/** + * \brief Converts Sick LD byte order (big-endian) to host byte order (big-endian) + * \param value The 4-byte value to convert to big-endian + * \return Value in host byte order (big-endian) + */ +inline uint32_t sick_ld_to_host_byte_order( uint32_t value ) { + return value; +} + +#endif /* _LITTLE_ENDIAN_HOST */ + +/* + * NOTE: Other utility functions can be defined here + */ + +} //namespace SickToolbox diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLIDAR.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLIDAR.hh new file mode 100644 index 0000000..b21a2a5 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLIDAR.hh @@ -0,0 +1,452 @@ +/*! + * \file SickLIDAR.hh + * \brief Defines the abstract parent class for defining + * a Sick LIDAR device driver. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +/** + * \mainpage The Sick LIDAR Matlab/C++ Toolbox + * \author Jason C. Derenick and Thomas H. Miller. + * \version 1.0 + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#ifndef SICK_LIDAR +#define SICK_LIDAR + +/* Definition dependencies */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "SickException.hh" + +/* Associate the namespace */ +namespace SickToolbox { + + /** + * \class SickLIDAR + * \brief Provides an abstract parent for all Sick LIDAR devices + */ + template < class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + class SickLIDAR { + + public: + + /** The primary constructor */ + SickLIDAR( ); + + /** Indicates whether device is initialized */ + bool IsInitialized() { return _sick_initialized; } + + /** A virtual destructor */ + virtual ~SickLIDAR( ); + + protected: + + /** Sick device file descriptor */ + int _sick_fd; + + /** A flag to indicated whether the device is properly initialized */ + bool _sick_initialized; + + /** A pointer to the driver's buffer monitor */ + SICK_MONITOR_CLASS *_sick_buffer_monitor; + + /** Indicates whether the Sick buffer monitor is running */ + bool _sick_monitor_running; + + /** A method for setting up a general connection */ + virtual void _setupConnection( ) = 0; + + /** A method for tearing down a connection to the Sick */ + virtual void _teardownConnection( ) = 0; + + /** Starts the driver listening for messages */ + void _startListening( ) throw( SickThreadException ); + + /** Stops the driver from listening */ + void _stopListening( ) throw( SickThreadException ); + + /** Indicates whether there is a monitor currently running */ + bool _monitorRunning( ) const { return _sick_monitor_running; } + + /** Make the associated file descriptor non blocking */ + void _setBlockingIO( ) const throw ( SickIOException ); + + /** Make the associated file descriptor non blocking */ + void _setNonBlockingIO( ) const throw ( SickIOException ); + + /** Send a message to the Sick LD (allows specifying min time between transmitted bytes) */ + void _sendMessage( const SICK_MSG_CLASS &sick_message, const unsigned int byte_interval ) const + throw( SickIOException ); + + /** Acquire the next message from the message container */ + void _recvMessage( SICK_MSG_CLASS &sick_message, const unsigned int timeout_value ) const throw ( SickTimeoutException ); + + /** Search the stream for a payload with a particular "header" byte string */ + void _recvMessage( SICK_MSG_CLASS &sick_message, + const uint8_t * const byte_sequence, + const unsigned int byte_sequence_length, + const unsigned int timeout_value ) const throw ( SickTimeoutException ); + + /** An inline function for computing elapsed time */ + double _computeElapsedTime( const struct timeval &beg_time, const struct timeval &end_time ) const { return ((end_time.tv_sec*1e6)+(end_time.tv_usec))-((beg_time.tv_sec*1e6)+beg_time.tv_usec); } + + /** Sends a request to the Sick and acquires looks for the reply */ + virtual void _sendMessageAndGetReply( const SICK_MSG_CLASS &send_message, + SICK_MSG_CLASS &recv_message, + const uint8_t * const byte_sequence, + const unsigned int byte_sequence_length, + const unsigned int byte_interval, + const unsigned int timeout_value, + const unsigned int num_tries ) throw( SickTimeoutException, SickIOException); + + }; + + /** + * \brief Initializes the buffer monitor + */ + template< class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + SickLIDAR< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::SickLIDAR( ) : + _sick_fd(0), _sick_initialized(false), _sick_buffer_monitor(NULL), _sick_monitor_running(false) { + + try { + /* Attempt to instantiate a new SickBufferMonitor for the device */ + _sick_buffer_monitor = new SICK_MONITOR_CLASS; + } + catch ( std::bad_alloc &allocation_exception ) { + std::cerr << "SickLIDAR::SickLIDAR: Allocation error - " << allocation_exception.what() << std::endl; + } + + } + + /** + * \brief Destructor tears down buffer monitor + */ + template< class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + SickLIDAR< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::~SickLIDAR( ) { + + /* Deallocate the buffer monitor */ + if (_sick_buffer_monitor) { + delete _sick_buffer_monitor; + } + + } + + /** + * \brief Activates the buffer monitor for the driver + */ + template< class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickLIDAR< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_startListening( ) throw( SickThreadException ) { + + /* Try to start the monitor */ + try { + _sick_buffer_monitor->StartMonitor(_sick_fd); + } + + /* Handle a thread exception */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle a thread exception */ + catch(...) { + std::cerr << "SickLIDAR::_startListening: Unknown exception!!!" << std::endl; + throw; + } + + /* Set the flag */ + _sick_monitor_running = true; + + } + + /** + * \brief Activates the buffer monitor for the driver + */ + template< class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickLIDAR< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_stopListening( ) throw( SickThreadException ) { + + /* Try to start the monitor */ + try { + _sick_buffer_monitor->StopMonitor(); + } + + /* Handle a thread exception */ + catch(SickThreadException &sick_thread_exception) { + std::cerr << sick_thread_exception.what() << std::endl; + throw; + } + + /* Handle a thread exception */ + catch(...) { + std::cerr << "SickLIDAR::_stopListening: Unknown exception!!!" << std::endl; + throw; + } + + /* Reset the flag */ + _sick_monitor_running = false; + + } + + /** + * \brief A simple method for setting blocking I/O + */ + template< class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickLIDAR< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_setBlockingIO( ) const throw( SickIOException ) { + + /* Read the flags */ + int fd_flags = 0; + if((fd_flags = fcntl(_sick_fd,F_GETFL)) < 0) { + throw SickIOException("SickLIDAR::_setNonBlocking: fcntl failed!"); + } + + /* Set the new flags */ + if(fcntl(_sick_fd,F_SETFL,fd_flags & (~O_NONBLOCK)) < 0) { + throw SickIOException("SickLIDAR::_setNonBlocking: fcntl failed!"); + } + + } + + /** + * \brief A simple method for setting non-blocking I/O + */ + template< class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickLIDAR< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_setNonBlockingIO( ) const throw ( SickIOException ) { + + /* Read the flags */ + int fd_flags = 0; + if((fd_flags = fcntl(_sick_fd,F_GETFL)) < 0) { + throw SickIOException("SickLIDAR::_setNonBlockingIO: fcntl failed!"); + } + + /* Set the new flags */ + if(fcntl(_sick_fd,F_SETFL,fd_flags | O_NONBLOCK) < 0) { + throw SickIOException("SickLIDAR::_setNonBlockingIO: fcntl failed!"); + } + + } + + /** + * \brief Sends a message to the Sick device + * \param &sick_message A reference to the well-formed message that is to be sent to the Sick + * \param byte_interval Minimum time in microseconds between transmitted bytes + */ + template< class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickLIDAR< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_sendMessage( const SICK_MSG_CLASS &sick_message, const unsigned int byte_interval ) const + throw( SickIOException ) { + + uint8_t message_buffer[SICK_MSG_CLASS::MESSAGE_MAX_LENGTH] = {0}; + + /* Copy the given message and get the message length */ + sick_message.GetMessage(message_buffer); + unsigned int message_length = sick_message.GetMessageLength(); + + /* Check whether a transmission delay between bytes is requested */ + if (byte_interval == 0) { + + /* Write the message to the stream */ + if ((unsigned int)write(_sick_fd,message_buffer,message_length) != message_length) { + throw SickIOException("SickLIDAR::_sendMessage: write() failed!"); + } + + } + else { + + /* Write the message to the unit one byte at a time */ + for (unsigned int i = 0; i < message_length; i++) { + + /* Write a single byte to the stream */ + if (write(_sick_fd,&message_buffer[i],1) != 1) { + throw SickIOException("SickLIDAR::_sendMessage: write() failed!"); + } + + /* Some time between bytes (Sick LMS 2xx likes this) */ + usleep(byte_interval); + } + + } + + } + + /** + * \brief Attempt to acquire the latest available message from the device + * \param &sick_message A reference to the container that will hold the most recent message + * \param timeout_value The time in secs to wait before throwing a timeout error + * \return True if a new message was received, False otherwise + */ + template< class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickLIDAR< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_recvMessage( SICK_MSG_CLASS &sick_message, + const unsigned int timeout_value ) const throw ( SickTimeoutException ) { + + /* Timeval structs for handling timeouts */ + struct timeval beg_time, end_time; + + /* Acquire the elapsed time since epoch */ + gettimeofday(&beg_time,NULL); + + /* Check the shared object */ + while(!_sick_buffer_monitor->GetNextMessageFromMonitor(sick_message)) { + + /* Sleep a little bit */ + usleep(1000); + + /* Check whether the allowed time has expired */ + gettimeofday(&end_time,NULL); + if (_computeElapsedTime(beg_time,end_time) > timeout_value) { + throw SickTimeoutException("SickLIDAR::_recvMessage: Timeout occurred!"); + } + + } + + } + + /** + * \brief Attempt to acquire a message having a payload beginning w/ the given byte sequence + * \param &sick_message A reference to the container that will hold the most recent message + * \param *byte_sequence The byte sequence that is expected to lead off the payload in the packet (e.g. service codes, etc...) + * \param byte_sequence_length The number of bytes in the given byte_sequence + * \param timeout_value The time in usecs to wait before throwing a timeout error + * \return True if a new message was received, False otherwise + * + * NOTE: This method is intended to be a helper for _sendMessageAndGetReply + */ + template< class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickLIDAR< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_recvMessage( SICK_MSG_CLASS &sick_message, + const uint8_t * const byte_sequence, + const unsigned int byte_sequence_length, + const unsigned int timeout_value ) const throw( SickTimeoutException ) { + + /* Define a buffer */ + uint8_t payload_buffer[SICK_MSG_CLASS::MESSAGE_PAYLOAD_MAX_LENGTH]; + + /* Timeval structs for handling timeouts */ + struct timeval beg_time, end_time; + + /* A container for the message */ + SICK_MSG_CLASS curr_message; + + /* Get the elapsed time since epoch */ + gettimeofday(&beg_time,NULL); + + /* Check until it is found or a timeout */ + for(;;) { + + /* Attempt to acquire the message */ + unsigned int i = 0; + if (_sick_buffer_monitor->GetNextMessageFromMonitor(curr_message)) { + + /* Extract the payload subregion */ + curr_message.GetPayloadSubregion(payload_buffer,0,byte_sequence_length-1); + + /* Match the byte sequence */ + for (i=0; (i < byte_sequence_length) && (payload_buffer[i] == byte_sequence[i]); i++); + + /* Our message was found! */ + if (i == byte_sequence_length) { + sick_message = curr_message; + break; + } + + } + + /* Sleep a little bit */ + usleep(1000); + + /* Check whether the allowed time has expired */ + gettimeofday(&end_time,NULL); + if (_computeElapsedTime(beg_time,end_time) > timeout_value) { + throw SickTimeoutException(); + } + + } + + } + + /** + * \param sick_send_frame A sick frame to be sent to the LMS + * \param sick_receive_frame A sick frame to hold the response (expected or unexpected) of the LMS + * \param num_tries The number of times to send the frame in the event the LMS fails to reply + * \param timeout The epoch to wait before considering a sent frame lost + * \return True if the message was sent and the expected reply was received + */ + template< class SICK_MONITOR_CLASS, class SICK_MSG_CLASS > + void SickLIDAR< SICK_MONITOR_CLASS, SICK_MSG_CLASS >::_sendMessageAndGetReply( const SICK_MSG_CLASS &send_message, + SICK_MSG_CLASS &recv_message, + const uint8_t * const byte_sequence, + const unsigned int byte_sequence_length, + const unsigned int byte_interval, + const unsigned int timeout_value, + const unsigned int num_tries ) + throw( SickTimeoutException, SickIOException ) { + + /* Send the message for at most num_tries number of times */ + for(unsigned int i = 0; i < num_tries; i++) { + + try { + + /* Send the frame to the unit */ + _sendMessage(send_message,byte_interval); + + /* Wait for the reply! */ + _recvMessage(recv_message,byte_sequence,byte_sequence_length,timeout_value); + + /* message was found! */ + break; + + } + + /* Handle a timeout! */ + catch (SickTimeoutException &sick_timeout) { + + /* Check if it was found! */ + if (i == num_tries - 1) { + throw SickTimeoutException("SickLIDAR::_sendMessageAndGetReply: Attempted max number of tries w/o success!"); + } + + /* Display the number of tries remaining! */ + std::cerr << sick_timeout.what() << " " << num_tries - i - 1 << " tries remaining" << std::endl; + + } + + /* Handle write buffer exceptions */ + catch (SickIOException &sick_io_error) { + std::cerr << sick_io_error.what() << std::endl; + throw; + } + + /* A safety net */ + catch (...) { + std::cerr << "SickLIDAR::_sendMessageAndGetReply: Unknown exception!!!" << std::endl; + throw; + } + + } + + } + +} /* namespace SickToolbox */ + +#endif /* SICK_LIDAR */ diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xx.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xx.hh new file mode 100644 index 0000000..0af0d16 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xx.hh @@ -0,0 +1,335 @@ +/*! + * \file SickLMS1xx.hh + * \brief Defines the SickLMS1xx class for working with the + * Sick LMS1xx laser range finders. + * + * Code by Jason C. Derenick and Christopher R. Mansley. + * Contact jasonder(at)seas(dot)upenn(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#ifndef SICK_LMS_1XX_HH +#define SICK_LMS_1XX_HH + +/* Macros */ +#define DEFAULT_SICK_LMS_1XX_IP_ADDRESS "192.168.0.1" ///< Default IP Address +#define DEFAULT_SICK_LMS_1XX_TCP_PORT (2111) ///< Sick LMS 1xx TCP/IP Port +#define DEFAULT_SICK_LMS_1XX_CONNECT_TIMEOUT (1000000) ///< Max time for establishing connection (usecs) +#define DEFAULT_SICK_LMS_1XX_MESSAGE_TIMEOUT (5000000) ///< Max time for reply (usecs) +#define DEFAULT_SICK_LMS_1XX_STATUS_TIMEOUT (60000000) ///< Max time it should take to change status + +#define SICK_LMS_1XX_SCAN_AREA_MIN_ANGLE (-450000) ///< -45 degrees (1/10000) degree +#define SICK_LMS_1XX_SCAN_AREA_MAX_ANGLE (2250000) ///< 225 degrees (1/10000) degree + +/* Definition dependencies */ +#include +#include + +#include "SickLIDAR.hh" +#include "SickLMS1xxBufferMonitor.hh" +#include "SickLMS1xxMessage.hh" +#include "SickException.hh" + +/** + * \namespace SickToolbox + * \brief Encapsulates the Sick LIDAR Matlab/C++ toolbox + */ +namespace SickToolbox { + + /** + * \class SickLMS1xx + * \brief Provides a simple driver interface for working with the + * Sick LD-OEM/Sick LD-LRS long-range models via Ethernet. + */ + class SickLMS1xx : public SickLIDAR< SickLMS1xxBufferMonitor, SickLMS1xxMessage > { + + public: + + static const int SICK_LMS_1XX_MAX_NUM_MEASUREMENTS = 1082; ///< LMS 1xx max number of measurements + + /*! + * \enum sick_lms_1xx_status_t + * \brief Defines the Sick LMS 1xx status. + * This enum lists all of the Sick LMS 1xx status. + */ + enum sick_lms_1xx_status_t { + + SICK_LMS_1XX_STATUS_UNKNOWN = 0x00, ///< LMS 1xx status undefined + SICK_LMS_1XX_STATUS_INITIALIZATION = 0x01, ///< LMS 1xx initializing + SICK_LMS_1XX_STATUS_CONFIGURATION = 0x02, ///< LMS 1xx configuration + SICK_LMS_1XX_STATUS_IDLE = 0x03, ///< LMS 1xx is idle + SICK_LMS_1XX_STATUS_ROTATED = 0x04, ///< LMS 1xx mirror rotating + SICK_LMS_1XX_STATUS_IN_PREP = 0x05, ///< LMS 1xx in preparation + SICK_LMS_1XX_STATUS_READY = 0x06, ///< LMS 1xx is ready + SICK_LMS_1XX_STATUS_READY_FOR_MEASUREMENT = 0x07 ///< LMS 1xx is ready to give measurements + + }; + + /*! + * \enum sick_lms_1xx_scan_format_t + * \brief Defines the Sick LMS 1xx scan types + * This enum is for specifiying the desired scan returns. + */ + enum sick_lms_1xx_scan_format_t { + + SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_NONE = 0x00, ///< Single-pulse dist, no reflect + SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_8BIT = 0x01, ///< Single-pulse dist, 8bit reflect + SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_16BIT = 0x02, ///< Single-pulse dist, 16bit reflect + SICK_LMS_1XX_SCAN_FORMAT_DIST_DOUBLE_PULSE_REFLECT_NONE = 0x03, ///< Double-pulse dist, no reflect + SICK_LMS_1XX_SCAN_FORMAT_DIST_DOUBLE_PULSE_REFLECT_8BIT = 0x04, ///< Double-pulse dist, 8bit reflect + SICK_LMS_1XX_SCAN_FORMAT_DIST_DOUBLE_PULSE_REFLECT_16BIT = 0x05, ///< Double-pulse dist, 16bit reflect + SICK_LMS_1XX_SCAN_FORMAT_UNKNOWN = 0xFF ///< Unknown format + + }; + + /*! + * \enum sick_lms_1xx_scan_freq_t + * \brief Defines the Sick LMS 1xx scan frequency. + * This enum lists all of the Sick LMS 1xx scan frequencies. + */ + enum sick_lms_1xx_scan_freq_t { + + SICK_LMS_1XX_SCAN_FREQ_UNKNOWN = 0x00, ///< LMS 1xx scan freq unknown + SICK_LMS_1XX_SCAN_FREQ_25 = 0x09C4, ///< LMS 1xx scan freq 25Hz + SICK_LMS_1XX_SCAN_FREQ_50 = 0X1388 ///< LMS 1xx scan freq 50Hz + + }; + + /*! + * \enum sick_lms_1xx_scan_res_t + * \brief Defines the Sick LMS 1xx scan resolution. + * This enum lists all of the Sick LMS 1xx scan resolutions. + */ + enum sick_lms_1xx_scan_res_t { + + SICK_LMS_1XX_SCAN_RES_UNKNOWN = 0x00, ///< LMS 1xx scab res unknown + SICK_LMS_1XX_SCAN_RES_25 = 0x09C4, ///< LMS 1xx scan res 0.25 deg + SICK_LMS_1XX_SCAN_RES_50 = 0x1388 ///< LMS 1xx scan res 0.50 deg + + }; + + /** Primary constructor */ + SickLMS1xx( const std::string sick_ip_address = DEFAULT_SICK_LMS_1XX_IP_ADDRESS, + const uint16_t sick_tcp_port = DEFAULT_SICK_LMS_1XX_TCP_PORT ); + + /** Initializes the Sick LD unit (use scan areas defined in flash) */ + void Initialize( const bool disp_banner = true ) throw( SickIOException, SickThreadException, SickTimeoutException, SickErrorException ); + + /** Sets the Sick LMS 1xx scan frequency and scan resolution */ + void SetSickScanFreqAndRes( const sick_lms_1xx_scan_freq_t scan_freq, + const sick_lms_1xx_scan_res_t scan_res ) throw( SickTimeoutException, SickIOException, SickErrorException ); + + /** Get the Sick LMS 1xx scan frequency */ + sick_lms_1xx_scan_freq_t GetSickScanFreq( ) const throw ( SickIOException ); + + /** Get the Sick LMS 1xx scan resolution */ + sick_lms_1xx_scan_res_t GetSickScanRes( ) const throw ( SickIOException ); + + /** Get the Sick LMS 1xx scan start angle */ + double GetSickStartAngle( ) const throw ( SickIOException ); + + /** Get the Sick LMS 1xx scan stop angle */ + double GetSickStopAngle( ) const throw ( SickIOException ); + + /** Sets the sick scan data format */ + void SetSickScanDataFormat( const sick_lms_1xx_scan_format_t scan_format ) throw( SickTimeoutException, SickIOException, SickThreadException, SickErrorException ); + + /** Get the Sick Range Measurements */ + void GetSickMeasurements( unsigned int * const range_1_vals, + unsigned int * const range_2_vals, + unsigned int * const reflect_1_vals, + unsigned int * const reflect_2_vals, + unsigned int & num_measurements, + unsigned int * const dev_status = NULL ) throw ( SickIOException, SickConfigException, SickTimeoutException ); + + /** Uninitializes the Sick LD unit */ + void Uninitialize( const bool disp_banner = true ) throw( SickIOException, SickTimeoutException, SickErrorException, SickThreadException ); + + /** Utility function for converting integer to scan frequency */ + sick_lms_1xx_scan_freq_t IntToSickScanFreq( const int scan_freq ) const; + + /** Utility function for converting scan frequency to integer */ + int SickScanFreqToInt( const sick_lms_1xx_scan_freq_t scan_freq ) const; + + /** Utility function for converting double to scan resolution */ + sick_lms_1xx_scan_res_t DoubleToSickScanRes( const double scan_res ) const; + + /** Utility function for converting scan resolution to double */ + double SickScanResToDouble( const sick_lms_1xx_scan_res_t scan_res ) const; + + /** Destructor */ + ~SickLMS1xx(); + + private: + + /*! + * \struct sick_lms_1xx_scan_config_tag + * \brief A structure for aggregrating the + * Sick LMS 1xx configuration params. + */ + /*! + * \typedef sick_lms_1xx_scan_config_t + * \brief Adopt c-style convention + */ + typedef struct sick_lms_1xx_scan_config_tag { + sick_lms_1xx_scan_freq_t sick_scan_freq; ///< Sick scan frequency + sick_lms_1xx_scan_res_t sick_scan_res; ///< Sick scan resolution + int32_t sick_start_angle; ///< Sick scan area start angle + int32_t sick_stop_angle; ///< Sick scan area stop angle + } sick_lms_1xx_scan_config_t; + + /** The Sick LMS 1xx IP address */ + std::string _sick_ip_address; + + /** The Sick LMS 1xx TCP port number */ + uint16_t _sick_tcp_port; + + /** Sick LMS 1xx socket address struct */ + struct sockaddr_in _sick_inet_address_info; + + /** Sick LMS 1xx configuration struct */ + sick_lms_1xx_scan_config_t _sick_scan_config; + + /** Sick LMS 1xx current scan data format */ + sick_lms_1xx_scan_format_t _sick_scan_format; + + /** Sick LMS 1xx configuration struct */ + sick_lms_1xx_status_t _sick_device_status; + + /** Sick LMS 1xx temperature status */ + bool _sick_temp_safe; + + /** Sick LMS 1xx streaming status */ + bool _sick_streaming; + + /** Setup the connection parameters and establish TCP connection! */ + void _setupConnection( ) throw( SickIOException, SickTimeoutException ); + + /** Re-initialized the device */ + void _reinitialize( ) throw( SickIOException, SickThreadException, SickTimeoutException, SickErrorException ); + + /** Teardown the connection to the Sick LD */ + void _teardownConnection( ) throw( SickIOException ); + + /** Acquire the latest Sick LMS's status */ + void _updateSickStatus( ) throw( SickTimeoutException, SickIOException ); + + /** Acquire the Sick LMS's scan config */ + void _getSickScanConfig( ) throw( SickTimeoutException, SickIOException ); + + /** Sets the scan configuration (volatile, does not write to EEPROM) */ + void _setSickScanConfig( const sick_lms_1xx_scan_freq_t scan_freq, + const sick_lms_1xx_scan_res_t scan_res, + const int start_angle, const int stop_angle ) throw( SickTimeoutException, SickIOException, SickErrorException ); + + /** Set access mode for configuring device */ + void _setAuthorizedClientAccessMode( ) throw( SickTimeoutException, SickErrorException, SickIOException ); + + /** Save configuration parameters to EEPROM */ + void _writeToEEPROM( ) throw( SickTimeoutException, SickIOException ); + + /** Send the message w/o waiting for a reply */ + void _sendMessage( const SickLMS1xxMessage &send_message ) const throw ( SickIOException ); + + /** Send the message and grab expected reply */ + void _sendMessageAndGetReply( const SickLMS1xxMessage &send_message, + SickLMS1xxMessage &recv_message, + const std::string reply_command_code, + const std::string reply_command, + const unsigned int timeout_value = DEFAULT_SICK_LMS_1XX_MESSAGE_TIMEOUT, + const unsigned int num_tries = 1 ) throw( SickIOException, SickTimeoutException ); + + /** Receive a message */ + void _recvMessage( SickLMS1xxMessage &sick_message ) const throw ( SickTimeoutException ); + + /** Start device measuring */ + void _startMeasuring( ) throw ( SickTimeoutException, SickIOException ); + + /** Stop device measuring */ + void _stopMeasuring( ) throw ( SickTimeoutException, SickIOException ); + + /** Request a data data stream type */ + void _requestDataStream( ) throw ( SickTimeoutException, SickConfigException, SickIOException ); + + /** Start streaming measurements */ + void _startStreamingMeasurements( )throw( SickTimeoutException, SickIOException ); + + /** Stop streaming measurements */ + void _stopStreamingMeasurements( const bool disp_banner = true ) throw( SickTimeoutException, SickIOException ); + + /** Set device to measuring mode */ + void _checkForMeasuringStatus( unsigned int timeout_value = DEFAULT_SICK_LMS_1XX_STATUS_TIMEOUT ) throw( SickTimeoutException, SickIOException ); + + /** Sets the sick scan data format */ + void _setSickScanDataFormat( const sick_lms_1xx_scan_format_t scan_format ) throw( SickTimeoutException, SickIOException, SickThreadException, SickErrorException ); + + /** Restore device to measuring mode */ + void _restoreMeasuringMode( ) throw( SickTimeoutException, SickIOException ); + + /** Ensures a feasible scan area */ + bool _validScanArea( const int start_angle, const int stop_angle ) const; + + /** Utility function to convert int to status */ + sick_lms_1xx_status_t _intToSickStatus( const int status ) const; + + /** Utility function for printing Sick scan config */ + void _printSickScanConfig( ) const; + + /** Utility function for printing footer after initialization */ + void _printInitFooter( ) const; + + /** Utility function for returning scan format as string */ + std::string _sickScanDataFormatToString( const sick_lms_1xx_scan_format_t scan_format ) const; + + /** Utility function for converting sick freq to doubles */ + double _convertSickAngleUnitsToDegs( const int sick_angle ) const { return ((double)sick_angle)/10000; } + + /** Utility function for converting sick Hz values ints */ + unsigned int _convertSickFreqUnitsToHz( const unsigned int sick_freq ) const { return (unsigned int)(((double)sick_freq)/100); } + + /** Utility function to convert config error int to str */ + std::string _intToSickConfigErrorStr( const int error ) const; + + /** Utility function to locate substring in string */ + bool _findSubString( const char * const str, const char * const substr, const unsigned int str_length, const unsigned int substr_length, + unsigned int &substr_pos, unsigned int start_pos = 0 ) const; + + /** Utility function for extracting next integer from tokenized string */ + char * _convertNextTokenToUInt( char * const str_buffer, unsigned int & num_val, const char * const delimeter = " " ) const; + + }; + + /*! + * \typedef sick_lms_1xx_status_t + * \brief Makes working w/ SickLMS1xx::sick_lms_1xx_status_t a bit easier + */ + typedef SickLMS1xx::sick_lms_1xx_status_t sick_lms_1xx_status_t; + + /*! + * \typedef sick_lms_1xx_scan_format_t + * \brief Makes working w/ SickLMS1xx::sick_lms_1xx_scan_format_t a bit easier + */ + typedef SickLMS1xx::sick_lms_1xx_scan_format_t sick_lms_1xx_scan_format_t; + + /*! + * \typedef sick_lms_1xx_scan_freq_t + * \brief Makes working w/ SickLMS1xx::sick_lms_1xx_scan_freq_t a bit easier + */ + typedef SickLMS1xx::sick_lms_1xx_scan_freq_t sick_lms_1xx_scan_freq_t; + + /*! + * \typedef sick_lms_1xx_scan_res_t + * \brief Makes working w/ SickLMS1xx::sick_lms_1xx_scan_res_t a bit easier + */ + typedef SickLMS1xx::sick_lms_1xx_scan_res_t sick_lms_1xx_scan_res_t; + + +} //namespace SickToolbox + +#endif /* SICK_LMS_1XX_HH */ diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xxBufferMonitor.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xxBufferMonitor.hh new file mode 100644 index 0000000..cd52857 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xxBufferMonitor.hh @@ -0,0 +1,56 @@ +/*! + * \file SickLMS1xxBufferMonitor.hh + * \brief Defines a class for monitoring the receive + * buffer when interfacing w/ a Sick LMS 1xx + * laser range finder unit. + * + * Code by Jason C. Derenick and Christopher R. Mansley. + * Contact jasonder(at)seas(dot)upenn(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2009, Jason C. Derenick and Christopher R. Mansley + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#ifndef SICK_LMS_1XX_BUFFER_MONITOR_HH +#define SICK_LMS_1XX_BUFFER_MONITOR_HH + +#define DEFAULT_SICK_LMS_1XX_BYTE_TIMEOUT (100000) ///< Max allowable time between consecutive bytes + +/* Definition dependencies */ +#include "SickLMS1xxMessage.hh" +#include "SickBufferMonitor.hh" +#include "SickException.hh" + +/* Associate the namespace */ +namespace SickToolbox { + + /*! + * \brief A class for monitoring the receive buffer when interfacing with a Sick LD LIDAR + */ + class SickLMS1xxBufferMonitor : public SickBufferMonitor< SickLMS1xxBufferMonitor, SickLMS1xxMessage > { + + public: + + /** A standard constructor */ + SickLMS1xxBufferMonitor( ); + + /** A method for extracting a single message from the stream */ + void GetNextMessageFromDataStream( SickLMS1xxMessage &sick_message ) throw( SickIOException ); + + /** A standard destructor */ + ~SickLMS1xxBufferMonitor( ); + + private: + + /* A utility function for flushing the receive buffer */ + void _flushTCPRecvBuffer( ) const throw ( SickIOException ); + + }; + +} /* namespace SickToolbox */ + +#endif /* SICK_LMS_1XX_BUFFER_MONITOR_HH */ diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xxMessage.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xxMessage.hh new file mode 100644 index 0000000..c8ae6f9 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xxMessage.hh @@ -0,0 +1,83 @@ +/*! + * \file SickLMS1xx Message.hh + * \brief Defines the class SickLMS1xxMessage. + * + * Code by Jason C. Derenick and Christopher R. Mansley. + * Contact jasonder(at)seas(dot)upenn(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2009, Jason C. Derenick and Christoper R. Mansley + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#ifndef SICK_LMS_1XX_MESSAGE_HH +#define SICK_LMS_1XX_MESSAGE_HH + +/* Macros */ +#define SICK_LMS_1XX_MSG_HEADER_LEN (1) ///< Sick LMS 1xx message header length in bytes +#define SICK_LMS_1XX_MSG_PAYLOAD_MAX_LEN (30000) ///< Sick LMS 1xx maximum payload length +#define SICK_LMS_1XX_MSG_TRAILER_LEN (1) ///< Sick LMS 1xx length of the message trailer + +/* Definition dependencies */ +#include +#include +#include "SickMessage.hh" +#include "SickException.hh" + +/* Associate the namespace */ +namespace SickToolbox { + + /** + * \class SickLMS1xxMessage + * \brief A class to represent all messages sent to and from the Sick LMS 1xx unit. + */ + class SickLMS1xxMessage : public SickMessage< SICK_LMS_1XX_MSG_HEADER_LEN, SICK_LMS_1XX_MSG_PAYLOAD_MAX_LEN, SICK_LMS_1XX_MSG_TRAILER_LEN > { + + public: + + /** A standard constructor */ + SickLMS1xxMessage( ); + + /** Constructs a packet by using BuildMessage */ + SickLMS1xxMessage( const uint8_t * const payload_buffer, const unsigned int payload_length ); + + /** Constructs a packet using ParseMessage() */ + SickLMS1xxMessage( const uint8_t * const message_buffer ); + + /** Construct a well-formed raw packet */ + void BuildMessage( const uint8_t * const payload_buffer, const unsigned int payload_length ); + + /** Populates fields from a (well-formed) raw packet */ + void ParseMessage( const uint8_t * const message_buffer ) throw ( SickIOException ); + + /** Get the length of the service code associated with the message */ + std::string GetCommandType( ) const { return _command_type; } + + /** Get the service sub-code associated with the message */ + std::string GetCommand( ) const { return _command; } + + /** Reset the data associated with this message (for initialization purposes) */ + void Clear( ); + + /** A debugging function that prints the contents of the frame. */ + void Print( ) const; + + /** Destructor */ + ~SickLMS1xxMessage( ); + + private: + + /** Command type associated w/ message */ + std::string _command_type; + + /** Command associated w/ message */ + std::string _command; + + }; + +} /* namespace SickToolbox */ + +#endif /* SICK_LMS_1XX_MESSAGE_HH */ diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xxUtility.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xxUtility.hh new file mode 100644 index 0000000..250506c --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS1xxUtility.hh @@ -0,0 +1,137 @@ +/*! + * \file SickLMS1xxUtility.hh + * \brief Defines simple utility functions for working with the + * Sick LMS 1xx laser range finder units. + * + * Code by Jason C. Derenick and Christopher R. Mansley. + * Contact jasonder(at)seas(dot)upenn(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2009, Jason C. Derenick and Christopher R. Mansley + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +/* Auto-generated header */ +#include "SickConfig.hh" + +/* Implementation Dependencies */ +#include + +/** + * \def REVERSE_BYTE_ORDER_16 + * \brief Reverses the byte order of the given 16 bit unsigned integer + */ +#define REVERSE_BYTE_ORDER_16( y ) ( ( ( y & 0x00FF ) << 8 ) | ( ( y & 0xFF00 ) >> 8 ) ) + +/** + * \def REVERSE_BYTE_ORDER_32 + * \brief Reverses the byte order of the given 32 bit unsigned integer + */ +#define REVERSE_BYTE_ORDER_32( y ) ( ( ( y & 0x000000FF ) << 24 ) | ( ( y & 0x0000FF00 ) << 8 ) | ( ( y & 0x00FF0000 ) >> 8 ) | ( ( y & 0xFF000000 ) >> 24 ) ) + +/* Associate the namespace */ +namespace SickToolbox { + +#ifndef WORDS_BIGENDIAN + + /* NOTE: The following functions are necessary since the Sick LD doesn't adopt the + * convention of converting from network byte order. + */ + + /** + * \brief Converts host byte order (little-endian) to Sick LMS byte order (little-endian) + * \param value The 2-byte value to convert to little-endian + * \return Value in Sick LMS byte order (little-endian) + */ + inline uint16_t host_to_sick_lms_1xx_byte_order( uint16_t value ) { + return value; + } + + /** + * \brief Converts host byte order (little-endian) to Sick LMS byte order (little-endian) + * \param value The 4-byte value to convert to little-endian + * \return Value in Sick LMS byte order (little-endian) + */ + inline uint32_t host_to_sick_lms_1xx_byte_order( uint32_t value ) { + return value; + } + + /** + * \brief Converts Sick LMS byte order (little-endian) to host byte order (little-endian) + * \param value The 2-byte value to convert to little-endian + * \return Value in host byte order (little-endian) + */ + inline uint16_t sick_lms_1xx_to_host_byte_order( uint16_t value ) { + return value; + } + + /** + * \brief Converts Sick LMS byte order (little-endian) to host byte order (little-endian) + * \param value The 4-byte value to convert to little-endian + * \return Value in host byte order (little-endian) + */ + inline uint32_t sick_lms_1xx_to_host_byte_order( uint32_t value ) { + return value; + } + +#else // The host has a big-endian architecture + + /** + * \brief Converts host byte order (big-endian) to Sick LMS byte order (little-endian) + * \param value The 2-byte value to convert to little-endian + * \return Value in Sick LMS byte order (little-endian) + */ + inline uint16_t host_to_sick_lms_1xx_byte_order( uint16_t value ) { + return REVERSE_BYTE_ORDER_16(value); + } + + /** + * \brief Converts host byte order (big-endian) to Sick LMS byte order (little-endian) + * \param value The 4-byte value to convertto little-endian + * \return Value in Sick LMS byte order (little-endian) + */ + inline uint32_t host_to_sick_lms_1xx_byte_order( uint32_t value ) { + return REVERSE_BYTE_ORDER_32(value); + } + + /** + * \brief Converts Sick LMS byte order (little-endian) to host byte order (big-endian) + * \param value The 2-byte value to convert to big-endian + * \return Value in host byte order (big-endian) + */ + inline uint16_t sick_lms_1xx_to_host_byte_order( uint16_t value ) { + return REVERSE_BYTE_ORDER_16(value); + } + + /** + * \brief Converts Sick LMS byte order (little-endian) to host byte order (big-endian) + * \param value The 4-byte value to convert to big-endian + * \return Value in host byte order (big-endian) + */ + inline uint32_t sick_lms_1xx_to_host_byte_order( uint32_t value ) { + return REVERSE_BYTE_ORDER_32(value); + } + +#endif /* _LITTLE_ENDIAN_HOST */ + + /* + * NOTE: Other utility functions can be defined here + */ + + /** + * \brief Utility function for converting int to standard string + * \param value Integer to be converted + * \return String representing the given integer + */ + inline std::string int_to_str( const int value ) { + std::stringstream ss; + ss << value; + return ss.str(); + } + + + +} //namespace SickToolbox diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xx.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xx.hh new file mode 100644 index 0000000..f75a3e4 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xx.hh @@ -0,0 +1,996 @@ +/*! + * \file SickLMS2xx.hh + * \brief Definition of class SickLMS2xx. + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#ifndef SICK_LMS_2XX_HH +#define SICK_LMS_2XX_HH + +/* Implementation dependencies */ +#include +#include +#include + +#include "SickLIDAR.hh" +#include "SickException.hh" + +#include "SickLMS2xxBufferMonitor.hh" +#include "SickLMS2xxMessage.hh" + +/* Macro definitions */ +#define DEFAULT_SICK_LMS_2XX_SICK_BAUD (B9600) ///< Initial baud rate of the LMS (whatever is set in flash) +#define DEFAULT_SICK_LMS_2XX_HOST_ADDRESS (0x80) ///< Client/host default serial address +#define DEFAULT_SICK_LMS_2XX_SICK_ADDRESS (0x00) ///< Sick LMS default serial address +#define DEFAULT_SICK_LMS_2XX_SICK_PASSWORD "SICK_LMS" ///< Password for entering installation mode +#define DEFAULT_SICK_LMS_2XX_SICK_MESSAGE_TIMEOUT (unsigned int)(1e6) ///< The max time to wait for a message reply (usecs) +#define DEFAULT_SICK_LMS_2XX_SICK_SWITCH_MODE_TIMEOUT (unsigned int)(3e6) ///< Can take the Sick LD up to 3 seconds to reply (usecs) +#define DEFAULT_SICK_LMS_2XX_SICK_MEAN_VALUES_MESSAGE_TIMEOUT (unsigned int)(15e6) ///< When using mean values, the Sick can sometimes take more than 10s to respond +#define DEFAULT_SICK_LMS_2XX_SICK_CONFIG_MESSAGE_TIMEOUT (unsigned int)(15e6) ///< The sick can take some time to respond to config commands (usecs) +#define DEFAULT_SICK_LMS_2XX_BYTE_INTERVAL (55) ///< Minimum time in microseconds between transmitted bytes +#define DEFAULT_SICK_LMS_2XX_NUM_TRIES (3) ///< The max number of tries before giving up on a request + +/* Associate the namespace */ +namespace SickToolbox { + + /*! + * \brief A general class for interfacing w/ SickLMS2xx2xx laser range finders + * + * This class implements the basic telegram protocol for SickLMS2xx2xx range finders. + * It allows the setting of such parameters as angular resolution, fov, etc... + */ + class SickLMS2xx : public SickLIDAR< SickLMS2xxBufferMonitor, SickLMS2xxMessage > + { + + public: + + /** Define the maximum number of measurements */ + static const uint16_t SICK_MAX_NUM_MEASUREMENTS = 721; ///< Maximum number of measurements returned by the Sick LMS + + /*! + * \enum sick_lms_2xx_type_t + * \brief Defines the Sick LMS 2xx types. + * This enum lists all of the supported Sick LMS models. + */ + enum sick_lms_2xx_type_t { + + /* Supported 200 models */ + SICK_LMS_TYPE_200_30106, ///< Sick LMS type 200-30106 + + /* Supported 211 models */ + SICK_LMS_TYPE_211_30106, ///< Sick LMS type 211-30106 + SICK_LMS_TYPE_211_30206, ///< Sick LMS type 211-30206 + SICK_LMS_TYPE_211_S07, ///< Sick LMS type 211-S07 + SICK_LMS_TYPE_211_S14, ///< Sick LMS type 211-S14 + SICK_LMS_TYPE_211_S15, ///< Sick LMS type 211-S15 + SICK_LMS_TYPE_211_S19, ///< Sick LMS type 211-S19 + SICK_LMS_TYPE_211_S20, ///< Sick LMS type 211-S20 + + /* Supported 220 models */ + SICK_LMS_TYPE_220_30106, ///< Sick LMS type 220-30106 + + /* Supported 221 models */ + SICK_LMS_TYPE_221_30106, ///< Sick LMS type 221-30106 + SICK_LMS_TYPE_221_30206, ///< Sick LMS type 221-30206 + SICK_LMS_TYPE_221_S07, ///< Sick LMS type 221-S07 + SICK_LMS_TYPE_221_S14, ///< Sick LMS type 221-S14 + SICK_LMS_TYPE_221_S15, ///< Sick LMS type 221-S15 + SICK_LMS_TYPE_221_S16, ///< Sick LMS type 221-S16 + SICK_LMS_TYPE_221_S19, ///< Sick LMS type 221-S19 + SICK_LMS_TYPE_221_S20, ///< Sick LMS type 221-S20 + + /* Supported 291 models */ + SICK_LMS_TYPE_291_S05, ///< Sick LMS type 291-S05 + SICK_LMS_TYPE_291_S14, ///< Sick LMS type 291-S14 (LMS Fast) + SICK_LMS_TYPE_291_S15, ///< Sick LMS type 291-S15 + + /* Any unknown model */ + SICK_LMS_TYPE_UNKNOWN = 0xFF ///< Unknown sick type + + }; + + /*! + * \enum sick_lms_2xx_variant_t + * \brief Defines the Sick LMS 2xx variant type. + */ + enum sick_lms_2xx_variant_t { + SICK_LMS_VARIANT_2XX_TYPE_6 = 0x00, ///< Standard LMS 2xx type 6 models + SICK_LMS_VARIANT_SPECIAL = 0x01, ///< Special models (i.e. LMS211-/221-S19/-S20 + SICK_LMS_VARIANT_UNKNOWN = 0xFF ///< Unknown LMS variant + }; + + /*! + * \enum sick_lms_2xx_scan_angle_t + * \brief Defines the scan angle for the Sick LMS 2xx. + */ + enum sick_lms_2xx_scan_angle_t { + SICK_SCAN_ANGLE_90 = 90, ///< Scanning angle of 90 degrees + SICK_SCAN_ANGLE_100 = 100, ///< Scanning angle of 100 degrees + SICK_SCAN_ANGLE_180 = 180, ///< Scanning angle of 180 degrees + SICK_SCAN_ANGLE_UNKNOWN = 0xFF ///< Unknown scanning angle + }; + + /*! + * \enum sick_lms_2xx_scan_resolution_t + * \brief Defines the available resolution settings for the Sick LMS 2xx. + */ + enum sick_lms_2xx_scan_resolution_t { + SICK_SCAN_RESOLUTION_25 = 25, ///< 0.25 degree angular resolution + SICK_SCAN_RESOLUTION_50 = 50, ///< 0.50 degree angular resolution + SICK_SCAN_RESOLUTION_100 = 100, ///< 1.00 degree angular resolution + SICK_SCAN_RESOLUTION_UNKNOWN = 0xFF ///< Unknown angular resolution + }; + + /*! + * \enum sick_lms_2xx_measuring_units_t + * \brief Defines the available Sick LMS 2xx measured value units. + */ + enum sick_lms_2xx_measuring_units_t { + SICK_MEASURING_UNITS_CM = 0x00, ///< Measured values are in centimeters + SICK_MEASURING_UNITS_MM = 0x01, ///< Measured values are in milimeters + SICK_MEASURING_UNITS_UNKNOWN = 0xFF ///< Unknown units + }; + + /*! + * \enum sick_lms_2xx_sensitivity_t + * \brief Sick sensitivities. Only valid for Sick LMS 211/221/291! + */ + enum sick_lms_2xx_sensitivity_t { + SICK_SENSITIVITY_STANDARD = 0x00, ///< Standard sensitivity: 30m @ 10% reflectivity + SICK_SENSITIVITY_MEDIUM = 0x01, ///< Medium sensitivity: 25m @ 10% reflectivity + SICK_SENSITIVITY_LOW = 0x02, ///< Low sensitivity: 20m @ 10% reflectivity + SICK_SENSITIVITY_HIGH = 0x03, ///< High sensitivity: 42m @ 10% reflectivity + SICK_SENSITIVITY_UNKNOWN = 0xFF ///< Sensitivity unknown + }; + + /*! + * \enum sick_lms_2xx_peak_threshold_t + * \brief Sick peak threshold. Only valid for Sick LMS 200/220! + */ + enum sick_lms_2xx_peak_threshold_t { + SICK_PEAK_THRESHOLD_DETECTION_WITH_NO_BLACK_EXTENSION = 0x00, ///< Standard: peak threshold detection, no black extension + SICK_PEAK_THRESHOLD_DETECTION_WITH_BLACK_EXTENSION = 0x01, ///< Peak threshold detection, active black extension + SICK_PEAK_THRESHOLD_NO_DETECTION_WITH_NO_BLACK_EXTENSION = 0x02, ///< No peak threshold detection, no black extension + SICK_PEAK_THRESHOLD_NO_DETECTION_WITH_BLACK_EXTENSION = 0x03, ///< No peak threshold detection, active black extension + SICK_PEAK_THRESHOLD_UNKNOWN = 0xFF ///< Peak threshold unknown + }; + + /*! + * \enum sick_lms_2xx_status_t + * \brief Defines the status of the Sick LMS 2xx unit. + */ + enum sick_lms_2xx_status_t { + SICK_STATUS_OK = 0x00, ///< LMS is OK + SICK_STATUS_ERROR = 0x01, ///< LMS has encountered an error + SICK_STATUS_UNKNOWN = 0xFF ///< Unknown LMS status + }; + + /*! + * \enum sick_lms_2xx_measuring_mode_t + * \brief Defines the measurment modes supported by Sick LMS 2xx. + */ + enum sick_lms_2xx_measuring_mode_t { + SICK_MS_MODE_8_OR_80_FA_FB_DAZZLE = 0x00, ///< Measurement range 8m/80m; fields A,B and Dazzle (Default) + SICK_MS_MODE_8_OR_80_REFLECTOR = 0x01, ///< Measurement range 8/80m; reflector bits in 8 levels + SICK_MS_MODE_8_OR_80_FA_FB_FC = 0x02, ///< Measurement range 8/80m; fields A,B, and C + SICK_MS_MODE_16_REFLECTOR = 0x03, ///< Measurement range 16m; reflector bits in 4 levels + SICK_MS_MODE_16_FA_FB = 0x04, ///< Measurement range 16m; fields A and B + SICK_MS_MODE_32_REFLECTOR = 0x05, ///< Measurement range 32m; reflector bit in 2 levels + SICK_MS_MODE_32_FA = 0x06, ///< Measurement range 32m; field A + SICK_MS_MODE_32_IMMEDIATE = 0x0F, ///< Measurement range 32m; immediate data transmission, no flags + SICK_MS_MODE_REFLECTIVITY = 0x3F, ///< Sick LMS 2xx returns reflectivity (echo amplitude) values instead of range measurements + SICK_MS_MODE_UNKNOWN = 0xFF ///< Unknown range + }; + + /*! + * \enum sick_lms_2xx_operating_mode_t + * \brief Defines the operating modes supported by Sick LMS 2xx. + * See page 41 of the LMS 2xx telegram manual for additional descriptions of these modes. + */ + enum sick_lms_2xx_operating_mode_t { + SICK_OP_MODE_INSTALLATION = 0x00, ///< Installation mode for writing EEPROM + SICK_OP_MODE_DIAGNOSTIC = 0x10, ///< Diagnostic mode for testing purposes + SICK_OP_MODE_MONITOR_STREAM_MIN_VALUE_FOR_EACH_SEGMENT = 0x20, ///< Streams minimum measured values for each segement + SICK_OP_MODE_MONITOR_TRIGGER_MIN_VALUE_ON_OBJECT = 0x21, ///< Sends the min measured values when object is detected + SICK_OP_MODE_MONITOR_STREAM_MIN_VERT_DIST_TO_OBJECT = 0x22, ///< Streams min "vertical distance" to objects + SICK_OP_MODE_MONITOR_TRIGGER_MIN_VERT_DIST_TO_OBJECT = 0x23, ///< Sends min vertical distance to object when detected + SICK_OP_MODE_MONITOR_STREAM_VALUES = 0x24, ///< Streams all measured values in a scan + SICK_OP_MODE_MONITOR_REQUEST_VALUES = 0x25, ///< Sends measured range values on request (i.e. when polled) + SICK_OP_MODE_MONITOR_STREAM_MEAN_VALUES = 0x26, ///< Streams mean values from a sample size of n consecutive scans + SICK_OP_MODE_MONITOR_STREAM_VALUES_SUBRANGE = 0x27, ///< Streams data from given subrange + SICK_OP_MODE_MONITOR_STREAM_MEAN_VALUES_SUBRANGE = 0x28, ///< Streams mean values over requested subrange + SICK_OP_MODE_MONITOR_STREAM_VALUES_WITH_FIELDS = 0x29, ///< Streams measured values with associated flags + SICK_OP_MODE_MONITOR_STREAM_VALUES_FROM_PARTIAL_SCAN = 0x2A, ///< Streams measured values of partial scan directly after measurement + SICK_OP_MODE_MONITOR_STREAM_RANGE_AND_REFLECT_FROM_PARTIAL_SCAN = 0x2B, ///< Streams range and intensity from n partial scans + SICK_OP_MODE_MONITOR_STREAM_MIN_VALUES_FOR_EACH_SEGMENT_SUBRANGE = 0x2C, ///< Streams minimum measured values for each segment in a sub-range + SICK_OP_MODE_MONITOR_NAVIGATION = 0x2E, ///< Sick outputs navigation data records + SICK_OP_MODE_MONITOR_STREAM_RANGE_AND_REFLECT = 0x50, ///< Streams measured range from a scan and sub-range of reflectivity values + SICK_OP_MODE_UNKNOWN = 0xFF ///< Unknown operating mode + }; + + /*! + * \enum sick_lms_2xx_baud_t + * \brief Defines available Sick LMS 2xx baud rates + */ + enum sick_lms_2xx_baud_t { + SICK_BAUD_9600 = 0x42, ///< 9600 baud + SICK_BAUD_19200 = 0x41, ///< 19200 baud + SICK_BAUD_38400 = 0x40, ///< 38400 baud + SICK_BAUD_500K = 0x48, ///< 500000 baud + SICK_BAUD_UNKNOWN = 0xFF ///< Unknown baud rate + }; + + /** Define Sick LMS 2xx availability levels */ + static const uint8_t SICK_FLAG_AVAILABILITY_DEFAULT = 0x00; ///< Availability unspecified + static const uint8_t SICK_FLAG_AVAILABILITY_HIGH = 0x01; ///< Highest availability (comparable to LMS types 1 to 5) + static const uint8_t SICK_FLAG_AVAILABILITY_REAL_TIME_INDICES = 0x02; ///< Send real-time indices + static const uint8_t SICK_FLAG_AVAILABILITY_DAZZLE_NO_EFFECT = 0x04; ///< Dazzle evalutation has no effect on switching outputs + + /*! + * \struct sick_lms_2xx_operating_status_tag + * \brief A structure for aggregating the data that + * collectively defines the operating status + * of the device. + */ + /*! + * \typedef sick_lms_2xx_operating_status_t + * \brief Adopt c-style convention + */ + typedef struct sick_lms_2xx_operating_status_tag { + uint16_t sick_scan_angle; ///< Sick scanning angle (deg) + uint16_t sick_scan_resolution; ///< Sick angular resolution (1/100 deg) + uint16_t sick_num_motor_revs; ///< Sick number of motor revs + uint8_t sick_operating_mode; ///< Sick operating mode + uint8_t sick_measuring_mode; ///< Sick measuring mode + uint8_t sick_laser_mode; ///< Sick laser is on/off + uint8_t sick_device_status; ///< Sick device status {ok,error} + uint8_t sick_measuring_units; ///< Sick measuring units {cm,mm} + uint8_t sick_address; ///< Sick device address + uint8_t sick_variant; ///< Sick variant {special,standard} + } sick_lms_2xx_operating_status_t; + + /*! + * \struct sick_lms_2xx_software_status_tag + * \brief A structure for aggregating the data that + * collectively defines the system software + * for the Sick LMS 2xx unit. + */ + /*! + * \typedef sick_lms_2xx_software_status_t + * \brief Adopt c-style convention + */ + typedef struct sick_lms_2xx_software_status_tag { + uint8_t sick_system_software_version[8]; ///< Sick system software version + uint8_t sick_prom_software_version[8]; ///< Sick boot prom software version + } sick_lms_2xx_software_status_t; + + /*! + * \struct sick_lms_2xx_restart_status_tag + * \brief A structure for aggregating the data that + * collectively defines the system restart + * config for the Sick LMS 2xx unit + */ + typedef struct sick_lms_2xx_restart_status_tag { + uint16_t sick_restart_time; ///< Sick restart time + uint8_t sick_restart_mode; ///< Sick restart mode + } sick_lms_2xx_restart_status_t; + + /*! + * \struct sick_lms_2xx_pollution_status_tag + * \brief A structure for aggregating the data that + * collectively defines the pollution values + * and settings for the device + */ + /*! + * \typedef sick_lms_2xx_pollution_status_t + * \brief Adopt c-style convention + */ + typedef struct sick_lms_2xx_pollution_status_tag { + uint16_t sick_pollution_vals[8]; ///< Calibrating the pollution channels + uint16_t sick_pollution_calibration_vals[8]; ///< Calibrating the pollution channel values + uint16_t sick_reference_pollution_vals[4]; ///< Reference pollution values + uint16_t sick_reference_pollution_calibration_vals[4]; ///< Reference pollution calibration values + } sick_lms_2xx_pollution_status_t; + + /*! + * \struct sick_lms_2xx_signal_status_tag + * \brief A structure for aggregating the data that + * collectively define the signal config and + * status. + */ + /*! + * \typedef sick_lms_2xx_signal_status_t + * \brief Adopt c-style convention + */ + typedef struct sick_lms_2xx_signal_status_tag { + uint16_t sick_reference_scale_1_dark_100; ///< Receive signal amplitude in ADC incs when reference signal is switched off (Signal 1, Dark 100%) + uint16_t sick_reference_scale_2_dark_100; ///< Receive signal amplitude in ADC incs when reference signal is switched off (Signal 2, Dark 100%) + uint16_t sick_reference_scale_1_dark_66; ///< Receive signal amplitude in ADC incs when reference signal is switched off (Signal 1, Dark 66%) + uint16_t sick_reference_scale_2_dark_66; ///< Receive signal amplitude in ADC incs when reference signal is switched off (Signal 2, Dark 66%) + uint16_t sick_signal_amplitude; ///< Laser power in % of calibration value + uint16_t sick_current_angle; ///< Angle used for power measurement + uint16_t sick_peak_threshold; ///< Peak threshold in ADC incs for power measurement + uint16_t sick_angle_of_measurement; ///< Angles used to reference target for power measurement + uint16_t sick_signal_amplitude_calibration_val; ///< Calibration of the laser power + uint16_t sick_stop_threshold_target_value; ///< Target value of the stop threshold in ADC incs + uint16_t sick_peak_threshold_target_value; ///< Target value of the peak threshold in ADC incs + uint16_t sick_stop_threshold_actual_value; ///< Actual value of the stop threshold in ADC incs + uint16_t sick_peak_threshold_actual_value; ///< Actual value of the peak threshold in ADC incs + uint16_t sick_reference_target_single_measured_vals; ///< Reference target "single measured values." Low byte: Current number of filtered single measured values. High byte: Max num filtered single measured value since power-on. + uint16_t sick_reference_target_mean_measured_vals; ///< Reference target "mean measured values." Low byte: Current number of filtered mean measured values. High byte: Max num filtered mean measured value since power-on. + } sick_lms_2xx_signal_status_t; + + /*! + * \struct sick_lms_2xx_field_status_tag + * \brief A structure for aggregating the data that + * collectively define the signal config and + * status. + */ + /*! + * \typedef sick_lms_2xx_field_status_t + * \brief Adopt c-style convention + */ + typedef struct sick_lms_2xx_field_status_tag { + uint8_t sick_field_evaluation_number; ///< Number of evaluations when the field is infirnged (lies in [1,125]) + uint8_t sick_field_set_number; ///< Active field set number + uint8_t sick_multiple_evaluation_offset_field_2; ///< Offset for multiple evaluation of field set 2 (see page 105 of telegram listing) + } sick_lms_2xx_field_status_t; + + /*! + * \struct sick_lms_2xx_baud_status_tag + * \brief A structure for aggregating the data that + * collectively define the baud config. + */ + /*! + * \typedef sick_lms_2xx_baud_status_t + * \brief Adopt c-style convention + */ + typedef struct sick_lms_2xx_baud_status_tag { + uint16_t sick_baud_rate; ///< Sick baud as reported by the device + uint8_t sick_permanent_baud_rate; ///< 0 - When power is switched on baud rate is 9600/1 - configured transmission rate is used + } sick_lms_2xx_baud_status_t; + + /*! + * \struct sick_lms_2xx_device_config_tag + * \brief A structure for aggregating the data that + * collectively defines the Sick's config. + */ + /*! + * \typedef sick_lms_2xx_device_config_t + * \brief Adopt c-style convention + */ + typedef struct sick_lms_2xx_device_config_tag { + uint16_t sick_blanking; ///< Maximum diameter of objects that are not to be detected (units cm) + uint16_t sick_fields_b_c_restart_times; ///< Restart times for fields B and C + uint16_t sick_dazzling_multiple_evaluation; ///< Number of scans that take place before LMS switches the outputs (only applies to availability level 1) + uint8_t sick_peak_threshold; ///< Peak threshold/black correction (This applies to Sick LMS 200/220 models, when Sick LMS 211/221/291 models are used, this value is sensitivity) + uint8_t sick_stop_threshold; ///< Stop threshold in mV (This only applies to Sick LMS 200/220 models) + uint8_t sick_availability_level; ///< Availability level of the Sick LMS + uint8_t sick_measuring_mode; ///< Measuring mode of the device + uint8_t sick_measuring_units; ///< Measured value and field value units + uint8_t sick_temporary_field; ///< Indicates whether the temporary field is being used + uint8_t sick_subtractive_fields; ///< Indicates whether fields A and B are subtractive + uint8_t sick_multiple_evaluation; ///< Multiple evalutation of scan data + uint8_t sick_restart; ///< Indicates the restart level of the device + uint8_t sick_restart_time; ///< Inidicates the restart time of the device + uint8_t sick_multiple_evaluation_suppressed_objects; ///< Multiple evaluation for objects less than the blanking size + uint8_t sick_contour_a_reference; ///< Contour function A + uint8_t sick_contour_a_positive_tolerance_band; ///< When contour function is active the positive tolerance is defined in (cm) + uint8_t sick_contour_a_negative_tolerance_band; ///< When contour function is active the negative tolerance is defined in (cm) + uint8_t sick_contour_a_start_angle; ///< When contour function is active the start angle of area to be monitored is defined (deg) + uint8_t sick_contour_a_stop_angle; ///< When contour function is active the stop angle of area to be monitored is defined (deg) + uint8_t sick_contour_b_reference; ///< Contour function B + uint8_t sick_contour_b_positive_tolerance_band; ///< When contour function is active the positive tolerance is defined in (cm) + uint8_t sick_contour_b_negative_tolerance_band; ///< When contour function is active the negative tolerance is defined in (cm) uint8_t sick_contour_b_start_angle; ///< When contour function is active the start angle of area to be monitored is defined (deg) + uint8_t sick_contour_b_start_angle; ///< When contour function is active the start angle of area to be monitored is defined (deg) + uint8_t sick_contour_b_stop_angle; ///< When contour function is active the stop angle of area to be monitored is defined (deg) + uint8_t sick_contour_c_reference; ///< Contour function C + uint8_t sick_contour_c_positive_tolerance_band; ///< When contour function is active the positive tolerance is defined in (cm) + uint8_t sick_contour_c_negative_tolerance_band; ///< When contour function is active the negative tolerance is defined in (cm) + uint8_t sick_contour_c_start_angle; ///< When contour function is active the start angle of area to be monitored is defined (deg) + uint8_t sick_contour_c_stop_angle; ///< When contour function is active the stop angle of area to be monitored is defined (deg) + uint8_t sick_pixel_oriented_evaluation; ///< Pixel oriented evaluation + uint8_t sick_single_measured_value_evaluation_mode; ///< Multiple evaluation (min: 1, max: 125) + } sick_lms_2xx_device_config_t; + + /*! + * \struct sick_lms_2xx_scan_profile_b0_tag + * \brief A structure for aggregating the data that + * define a scan profile obtained from reply + * B0 (See page 49 Telegram listing) + */ + /*! + * \typedef sick_lms_2xx_scan_profile_b0_t + * \brief Adopt c-style convention + */ + typedef struct sick_lms_2xx_scan_profile_b0_tag { + uint16_t sick_num_measurements; ///< Number of measurements + uint16_t sick_measurements[SICK_MAX_NUM_MEASUREMENTS]; ///< Range/reflectivity measurement buffer + uint8_t sick_field_a_values[SICK_MAX_NUM_MEASUREMENTS]; ///< Reflects the Field A bit value returned w/ range measurement + uint8_t sick_field_b_values[SICK_MAX_NUM_MEASUREMENTS]; ///< Reflects the Field B but value returned w/ range measurement + uint8_t sick_field_c_values[SICK_MAX_NUM_MEASUREMENTS]; ///< Reflects the Field C (or dazzle - depending upon sensor mode) value returned w/ range measurement + uint8_t sick_telegram_index; ///< Telegram index modulo 256 + uint8_t sick_real_time_scan_index; ///< If real-time scan indices are requested, this value is set (modulo 256) + uint8_t sick_partial_scan_index; ///< Indicates the start angle of the scan (This is useful for partial scans) + } sick_lms_2xx_scan_profile_b0_t; + + /*! + * \struct sick_lms_2xx_scan_profile_b6_tag + * \brief A structure for aggregating the data that + * define a scan profile obtained from reply + * B6 (See page 61 Telegram listing) + */ + /*! + * \typedef sick_lms_2xx_scan_profile_b6_t + * \brief Adopt c-style convention + */ + typedef struct sick_lms_2xx_scan_profile_b6_tag { + uint16_t sick_num_measurements; ///< Number of measurements + uint16_t sick_measurements[SICK_MAX_NUM_MEASUREMENTS]; ///< Range/reflectivity measurement buffer + uint8_t sick_sample_size; ///< Number of scans used in computing the returned mean + uint8_t sick_telegram_index; ///< Telegram index modulo 256 + uint8_t sick_real_time_scan_index; ///< If real-time scan indices are requested, this value is set (modulo 256) + } sick_lms_2xx_scan_profile_b6_t; + + /*! + * \struct sick_lms_2xx_scan_profile_b7_tag + * \brief A structure for aggregating the data that + * define a scan profile obtained from reply + * B7 (See page 63 Telegram listing) + */ + /*! + * \typedef sick_lms_2xx_scan_profile_b7_t + * \brief Adopt c-style convention + */ + typedef struct sick_lms_2xx_scan_profile_b7_tag { + uint16_t sick_subrange_start_index; ///< Measurement subrange start index + uint16_t sick_subrange_stop_index; ///< Measurement subrange stop index + uint16_t sick_num_measurements; ///< Number of measurements + uint16_t sick_measurements[SICK_MAX_NUM_MEASUREMENTS]; ///< Range/reflectivity measurement buffer + uint8_t sick_field_a_values[SICK_MAX_NUM_MEASUREMENTS]; ///< Reflects the Field A bit value returned w/ range measurement + uint8_t sick_field_b_values[SICK_MAX_NUM_MEASUREMENTS]; ///< Reflects the Field B but value returned w/ range measurement + uint8_t sick_field_c_values[SICK_MAX_NUM_MEASUREMENTS]; ///< Reflects the Field C (or dazzle - depending upon sensor mode) value returned w/ range measurement + uint8_t sick_telegram_index; ///< Telegram index modulo 256 + uint8_t sick_real_time_scan_index; ///< If real-time scan indices are requested, this value is set (modulo 256) + uint8_t sick_partial_scan_index; ///< Indicates the start angle of the scan (This is useful for partial scans) + } sick_lms_2xx_scan_profile_b7_t; + + /*! + * \struct sick_lms_2xx_scan_profile_bf_tag + * \brief A structure for aggregating the data that + * define a scan profile obtained from reply + * BF (See page 71 Telegram listing) + */ + /*! + * \typedef sick_lms_2xx_scan_profile_bf_t + * \brief Adopt c-style convention + */ + typedef struct sick_lms_2xx_scan_profile_bf_tag { + uint16_t sick_subrange_start_index; ///< Measurement subrange start index + uint16_t sick_subrange_stop_index; ///< Measurement subrange stop index + uint16_t sick_num_measurements; ///< Number of measurements + uint16_t sick_measurements[SICK_MAX_NUM_MEASUREMENTS]; ///< Range/reflectivity measurement buffer + uint8_t sick_sample_size; ///< Number of scans used in computing the returned mean + uint8_t sick_telegram_index; ///< Telegram index modulo 256 + uint8_t sick_real_time_scan_index; ///< If real-time scan indices are requested, this value is set (modulo 256) + } sick_lms_2xx_scan_profile_bf_t; + + /*! + * \struct sick_lms_2xx_scan_profile_c4_tag + * \brief A structure for aggregating the data that + * define a scan profile obtained from reply + * B4 (See page 79 Telegram listing) + */ + /*! + * \typedef sick_lms_2xx_scan_profile_c4_t + * \brief Adopt c-style convention + */ + typedef struct sick_lms_2xx_scan_profile_c4_tag { + uint16_t sick_num_range_measurements; ///< Number of range measurements + uint16_t sick_num_reflect_measurements; ///< Number of reflectivity measurements + uint16_t sick_range_measurements[SICK_MAX_NUM_MEASUREMENTS]; ///< Range measurement buffer + uint16_t sick_reflect_measurements[SICK_MAX_NUM_MEASUREMENTS]; ///< Reflect measurements buffer + uint16_t sick_reflect_subrange_start_index; ///< Start index of the measured reflectivity value subrange + uint16_t sick_reflect_subrange_stop_index; ///< Stop index of the measured reflectivity value subrange + uint8_t sick_field_a_values[SICK_MAX_NUM_MEASUREMENTS]; ///< Reflects the Field A bit value returned w/ range measurement + uint8_t sick_field_b_values[SICK_MAX_NUM_MEASUREMENTS]; ///< Reflects the Field B but value returned w/ range measurement + uint8_t sick_field_c_values[SICK_MAX_NUM_MEASUREMENTS]; ///< Reflects the Field C (or dazzle - depending upon sensor mode) value returned w/ range measurement + uint8_t sick_telegram_index; ///< Telegram index modulo 256 + uint8_t sick_real_time_scan_index; ///< If real-time scan indices are requested, this value is set (modulo 256) + } sick_lms_2xx_scan_profile_c4_t; + + /** Constructor */ + SickLMS2xx( const std::string sick_device_path ); + + /** Destructor */ + ~SickLMS2xx( ); + + /** Initializes the Sick */ + void Initialize( const sick_lms_2xx_baud_t desired_baud_rate, const uint32_t delay = 0 ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Uninitializes the Sick */ + void Uninitialize( ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ); + + /** Gets the Sick LMS 2xx device path */ + std::string GetSickDevicePath( ) const; + + /** Gets the Sick LMS 2xx device type */ + sick_lms_2xx_type_t GetSickType( ) const throw( SickConfigException ); + + /** Gets the scan angle currently being used by the device */ + double GetSickScanAngle( ) const throw( SickConfigException ); + + /** Gets the scan resolution currently being used by the device */ + double GetSickScanResolution( ) const throw( SickConfigException ); + + /** Set the measurement units of the device (in EEPROM) */ + void SetSickMeasuringUnits( const sick_lms_2xx_measuring_units_t sick_units = SICK_MEASURING_UNITS_MM ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ); + + /** Get the current measurement units of the device */ + SickLMS2xx::sick_lms_2xx_measuring_units_t GetSickMeasuringUnits( ) const throw( SickConfigException ); + + /** Sets the sensitivity value for the device (in EEPROM). NOTE: Only applies to LMS 211/221/291 models. */ + void SetSickSensitivity( const sick_lms_2xx_sensitivity_t sick_sensitivity = SICK_SENSITIVITY_STANDARD ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ); + + /** Get the current Sick LMS 2xx sensitivity level. NOTE: Only applies to LMS 211/221/291 models. */ + sick_lms_2xx_sensitivity_t GetSickSensitivity( ) const throw( SickConfigException ); + + /** Sets the peak threshold mode for the device (in EEPROM). NOTE: Only applies to LMS 200/220 models */ + void SetSickPeakThreshold( const sick_lms_2xx_peak_threshold_t sick_peak_threshold = SICK_PEAK_THRESHOLD_DETECTION_WITH_NO_BLACK_EXTENSION ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ); + + /** Get the current Sick LMS 2xx sensitivity level. NOTE: Only applies to LMS 211/221/291 models. */ + sick_lms_2xx_peak_threshold_t GetSickPeakThreshold( ) const throw( SickConfigException );; + + /** Sets the measuring mode for the device (in EEPROM). See page 98 of the telegram listing for more details. */ + void SetSickMeasuringMode( const sick_lms_2xx_measuring_mode_t sick_measuring_mode = SICK_MS_MODE_8_OR_80_FA_FB_DAZZLE ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ); + + /** Get the current Sick LMS 2xx measuring mode */ + sick_lms_2xx_measuring_mode_t GetSickMeasuringMode( ) const throw( SickConfigException ); + + /** Get the current Sick LMS 2xx operating mode */ + sick_lms_2xx_operating_mode_t GetSickOperatingMode( ) const throw( SickConfigException ); + + /** Sets the availability of the device (in EEPROM). See page 98 of the telegram listing for more details. */ + void SetSickAvailability( const uint8_t sick_availability_flags = SICK_FLAG_AVAILABILITY_DEFAULT ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ); + + /** Gets the current availability flags for the device */ + uint8_t GetSickAvailability( ) const throw( SickConfigException ); + + /** Sets the variant type for the device (in EEPROM) */ + void SetSickVariant( const sick_lms_2xx_scan_angle_t scan_angle, const sick_lms_2xx_scan_resolution_t scan_resolution ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Gets measurement data from the Sick. NOTE: Data can be either range or reflectivity given the Sick mode. */ + void GetSickScan( unsigned int * const measurement_values, + unsigned int & num_measurement_values, + unsigned int * const sick_field_a_values = NULL, + unsigned int * const sick_field_b_values = NULL, + unsigned int * const sick_field_c_values = NULL, + unsigned int * const sick_telegram_index = NULL, + unsigned int * const sick_real_time_scan_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Gets range and reflectivity data from the Sick. NOTE: This only applies to Sick LMS 211/221/291-S14! */ + void GetSickScan( unsigned int * const range_values, + unsigned int * const reflect_values, + unsigned int & num_range_measurements, + unsigned int & num_reflect_measurements, + unsigned int * const sick_field_a_values = NULL, + unsigned int * const sick_field_b_values = NULL, + unsigned int * const sick_field_c_values = NULL, + unsigned int * const sick_telegram_index = NULL, + unsigned int * const sick_real_time_scan_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Gets measurement data from the Sick. NOTE: Data can be either range or reflectivity given the Sick mode. */ + void GetSickScanSubrange( const uint16_t sick_subrange_start_index, + const uint16_t sick_subrange_stop_index, + unsigned int * const measurement_values, + unsigned int & num_measurement_values, + unsigned int * const sick_field_a_values = NULL, + unsigned int * const sick_field_b_values = NULL, + unsigned int * const sick_field_c_values = NULL, + unsigned int * const sick_telegram_index = NULL, + unsigned int * const sick_real_time_scan_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Gets partial scan measurements from the Sick LMS 2xx. NOTE: Data can be either range or reflectivity depending upon the given Sick mode. */ + void GetSickPartialScan( unsigned int * const measurement_values, + unsigned int & num_measurement_values, + unsigned int & partial_scan_index, + unsigned int * const sick_field_a_values = NULL, + unsigned int * const sick_field_b_values = NULL, + unsigned int * const sick_field_c_values = NULL, + unsigned int * const sick_telegram_index = NULL, + unsigned int * const sick_real_time_scan_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Gets mean measured values from the Sick LMS */ + void GetSickMeanValues( const uint8_t sick_sample_size, + unsigned int * const measurement_values, + unsigned int & num_measurement_values, + unsigned int * const sick_telegram_index = NULL, + unsigned int * const sick_real_time_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ); + + /** Gets mean measured values from the Sick LMS */ + void GetSickMeanValuesSubrange( const uint8_t sick_sample_size, + const uint16_t sick_subrange_start_index, + const uint16_t sick_subrange_stop_index, + unsigned int * const measurement_values, + unsigned int & num_measurement_values, + unsigned int * const sick_telegram_index = NULL, + unsigned int * const sick_real_time_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ); + + /** Acquire the Sick LMS status */ + sick_lms_2xx_status_t GetSickStatus( ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ); + + /** Indicates whether the Sick is an LMS Fast */ + bool IsSickLMS2xxFast( ) const throw( SickConfigException ); + + /** Resets Sick LMS field values */ + void ResetSick( ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ); + + /** Get Sick status as a string */ + std::string GetSickStatusAsString( ) const; + + /** Get Sick software info as a string */ + std::string GetSickSoftwareVersionAsString( ) const; + + /** Get Sick config as a string */ + std::string GetSickConfigAsString( ) const; + + /** Print the Sick LMS status */ + void PrintSickStatus( ) const; + + /** Print the Sick LMS software versions */ + void PrintSickSoftwareVersion( ) const; + + /** Print the Sick LMS configuration */ + void PrintSickConfig( ) const; + + /* + * NOTE: The following methods are given to make working with our + * predefined types a bit more manageable. + */ + + /** Converts the LMS's type to a corresponding string */ + static std::string SickTypeToString( const sick_lms_2xx_type_t sick_type ); + + /** A utility function for converting integers to lms_sick_scan_angle_t */ + static sick_lms_2xx_scan_angle_t IntToSickScanAngle( const int scan_angle_int ); + + /** A utility function for converting ints to lms_sick_scan_resolution_t */ + static sick_lms_2xx_scan_resolution_t IntToSickScanResolution( const int scan_resolution_int ); + + /** A utility function for converting doubles to lms_sick_scan_resolution_t */ + static sick_lms_2xx_scan_resolution_t DoubleToSickScanResolution( const double scan_resolution_double ); + + /** Converts the given bad, returns a string representing that baud rate. */ + static std::string SickBaudToString( const sick_lms_2xx_baud_t baud_rate ); + + /** A utility function for converting integers to lms_baud_t */ + static sick_lms_2xx_baud_t IntToSickBaud( const int baud_int ); + + /** A utility function for converting baud strings to lms_baud_t */ + static sick_lms_2xx_baud_t StringToSickBaud( const std::string baud_str ); + + /** Converts the LMS's status to a corresponding string */ + static std::string SickStatusToString( const sick_lms_2xx_status_t sick_status ); + + /** Converts the LMS's measuring mode to a corresponding string */ + static std::string SickMeasuringModeToString( const sick_lms_2xx_measuring_mode_t sick_measuring_mode ); + + /** Converts the LMS's measuring mode to a corresponding string */ + static std::string SickOperatingModeToString( const sick_lms_2xx_operating_mode_t sick_operating_mode ); + + /** Converts the LMS's sensitivity to string */ + static std::string SickSensitivityToString( const sick_lms_2xx_sensitivity_t sick_sensitivity ); + + /** Converts the LMS's peak threshold to string */ + static std::string SickPeakThresholdToString( const sick_lms_2xx_peak_threshold_t sick_peak_threshold ); + + /** Converts the LMS's measuring units to a corresponding string */ + static std::string SickMeasuringUnitsToString( const sick_lms_2xx_measuring_units_t sick_units ); + + protected: + + /** A path to the device at which the sick can be accessed. */ + std::string _sick_device_path; + + /** The baud rate at which to communicate with the Sick */ + sick_lms_2xx_baud_t _curr_session_baud; + + /** The desired baud rate for communicating w/ the Sick */ + sick_lms_2xx_baud_t _desired_session_baud; + + /** A string representing the type of device */ + sick_lms_2xx_type_t _sick_type; + + /** The operating parameters of the device */ + sick_lms_2xx_operating_status_t _sick_operating_status; + + /** The current software version being run on the device */ + sick_lms_2xx_software_status_t _sick_software_status; + + /** The restart configuration of the device */ + sick_lms_2xx_restart_status_t _sick_restart_status; + + /** The pollution measurement status */ + sick_lms_2xx_pollution_status_t _sick_pollution_status; + + /** The signal status of the device */ + sick_lms_2xx_signal_status_t _sick_signal_status; + + /** The field configuration for the device */ + sick_lms_2xx_field_status_t _sick_field_status; + + /** The baud configuration of the device */ + sick_lms_2xx_baud_status_t _sick_baud_status; + + /** The device configuration for the Sick */ + sick_lms_2xx_device_config_t _sick_device_config; + + /** Used when the device is streaming mean values */ + uint8_t _sick_mean_value_sample_size; + + /** Used when the device is streaming a scan subrange */ + uint16_t _sick_values_subrange_start_index; + + /** Used when the device is streaming a scan subrange */ + uint16_t _sick_values_subrange_stop_index; + + /** Stores information about the original terminal settings */ + struct termios _old_term; + + /** Opens the terminal for serial communication. */ + void _setupConnection() throw( SickIOException, SickThreadException ); + void _setupConnection(const uint32_t delay ) throw( SickIOException, SickThreadException ); + + /** Closes the serial communication terminal. */ + void _teardownConnection( ) throw( SickIOException ); + + /** Sends a message to the LMS and get the expected reply using th 0x80 rule. @todo Check difference in comments? */ + void _sendMessageAndGetReply( const SickLMS2xxMessage &sick_send_message, + SickLMS2xxMessage &sick_recv_message, + const unsigned int timeout_value, + const unsigned int num_tries ) throw( SickIOException, SickThreadException, SickTimeoutException ); + + /** Sends a message to the LMS and get the expected reply using th 0x80 rule. @todo Check difference in comments? */ + void _sendMessageAndGetReply( const SickLMS2xxMessage &sick_send_message, + SickLMS2xxMessage &sick_recv_message, + const uint8_t reply_code, + const unsigned int timeout_value, + const unsigned int num_tries ) throw( SickIOException, SickThreadException, SickTimeoutException ); + + /** Flushes the terminal I/O buffers */ + void _flushTerminalBuffer( ) throw ( SickThreadException ); + + /** Sets the baud rate for communication with the LMS. */ + void _setSessionBaud( const sick_lms_2xx_baud_t baud_rate ) throw( SickIOException, SickThreadException, SickTimeoutException ); + + /** Tests communication wit the LMS at a particular baud rate. */ + bool _testSickBaud( const sick_lms_2xx_baud_t baud_rate ) throw( SickIOException, SickThreadException ); + + /** Changes the terminal's baud rate. */ + void _setTerminalBaud( const sick_lms_2xx_baud_t sick_baud ) throw( SickIOException, SickThreadException ); + + /** Gets the type of Sick LMS */ + void _getSickType( ) throw( SickTimeoutException, SickIOException, SickThreadException ); + + /** Gets the current Sick configuration settings */ + void _getSickConfig( ) throw( SickTimeoutException, SickIOException, SickThreadException ); + + /** Sets the Sick configuration in flash */ + void _setSickConfig( const sick_lms_2xx_device_config_t &sick_config ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ); + + /** Gets the status of the LMS */ + void _getSickStatus( ) throw( SickTimeoutException, SickIOException, SickThreadException ); + + /** Gets the error status of the Sick LMS */ + void _getSickErrors( unsigned int * const num_sick_errors = NULL, + uint8_t * const error_type_buffer = NULL, + uint8_t * const error_num_buffer = NULL ) throw( SickTimeoutException, SickIOException, SickThreadException ); + + /** Switch Sick LMS to installation mode */ + void _setSickOpModeInstallation( ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Switch Sick LMS to diagnostic mode */ + void _setSickOpModeDiagnostic( ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Switch Sick LMS to monitor mode (request range data) */ + void _setSickOpModeMonitorRequestValues( ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Switch Sick LMS to monitor mode (stream range) */ + void _setSickOpModeMonitorStreamValues( ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Switch Sick LMS to monitor mode (stream range and reflectivity) */ + void _setSickOpModeMonitorStreamRangeAndReflectivity( ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Switch Sick LMS to monitor mode (stream range from a partial scan) */ + void _setSickOpModeMonitorStreamValuesFromPartialScan( ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Switch Sick LMS to monitor mode (stream mean measured values) */ + void _setSickOpModeMonitorStreamMeanValues( const uint8_t sample_size ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Switch Sick LMS to monitor mode (stream mean measured values) */ + void _setSickOpModeMonitorStreamValuesSubrange( const uint16_t subrange_start_index, const uint16_t subrange_stop_index ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Switch Sick LMS to monitor mode (stream mean measured values subrange) */ + void _setSickOpModeMonitorStreamMeanValuesSubrange( const uint16_t sample_size, const uint16_t subrange_start_index, const uint16_t subrange_stop_index ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Switches the operating mode of the LMS. */ + void _switchSickOperatingMode( const uint8_t sick_mode, const uint8_t * const mode_params = NULL ) + throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException); + + /** Parses the scan profile returned w/ message B0 */ + void _parseSickScanProfileB0( const uint8_t * const src_buffer, sick_lms_2xx_scan_profile_b0_t &sick_scan_profile ) const; + + /** Parses the scan profile returned w/ message B6 */ + void _parseSickScanProfileB6( const uint8_t * const src_buffer, sick_lms_2xx_scan_profile_b6_t &sick_scan_profile ) const; + + /** Parses the scan profile returned w/ message B6 */ + void _parseSickScanProfileB7( const uint8_t * const src_buffer, sick_lms_2xx_scan_profile_b7_t &sick_scan_profile ) const; + + /** Parses the scan profile returned w/ message BF */ + void _parseSickScanProfileBF( const uint8_t * const src_buffer, sick_lms_2xx_scan_profile_bf_t &sick_scan_profile ) const; + + /** Parses the scan profile returned w/ message C4 */ + void _parseSickScanProfileC4( const uint8_t * const src_buffer, sick_lms_2xx_scan_profile_c4_t &sick_scan_profile ) const; + + /** A function for parsing a byte sequence into a device config structure */ + void _parseSickConfigProfile( const uint8_t * const src_buffer, sick_lms_2xx_device_config_t &sick_device_config ) const; + + /** Acquires the bit mask to extract the field bit values returned with each range measurement */ + void _extractSickMeasurementValues( const uint8_t * const byte_sequence, const uint16_t num_measurements, uint16_t * const measured_values, + uint8_t * const field_a_values = NULL, uint8_t * const field_b_values = NULL, uint8_t * const field_c_values = NULL ) const; + + /** Tells whether the device is returning real-time indices */ + bool _returningRealTimeIndices( ) const { return _sick_device_config.sick_availability_level & SICK_FLAG_AVAILABILITY_REAL_TIME_INDICES; } + + /** Indicates whether the given unit value is defined */ + bool _validSickMeasuringUnits( const sick_lms_2xx_measuring_units_t sick_units ) const; + + /** Indicates whether the given scan angle is defined */ + bool _validSickScanAngle( const sick_lms_2xx_scan_angle_t sick_scan_angle ) const; + + /** Indicates whether the given scan resolution is defined */ + bool _validSickScanResolution( const sick_lms_2xx_scan_resolution_t sick_scan_resolution ) const; + + /** Indicates whether the given sensitivity is defined */ + bool _validSickSensitivity( const sick_lms_2xx_sensitivity_t sick_sensitivity ) const; + + /** Indicates whether the given peak threshold is defined */ + bool _validSickPeakThreshold( const sick_lms_2xx_peak_threshold_t sick_peak_threshold ) const; + + /** Indicates whether the given sensitivity is defined */ + bool _validSickMeasuringMode( const sick_lms_2xx_measuring_mode_t sick_measuring_mode ) const; + + /** Indicates whether the Sick LMS is type 200 */ + bool _isSickLMS200( ) const; + + /** Indicates whether the Sick LMS is type 211 */ + bool _isSickLMS211( ) const; + + /** Indicates whether the Sick LMS is type 220 */ + bool _isSickLMS220( ) const; + + /** Indicates whether the Sick LMS is type 221 */ + bool _isSickLMS221( ) const; + + /** Indicates whether the Sick LMS is type 291 */ + bool _isSickLMS291( ) const; + + /** Indicates whether the Sick LMS type is unknown */ + bool _isSickUnknown( ) const; + + /** Given a baud rate as an integer, gets a LMS baud rate command. */ + sick_lms_2xx_baud_t _baudToSickBaud( const int baud_rate ) const; + + /** Given a bytecode representing Sick LMS availability, returns a corresponding string */ + std::string _sickAvailabilityToString( const uint8_t availability_code ) const; + + /** Given a bytecode representing Sick LMS restart mode, returns a corresponding string */ + std::string _sickRestartToString( const uint8_t restart_code ) const; + + /** Converts the LMS's temporary field value to a string */ + std::string _sickTemporaryFieldToString( const uint8_t temp_field_code ) const; + + /** Converts the LMS's subtractive field value to a string */ + std::string _sickSubtractiveFieldsToString( const uint8_t subt_field_code ) const; + + /** Converts the LMS's contour function status code to a string */ + std::string _sickContourFunctionToString( const uint8_t contour_function_code ) const; + + /** Converts the LMS's variant to a corresponding string */ + std::string _sickVariantToString( const unsigned int sick_variant ) const; + + }; + + /*! + * \typedef sick_lms_2xx_type_t + * \brief Makes working w/ SickLMS2xx::sick_lms_2xx_type_t a bit easier + */ + typedef SickLMS2xx::sick_lms_2xx_type_t sick_lms_2xx_type_t; + + /*! + * \typedef sick_lms_2xx_variant_t + * \brief Makes working w/ SickLMS2xx::sick_lms_2xx_variant_t a bit easier + */ + typedef SickLMS2xx::sick_lms_2xx_variant_t sick_lms_2xx_variant_t; + + /*! + * \typedef sick_lms_2xx_scan_angle_t + * \brief Makes working w/ SickLMS2xx::sick_lms_2xx_scan_angle_t a bit easier + */ + typedef SickLMS2xx::sick_lms_2xx_scan_angle_t sick_lms_2xx_scan_angle_t; + + /*! + * \typedef sick_lms_2xx_scan_resolution_t + * \brief Makes working w/ SickLMS2xx::sick_lms_2xx_scan_resolution_t a bit easier + */ + typedef SickLMS2xx::sick_lms_2xx_scan_resolution_t sick_lms_2xx_scan_resolution_t; + + /*! + * \typedef sick_lms_2xx_measuring_units_t + * \brief Makes working w/ SickLMS2xx::sick_lms_2xx_measuring_units_t a bit easier + */ + typedef SickLMS2xx::sick_lms_2xx_measuring_units_t sick_lms_2xx_measuring_units_t; + + /*! + * \typedef sick_lms_2xx_sensitivity_t + * \brief Makes working w/ SickLMS2xx::sick_lms_2xx_sensitivity_t a bit easier + */ + typedef SickLMS2xx::sick_lms_2xx_sensitivity_t sick_lms_2xx_sensitivity_t; + + /*! + * \typedef sick_lms_2xx_peak_threshold_t + * \brief Makes working w/ SickLMS2xx::sick_lms_2xx_peak_threshold_t a bit easier + */ + typedef SickLMS2xx::sick_lms_2xx_peak_threshold_t sick_lms_2xx_peak_threshold_t; + + /*! + * \typedef sick_lms_2xx_status_t + * \brief Makes working w/ SickLMS2xx::sick_lms_2xx_status_t a bit easier + */ + typedef SickLMS2xx::sick_lms_2xx_status_t sick_lms_2xx_status_t; + + /*! + * \typedef sick_lms_2xx_measuring_mode_t + * \brief Makes working w/ SickLMS2xx::sick_lms_2xx_measuring_mode_t a bit easier + */ + typedef SickLMS2xx::sick_lms_2xx_measuring_mode_t sick_lms_2xx_measuring_mode_t; + + /*! + * \typedef sick_lms_2xx_operating_mode_t + * \brief Makes working w/ SickLMS2xx::sick_lms_2xx_operating_mode_t a bit easier + */ + typedef SickLMS2xx::sick_lms_2xx_operating_mode_t sick_lms_2xx_operating_mode_t; + + /*! + * \typedef sick_lms_2xx_baud_t + * \brief Makes working w/ SickLMS2xx::sick_lms_2xx_baud_t a bit easier + */ + typedef SickLMS2xx::sick_lms_2xx_baud_t sick_lms_2xx_baud_t; + +} //namespace SickToolbox + +#endif //SICK_LMS_2XX_HH diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xxBufferMonitor.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xxBufferMonitor.hh new file mode 100644 index 0000000..ee816de --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xxBufferMonitor.hh @@ -0,0 +1,51 @@ +/*! + * \file SickLMS2xxBufferMonitor.hh + * \brief Defines a class for monitoring the receive + * buffer when interfacing w/ a Sick LMS 2xx + * laser range finder. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#ifndef SICK_LMS_2XX_BUFFER_MONITOR_HH +#define SICK_LMS_2XX_BUFFER_MONITOR_HH + +#define DEFAULT_SICK_LMS_2XX_SICK_BYTE_TIMEOUT (35000) ///< Max allowable time between consecutive bytes + +/* Definition dependencies */ +#include "SickLMS2xxMessage.hh" +#include "SickBufferMonitor.hh" +#include "SickException.hh" + +/* Associate the namespace */ +namespace SickToolbox { + + /*! + * \brief A class for monitoring the receive buffer when interfacing with a Sick LMS LIDAR + */ + class SickLMS2xxBufferMonitor : public SickBufferMonitor< SickLMS2xxBufferMonitor, SickLMS2xxMessage > { + + public: + + /** A standard constructor */ + SickLMS2xxBufferMonitor( ); + + /** A method for extracting a single message from the stream */ + void GetNextMessageFromDataStream( SickLMS2xxMessage &sick_message ) throw( SickIOException ); + + /** A standard destructor */ + ~SickLMS2xxBufferMonitor( ); + + }; + +} /* namespace SickToolbox */ + +#endif /* SICK_LMS_2XX_BUFFER_MONITOR_HH */ diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xxMessage.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xxMessage.hh new file mode 100644 index 0000000..92056d5 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xxMessage.hh @@ -0,0 +1,99 @@ +/*! + * \file SickLMS2xxMessage.hh + * \brief Definition of class SickLMS2xxMessage. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#ifndef SICK_LMS_2XX_MESSAGE_HH +#define SICK_LMS_2XX_MESSAGE_HH + +/* Definition dependencies */ +#include +#include +#include "SickMessage.hh" +#include "SickException.hh" + +#define CRC16_GEN_POL 0x8005 ///< Used to compute CRCs + +/** Makes a "short" in little endian */ +#define MKSHORT(a,b) ((unsigned short) (a) | ((unsigned short)(b) << 8)) + +#define SICK_LMS_2XX_MSG_HEADER_LEN (4) ///< Sick LMS message length in bytes +#define SICK_LMS_2XX_MSG_PAYLOAD_MAX_LEN (812) ///< Sick LMS max payload length in bytes +#define SICK_LMS_2XX_MSG_TRAILER_LEN (2) ///< Sick LMS message trailer length in bytes + +/* Associate the namespace */ +namespace SickToolbox { + + /** + * \brief A class to represent all messages sent to and from the Sick LMS 2xx + * + * This class helps to construct messages to be sent to the Sick. It also + * provides a container for received messages to be parsed into. + */ + class SickLMS2xxMessage : public SickMessage< SICK_LMS_2XX_MSG_HEADER_LEN, SICK_LMS_2XX_MSG_PAYLOAD_MAX_LEN, SICK_LMS_2XX_MSG_TRAILER_LEN > + { + + public: + + /** Default constructor. Constructs an empty message (not well-formed!). */ + SickLMS2xxMessage( ); + + /** Constructs a frame by using BuildMessage(). */ + SickLMS2xxMessage( const uint8_t dest_address, const uint8_t * const payload_buffer, const unsigned int payload_length ); + + /** Constructs a frame using ParseMessage(). */ + SickLMS2xxMessage( uint8_t * const message_buffer ); + + /** Constructs a well-formed raw frame from input fields. */ + void BuildMessage( uint8_t dest_address, const uint8_t * const payload_buffer, + const unsigned int payload_length ); + + /** Populates fields from a (well-formed) raw frame. */ + void ParseMessage( const uint8_t * const message_buffer ); + + /** Gets the address of the frame. */ + uint8_t GetDestAddress( ) const { return _message_buffer[1]; } + + /** Gets the command code associated with the message */ + uint8_t GetCommandCode( ) const { return _message_buffer[MESSAGE_HEADER_LENGTH]; } + + /** Gets the status byte from an LMS response message (NOTE: only applies to Sick LMS response telegrams!) */ + uint8_t GetStatusByte( ) const { return _message_buffer[MESSAGE_HEADER_LENGTH+_payload_length-1]; } + + /** Gets the checksum for the message. */ + uint16_t GetChecksum( ) const { return _checksum; } + + /** Reset the data associated with this message (for initialization purposes) */ + void Clear( ); + + /** A debugging function that prints the contents of the message. */ + void Print( ) const; + + /** Destructor */ + ~SickLMS2xxMessage(); + + protected: + + /** The checksum (CRC16) */ + uint16_t _checksum; + + private: + + /** Computes the checksum of the frame. */ + uint16_t _computeCRC( uint8_t * data, unsigned int data_length ) const; + + }; + +} /* namespace SickToolbox */ + +#endif //SICK_LMS_2XX_MESSAGE_HH diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xxUtility.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xxUtility.hh new file mode 100644 index 0000000..f440ebc --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickLMS2xxUtility.hh @@ -0,0 +1,121 @@ +/*! + * \file SickLMS2xxUtility.hh + * \brief Defines simple utility functions for working with the + * Sick LMS 2xx laser range finder units. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +/* Auto-generated header */ +#include "SickConfig.hh" + +/** + * \def REVERSE_BYTE_ORDER_16 + * \brief Reverses the byte order of the given 16 bit unsigned integer + */ +#define REVERSE_BYTE_ORDER_16( y ) ( ( ( y & 0x00FF ) << 8 ) | ( ( y & 0xFF00 ) >> 8 ) ) + +/** + * \def REVERSE_BYTE_ORDER_32 + * \brief Reverses the byte order of the given 32 bit unsigned integer + */ +#define REVERSE_BYTE_ORDER_32( y ) ( ( ( y & 0x000000FF ) << 24 ) | ( ( y & 0x0000FF00 ) << 8 ) | ( ( y & 0x00FF0000 ) >> 8 ) | ( ( y & 0xFF000000 ) >> 24 ) ) + +/* Associate the namespace */ +namespace SickToolbox { + +#ifndef WORDS_BIGENDIAN + +/* NOTE: The following functions are necessary since the Sick LD doesn't adopt the + * convention of converting from network byte order. + */ + +/** + * \brief Converts host byte order (little-endian) to Sick LMS byte order (little-endian) + * \param value The 2-byte value to convert to little-endian + * \return Value in Sick LMS byte order (little-endian) + */ +inline uint16_t host_to_sick_lms_2xx_byte_order( uint16_t value ) { + return value; +} + +/** + * \brief Converts host byte order (little-endian) to Sick LMS byte order (little-endian) + * \param value The 4-byte value to convert to little-endian + * \return Value in Sick LMS byte order (little-endian) + */ +inline uint32_t host_to_sick_lms_2xx_byte_order( uint32_t value ) { + return value; +} + +/** + * \brief Converts Sick LMS byte order (little-endian) to host byte order (little-endian) + * \param value The 2-byte value to convert to little-endian + * \return Value in host byte order (little-endian) + */ +inline uint16_t sick_lms_2xx_to_host_byte_order( uint16_t value ) { + return value; +} + +/** + * \brief Converts Sick LMS byte order (little-endian) to host byte order (little-endian) + * \param value The 4-byte value to convert to little-endian + * \return Value in host byte order (little-endian) + */ +inline uint32_t sick_lms_2xx_to_host_byte_order( uint32_t value ) { + return value; +} + +#else // The host has a big-endian architecture + +/** + * \brief Converts host byte order (big-endian) to Sick LMS byte order (little-endian) + * \param value The 2-byte value to convert to little-endian + * \return Value in Sick LMS byte order (little-endian) + */ +inline uint16_t host_to_sick_lms_2xx_byte_order( uint16_t value ) { + return REVERSE_BYTE_ORDER_16(value); +} + +/** + * \brief Converts host byte order (big-endian) to Sick LMS byte order (little-endian) + * \param value The 4-byte value to convertto little-endian + * \return Value in Sick LMS byte order (little-endian) + */ +inline uint32_t host_to_sick_lms_2xx_byte_order( uint32_t value ) { + return REVERSE_BYTE_ORDER_32(value); +} + +/** + * \brief Converts Sick LMS byte order (little-endian) to host byte order (big-endian) + * \param value The 2-byte value to convert to big-endian + * \return Value in host byte order (big-endian) + */ +inline uint16_t sick_lms_2xx_to_host_byte_order( uint16_t value ) { + return REVERSE_BYTE_ORDER_16(value); +} + +/** + * \brief Converts Sick LMS byte order (little-endian) to host byte order (big-endian) + * \param value The 4-byte value to convert to big-endian + * \return Value in host byte order (big-endian) + */ +inline uint32_t sick_lms_2xx_to_host_byte_order( uint32_t value ) { + return REVERSE_BYTE_ORDER_32(value); +} + +#endif /* _LITTLE_ENDIAN_HOST */ + +/* + * NOTE: Other utility functions can be defined here + */ + +} //namespace SickToolbox diff --git a/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickMessage.hh b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickMessage.hh new file mode 100644 index 0000000..617a306 --- /dev/null +++ b/sitl_config/ugv/sicktoolbox/include/sicktoolbox/SickMessage.hh @@ -0,0 +1,230 @@ +/*! + * \file SickMessage.hh + * \brief Defines the abstract parent class for all Sick messages. + * + * Code by Jason C. Derenick and Thomas H. Miller. + * Contact derenick(at)lehigh(dot)edu + * + * The Sick LIDAR Matlab/C++ Toolbox + * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller + * All rights reserved. + * + * This software is released under a BSD Open-Source License. + * See http://sicktoolbox.sourceforge.net + */ + +#ifndef SICK_MESSAGE +#define SICK_MESSAGE + +/* Dependencies */ +#include +#include +#include + +/* Associate the namespace */ +namespace SickToolbox { + + /** + * \class SickMessage + * \brief Provides an abstract parent for all Sick messages + */ + template < unsigned int MSG_HEADER_LENGTH, unsigned int MSG_PAYLOAD_MAX_LENGTH, unsigned int MSG_TRAILER_LENGTH > + class SickMessage { + + public: + + /** Some constants to make things more manageable */ + static const unsigned int MESSAGE_HEADER_LENGTH = MSG_HEADER_LENGTH; + static const unsigned int MESSAGE_TRAILER_LENGTH = MSG_TRAILER_LENGTH; + static const unsigned int MESSAGE_PAYLOAD_MAX_LENGTH = MSG_PAYLOAD_MAX_LENGTH; + static const unsigned int MESSAGE_MAX_LENGTH = MESSAGE_HEADER_LENGTH + MESSAGE_PAYLOAD_MAX_LENGTH + MESSAGE_TRAILER_LENGTH; + + /** A standard constructor */ + SickMessage( ); + + /** Construct a well-formed Sick message */ + void BuildMessage( const uint8_t * const payload_buffer, const unsigned int payload_length ); + + /** Populates fields given a sequence of bytes representing a raw message */ + virtual void ParseMessage( const uint8_t * const message_buffer ) = 0; + + /** Returns a copy of the raw message buffer */ + void GetMessage( uint8_t * const message_buffer ) const; + + /** Resturns the total message length in bytes */ + unsigned int GetMessageLength( ) const { return _message_length; } + + /** Returns a copy of the raw message payload */ + void GetPayload( uint8_t * const payload_buffer ) const; + + /** Returns a copy of the payload as a C String */ + void GetPayloadAsCStr( char * const payload_str ) const; + + /** Returns a subregion of the payload specified by indices */ + void GetPayloadSubregion( uint8_t * const payload_sub_buffer, const unsigned int start_idx, + const unsigned int stop_idx ) const; + + /** Returns the total payload length in bytes */ + unsigned int GetPayloadLength( ) const { return _payload_length; } + + /** Indicates whether the message container is populated */ + bool IsPopulated( ) const { return _populated; }; + + /** Clear the contents of the message container/object */ + virtual void Clear( ); + + /** Print the contents of the message */ + virtual void Print( ) const; + + /** A virtual destructor */ + virtual ~SickMessage( ); + + protected: + + /** The length of the message payload in bytes */ + unsigned int _payload_length; + + /** The length of the message in bytes */ + unsigned int _message_length; + + /** The message as a raw sequence of bytes */ + uint8_t _message_buffer[MESSAGE_MAX_LENGTH]; + + /** Indicates whether the message container/object is populated */ + bool _populated; + + }; + + + /** + * \brief A default constructor + */ + template< unsigned int MSG_HEADER_LENGTH, unsigned int MSG_PAYLOAD_MAX_LENGTH, unsigned int MSG_TRAILER_LENGTH > + SickMessage< MSG_HEADER_LENGTH, MSG_PAYLOAD_MAX_LENGTH, MSG_TRAILER_LENGTH >::SickMessage( ) { } + + /** + * \brief Constructs a Sick message given the parameter values + * \param *payload_buffer The payload of the message as an array of bytes + * \param payload_length The length of the payload in bytes + */ + template< unsigned int MSG_HEADER_LENGTH, unsigned int MSG_PAYLOAD_MAX_LENGTH, unsigned int MSG_TRAILER_LENGTH > + void SickMessage< MSG_HEADER_LENGTH, MSG_PAYLOAD_MAX_LENGTH, MSG_TRAILER_LENGTH >::BuildMessage( const uint8_t * const payload_buffer, const unsigned int payload_length ) { + + /* Clear the object */ + Clear(); + + /* Assign the payload and message lengths */ + _payload_length = payload_length; + _message_length = MESSAGE_HEADER_LENGTH + MESSAGE_TRAILER_LENGTH + _payload_length; + + /* Copy the payload into the message buffer */ + memcpy(&_message_buffer[MESSAGE_HEADER_LENGTH],payload_buffer,_payload_length); + + /* Mark the object container as being populated */ + _populated = true; + + } + + /** + * \brief Parses a sequence of bytes into a Sick message + * \param *message_buffer A well-formed message to be parsed into the class' fields + */ + template< unsigned int MSG_HEADER_LENGTH, unsigned int MSG_PAYLOAD_MAX_LENGTH, unsigned int MSG_TRAILER_LENGTH > + void SickMessage< MSG_HEADER_LENGTH, MSG_PAYLOAD_MAX_LENGTH, MSG_TRAILER_LENGTH >::ParseMessage( const uint8_t * const message_buffer ) { + + /* Clear the message container/object */ + Clear(); + + /* Mark the object as populated */ + _populated = true; + } + + /** + * \brief Get the message as a sequence of well-formed bytes + * \param *message_buffer Destination buffer for message contents + */ + template< unsigned int MSG_HEADER_LENGTH, unsigned int MSG_PAYLOAD_MAX_LENGTH, unsigned int MSG_TRAILER_LENGTH > + void SickMessage< MSG_HEADER_LENGTH, MSG_PAYLOAD_MAX_LENGTH, MSG_TRAILER_LENGTH >::GetMessage( uint8_t * const message_buffer ) const { + memcpy(message_buffer,_message_buffer,_message_length); + } + + /** + * \brief Get the payload contents as a sequence of well-formed bytes + * \param *payload_buffer Destination buffer for message payload contents + */ + template< unsigned int MSG_HEADER_LENGTH, unsigned int MSG_PAYLOAD_MAX_LENGTH, unsigned int MSG_TRAILER_LENGTH > + void SickMessage< MSG_HEADER_LENGTH, MSG_PAYLOAD_MAX_LENGTH, MSG_TRAILER_LENGTH >::GetPayload( uint8_t * const payload_buffer ) const { + memcpy(payload_buffer,&_message_buffer[MESSAGE_HEADER_LENGTH],_payload_length); + } + + /** Returns a copy of the payload as a C String */ + template< unsigned int MSG_HEADER_LENGTH, unsigned int MSG_PAYLOAD_MAX_LENGTH, unsigned int MSG_TRAILER_LENGTH > + void SickMessage< MSG_HEADER_LENGTH, MSG_PAYLOAD_MAX_LENGTH, MSG_TRAILER_LENGTH >::GetPayloadAsCStr( char * const payload_buffer ) const { + memcpy(payload_buffer,&_message_buffer[MESSAGE_HEADER_LENGTH],_payload_length); + payload_buffer[_payload_length] = '\0'; + } + + /** + * \brief Get a specified sub-region of the payload buffer + * \param *payload_sub_buffer Destination buffer for message payload contents + * \param *start_idx The 0-indexed starting location for copying + * \param *stop_idx The 0-indexed stopping location for copying + */ + template< unsigned int MSG_HEADER_LENGTH, unsigned int MSG_PAYLOAD_MAX_LENGTH, unsigned int MSG_TRAILER_LENGTH > + void SickMessage< MSG_HEADER_LENGTH, MSG_PAYLOAD_MAX_LENGTH, MSG_TRAILER_LENGTH >::GetPayloadSubregion( uint8_t * const payload_sub_buffer, + const unsigned int start_idx, + const unsigned int stop_idx ) const { + /* Extract the subregion */ + memcpy(payload_sub_buffer,&_message_buffer[MESSAGE_HEADER_LENGTH+start_idx],stop_idx+1); + } + + /** + * \brief Reset all internal fields and buffers + */ + template< unsigned int MSG_HEADER_LENGTH, unsigned int MSG_PAYLOAD_MAX_LENGTH, unsigned int MSG_TRAILER_LENGTH > + void SickMessage< MSG_HEADER_LENGTH, MSG_PAYLOAD_MAX_LENGTH, MSG_TRAILER_LENGTH >::Clear( ) { + + /* Reset the parent integer variables */ + _message_length = _payload_length = 0; + + /* Clear the message buffer */ + memset(_message_buffer,0,MESSAGE_MAX_LENGTH); + + /* Set the flag indicating this message object/container is empty */ + _populated = false; + } + + /** + * \brief Print data about this object + */ + template< unsigned int MSG_HEADER_LENGTH, unsigned int MSG_PAYLOAD_MAX_LENGTH, unsigned int MSG_TRAILER_LENGTH > + void SickMessage< MSG_HEADER_LENGTH, MSG_PAYLOAD_MAX_LENGTH, MSG_TRAILER_LENGTH >::Print( ) const { + + std::cout << "Payload length: " << GetPayloadLength() << std::endl; + std::cout << "Message length: " << GetMessageLength() << std::endl; + std::cout << std::flush; + + std::cout << "Message (hex):" << std::endl; + std::cout.setf(std::ios::hex,std::ios::basefield); + for (unsigned int i = 0; i < _message_length; i++) { + std::cout << (int)_message_buffer[i] << " "; + } + std::cout << std::endl << std::flush; + + std::cout << "Message (ASCII):" << std::endl; + std::cout.setf(std::ios::dec,std::ios::basefield); + for (unsigned int i = 0; i < _message_length; i++) { + std::cout << _message_buffer[i] << " "; + } + std::cout << std::endl << std::flush; + } + + /** + * \brief A destructor + */ + template< unsigned int MSG_HEADER_LENGTH, unsigned int MSG_PAYLOAD_MAX_LENGTH, unsigned int MSG_TRAILER_LENGTH > + SickMessage< MSG_HEADER_LENGTH, MSG_PAYLOAD_MAX_LENGTH, MSG_TRAILER_LENGTH >::~SickMessage() { } + +} /* namespace SickToolbox */ + +#endif /* SICK_MESSAGE */ diff --git a/sitl_config/ugv/sicktoolbox/manuals/sicktoolbox-RS-422.pdf b/sitl_config/ugv/sicktoolbox/manuals/sicktoolbox-RS-422.pdf new file mode 100644 index 0000000000000000000000000000000000000000..99132b04386b43546516c87502600976132ee5eb GIT binary patch literal 224402 zcma&NLzgJZqGr3&wr$(CZQHhO+qP}nwli1Sw)OTtqi(&%Y1C~+jQ9a_d(Y(l^e1&xzK?{n*#qH$*QX$k;q6#2$LR!D5fpy7 zRd|+|dd%bF;cBmI$JF$AJb7JF>zh8rtUmz;#`qWhJ^`a{fHvKNwZZ~6c3{F8G202B`>er?*|K zIG}D9MPfUeI<*aFA}4m_CS zWocubXd-vJ!{g$5LGE=E|F-FaBJSE3x}{J>z!E2^&D~MIiIbSjK_qg-drhyf+%dIIWrf|Q{Qn85WTBoQgvM8xX%id z2|DXg`Vbi*iQ_{##7{Wv7vcIQCQBZs;|&KJ>a*gT9i$neqEp9r+?f!FH8S$Li8P~b z6Q?fqlz;fsX7nxVD$Xp6dX~rUSd2p_Cwh>WiRYdnCkCbG40~JGL?uMm&}%kT^9#|_ zeF%hxvcDIF$sk`dQt5p(Pt*R<`KjIA%%Q!($}rjOra)Vwy{y! z!bt(Lu~;SUR7j(d?<8hLLzd-vxyC2e_vKEE!Xej{p_L@Rx8>v)xe2n(^iJW?xaF>ul5s9>3?~0tsP?@FrkQ zw8(fqZzX6WFznr7Q=klv5Z!ROWQ~$4iBncHy-e2!YK3aqG8vy_ ziSxg5$ z6qnh7DIVJ7p?>|`A-Pk0V0|ScSn|yJ-lU=r#!xeX+C93(Q?4OfHL*4RKY;k>_AgZaMajP>13fbvn&B*Q5ljR!5?A=tGdpql9@lHm&IaI>~9Uev;K(bW- z>yd`~ohpdqI72X5&$rFv*yaNnA%*(7s1zZr3G|f8x&XvqevJ=C6vKo9@~OdLRZIMgCeA+8My+4`BaJyRitdXB3Lygo=B4* z0z4uvvV_^CEIusTYQp?M!1u(UC~~j{vx1=YqPJ-<9K7r<%xt)t+@Z5bxje{}>)pZEY`%t`$j_J=`0*IPYmHb|RbYV{8`lFSgjpxeNOLZ^ zba_DNGJ?u3ZV0ef26Q`ZJEbHApq~iPDRP zBa@|k=u0W36;H{mN~w;t-}UXjfQMW_$`(kNXR-r2e-eRX>dz`3bJ~VYGeM$(E!dzP z;Z)g}+DcynrXg2V_g-Ism1WR>IYaVP>*!d)to&awl)Of<(Kbd{&sR&s%Io|y(O_pQ zy+j94n;t9^CQiQ70a9??;TZ zq9IpgcvW)yf5QfsKAMNE@L+-=qEqc{3#^5@&UZF$d&hS58h!Gk|BDy@0l~k(;9#f! zA6_ug{}(Tq{zb_DQ=+tJPS|3LA@(3WBKTBewo7%;^=jzq$MMwDERb2jB2q*Ik|;Jx z+dV!$60Vh3T1SG8!h^GPF%l6G>2|9}-ohFtfC>Cg{-W8<;&MNPrQOc$;1nnD`cR|{ zJGsQmW{_Z4yO|WIhRxZ|_Kt1pUlAH=(8g#bbDD?!#z&nrY zHI?T#XW5$dgzp)r`{u^^HYjeKzk4t1QY%zRl!g$NpBr7FT0+=*GS1jKye&%aPCFv( zc!cnvo}QVPqCGCqu%g?P>1_^@F&Tq4y_J_fzLTR;3D28$T8^~|9X}0uD?>rY*x|LE z!daxLQA)CXw^=+>Bt2hyCr1$_N&l8sd7>Csx3#j~1_CDFTAiZpyNZeI^Wc>9ggFs) z4Z!I1(?KrcEeL3Sl;*uQo(YqxTqogrzvlZe29>$hL0u>1#Qixa49V>cjFhx0E4?h8 zHu-ekvVHdbnS1Y>O=gL5?w@=onO~?=>$bzM*SfOcx@FncrNO-UEY7-Wgt(>JZ7oW& zzx5&C!yo&Sc6>rC$)nv&^Lb?9fsJx?^$a!IBRrQ03#G9qIlq;FIjp%8=>{)`SG9aA z^^_Hx;8|01)p}maYq`~BLz>?R;H4sEC{o>w)#NYP+Yxj}n`pk;>Ow6VJ1Q}9SYjZI z54gFifn`OVL~Ck|ax5x^LkyM;d&jDNFV7ESm8 z;YN0n+v=>&Sv)##mM5PgwHBRTizcl#g}h@a;pbye8Ds{mP80d& zQKvMNv_aP;F^+En-_qUCj&}0OBC1T!Tf}JV{)SAPK3dG`kW3-BT3ht13gSa}4!Ks8g@O+jhHspgKW3M#DMvajUVl_HRa@Z@|0II~IV&$!i z8Ij6z%jZ&ZF}<2<{vEN_UZ7isQeqRHLA5kuls!k)S{_6Z2LJr zVQ;IbV5VrP@WTFL$Uf)3fEqP_=YovJO6;huhA1aq&kPnu6dCB!?bM4`!f{4!L_UY7 z_IZ{hVBX=I|CYumKpAHHmT9Re%5qM~>hvJu}>!(aOHG7t5cC zr_3eyr!DmEWKI#@DXk=xFD7?pV#FX3Vg10IV*Qft1WIh5uX|f8)GBDqL6#yfa{)w= z3PnAm0J<9>N=`o0EDEo%P<9{Z4jh+-2BhpHl*2S4+<@&&@TRO47WSYRKvj;oP18QP z%^r^rdbD`tE~iXG{X32MP1WMn_v~~Iy*MdZE2t~U{GvsJN3lKdVBb8O?ysUm zre6PmB7<>1*)vr2~K2@&<59apI^Jc!9 zWhw!V?rEU}grJ3vcMw=aK=xzoxHy#LbmrEpr~Uy%rPr8`|vxmg#uLD)Y;3a@B(=o*N@-C1swXx`tJwm5M`gVqd-6sRJvG2s4 zFtq3jW#)lcUMC7{G$!u_5Ilx86L539Z_iccd>u)3N*XnItDpp$rJ%xzg6Rk4g6Fd4 z>XxAwsA-3!U};Q=f1kPgB!ff@QcB%6M>K;c_0rL?cL-|4SNZ_Gq zYY-V#;|0LHji6^ki{Fv32*I!WxNJ7o6D<4njBzRZ3qj2EMs{01!y{DTF#MkxTxzWfl;{ zkU``-iqWellJ-M6ZKxJ*7`L58$oNV}q2gZgnB0Jsq`D2HR5NrD#232C?9-0cI-mD(P(G>9F~6OBhY0SC5yW^)ru)rgeba^{y3lPe9ce;EiuJt|{l6U2JhK zrXPhj%eBZgatTi~;o+=e2(VTZm-F&lD$#OxsV>VLVNzb|C9z8)FKN$7W+9bf+8Km7 z7#P3V3dFJP z8nuFnq|#8f0MDKT{Cw`*DOxumR_ZEUBv4ybLyS)&NiTN$a+KN2$1$-e#B(e31yXjv z7!hF_TBTlU^Ipcfe5HxO*j-$QDLW#FgUx~+g>ly95orJ|0CPQrwnU!Kp{Q_T>P`}C znA=|dgO=W&W&B?J4)K8AHu`*07TL0;TYc|qm=ew^1ci$B6gYqVmZ73q#9H6RC$oAD z_F?;SoLjaoyfB}&!`i3lQ~35S-Ndth_!LV`!xFqgQQ%w(4SWvryT!}t4OCe;FP-Gc z?KYd@QQT~e>tU%qPAup;9Qb}xOQ3;az@33<=+4k!v7kCV>^UTppk>K@suU(pQh8z& zZ_{Jvv6g)Jd$^czx{;V=)0s}qx6H+pQ3c$X*Bo^TtEq90JA{#I$^vK+Z>rXWLE8jt zvggv4rJWkPe~UhuED(bHbJH*#s_*6$Asc0#NPz>sM&!2!v8-piq$E@zID*3P7mW#^ zpG(iv3KJnx-Xr_iDDPLl!g35#ZUYA{qQtZDJdQ#&dwkxT1%2X4?urmkjfk6E)Xaw~ z%djbK%Kss~BG2aWI>NU$0s}VI2wWly=ZG@e3&6ck;xON|I7}ugVL(05uAmc^ztL|x zCcOmhFC&*=ozZ=)Ln2c&^?Gqe;hn>+^+q{Ii+o=ik73xtzVLo*0b)nsw$n1m%H2GH z3M7$a37c>UCRPJJ5Gh<(qlZ#b>>~XL|6vMJaZh5}wgpQbgX@}2xA>FAD($7NI>NJ4 zWw5qo%(>XiQEzkutIXBL%$7}>&qS1$dlFc3!%_S#`MH)7sCf~_ z!o({L`!-Fe*zznf=Uf8%?5$efg*LL8l4kaT(9?bVVgQdd>Cy^z>aM@3VMu~DmS&@3 znn4Fj2HK}*+Di1%bllkqL&3hVO}($ja3m1tlO+zn&!1t)W5MG@dB;wqUcLQ20@0Mo z0lP{tt;Orkz_#!?4Y-!W* zW+BjGhL-mH2Tn*<$X>X*h0I>hIV(Z=B1b&kqVGKxGA6!XJ@*=ViH7`RWX@)TfZ%bY z+P+Cw&S7TjA1Q0FEBsYLI>%Ag+ap&u+KDD$nW8p8`~wbyAJp8Xg=bQ7g=f#N_E0l2 zCfDtZz;dJ-E19h*HgNkypgWcgRi=&mCGi)IpL4NrL)I6 z*mQjAoBIABc0O)CB#UnN00$r2o)W$=HnU&MBXiKOxRFyeZ(v?fypXuD(+PH2QS#9s zyxP0(@H%NLoasC3>}D5fES7E>x7~eOB}p)jzlL9OMTR?EC8593m_o&iL(h&XxxJVq zPO}yJrwaR&_CXLyu-O=gVQD7cTMmi24mZ}l$eJ`>4MRx=8jttv4ktive@A=xveX;~ z(Hxq`rW!p-!cDc~B4N$9?=S(oO%ucRFC7%qu>-@6CNa*oWP0wPynC_9%3zW##a4cK zzmBCHCZdBQVCVD^6PDptmL@?7@eH&!87P)UgBFIIuErNk!{ii9W+TX-gg8hx200o< z7di6UzM7#sG**dRy5LuIg1hm^2BJqAEb^2#&w#_|N#8vBW*Vp-=RnccolCr-w7dfW zTl5vvQvkJ8NRP8dDNPip%crk=O?GH#Y&7m#J2#~Bl9|`L%e(6pA!0OU1%pydKq+r{ zYPlQkkzlzf(60Iy#TB|bPprt)&O?4&{m{0NzepNoF!seMy{w4yzihRT zCyn~bU?NlSU40hYuDr@+qh=m-UiCr^FvVltUKDRVF0_q6wkzY#o_*Tt(0CxMB#tS= z_KdnpnudTkM^VHaIpS%3o2LD8Yt``ZD(m_!9?DoX+KJm~Vv$`cC#AS;JDlg{)Mj0I z1~F+|DXy=0B*Mfrle~Wa21H3NpEGN3sm}Rfu3;aMJpjxF%Wrt(q`1s>05zW*=g-%q zQrY=ws%{Q>qx%be{Z=QLC0m(#Hv*kbIjrG}74?q4f(Imr?=Ku@O|S~nDVQq% zIQ4*vO}Vh#rkO*~h15F9%q{uqx_iSBLPZf5nwX(>$aA2a_xw{g5gIr{$GS>PAdW+t zzCiN!JMhI1=|93!2Vsu}90)G9ITKEyxQ$P&Gu{ZGq&0P@uH<#9E|0(N3IZg0~qCI#ChXdJJGo#+VD!mN?B+Z;`8TLUKrGYY$_> zgULJlTV;ZbwUWjZe{WMK?jUib?pUo6?dNOKKI~3Qa~^3?AAK@p1X6)y=?W%?T$30Q z&jRen{pCS$P@z3$%oiIO=%-NuumJOmEfct>N_~Jmo+<5JnjHgsYH=*?ayM7v8evIR zKThz)P)-29KD{_k3#5zsWkpfb*4y%R$Rxr?Eo%*JrR+l}PuQ+n`E%P8TjxIb|Zi3F&m>Xbg5O$rR z8u-mc0#y7HO2SNnufWRj(}-SQ%I3JQD{jpSpXQW78Q9G1(?Im=s$D{L+Q26o&*>edgTsc|MHE1cPraBhvv@)s_wD3NE^saflW1W_u8sb$qe5;b* zg`E;gv-+z{*#{iL*&dDR6eRy#9}m50Xkgu~NV!hOD63y7YqgTDso5~t2+!dZgkaOs z9teB^h_x#ySdD_J1y#E`Go^fx?R>8uH}x4HQ7pI(N#N4q39udXk(%_hGjBW&1a0fI zX+6GO%xb_BZ*1ISWBJ*59&WYaT%rIP&r;eUmVljp0e9tHsB_r2HarXXXMLDQ6i4(c zT2CS}dNY4tAgQ+f>E2%l6u~n1#()&a`PBnN3C)&j zDv4(APU4GZ@e7s-bD8X+OlwIGTY9 zP{vAh>Y|-dyfJOJ-Dza1Kfx;GEY_U%&$GM9n=SiHx8~Gl%1hlkZJboF!qE{=0y8Bd zU2qiPMY%1tul6Dl$Od+-%%o_YgZ28W^gh%gK*y-a6$HyLZ(FOQW4c%;#1)z}@*6+P zRK^(T^dPmJ+f*L6Hz~GSs;@V?=YaZQ46PQ<-aIwuVnjAM$~}8sH{_;5@>S)9^0nk9 zD&T*uE#WQA?a{VhT)#n!fzYjBk=<;mRj4VyJB{lYs+6nuafgKiU@-kDw^-k=uQEb6 zN1lTI*jjSBb~1ERN35@3xB4_FEWzY3|InKRO*Q|t4j}lMGl22MUW%N

;&inc`gR zR8ntuFNpK$5m-^$MGhR{IumCx(}~q$7I#Qy?VS+l1pl=Ruq$4rGXMU75$3hk(x@5A zn^$vciCdk)T2}_C_3a3p42?gowKP!DxP7O%j)hc}!9B)1!*)n@yq+q(DrqTJ#(i$n zIc>#WazVidDR|;oO<#%hFWB0}p8bjS`vv)fLId<)8udTg^Iwh1$jZdE!Gf0ZcA z?EkwGMZyVr0;PA#uh1vc7EI@;_l-T8Y|yA1+I%o<04$y#9?^0jp8))G?9+?x_2NR5 z5FguAQze6L_o0X7a$8c`k>t$pz0b@}4wv`7Dr#5u?Od|OM+0l<;t6|jVt6bS9rw3l`GoERDKvx>G*#whY|%ot zeC7NwX^HQs|vGdO-!}tKz@==f3 z@353nVMrh5SE6J?pCv~^++>W-FWN8JHaeTg*$u}}FjSU=6%tBUhiekc)yuj`kJ2R^ z7Ej1t3$0WReRor?cL1NRUGf+xRs*i`7jejSYp?CJ3)oHlJ!{WBqcNw;J`g;hLJ1+> z+Ju{|SUhQ>z#Wt5_8WzuR>zOHvcsNQt#4J zY%XN1ommQE&Szmw#RK9-IlrpOYI`)e=|kfa}fr8ma@RdlBjhc%V+17!VDzc+2PXKy5@h+eb z-Zr{Os|MAU=5@T|kEB1i0{(JuVRs=1IUaNb=;}kM&>KQm@`#XnTj%D*g+4c3@LX1& zcVUmEBB3!C8tAQ!4ju*2T%z!7+1RmaR3a*s`&!P9R={F@#G4dK0ODj=^qUTW*ajL3 z2;hr!^Hj_UNg_sL0EQ>i7OCOloXi7|KWq8{Sd(Fa!Y|Q^PVrWFW3Db0TIFC1WmdN{ zjlgky0SO49cnmPkTA!OD+ml|~murFw&b5FTW#w!Ft$B;PIgtEAax>vRw*=1%JdC;# z2B3O@w#f(3urx~Wfw9Xp)8r@TMX2CZKpctFWCTi-5`5hdCcWxHhBb@P|y&r z6~kMm2%~#nNGOzwg|U}YQ3Z$_mhQ9{?Xc3@i(k2vV2F=!`ikuIj_qeGf)4XHkTIa! z)S`E`yT#3Olh1}B()uWlmbRg=;JAgnLm{17KXg%O+{8GW9OK8j!GJMXhT`=pVb%Pz zvbpu^QY->?7Xql*(pfb^;X;9af@TCQp8KiWg;7?~hBuGK0ryapff7+dN@?QW^1EAn7)uP`{M{ zqN#js)nb7b7D`F&tL!28NUzz5+&cbG@~=e(CFS!b#|`1+tG!lR zO0YkLna-0`9v>EDYod92bBf~w&dUxX8yYCW4eK9?l(kKE*j5san64I19!^PxWeowl z&e?7xPEO;RuCz4VyL|I(W+kcT;*_6=Ob+`su+W`~GYHP(&>R(#Jpp;5Ji)vf*V0?EId%hPe85>MJy%%nx>D*_^CKq}nd%hV| zU)~SZvA1+9m-*!Y^2=-{xsmX}QT3f$45G6d%Sy012)qD`gQ@Jo;&4=)+e=5bHhQW3&oyNp0T^OnKUHp4O_b(WCaJ2MyD2E9<#I z_=|rC?`Gi_pLCd&i008WaWs*1fG3O12+sJQxK|~RTrQ{r{_yX``2uoF%v~|)H&^kOvs#6J;pX^w9DFv`mW||>jYfE zkb}4I6u%($>yphNM#t;Ic1dAMBQ#Z)Ukh_v!zOp47F?M}PjNg^8OAwfNYdz`6{U4X zFBVOMJwVZ%H)!na6pLH6Da$DQWw@|~KmI$;gmL%dEU{c0{NW%Zu*t=@qwNa3dwS1D zU8>1k3#{m}6>v;fM#h)dtwqo)qigZgO~_end#>@jDqbATU9)a4G&%DTHpOkc`>P^Iz&=65UI3wCRS*bgW?jZBr)yFYa1N;^>Nxmp{hvhtPhUb#TzHr} zLC!5Fgh~O#77QJZ#Mo+@&BkS)J@jE{I5KOn)Sg=K8@ z#_}2j9xiC^11oKV7|0ym+6m`K(L|Zm(1dEd04GdFXVFmUjN<9TmLn8C`sLnV(tvCASb%yk;?!T%JM z{tk-IjH0RCEKt@Vc-t-YuLMinXEDl@q9}d3`T16Je{7iNtaQ2B+elj+P<9te=jema z(`DLlBW)Fwsa9emA2#|0%>&}x5SdZ2t^ujs^1zid-U|DZR%v`yLdb=5`T&on$moTd zzRP{i9JWf;t$)VTNZ%EMdz~F#`q9vjTTv9u-^2~xqK%?*$n9D-^Hlv#Xr+tD>s#?o zrbiQEN7b)ShW$*jN2@nSEbOJftK;1+Tc;ou%O!THkLo~(xue_#DvYlNbuf1uvJ9qo zC-)0@jL&mSwD-%zgX8qR9J2tkE+fCcqxP)fgJ(DPI(hgUXU)sLC`3E=FFZ4ec5RMO z;6_J*R|dZ{KQ=x?8t!GV1l`pB)KF~Lywu5r_tP)Kgz5l6g!OVA4PA|{7QUV){Q|A} z8x{Yz8Tr>_{3kGHVEn&}E|&k9h5rAWbC!So$^UcF)uW{qhcbpR`$)-m&}|}m0PWMq zE=Rh~7>hIVBB_e}Q2!Sd@M@rcQ{d;Z;=;;BZjPf1T?_Suerah*M@8p(MU92;dVSCh z`d7-2&)3KG)vK$^+YPn$=I!S8cx|dFZ`S<-OsdH3b#@=Xc5m_^^JwRy3Az9iWF_&`3dMtJ6Taz?$)e>-K->gXV$Al+#)?wciOOFb@CiW zJIPWZF)3i~a!KyKSGO5;2|(9@C-e0j8i|}%*ga@9YI&*4V{V_qN|*~P7FkgStx30U z-cc;H-?f@GO5gQk?MlP9FVL#}@7RpCn!V5fcH*qOYez#1H*8uBKXc#`Od^dj1-VFF zEpb)1IdRr2FkeYf3&TPWGY^mx<&A+V+c%)lzQ^sm`|~fy?}s#FoA~Vj@@$^}h2ET3 z1G-U+WD^svu%N1^&RU`_RdiL67?bwQ;9#hRZ;vT&wbFhzBY9Eyj11o#BX#N;#9|aR z+ftavTt9UWa{E`$9sTgfcCJ+VR98DpDvtAOVga;x< z-PuKIN~GDRN8F9|xx;yb5BilB9s`OnNDe6qyV4PkkcsXFMToOtjA zIyJB#V9kOgqH}W#>hF6?Zbe}FMg<1cY(^Kl9~TfhHo>J7#pzKPprMAGa$YWVsJ7{5 z=X$w5EyhAjq7Wb~$lGsSwFh?>ubSugHl%?mH?ME-4u~`_>36)~0(5TmIrcWZv2VRG zZ%%8(~;P9$%+Ar5}}+(KbY^7 zwS@-&kL>X|FhCi}O6T~QQC-1^@MN1bptV(&*!DUx)F~&Sifu~N$`$4#h1x!Pp}pCM zibv^G^B0cYMnCr!AGa11N?j!J2$PrX&6A0hc;Mp3`q9xWq0yyv&z|*P+S##$%AM`0 z17QO9HDJ`qr_VB4jM30UgthEId%X4^T@9$WhYPr4O{>2KW4L<3ShmH49C5h!IMqEBckonm$eH8TV(;CWWJ=L=V>URJL;Sl?b0NAs{F>J>K@Vy{+#e+KR z^aM!+bJ01UxZA9zU@X>n=GAia!hvKq`vzFs2U8&|ht%L8mpE5z+0%jti&+jt(Cas= z0ZwX}fOiVS!e<2hse4l9t80^$Iv4}o16J<+?1Wx1LQ%Jr)YFnk**kRSQt$V~J=$Hc zPJ<%B#&na>a-d7Z;@2P^?Ys%r;}Qxs;|tRbusxLh%p>kVC#Z1AK`SosDMPh>A$*yF zWBynSn?#Tt0G{w+lA-L)Q?iip8^bc;@&lS2C_YK8Cec*Je8mi-e>z)LGZ~5ep9mB< z4N&Q63pZHP!lAC?Rw&d}#a@xYb%{jj|LEfj3b%p#@fU*kvS+Kb1!;rHMhelp+zxDP zgYDkz^!509y1tI#@O6En{M_#F{et@OwD)~3ZJ@!qvZL|hkuHiZL=5h>rJDmaLhuyl z;%g6H-i2!-C}4>yMHdO+?TrzFHI3mDpnv^9E94Bm(LXH0NB1+`d29E9Bw!Xr%SLF} z_jgZ_Efz3PpNtW?SexJ(-H>2I7-^0{gn~5C-~xw-nODcWAAcsl`)AzM=N)C0r@>)l zh`yIV$EQE2aQ94RJAQ3CXKz8M@lF3oT)^MKK`}fiw47dE1j?`I19p?dRZhw`vZRpM z($eyo{?yATAoqbK1dJKbo@_7DL01=+gpc=DG!su+EfrmpsIiZ2A}TtjapV@J5J)(g zYXCE2jR(|-T;NrY)pWG}o0yjMvIb6nhU6P|dktDq$A3-UEO zh1o1C_}-t~GVW|8o-B{T` zDF9%Et79m4E6^I`M!R&jM5ik@q?4ExLEc>AsDG3~YL;i27ELutrp2L1K%54asTxEI!1 z0`h0-7`{A0ys%!Z%Q-!oU8lY7n}J^nlOL!P(5nQgLi#zPKX@L5R-qA2T8y@;N_M(& zMNt~rD5VtHKb&=2(Bh?tL$K+P>4|pmu7D}9*%n}wmkO2{>7Zo7T7SUq>?wr~A$!zj zAa|F?F0^5Oib-a2JrjdannlKIG{6Q*5aA+FAhT`*#8m+~CBQ-{Z0xb}eVvDegPqeB zo{-(K2J?i8L4Tv!56Pu~4vwbfyG12iIg6&Wsp0BXwm82;LJF8SM4ijeA9kw`yhl5L zd-pT{2em(NHcp-Kf0TA(+h6r$CGE@0ecpUJrxxH10^q``>?I|I);JT$N^Iv(> zfb=twLWZE1#*)5@#_>C}MfwV0o{J(}?gPCh^yHfWHjYVmFrlFS&U9|ydPOQFZS%{x zxMkdgBJ(c&_}T_TC899Qh)XB7^8slew*Xe8Zflq#-NP=fvXcXY_MX#8uoKxpx&;z9 zcwS&f2|YiA0O44tvQ-!M9nEAe@5NHP_Ne)x_-DTqRgG+M!LYa_6GL-ao5DFH1TrlE ztOgUV9)GSW9%lMvVKzWGaRzH}XF4WjaVZ-dE3ghoZ0ywwDW@!a3~UE*y9=R>1k$I7 zMESGx;Z{iz>j2(VRikq-*s+FY%?&wu%PUBPHgZPD8NS|e@^16852DFv!3H@MQ{{#( zdYsTlkLA*TO7xekd#-T-tfi0L>y!7ZT08!6Z^or@nIJZZ0gJ98c<*ZOIYSN~@T#tw z(d-!!8xeQo2)1^grQy6wBrJ~ms9=GiQ-n+2_{G0a^$V}i3R{?*mXdnUkw*Dnm)M!L z!Pp?(ee&m}KTw1l*-0URmRI*F4H56bCt(6H$qrr8#mL5Tg`$Yjpg$##5E;!s;Cc1e zmB86lFI`Ei*wVuyuMdBC0v{to9Fc-YM!7l5gYO!TmXoy?$Ndc9GB zQB&sG1K5ZGuzkK86QD{n;?!W|mZBo3;)+qX42=?9F8eiqJawqP<9kQ-eaU?QYsK+) z+jV*+%!0C0Y&k}&PowHBj0ZYzTSd41X%2i-$elBwR;?7V&QY*89V~dC>ROaD4S&=X z8DbLyfS63@A<=Hs9lRWUFP%!uCtsv;H<#5Hr6;>cfPP~{D=yW{BQePqw5Rl+NljW zxDKwZ#ib@&NHKl48HQijh}cMy)S^JO>V}SrdAsn2=6B&47+SShNn9i@6eIObERPH? z+TI6?!AdSc<)ZEg2G+E5fv+Y7t-R#R+b~gJ-%PU4S*5T4|yk=P2}=*d+`&S zok;z!l;c0?#lI;BGb0nz|5UE5%>Pxnvi|$o{(qBl*pZAN_`VAH4k6HS5jmKC`tHL3 zixZP03@aj=JnpriZEfn{4UIyP`|+x*v|VuU@Ujvk2x8AkyR98pNvWam-3$}D0sc<> z_IUffJb3kW{n(4jxjDX;eOz8|#F;Vv5QhoDX%UMYRCz?9O@NpcVn;jJ!;eKUk=

xuf1&Wb4YLXt~NG4MbK{JuOYqZ_irZ z?_B1ZacYC>6(0)|hx!h(IV^~hG~Q{LZcvV~cL{9*LmcRE?Emo!5fLw%>U7*Ad*qw@ zbuSIn>jrwx)eGR%n-T5_NeWOPqM^UwBvekJ{Z1G%hP4GdrUGZwV1_(Z!)w3jYoj>IX#98Ue6jjEW0!!bBNVk zZ9QCf*8`L+#rDm43sSN92}!nBB(o+V1AAh=9l8h)n56*L%G6n3%#WN zS<3??K?Rq%id(+etcl8{L_4UK+T_Gw)iqF&8o#8HAy2W=a+koXha`Q@n?K4 z+-6=Yx!eMU-;NOW{Jb8fIDl4waSUB$6^OfZs*~PA!h@cL0a?Op!q|Pv_$+k~g+dI( z@W8-)s}1A-BkmmoGi$bW(b!hU9ox2T+qT_FI_%iCZQHhO+fFCxn=fnay}o_czW1Cz z``kaT=36z#7&U5)s%KU`HR3XZIszl8r#|WvZa^;+@B}+#04Bty5*s~aiE?6?1yDhi znuBYQ7UQO#Y3#ZO=-9O2pkvw(xqzlyaU;Es*qI?0B7P~VcVn>5vTt}>Fb+ufXKnpd z)C8hwB4jz?cxIidz2%7SJe~Z*eFGQ2?;7GQ4aONmA}nU5`}K)E)PZ6dU;OzB;Le0AJ;D(t!>!|xENb`cI)E`21Q}+jymhEWSHsrTtGN38VcDq z0LWa$ec10yD1*{U?P%L#{971{FpU^x+x{}$kFb5XHbwj}BX9md^i1fThF#lZ`)^Ub zXq~3RCZ$$qw9^AdS*2c1AUnMhS9$XItA5TF-I>hW{roHtnWs|UIc@;-$X#?*hCBD@ zE(AVwuw;vEYkBJTK;D!RgKm(HVU|;4g+K+svCC1yvkPCtK7`(uL3&pZ7{e7Z{23?& z@<M)C7QT!r5*T3{MN)QGjJtoU78=WjZZ$Zs@4WJDoMoEcIwc^8ZpHdcRZvbBg zc6j5J78@oA$6cGT%S$lkVoFtoWKFGmz&@codc@xor=l4KD#nzh^|*00Ny7VFo`H00 zyr1J+I>pq$z}0qY;9jV~{&-%8N`xH9O=1fMDffFoV8~RMmeyD3Eve=BO%ZD1Cyns{ zXXN;KRfgSo?@Aa_X%cF>2k(rS=ZLmFD14ZWm(S7Z1R$S*N#L4M!61SRVdc4fuZV7? zt(|{)1JZ=2iL2z8I3#f20p2(*`B*-}LhntDOA0$m%T90A7p!Fu-s@xfA_A+9w){ti zycsW~nsIZ7?hA?0`qlZwdHTx%bU*I%Wa1S2%HoOf0 zUWny3)Gb29Bv5S5cC0oKt-=9OKM;Ie&XtfHz*L7X$QEF7X9~S&9TL7WS{EQWrfmc` zxkWoL7z_#=i~xwD%wmicA`H*6&x`M`ry28)k4l@6PU&50h1v|8W9Qbr=z*8`@$L%k z;OsH*$Xv0F`iiRZfm)~ly|Jc6H1ceTu_h8D@)sv)P~BZrO$SxoU1`GJf5T7-rxn|~MDyfRB_D9|JU}ti-bI3cDO4Gf*PE)l6L_>r;_2wS z_m+Xl+6BG(a%E%ZkxL5@FyA(K{k2lK45MBQ!=BOttpr88|Y*K|nmG+^nI&e$5fsYLI zXipDVUa-IQ98yoO=?L|0;QZ>0(ME7!aptbKKq{KK2Rqx zNzy66Y$7IzN1)|(?~p8)9yJsl@&sBV9=5**tSfEA_#9Bd!5|$OGcpwl`AXgfU;2>5 zFq$x)l~j@_X{B*UIO91BMKV+BdlQZ>JPg_Q2y*7Sw8q1WnxbaOkDlXQ>`KK8W$~>S zWU&gEPn^@&G7pbzi@_k-9Mc>vXF;OME%FA&ObP*f@B}yg7ah*eZ@^3HM1`E39(Cpe zLf3uA*Fey$k7!Z@LCQ=OhXR)+_ADM_o{-H{;3H)$4jfs60d%|CYnl;5)nhOWW*|Y4r1@Po48abgHLINHD%K<)#Z1A-Vvz|R-luqY z%+8Xbcg&8N8dDw+P8yhVXKB%u&b;}KH|7>5$(23HlaP&<(wBV-_00X9>kc@mzNA!q zuEud#&YbgI0cMvcBhPwS0yOo{6er17rpQgQbasS8RC%fG%qClKCc(zHwjfc;ZC-bv$Pz}<#A?_CDo{VwVpciJ2B0QU4A)(pBC)f zOkc?7Sk7bV0RvW`*HM&IrV+F#1T>+Hg$a0xl1$(i^IwfmqoQm2=7l1b@h1ps5UvEz zj~XB3hIR7)R6^v%MGw9un%Rr&zOdJShP@Eg?wGOfW6&>s*y~U(v$uYHDCSmTo?vzm zgBMS${}gC*m5@e>7otApp$m(Z5bQf!(aZ?cZ+o1Sagd*Lr`C1 z!!DWyUz3$ROpovBJUQ@Laz7b5j{u~6GP0zWhD6){;n=Hy=)hfVNzyyQZ<8;I#=icqJD*9uO+v?Z<3X?DOd<8QMLJv{kY?bO~atBEPMPe6Y)%;c5p>n zllfi_^f$ES79NJYNIp2Nz5t1bfL}3cD&Ff$`E&W6nPN1Q(NI`p)bbp6T@inDar7X8 z1YP{$MNCR}f?GTMb@pOz{ldgBs+JX$!CFvGgjaxJB_1U>{=T8Ok1pv}V6 zJ`VRP@DZs8p(pn>RCq@oa2%t|hN)Cp7;_CE(OQ( zPduq_C3{gRuRNGmWQEOAnaT>!AFw>%_N4`<@}$^_9S`>MW}Mo?^j?9qDD@aO0z2+x z+o6l<$NBim_w-;kwiM2y4&AXVmgQ`aVa0J3$Pj^x!o|<|2>TH>+!VBHk*io^fAHWu z4YL{Q@6G=%YCa7xoH|{b0wP4?o&l~QD#ALsX!lsFB%)Qp$&x=jUAeqS`*ql)$ttyL z%#C246)lL6*{~;XXZ*oDL@sEciRjJ!-5=4Xh{xE0*oTa~0HsY2u(;Oo;G|K;NrVcAGHS+T!+hqXN_&@Xg2LUd zLWb8;s2e(w9Z2tqJ!$iT)s>~FsbOisy}!(The(-d9aVY2Yj~w9c?-16kiL}GX@Gt~ zwsY?&&jx+LPLs0%=A%0FyEriWHe;S#dy8{zLA1xjojQBlFcaN}xkI^QQ=+|x6Y64n+Bb~z=C>a(3eYU;ualY02^|iGu)wlYbhk3i=N}Q8MP=j-MOc``=3%6iB~)Hp|9CW)@kn32wpz)Suo}S8 zonHbaQQ-L;gRI65#3}snH%0s-IO^Krb!cQ3QaJD~F(zEN_;1hw>tATX{}wtJ(9(?38u(lw0d>GC<)$yQ&%O2(_B{fh4Y1$1 zfUGyh;75eC)s;aXCc-Cj;8nr1VLCZktAIitZu+XTpsVbq++pi#b;$YakK`Y($HV<| zthUd2zWB4tkn10^ES-#Y?wynGR1KTlY(a4A-K=${pX6CxygMb_rXGg|rs*jus~KJF zFE&@C9a%++6Z=%no4o1s=jk&xKS6o5`rzvnM$g{oUT+?VOe`zbd9!2+nCetK{#eDj zsA!zMkF8#_!xW-?BY39@U+wba(HIvPexHg9Xep1cpF&Q4G{s(;9RGbi#js`hw%Nlm z@iDZz7u1TKE+YmycOd)FmX%$HRQJg-cieWOG@(F2d&;7ObB5IAkCBf>TNkO>+TI6w zPsOZ_odO1r;_VAdcEXMU$O#2mk(z0|)V!Jid!ue?2?9aa`2O^=C2QxiLB3SClA-J4 z!|r5S5&Z{@vv!?Q_1hos*z1uVm$K<=7?2Oas*IkJeW=9kr><_%udS(ymJxcuN03?t|~Xhlt8%MV)SRdQByyU zGecxBRx|u`FvLExbS-rUJ+`?62w{t}M;AO6F*OhvHw2o%6m~0*d@oo}2juK0bCe=9 z5-JQkeoaKM-;NtARdeKhi;Gybvta?@5>XE>XMS2r3&kE47y@3=2$k>VN>+d@(?$c8 zn80z6;Ev`A6Om9Z1ypF+GUV0By_a1*RT-v9{ZdlCUgk7+-WlSfa0?peinty zU<*uAK5yKlU4bZ*u;jI@1fn z?;z{cIwOFAJ>Lbv~|HL-YgWB z=K}Au9&^O@3Qo}wNccz*uc*J}m9aGcxC4gk;}?5RlL8t>4Ho0!U=PvC^XEIh$Lvg* zeZvqn{T;2|FWEiNDh)J5ls=rXa%x3XdzV9`Y{BpX^gRqrE8E(zr`4vYyU9$4+z>gWLuRRR?FMo{-S~=vDbWMl=iCaq8wO@Zu+qc)_(us z23EQ)g`i>!R5v3h`XwLmh@A^iXdVO(0ZMtQl;S6NjknmD4ctxqQ%!9y9Bt33=TL+d>*16^>E=hgwi-pp-wuc$vl zKMl2~7+UJklE)^yd!FrpiHm=z9DznC6=~$q^04#1yzXDXIl*GUnjWJ@@u@eSh0O&*JoUc*OYF@~`6g^@q!&`S;uiX_N~a+9NzLKJIKz zcXVssFAe;)0Nhw>Jf>=&RkLQ>7^~k%*?=-azoM-hWk5SY^N$1du3tU^rl-;y+)yOZ z;G;M#Hwn48kJ_XBlo-Se9+r7A6%eOsTidJ3IB^6hQSc-A{7dQU94MUms*!>P)(74w z%+XBicb_HKmJ_^Dw^2Q0Vclh+j99;m^BEpPd9$%`Du_a9(TE#Z)Xq&rbKW2n>{%oqL1nxxMte;fIc@QhO)Wa2g=V`lEb^OnT!Sp;{7hlF6elV z!EiK-v0K!vFSW&F8f-E8Hf@&Ww+$p1JWl^=ryrMXhkfxgXQ#j!A5e*KT{py4w0c&Z zaU5wO(yWR~ROBW}98Wo$z}x&=tZq|7J2fzjitY%o5v`0#YPr53oWb&5OVQvRLj}W(LVwecFC^Vnl9KB9MI+?6-{&;)tK=G>o)T0Qpw@9ei?&$ zl_oREZw$vvM97M#*9dJJ%@HFh(>iG4C0OLx8h?6OqZWX$p|9YLAmV^)4)fr8OQ<{T zq_9oki=sOW2oU*POfj5`2;9lad*uRWK(Ibm^OIsc=;`~)p)zwSZ&*e=dDu~VO!tdA zLinNePDF~ci#HLgXbTgId-LHLSWwoatU$IvmvE%1`17vJ(QY~=*zBE>5HIjl>_-Qk#DpgU=|_u zQJ;APMOH=Oo0o)fVLvdb;8lmh_eX7lX!{hw2hPrBWwd;fH}WxxB2=uYj#RDhRb`Ie z9b#7$;pYA{q-oa}NV3BMH4pR~`l$2#gZ!%!9Oq4_0-Q@mWY0B)M;sZKV{xu9HKY4H@dPM77e$|39&Mp!v(t-bI25iC%W^N( z5ysBd9KXZ?dyQcc-AcI3?=HOEF}b9KR9r{P1AQ#-7_rvSZ&-J*%4AnqC+V3NzGjZ>LqUO3m2UBdM|X=BrB*DTJ9%cyTkuwFaZ+K&v_*Lfh?}lk^q*if zjouoUam_`B#N@K=jheHFpS;y6Ni|px*H}!OS_b7R@*34^d0on4%iK^Z3EE7O2EOG# zXbiz5?jcnNOlT&8?ME8I;2fq!H=5sYp}|}_Hx#hm4jVEDW#BvMYNZ8IvXonixnHl7 zEC#9X8G0rAgejc%#dFh0)8Jh$8Q9Z$xBy7|ZDXxUQ)tx*C$UPz;JD8iFcTNXN*LQZ zz>BopYL$yY{S2c1wg^ymEHK-cWc4n@@{^bL0cO!vWp~7m6(TdnmJ$8_0h~M%vv&F7 zfgL487>#>S8Sd;`+-`z}wqGp$acf<-+*`xY6+WGFF8kM}rHQS#6aSoUbjVLv>N0FE#VKO!I* zAdX)ia>xn=R2m7WI8hk8vk4HC_9*Hi`rSDsB0ZnD(N^)!$ zx(d-TEJmxr`K-m4l7LaITGi0RUOL-V`Lu|aN&&`lwxSKj8Z|s*kc2 zTWbx%Tvf}wUaHmFp+VVJ4+)LT%;w~b=NipWj+M&p;=x?d+nMU;<=RSIq46EyHjFhhPa5L?J5VaiRYnE@UJR>oh$6zdK>$Wu zDx@JSEig!18c#W14763Bn}5VE_LG8$5zA&6O;v>b$YFz*m;KL~YYE8A@xWNy0#d)) z6YV3*;vllZ_8w-#>>OO}G4%a6MDj(OKp;;OmEBvz)aeEd~^9CQFI zm(h~)FK0YUk#u@8npmOVsgu%g<_`uXu`V>p42vBJ*81OS&8B1{2kpHS3SgeaK8rn} zeJJ6D#Y3+L&hd{HJ;#6p`8H220bBYZ>#Jk)ZUVv&xEpv5h;rT31%{lGbKI`qi_;-k zXV%S_E8skDv3%fE9O=|T3*48?p>KKErPkqYk_Dx*vz8(4$$FMIB>SKg>K`f+T#1(y z5p`B}R(pl2*&lfgy;6;<<3H?vXfQS=gkw33hjj_fvN0?35Rcp^=HFC;pJHK99cb;T zBAE`UH%Hr%l!=cvu1hq!kJ6aN&)|@=psyaAfh%6@V)`I0{px3GfCCwe)KPxfc$d7~ z7R2n7`$pI|(9w5-CWG5-mOQGf9Iu4xp}D^tIbo>fzi-=_#=U|nqUe41Za|aeV{47- zKBYTgLD1kTo*?C^mQL~HqR(TSvb zUdVo1(8+7sBTojjza~k>Um&T#zae`{i%;oSBfFk>0TKT^(7*)ePa&9~;Q`uJt>QKH zXx2Fy+O9vGB*R*Y1G;FNh?)~kkTdsw_}E%4|7-ecwwU3%JC3TS|A?KvLUSz^WeD-%?ia7YeLe>G-28hkE8z&f(MX~mDqPS$xE^S) z7Mgaq!u1`GdQxTiJc$g+ABQ` z<6J_ebQszy^cJxurUB4#QO06af>yW$w`FZzQ?gT&-aK&!-*e9mT#v8~>sMaLJ@5}M z-)>TY#!#{Rd5bSpPbD6XwWBSk5M;= zM*cG{f7af1;lZU&vsKHzz1c!XppK`Na+vmiu!qfNs_6cp#pm9?i<8f!zMgwy4!I)g zkNh2U7i8>8@cMqhpC&G9_3=|3;kd`ZL+Ufb_0_gFIJYBmOjI2ZW$14$?GPAz=(HHS z8}0?*7<2bn{ocB%fJS5FNfvEq!$z$p%UJ751?SCDO=&`V`~=ijkAwQ~A39F1v+ii8 z;%nkuL6YvExBXXc=i2QpQIe1>mg0b7Q!3LcQZ&*6FFvqRB`A!QkDWkna<9GrP?q%Z z1$xk$o@`CZHlnMkc_`{rQ*zB&u5EzUaf}cNY%?@iYem~lH<7PR%Nz98hr?xhCEF8O zt5K$r*b3|$2SA#15Oj1ai^vWOK2*zhLzPQFHjD z0}IKlIW%Zh)6Jce7u53tk%E5Vrz26#w25QEE`i2isj5|)b@iQ+iMKV=+tk7}NW$ab zyb9sl4=|c-!4+~b{gt!{>a-?icu%M4L_eP`Udc_I;fqmEqpqnbMT2RQ-3FA}s9|o- z67nWIJ4=0fQsO{P*D0H=caNtv+Nz&iZSPeXpD&>ASCgz+yH#yj7avZKFB>=$!h3f@ z@m9}DNC+(>N?0Kx>Yfb3h;2fIh(Z}F>f(IkEr&b~(h#_5{vrUm=pa;g$=BQYb&2i3 zQ}X0Fz|(mI4lq`~!I?n#Ac~?Z^|WxfQJ&)&lJG(MIFk9*E+9IWGw5Olzcce0(JhFg z3$J!~$#T$8GL-izF)w=g8lmoB1fUU#?b`tJlS|^j-WDo>I6@cq=nZxYp)8yc22$BZ zpQE~CsXQWj-=XZf!K?n*#Em2wj_3N`IAbLv0lE#R(;Cl&y_^0x?JI*UrzBC81~7n` z24Z9&hkaLFhfjpdoJrMRNZ%DZnqy=Z!#xRvrq6|Km-qmm3Nu-5@JMmg&M3?-koc6# zEG~#AtZ-WEeoZ9NVlI)uDA^eV5ZJvd?A4ONkBU`SY$ilqXtbufT_C! zwI3Ay3VeNc(4rI@8Th9TKly$IS-MHE6EGk|M1~U4Aj=f!7M#gS4o%Q}XqcnJO`_~Op8tco{-mCm zHc+l6_+~8Qa-VWCNqYDO+~{puXRfu_OwdZS6Nly%LDxlqVX;2Mng)^+tdao=64|7@ zmr08?Z5`2d3v%o#(I%>XlARC{vUYhPx!ifqu&)y02Y^C|(JmL~m(uU^_65%s|X}M&W^W8BQup z&3^l!@d`cFd^V!=lt_=3&jUvprzev~u;#mKZi+c|PYh%#X0lo^pXowQ|B19%ucH^C zzkM>^V}jr`LSZZ`et}z4%L{1N*rlmBo^IBw=TEk?28NNowq%QDB`}=+D~?Rl=#pWL z70k6y3_34wloJrjdC#n@$1PeYZW3L%?u;)h@%zn(Onzz$>j4oLdL3$~>a?j35Ay+Y zAFK7U4ylJCqa+}f?rbKxK~3`Lyw--$;N~4;iDXE_cC2u_eSMjWl=BEui7@jwF1sm{ z+z_6_1_>m{%-&_fFt>g@)pPog*6{qgM_XLDF&UMe=;)?UZIK#VPBeAa%#KzSstMLA za~BIYiVn)5WFD4r7Q@2^JUEl{O^>WHoSq8nlPIKq9*I&TC)iIOo znV!xrA4ykFe|UuGmqzfy3PVLSDC-iZIF~MW`(_{#);*M{zj=aOJ%hRLl>3AJyrTHs z2{TV$=71RAD!@5Xz0GIUA?&V9>TH4@itc4J<~jqS&mp|k;C?EW3q;S?eGx2(Ot{NL zM@4WrMhvwR!kAz#UTNIO)oH>&U&IiAZ(4%F`1|+7jjDOOj+KXg^c+PXYc|zQJ~>usHCe>SxSFqasw1)T0KiQ>LkjK~f$k zzxh=ty;rW9#!h%Kk^J-kiRxuhZX2DXjArUo1GUr0iLX3-1y_2A)jO5}98=^IV3+;_ z)MipX>rm)CW9v^GZi2#ahVI->R9xyo@}92^32LWTXex?*8`p_MMbq$ip*1b zSTkl+!m~Lf3kOXv!|g(yj*ZG?soF4ZP%VMwz7M8+fTYxcl$B=kYs`$vIE0_nNBGpu z_0!73U=f#Nan8TPy6sbXRReIS zJE=1>3P;f3i&-ss^GOh1;Q{spesCW?3bJBf3c5DBqiH^%85FS>_vEs2I7%mU9Yyf4 zDTC(VEVWfrFJBmGob)snpY}d_Tx@J7{91%DJoIvdeZ{HNTVE>U*PX1<9mqae161J# zsKo&~0G@G}IoA&2hpqJ8R1s?kx=FaK110C2sWni(k?P2ARZ;8id_ZL*K}!m}DNJj< zn~Bm|T~EAV@%XfR&6U)wO{V6n!@+J4l#<1Ca>= ziDuIV8rE#bx>Mgoqc5@lIV^Re_q4Je*>>yF1KZjH56)7C8tH0me#XTcBICu778Wy0 zO1RPXG}F<$I=Q5l42Lw1YVGESGMbKiQMKBAx-OxUA$D+@+tbi6{oV9z{Q0+n856Z; zLZ6NP|5a@o?`$xSkW< zwU2vpq-2oh(~{p7&w0OrQLCc-BTp0vBet8&>ESp z<{OVlYdQ1$(OHAUF4)b_QQ%Ib5(?vL-Ar>JzO1-xuo^vBkyE;p7lPI8c>_1^Y5gmA ze5=r`7U0(_j>vy;ijJ9lKlfaGCUWFnyorsb7F`S#u*Q>O;Ep=9cn0o7u1Q?s1miO^9$anbGdf}n9_-8Kj%HUx3g zAlNQUl+taTFIo{cK*d|VKnVP)>paK1p8n?Q36aqQ0e2H1Pd#I55(8pUKQ9 zo_as11d$S6D-DaG=C`h9_+~6Fg0Xd=)pE3=iB`zd6hn@}v;R$vVyFX=l>lyS>nBd! z)XvP|o%1t}ar6x8TW6N3gY}%La7QO{)A65)FnY3Bf?!)$Q=6o)!nN(!pYOL1cvv5a zb^O7|oXI*{C9V+@^PX?J(cUY^o;^s~$H6RAU!nn^I z8H9Pm!mjLuHSnzskk3Z%Aap@7?8f4(&DG!BvNWN}h%`f+JXn)5Dm$qFmM(-U%KYQx z{IMi7aTn&|mk1G_SeiHjD?zbJ8%N&TaADt&p2l)ba4ew5lI3~xB`L?&8nq|eT$IhCUI#Z4e$F4 zhi%faH3@69iA6_gOIYe32*Qt#myoY!bq|jB0;3lrvRLY?lC*~ijf;C}tC{WVZ`Hr8 zkm_z^KEpE0#Ray1q|K8PLmd=B@y0^FDPlTI+nD*4DP_XOJKF_wAy)22V8M>)+@>4z zk9w|@M}tNIb5mE|qL0n7f+W^9URv6zq@p<@NG})K>FF1B$uXVIlt(D!hTbJn&=9n) zn&FKx@fUT-VDEMa&zK}bYD-rUM+gM*s35|wjP>(sOn=uO5es6>iO*1q-3mtcZKQFH zbr15FnQ?Z!oMkE5T#b>1r?S~ok{bNMZn_C@DML#73*}bp?@SjPR=}Hv_pk4)?EYsen)+{mctBLvCPY{ zXi*%a@(#56mOXc%UuhV<%=uIR%yUF$Ah4$+DYkss0H$Fup4TC~gpmG}%=3zAXr0;R zJ6pXZOP5NoKyEfXf3e`r~t^+7|YfB4wfu zD%~^86zGo;cTYNoEPd7vYquE?q0v=PFrW^lsdUj$Sz36R&kgH?v3bIw+!tPs^^@cb zq7GpbvH#7g{BDIKTT^&3W*Th*`!irrYBT|xn0<3XBAP?0T5UyI-GF&lnwVWHUon%$ zkkVg1+V`c452DR`4@O5ndx4=0(i<;y_VAzsBi}H5LVp!V)82F}5-LAcG%rNw5K$Zc zIqmdoMXYa||7;@(^vc)U(s1~UW}@KO#UDkMvv8ftpjm&2>g@y*EWpGD6tz(Mj|J#H zD(Z*NUh9TSuPYZV+k!DDZkR1$rx`rLMI3$kfq32=7^}EsnDFEsDAaoA?a;YK{3d~d zfg?%_nsfvRZr6JH+e1*sKrf=cX^AWR$RBfKb6~_9C5T^gK1pVX;?__K@gV>p=_LAm z0#{J4%D;M-Z!_-Uem?^6A;04N3~IQ%jOB?>0{r^Z|3)~PMol;q zRc{)Oao7=mxmxFfv*K|Mxf);>hJJE0KiS4B86UNtKY+cJ`f+Z;t|^7>SPI*lP@M0a zSrdogdHA*!>H_6mf^gMBdP!dXVuFqbVq{vx9D8Sgyr0rXK66EDy01Nz# zG^fi0`DoJ$w6Z&wW#`rawHvh5b~@Dj(ZYIe`g|bNu!K;=)vpLXFR!%&8)#)%3GS_) z)_v8l^^2md3de^RZC07 z>q#&~w9Jg~q$|O4?rUGk>=VXA^JNgntB^iR*ZwR>2Zrhi!fp&3z_O4&W}?%gTq#ER zJQ&wtK0R^X%x>l*zZ-y+YC+n!M+t3D$OtZ;9wByJ*!k3y+j1OzP(2fmJTCr2vCt39 z=Dg5+9lJsj?BfeGEmm%d93C^>SBd<$DpJ@eRQRs zB(fWcHOZxtV#Mq~-b}cp9_W$VQ}~N4Z(CAjV?vn3`Iq?89YL3R`WL^WM`i^eLd8Tf zs=~o-@a^ZV+U@ujgM~t4NDWmA38Fjzmsn|HFuKcnIhY5AfGTPTg5nR`W4KpE=_CNF zxorSAt%YJSGvq_j0TzeZjde&SR%lote~#3P$Rp9G2lELT27Qa|;rQCimd3T&lEU&O zM|Tit-tdWG9atbVsr{T{taVk~J*Wmi_phNJm;pA#)0T@Ij=2 z^L7p%vQ%(mRwF_j%34WZK1M*EpUH|l!mQ?X(JJO&RW4F@TNZAlptRQjcyj0_cG;P! zw3^&#W&oY)gg&IHloFz0X*s~AB!j%U7A5bl8CqWy4V;7&S>CjbX_w8~dd0i@3Z7Dgi6HLIjNlzqZ5zU0of4cK+%jI0OWy9LKcilg zA>!`w=wX!=Cy{Z3a7U8Deg?YmID4dIC2vN41RLjjleVSSZ`IQ*q$C4ai8$tFD{iWn zXI#lUemv5wB(WF%Ov!$rTNB|9s_4U;q=JLe$YSCA-WRB4ZJp_&Z%XTgX*B!8#l&d1 zAhB7JL}wR8LWKh`0Q}76_SUKs{UjC@Mu->rs5m66-YUX zNkJ}DmYRGqSh7g(vJ653;V()@3Hx}EL~&eV-ycr%sS25ziam=3qyg?YqGQ|Yd;k({ z6t&exrquTxrwskfL%J_Yze+6KzT5L;xa$g>C|twDtc6e^0jE2Yvje$?1 z8y&PM$Zt7E*}fklVkvm!={Iqe0Lv2i%{xA?%ZTK_e9U{^ACQTr3IhxWoVxs~b+6Gu zVms->oRIu&aR_Pu8#D|?Ytmqq#|h5Sxx#I{$~Q+4oc%=MymV$o^JdentV97t^&eL? zYcZsI+N{d>7)e#~W^Otv(1E`Q>SU9(A1#fj!iyutR{Rm6w~NAtasg4($jzt2GYSYm ziYyNFfFWw@B!>`|qpB13DYTX;fO!J8WOZyVH`mr%o)#W24i=))IJayM4kwT9r#5VP z2djQ$S^cShx!+7QlK(?Q=CKrllx^Q7J|EMEZ0sKB!Oq2Bx-+hVFIZYc`ZF!qAX({5 zS|;*d9e3^^fIDNF(zoeo9>wE4l_ziRo1n78El3EAyF}@+6m+=&P<9k)>(UMian3zT zcv-Ij)_A_ghYsl4led3{U2p&N!~s$)Lanre-#kFxC69#Ti~`))y@IGvn8i-uyx23t zuKF)H^gVnv)Z1@+BJ(r*$cOd=#uGHP4aB%){mjn%8SqZF*L|!B_u#})9S(l$khGgi zLYr2B1gnM6CyET%wj^b z(%(S?<+v2C8@Z`>7xUtt}{IL#?(G9SNWTpKcq1JYC`JaZ=_k;q<|l z+P3H&D9cvnc0C5vJf2L6h)mif`_?gN8iu6f)-T|xS1AH4I3>cl;keq07B<&%)uzk8 z>xrEf=aY@c#1drdVRtdkt)D_a#uFb;ZabioGLG%@dVEsStnC`6B+8!cWaVQaJ0t|J zpG4`vQ`m<-V=^10D1_n67Uqcwwq^f3dciC^b*qM4MuL{Q3bkWTCU!PB(k|l0&{~&U z+l3#a59RVuQX5#*ch0R}2mH30VbQmgK7^rsH>STXy|q!JL5y{&p4Y{)lZ%~De^=90 z{ic*B1@~5wDK(wb?$}j;_rnS-*jK;>ua!)_x2D^z8nz(-$W8Ch;9^5#C}*5Djr?il zaJR^*Oui!Q`uopZXWhhoVpNXV_*PTo1)PDyNGN*x)e75AYEF*p@SttV5TnEm&I)Dc zhV^ngljIA=kL1eQ5R^1@@?uwREisb!AYH+MP6_AzRMQ;O)XIjE=T0Us&pWWav$U(_ z`aNI%>%27ynnK{?OC$vjXPBm7(`bRpk|V9LHIIj`c`A)oV)hdjYzw>)%mk2y? zo)U_VvDi75oIZRsBr2!m%xfH{BJ=F`D3k~vwh@gnbgjL?7s9R1{o921Ya;vCgqM+( z@jthL{Ea|D$=%MFR!-m4m{!`@$Xs8*)(ubdujw!gJp&#qJA*b9t%9wSzLPN?-RHj? zjBT9o{@OyK@cFZ`qph=pp|Rs9*QT6_Mn}9a_6n%apFYL^OIC)zP00Um2*~h768cX88U7*d ze-ZHOXnBRdOZb--e~J33{r`Z3;?|!nBKY5!lJPHw(@*QG$r@M~8-6y%-z8`KZzTUZ zI|^f77^A46T6ziY1XZeSE|3!l@!rZ^x zp5<>F#QtyEp5-4=;XnPF^`Dx2*`Diz#{d)9yU#Q*4-tbY%B ztp82W``U~5cMaJ7XQSSi*ZhBZ58M9|TiE^{TiE`a*z&cc>%VC5KO0;Aw;HhjFB-7_ zT?6+2MuRWp_wO3~%l$ut?`LYn`^t@uc(jt{Mvi!zQ2&SmU-?M^is2uv`V~08;F{)Y(v zh(`YkHh<~%cYpuSd<#V@D<_Rd&%^W2Z2Fac|M^b^R;VwV{HvO;eEc6*=~U`^hzdZ_s+t=)nc>m1GC|Rb8JnA$IpHxdvOv)a zm^(Sj89NC6KkU5)P+ZTJFh02Z5ZrZ!Ko}U@NpK$+EI@E~mk=O?$ON~*gx~{%y9G#) zpb4%4LI~~&7J`41-;>?9`*#2DZGH8x+OOWNYUbAMdz(Jpr~CM6FAr}o&)@8jBxZYc zarbxdy>sub(LDz{FMEeO+76yhn2*IF65{gme*V4=HXg(`vp4$yawQCZ;{dP+U@oki zdB9x&IWY+t2@yFNDH$aNIn^z0x?4ctt=sGzjNDKm32{*&5fN!6Lse-xU3n2q9F>Ny zv8kn%rKF0Zhl9Dh;eAW9-;H2VP*UEaxdo=91DnZ+$e8`p*G&h2iV(01sKmkI1YlEP z;ZR}Sd;qXv`iO`1$Mw6vzb`Co99%qn0zx8U63hz?lmKij92{(196UT+Tuf~^rXGMx zg-6W+QNpJ&up!{|0g6N=iz*L2dt#(r>%+WI~wBECgO&%nsT%f}A_L&d};B&DS9 z-cwOkQ`gWmG=dwOn3|c}**iEoIlH*}`3D3B1&4%2KZ$wz?D-2sa!P7i`m2mgWPU** zs;C%UQd(PA-_Y39-14@o`$JD}U;n`1_{8MY^vvw%xo^uWt842Un_JrlheyXJKTm(1 zo&Sal3xM+{urPoBE?iU?xUg|?ac~KK!-a(%^c!$0Ts#g4KDCkofsGFhr$`hbP&p~D zrjv+E6!wGG)_08f7B}=8&%tld{($Ts1MKnt2(rHd_HS^_0Z4JMFq4Nv1yBIYVyRzr zv!52iiuvRx7Z;94fVqHoSEZVCAHPIJXX`EQsEV(W6NEZHWF|dO@~Q%U5Kgua$s!z{d`Tz2aklo${tk5ock-^UWR@yANg*!3PZ%;=ht4T zg<*(dRwJE#u$#WRcw+ZgF<+*Bdv*dA0sQr8Xa-u5eD_iP=TWl(PQO&iA(dYLp`*uG zXX>jk^wyA_%jpm}B&N zb&Q{V&@MhrKN~r{f9cxxHr3BkwpHA-&mHOJEq$e{RWxS%Hb8O1*+PQ(;t}l|H^J`N zFKwIjs!^#`wtAse=$-VS^h70~a}2p@qbu}XlO;GfZBj$v4)K>~71Hs`h+C6&o!m!i zyk8b!89#hyhoyGRQgoB0Bm3CxNTvOT+~$X06wQG`fUlor?48^Am}=46iWD&*GGGij{DpR>EmF`@nR*uo>Zq`ra_i8$Mt0pU%bmjbze%4{*yjj*36Sq z=`ps?LEunfoFmT4l%rMT$joycu!+KleuArGGJtQK=QAEHiY@&!0tPaZl|ze&azZ^v zTKla}gT%5PIiamIel&v~v&@sh8`%PmZVVpFE|!nr-?z-I$R{{j=;(r|%3srS;xhnN zxUchH;td;xtGf6Mg_eDuR~PhJ??wYfY zUemC<0R-N?a?N^2-XwKcS@hsE5?bEp_YyaHay_d~{TctRK+&ttCY&qyq|WtW5}fBp zC5r8f`q~X3;0Dl}Xfg84xb+F12|a5mc=ZuSi{Vip)0JfD_$D%z{Z-v7oVRgb2hrid za-i5vg>O7~OaZL|wCt2$B+rd0A10e7YYgxfKm&7$jE&=(RM+m;5a74U$!}G<+oY?K z_dK$dVf=OjAl|x^NBRGBPzV{gEH&kF7Z&IrcG+$1g?xvPV$OpuB8Xov%r|+EarvbM zJu7~hzA~QWU3kJJiR!Rb^-DqK5sGMV$G7>IUh}8MiF3O@JdEJD0nE_WL`|{^yg4w+ z6n_!#{V77}3Y05#nYh51E|bY6Me0hL(sL&?hGq19f@}CPk}FTVY>C(gE7FM- z`S6-qPpl}(`n#UYX3SqL(j`nzCRbnF11s?*6YljYR1gxWSJLzf_mS5Y31g*G?j=|x z<&3wEpuAaczxs4Q8eQ+kc%6A&4~5!hjYoC%mpwk9Un|gyNQDjfd0q)7hLa0GQUfEU zXABGY6SSX1gx!vyv6%eMpgQ+Dcm=u3{s2t4+;K*EXB8xpB<;V0$QEuH4(?H+KMTPb zjh%|=pkE4i#TRHKfJSC*VNK)9H_t*e;{g26nhc7-V#C6e;=l@^?atd zBH*@02d*{ohFEifhsH;mQ@S(#Cw|9|#C-PB!b48b+KP6_K+5T5{EcMAz6~oB=_A!Q zq^1h3F(&bCSXNG?^7cP#D9&6&DitUNrr5scXiuSXGs)hO-jCvjjBo+x9a8*zjY&z8 zBUz)ziheJwR#ePvJl?NqWE+J zh(yix{-A!(e)q`k{mfC(XO;umXTM%66yE@>-Voma3N0j40@ax!T4E2BsU!@oT&f1v z-DZYnHH{wOu#LA1+i|ubw;xEan?=0a{hFBQ}pTme>7aj%_d$M=`WbA2o#p67g;TJ7VYHAz50 zfT(7XM$@b%tX&X}wY~kyTz-k2&Ij^c#WM36(Xt6y3Ex-ZbmIebsjUvPL<=&A9hS!> zt`A?X5BJb>V!%5ZWitU_dckrOw$ zSD!j~y>0q>_&!N`Qx<Wg^_S5H(ufR8FD1&5tOd!z!)!mQyEYGEA@#vsDg6LZ# zAO?ka#mX2g(l3PN?bMW<$%dyHF$A;5lj_BQsOfz3+9YXatd5Zet(26gvq?}r2cUJlF&a-0OLZ-pnPgl>+REy%r=k0$?2% zmli)9zxDBWIpq-nNtVxeBDwntdObr`SB{?~);Nx4PuL1IL}Y_>myToJf zt$IJmx&rIhC9K3=86i}Wbe6T)1Q(hrVt6eVDOAUa6WB6a#qq;V&ZCjV+zK}U^S0(U ztJy75Vw>;Sot~*RCpp>@Zh9*%x9t=`^aqt~i|h47_JImL>;y+>9~1x7uO&*Gg*BIW zS`42RQ5@{7?V_+lI=R*f%7@YC6a6E)y>%dB$sur##e`AvR|&QlDPN_ZlDYW%150)j ziz!^(2Rp~P8*)Ax@zTCJrmiC)UthIm$E{m$e%7hQ!FPgbJ&R)1~sK98LrIt(r zmYjcX1^M0pMl>E@Ygvd~nB@ObRk+jbo#n?Je*>r#Fs0&B58qFvFR(k}%;`!EKo#Qh z&T)?HMx z-7XY#btcw1f^5>9U_$2{j5nSE_cQy@Y_AliF&^Rppi{+_20#Go3FABIrzo|B57>_y zGL;i?>_aE=6BE_6S^04mCKNwXi|#3Q%k}SQt_7YHMpU`R;#}rOsCtdok05qB z5_^dppP3IV-MQ+ZJ1!qH;^(@2@}a|V5I+{JUiYBJ<2yKP~0^X&=GpcE1BFL0&RaLJwH^3?;K zcRoCI(cAQlX|gIsB55)!WRvv2uK3pyZ^cY?)Mi_6vENOzezp$qi`vRQvA1|XZ+uII zaNAUTHyhtKycJHrU+=9hu4vOunOHz{spY$%1M*e=fddVOgM z!Jo~z61jr)G$$oXE%7T6uW}NXR;}4kcX=LbM6k^E+QH!#-hh!`*Qx2#b@!O-OBu2n zDZPVl0IV(+B)q{<9^?G8itb6Bd$1Z@0O7!@F=azb(_`<^^6$4h_L-MFI^Eg&5Dmnj z$-Fq*BwT(#QtI{5TCeD)!W)68fnS4`=e2#GY0hr|CuP|~F2A07$(Xk&e36M5*)V(K z2OCtHsqlZtn&6T6kfwd$I%mA4^6}d%TEgl`nuJ#hIbzhag|57&{#*#l=xk9*yw1?){e(Y%3-n#X1JF(zOteRrk1 z_I@jmR^Rx;TZ`J(L8{)Ld}*hpBSrnid8I9Q&@w$Q0amP$=?srTtKJ6n?yN_t7LH1f z{S|!PgLTIFNGX=V(gPqIQwxS-p1`QDMks&9ytF9CGIde@rhwNyXqNbOXy za(PF$UiyjtRa%O@KnwBH0ofDu%8$Law^=?Tj?~n?Jw(iQlFP4ClcYtHw6-wffeExf z;4*R|-F_58c{E;4Jzu5_hw9VbXBdV|KgFHE9ibPqvS-pA ziw93s9icv_F|fQh&!e8F=ZV1)dDsDvi6ze{9xCP^R%6XaLmzyg%P}`L6F;~e9skKq zhe436d4gsjM7*S9Yq4co%}N^vP{S?htoXLE*O6HrX1J2R&EF*;z)z3$Ow&AwMD*q4 zSRsU#0Y|FG<(Et0+xGhEG`-YXY`>Gr=js&aAJq#_xF=Y{+;C{8+DktiG;?Q>EgUbG zN<%~+ozVuoSX8UpH6cMg{tQ;*8h8m3o6qlUEFD)rZTX*eDmh6Ho zHj3AbM`Np~RXua7WBXBdkxyAOa4sV>2isb-GAq&u9T1|)()LRft8NbrGsQ?U7wKgm z+kl$3A*Sg_i-R(c7xB_ri2ghiS@NP1S6y=+`1Ma6m+oi3Jxx^OaX z0-opzV7Q9^UU7%28FNI3pMGPedq-CD@zp%(M02Hsi$SIsp{fX-;JJwt0R$`7m?ti> z>Aj?}0T8Y)UoPnM%h2e|n;2;1` z?yxSlpyntf72Zhs43oPoK9k#u{POaByySWTlCY8s#OZZ+0KeSsAUBqk!W`F5BX7Ru zD|2$M#x;$WP{#T_=Y7JiJqCu2=>}EtNNFRl{;r=tbBVd-JFH-%lBTSEvpU;tI?kuTH|hbud<$S z38~`I+0_cDiQIb+72FJ4FS;41-* zw1GJBzlx(~M}zIYV&`p(J2#W=55I{91@Ggc7zSWD{-=vE zZ!R8H0%aW;c5Eed&a1w5Ep}|Kc**>g>av*>T?Z*#BX)8%&-yLVw6g@T=#b2Fd~XW7 z9_U6gK6wZOszblSpCG|idml%>9#GoT0yxlB=#GDn5|cOR3k|UaNbP7Vd(O4jTyAwX zuT($=K2K*ypE^b|9Imj`AwySW1NID>$W{0i#KY0_u_Th6?664RkR7D5dMB`DI6Q_O zPeBN>m=xL3iQ4=S_$6U|OM zekOW?b!R^}$QDAUE0Zcwv$HF12&5eS`}3KlpR~4LwJ}-2ATNUyiJ&IR8YiVY1? z6Vl%(QfO#iAgU{wec&J^_5*d2dLtqU$IETkySM(Yf~RSx{&I2@Hx(Y3b5U@F(s=*= zY!vqx767aV7^na-1+uE%Yxy|APmvr|>Ue(p8;-)LkNU)?uK{rRHYA`$f54BL{Jzhz zm5xCRDVI}_Q=j{R&Qp7OW$Y#tz%=;~Cd#a&R)%~s#FezJt>_sQT=EuS*Vi1MWmp|! zI#DUQ?-Czn&_4j(ocL&XM6;MU+^R*cm}}?p@ywY)*JnTs!X6-on<5Oi7M5Ah=*(71 z^bWy~yj{6)FkSLso5bmKa%H+)jRb!|Z)m*GIbG!gf@w#QUN|_8_pND~E>Vv^u`d=H zHvEOjw=1gMM>jcmMbZ&FlBc*Z=23PU_6QS3nl3EjoRfT%lO|t+6P*O>`#s32rum7? zhz&ffT~GT}36YsT64@G;m6Kj9n~F`^L*e2bj{m-cYRbSJQE~#8JJLBAL#; z@UbSY1fG^AUtRrp{OQr*Pcg`|^}#)yEp5W0=2Ug98s`g-y^}nLWYMFC-x2@;v`}v_ zot#!caVhv%pTC-XPX%a5#qFEAbl6}`+08yBt*^eRjyyt$KeXPO+!>IMFb8PzqjGWc(~~2KLC(K#5CBb( z3qRoZ&F{{DFi-J}`F+9msS+$?Ci#hU&ZS$JeslgY5q9W*pwA^f*G)gr+gb@H-B)w* zXyxA{{se}D2;cw$mi)8~{EMTJfPlXaJ8U_FNJWUh5KBWv5CAmLQY2ClJ14SY|{1o8hNbYVdF^}+De#a+5bFee+O{PAp9}Q ze=KVRKeiOFdNoUn*V}^R2x4meT@$ww=F349YQ<#f_X3=&0-#R7lph^Q-9d zQS6~$t`=b%qZm?>jrEaJ#T|oBjGLSq89ZNF?CcKv3D7%;bdo^fL&-D6)L_Le0+ z=AGS9jeK{Mt~Plz?Xb(+It#0OB9gA9tNpV3rN4NQRBp0{qC?6~RxvfYhDboFq0%?l=ff~MmCB+i;YPC-sTG;69i(xoC6Qr!HlD&M@pCK3dBKF z#t1TAm&kK-N0-mJc6GY=`F>CM#?iO;m|LfY6<$y%gH0K`(lcTi?&2i6ENAqffT{VB zw-OQN{8$!J1`=SdX*Y-#QKx0n?Ar&OXX631)oDpz z@fYK)dnpYmfw24p4$g=_zBX@45b%6w!}jG{gfw8vg(pJ2?>%psmY z&gb|Rh-A!(vRz-HPmW8PspjT-u<-OfS+-YaVk>DWFTeK88ppIZ;%}uH&cef$SM(Ya z+}H5KbwNdBv_^DNe#x$D?VZuj&Qi{d?^<p5hF+n9E<-c$b&2^TZvdg?xSWTOd4^JLh5{9!(chB! ze@`}4R1Y~RG9z;di=(|4qSud4N>yr%3tLxC?GD6VaY?Id9TslLr*<^FOBGYB&@)sV zcz0NPj>rrAS$)5EN$PbmOS|hK5@A1UIfaAI`UXUZB%1SSe;j+YH~z6+aGlol0w)?lp3Z%X3_a zQex8B=|chTV@yO~iA&(DLZ5iFBwL#KyU{&E#b>a`Ypi$U`sod+Tu(okzuEPit~oQf zV{DLqx$`>R1gUcICBuYYj1Jx z`K9lq5;^(qWuA(FXvisUVZ`xJSd#uPHNAKpjaEdsxz@kS7Vn5;3MNtd`#+l zTIkp-R^Ex_F8z=)FvKH6n6wf2J!(&Xd@ObX3ly6h z%a~dr0sLTO@2sl^x-7kCt*WA}>e{M0_GVzBxp4F&v8#%hl?15>H~@-Z%_W~a&;fo^ zBnNI|XcLLnpZRE#-z=PX3h-Q+pK=hS!vnz+8?(2pEZvTXd8#6fG$jU5K1deYO$$CPS z_IjT~ej`e`H+O?UzBom%2se!3-343zfv%Aey*?gyZ6W9#X7xnSFcS~F{veLNU^mIR z!sJg`(Om1LPVb+Ec59Zi;NT>7a{-??J`QBmQQpN`T`m&n(QlS_H1Zz;NLA5D?wDTl zB9=Ox1mAz+7R-V#Wt2*%l~1U?Gm6c-?`?6AV{U@$VCKqpG|KO}((W~H5%QdYu(O0RD zv#SXh$2NPQP9K4bzs?UX%d(~#obNz)OsV_tLLY?cKl)LsXf|G7Jnd2G=oULf zzaSxDJ~UBGvO}&kbefu=` z6m~D^)-^6O{0*0SjxkMmM$F+WKTl|#rP;@C$4@HnaHXuV2bhmEylbiTogQzy_ahJ~ z?ToF#5U*-DrAv0(hv0nTUhGgyyvByuSg?uqg~Rtb?i+w17U^AzcVWau1P&Lgp%#v5g znti;p3?2evy;dBkC4z0D6N+ z8g4g>a^T;sz^QcecGI~mY6Mp@y0zb z9jiBG!c+C8AP~!Ud`ia?_+vLPD(OweWgW6`f1LVLNPZ8fskT;{1m085brl6$e$Dog zn&PL5OoiF{$H2St_uNe?oK|SdjVP6vsf@UzX3~4ZOCYofY??^*mB$u?A6F^PoQJyE zRB%d)dfZP9pWslH;LXNUT!?;!=0z;d>e z<^3BcHR?=dNsItIRpa!I79`6bL*RH(Ds5~LA|d7Tc<5~kPTH@?CvFEdn;sMA(~gK~ zl}gU{GBEY{0g4~O6(i3H73z0aWux&G3@s8j@fTgsNln+B9o1Cl27T#`W=`u|>9FrV zTb!Nm=)=xeXT5vK;e~SFx@K%|o!igWc4|G)QiKFzv4)4cy2*hL&pMi-G9toqE7!Zb zZy7hcD81=BeftPrk4EPiC`Zj2_%K)Ie8bgA2w}HXh;l2!1U@hFJjEq^Ict=sv1O>n zDqsIZ(i`Mz-xPT9mA{OLm`^EX+qDu;fn&|GATkWu_Ob>$z8iQBR{VP`=I>`|FkzH;pspl(cg7V)e z#-K2f85qF^!;T1IV?MgN(2J&XW2&&7xMrj0zgdUIw~XgxvOBxb;llY6^ad2kp5XSmE6=KM`$- zvt>NuZc7L}AzNUqV##YAvwI@mYfmqKyz5vdz>Q$k7Jz09%g`3fMeA)(9eW$>0 zfSR&0&1bC9I{+9P%9WqeuXY?sphwX8bGW5*_5}#^8P_ zfWkqer3u%ST%Yf7GvX}9JhDG2Z!lV%?{AB5NV|i@nOMe_G=CMF66afnfQ2_UOftI@_!8YLt zAPD$*4QZ)im#z$VpttHqR(W~(a5?fgj2!q^2zV%bOw8l*A0uHr)7t7^Gz|0aXecdmd^t~(tJCCM{vVF@dAZxF z=0sRFz&D;3FA>xwbR9sJ3wsrTQ$!@;nFQU3_{7B^r4{ekCyt7OBBPrW|wJ=H5q;%3 z`$)ANl_f#X!2<3B&B0F_&O`d7`NgIRZ4ux!1Cv~ow?O&rFTt!Q;I6V6Br-Xz1LXV< zZYBRg_4wauMgPC*s4?1&|EwVVhxMTU`u5KXJeDvjlgSWl>aq5w>t5_` z7}ovKUkb2f;ZG&3s@}bCV*Il58}E0UCyFd%cZoh$i$FPA+}ClxaEwblr&709P8}x> z#$CbTjbvzfrtEUCAT2C4Wd2g4JDH6VII$GqT4IWkv1TS4ZD#Eq0c3TY5!JT+BbOKX-=IdCllm$N zQU%b|TpCL?dKhf{PsTbPU@o;co~zlW#Ee@D7e}}bz`+2q&H2M)BI=!DgN-ck+e|=5 zZ^*fU&tYBK<2koy^Q2x}q5MN$&ey=VZQ-Zvos_a0C6zY-wT7ngicjKW;FPHmLlcS8 zr*gXB`g<~&!scc!x8^v6m3WdLRQv}kLk$$A_0Jhv; z7=tzngeQUz7bbP^DaZ_Er%1HH<|;zAyo>Fwyncy(hN4f=%ziy8yD|^_QV+}o!HJUd z)6JjNhTSH-a^r(D?R7d3M`wGNtyHVjIFan2_)Gnv9We{Vy&C`s91-&{b5ObLzEmNrpUzQMKT4 zKMVA3ivoR#%@W+#$MEqj$c}kWG>N4Ur&|yFT`jPA5tZagTKBPM=ut-aQ ziV%=}SZ~{kGdU^g=jk-*sf%9S)?-Q?oGc7RQ${)G7&czMTvvB`!L2 zYNuvKM#Y0IUaG6P#$-%nOlrG{4;iwo!{~;ThY&WQPvMp7E513JYY(*?@#jSbEHS? zt8v2Rm)m^}{#hzvOcKo*oI)C6o6@|gjY<6TnM~gqU#pL?*G6;U9Sl^U;kFi011Q_^ z>f;B3!UURevq-QL#jF;PcWUU zO8zIEL&$OIDLD>nC?Z`%rRK!$91faiK-vshSNROP&@i3W>^>q>9Y-wl?d?|pTO=E;MH4iyC4a5ZoD7+yV{C}b)Ww6@ zL)FbQ%oDR+21T_KaRQx7l$XNBjADnmltx!4i#ze`aJXl3x88cZ%K?~tNd!Q#{_aHPK z-m5-Om)#CAdj<2>G0)aMEiW7JE=0Z=)SS!o9n^xbh)$Qtwq~}*8lA>nR1*6`$b%sN!}f_ z5j8|>=h`>sTv~&7HTmUo%Bw!`yVg2sw(HsR8mUJvu^sUZSSgiYk@eyX7n&Rc1BD39 zgrPzagHMq7%%OY1-(jK~$hZvKq7`jDQ5NSTQG+DyVUT5-y{`Ro*$}%_QGEujxmqFY zE^i7$xsLAYhg>0%-uj|PZm%bKk19>$Uv`uhGu66kjtSI>Hkz)E>WCw@Bs-?|q}?5e zPD^>yB_PcJ_8-K=JGjj&KM2`DW$?0domw9d=*2I>O?)r6(Oxx{XcuTW$< zwd%|Unq7$G=MTqtgM`S$UP*ynInOp-9)9u$OSPuhNF;hsew9c;`gp5Sh>=Fx#ni20$+5zMzFq2{p9;0MkA}D8) ziGIsro_qL8M>*-#%Zq5}2Em#Y9=tL`wSTQd$Pr^AFs~CX0K!Ib8*4KP*}llR`EV~p zFScw?OmMr{n}%jj(ZrpI7t1*N8&fivM)(^aE3yNK3!ESGcOl->+Q%^oax9|=5K*p* z!9@ZTxyaZC1}J%#ggJ=lBtLP`w|fgd@0-Qg(7c?Vk~HLaLM`yBM|Ip!;|{Im3pA9+ zE~kR{*U}^)$2<+dhXiCO0BN+h#-p|GT1*Np7%m*a9r=KR>Q7B}%*@kGw-2tj@tNVk9z2f_`Y zAtNHaH{$OJuYZVp{{xv0BPsqRuM-4wNaa73*GW_YBKf~arb7VE|0UD?zai6AnuUWz z-le)1SXYXo-N2X~p{uyTbdLYbB}%EHy;QtWF2>cr)y9v19(k9B_}wAtWq}wD zzUOTIiol^XGMS_RH!6y6Qs0`df>l+<5XY6_Nhyn-c>~j`F;5*-@Oq#E>kf-6BaS*t zS3Z9b>G5$0~x1R}KngaJ7yo9ihg2eP8a^NtR zhuK*)<|=Xdm*&3Y4m=~puCI50kmG8d8Bsl;nnBjTQaZ2j%+j7q>~tbh@WdjR+eP*6B6l>)B^~psWqt1t%kXY#+`bJ(2?)znLnK%%Z(snaWnKqcXT{Z>T#i$`w%m4?n3l?p=Fj_SX8C`?}EW*7{5NcUU#x;ni zJbr5vM4I+R<(?2gvdDw4f-hahknCmk$3Fb>^2L+X!s5{2^rD^$oq*KP$uc2b0T!pe z&`eK$71Q~c88Pc#`iDi;D=nSFu7g%#Q+}qeZdvJXE<_`$>mmhY_7vmm$3)fV?O=VQ z#Mz!*ZY{Z|YAilRj%@?%Vx~GGAuVq%QF70C>-;%Z-I{J4UVbW!G<^iuq)s9)w5#!4 z9Nu1Cy_24^=qZppv76hd*hj$^2t9dV2}h~Bo5uFZ7R@Qd{?t!j8pmPP(K z_dR{-MB`eodVjBqp<^I#@-{zRI{YWC=CX^>x8U(RUz*upt#Be=03Qf5y}lS4Ks&s* zoTm{{I5j~khFl%WHGE3!7anVz*q32^%=EZ6`o270W8wnOM6MG1YzOnvyjYS~(Za9< znDYIiEOB9<9h`|REDbv0ge5iGHpVDImM~!O*rglb?~3nUA8AOEz6t7rd_|_LVYle! zw~&SzdaIb)g2g$bl9j_3Ba!coRQ86-keBP7fniM1|Xr$LVdO;xOcQGKlyfGk<4?xzEJPx zzR)sGI~0)zwD7j;r@mZ+6x|s%v6p25BfPEiMp1%x5LzP#TuSK~Ce)_GgHMwlBo9ZKL$lquE!fP-I!{VA?*1ekcZ=GAujZgf+Kn!h#DLFy2D4xr9HVYF zN48EM`!67;SRLr>eSWo9^d#3^K9l2nrq-qtk_J&o6w9Y%Vabj%p)+%xO$$5QCk50}Cn#cX`4jGFKW|avGgf_fy^Bz*0{_5LpSA*iuQ3--B3BF;B zRXhVHWo`N`_xX~0KSX@wfp$7!($b9ZTyCc9Annm$hM0?T2@8Qg*a_#8m`ZdYLDg2D4r55HEUNlX+J@WIxTWrGeMQ8jjUyAl9CG zg3DV%Q=4en%E@yhyFRB;=uP5Ftq$GQ9T4;i=Ak%|qLr2i zRYlG7&=%D}`}^m2@8`b%&wBP=>sj~9z1MyfE7z4P$ngE1=Xo5TqoMXKB1E;lK*6~0 zFF;&2;20Zs;bk{xDGA*jDN90FhvX~Kv?|e zs)*-_%3y*51T#gDtt=PF7saf{k;~6MrThj8Vzo7+x&wLP`Yf4?je`Z569m{vn?{DQ z+UKyIDV<_KJcKdjEZ8==pU$PqN9eL%j+y)596Ha1&wSl~ z0DgS60dAus5G%5l64}1kBAeAMu~}Uhz2WL7EUece+iZ4K-q55$pc;GG9%8dfHWRsl zb!5UuUbHdRqcEE<3Hq|fDKsg`XG8n_tBO=OtutdNU$G~8Sx-W*qgkrjKaY#U-=s>- zUg)5mH|`uwUu2aQ2k{`)^=5a>!ggVIEsWQQW-))r6$cGKL&&{-its$Wu(Hh93Zdzt zWh<+x!Rm6=M;ET>nJ?OGw$@<}2v2Jg0Z2hBe$mb1LYLR3Gx#80UA?%wpY08=)Lz6zvzhhrM8-XG^1ia(|JD86gmmi{oSuPS3e`yA2(F*M*kEPM*g zHY`izc*|`?2I{Wnp4@)1K^5bPf`&aQsDiw1kkBQtB@%Q+DC2TZb$mZnI47NqV3R(b z{yEwy91h}&5j-P#kc7A@9X?NsVp>My#fa9%r)u9}BNda8o_T*3M_Jqhl8oU}d17rN z{`iXD3$|8jZokCk6Gxn#`f=)wKw9hbInSo(qvs&NV3koh(KTSpZ8yQiZO>V=Nl{Qh z5!->3E3i8u7bmyA>{1#|kjoXVMGaVUb4zzeo}N9{g)PoF`ENp<{xs7+fL5*+x!n^K zsdO+!3gD7rV06pK9U0w^mR_rQ3C>+xE+HIkN%79)iqT4J;GcFc^Spa3L=V(xq$AO$ z(nwTI*6#X`9fwVQbSxO;1H8RjDG5qIgM5CGa(Shfqx5OZAd@2maLi|D`RYx`) z8aiS1QBYT}8E3vep(G;6{Ke^>jhS#?ZKSJcZKNrm^XK`WqC49G{2u);e{~F4DK~sR zo(rt%i*xe6a?z}+ZZnjJVcY4DZYe8es0Goh1V2$bhOLif?OEP0e4y^{G2}n=Uu<;@ z-y73_gT$K#r@VD6NQwEUSAC`qd&{)#1LFi&RcrBkBCqjxSl>7$+S5+))ZjWKq9#4x zm82F$86qxE&%KCX$~LJsbGP9ZeTBh8u`UJ^G1wx{hcJ0XxR}$XHi1?1N{bZFyOmkt z;e{qWs!-Gqx5(#qqSJ*fa!}m*o-;$*DHpNcd^VGw^gb}#4@oa01!a!;&ctDn^gfIh zB4sV6&~^P-J+ zcf-zUxZHio;$T~P$$P8|oArb2sd;1>Mtrk6)jv1YRMvc%*Scr$@)0s*_3?O*?$mF3 zIBAt(HemD+F|eQ{1MnfN5am($pPioQ|8Q^r?JD4Z3Cq(}>KEOXi4D2-;n^2QWMmsR zjeOMlf=ABrESD=B3E90;C3-U-(Q^F7>v`J6Q#^!2!SQb`^S|krPLt<@85uxm>@XN_ zhc^zUDrbI<=y&RZWr%6?9&fq!O}?X==;qs1_cVyWSv1$1j;?aZH+Oz%MrEsaxa97C znoH(G7(Nz+jz=OP4fEY(lanx)1Eb~X)w242lk5i^R*A_eOs!Ka9c?(}x9DA># zb3P%P-kRozatm)ix_!!_$_O=0VVE+4>yiaLxn>$BdxB?*T4P^CNAT9POnn#3GK;rZ zyF>awW;5#7@J_qdDrd^pq4cNYqif+G0li}rTWdtHaXUJw0G9N{qq7g?rzd9N(7k2L za=aZqW-aCAd`2m^NqwEU0$nd{Xay^k7WtT@Rn`8T@0LDa3NZd;4C|MviS$xSuJUJ> zLa)!!)6kLoOk3W-JFun@Vn_ywEB%G(B}(fJOLk+RFK+JhxYQ?w$RQZb6de_L&x7j318e-^GaZajZ0d!l6Fv5YGH=k0ox5f`l~P{LF51I5pu z(%9;M*R3}{AlpEEY=uFk%BDbNB_ zOv_uLn|Bt5wI410e($i!jXnpUr$wp&CG?CIF63rvjWX>Z@e6Vyip*Jn`S#~*US=90 z8%uZN0o5AtF~!tS8{bP&iBZadYO=nJ56kcI7?jO$mUTV!&C56b(W?aFD}6ps1n98w z$PE)}>~TV|Go-TmLO}PWd@tw$xV1PPe#ssw4X0w_M=om(%M(j})f~3GIotl&bohk? z;%sujm=#i$#XyV5WW6z9&r zilr4?Hk@XT%FF)KF@^wHFxRZn$NN&5^s(mmR zFzNtqAe!$uzDmZ|`I}&~%4Ks0&b%OYbOQ=ib8K4A=PRGv)m_fJPW@=|M<7M%e1Yz) zgnG%`0|OHop_S3VBKsRfT&|nI-PVSSt=tHT$`{Y>Ac0!6W_{jw*E_1&rcNbBo`K50 zmktRn=1NV|CLhUiu@cyad5_F@Iu42K4x8M_HAwJ&M^-@`;59-yk>0u`H z#e1fu%nvJCFWXmk1d_4q1~HA1F->y1WQ*qcD^$%TbQfRmlbZsPDNlh`qhVL*tZEwx z-CM5Pp<&x${jTd|V9k~*XTm{C#akD?@1Sb~auu1Px1T|D=+UQqy~`5vJJ1)pnVZAO z0ZUbLMcl>d!t>*P-2tIGv#tv%Q42EL~*%fD^x^)+c=i#4yT`#_hyjc{3Khs=+g0Bae|UvEVb>UWy#WbxOW zg(xG9zW|f1hH}HJPdU9G>3BL1v3po7918ZCY9a#O;^OOe@L_^PNoa)`z=Z(MxMZV3 zwAXjJLU|!v%Te;7(m_u)*M?g%=m0UR4=BnVi zex+Fd$$g*jnP+J|oJh1-a_07BGcWmYgeNZQ#AP^_i*(e~b zb35iz252oRUbNv}`rPi>(rojlTZdrc{f+f)6R|5zeE52?2^$PmH`;cPZdcA6`zrSoj}VYX7{z ze-a@7BU$aAN8x%P_&=n^XV7q65d8lWi}a5}|9&B^rK|U^LR|CjY4yLAJfx$k^WUft z|H+j4zlHe!j6!^G#IG*cqzUXtMsTPm@3;g$aGLHsL4x_v?u*a-3^r`i4^z*ack}st z%Vqfyu){3Hzq{YoZ!=-SExCl;I(;5)*m(QrHN!>;jeT(v4Py4-2>wvJ!qUWf`9a{0 z?i zPd2C9BOD9|%fp=~t~uDet?z!SdiOlhbQT*c$m`@$E@Qk{$Y8?M=GU&0oU#uA6!0jw zK$BnPbNC5ZcTMqKYcQ>^UZE7p+$Q6T3}UXM!Yc4UpQ{Jt^Y}Ot9@HiRe&v}*Avm&* zLO$Y)N^k)zxUw`h#Bf64vT&mtNbHu|N~7ji?Bb!6so-6WPjF3hjR9F6Y@a2bG>j5$ z!{sV=SheNqJL8^BoPze-kgCA+*U#wlg{?wzUbrd^eE6rg6@+X?&+`?e_sfnQ5SFMU zyhxwfx5R2#HStivJW4eMW5EQf$UXD@0YW{jtOhVH>~xm^J8?HxG+|JFRi=cY?({typp{(OH^xeY%e zIZlxh7lzIoDKZ!Xdbw77L&SsLI--M|rY57bNyAf-D1Urew;(57OomO@$w=D=JzWDU1_p<;`ka+MSrYiKS-<0 z`HD5S0AjCB7A~elXwD>zGW%r)M7ryzk$0l_nPVx-*@ta`@(+wfBhxNl=m=L;&LxyT zPz1i;rvQei>e;gtCTQezO`X|*f^q#>3WN)75lmV$RI1@c)Wgtjb#Zl!1_DOQ4u}@D z8#6wEfgoi_G7PAOmEWkdC6$?jo`(wt3SzbOMA~F zTiuoKDFeP%_dzrNJYLHxw{=5UNwOoEyqR^*@0JYjjn&$}0JijiCHeTOl#b9Vg}3)^ z&grf(^d)umO`1_rAN`&ckWQM9t2qS1?~ASdh;WWs#CzX&=B_z3q(XDqfdJR2f>3g6 z`i&?^bF}qiJjNFtZ0K2H;4HmB`ABB^K?PIkXcpQ->kAHHixT!zStU^?&uYvVc}{eG z>G-OxU`3R&V+4nYRVC(_!irv-EM-^>R$i8s{AC5FTwY9sE)j>!*5`4op(sbh)ytZz zkfn&5J-ze~BxX??PX+^rjp4ncjYpfnl1#DMuy161?$FGn>%&v!4I>))>s{iU zHSZgq7%+1~$lbZy-O%-dynGS5%An}?^gH*5JH#)=2gfRK(n`P+aOu^2&U7~Y67aTD z*REzM*0i10&aFWzpQ}K?a95#=qG1L&WINld>~)V1_4Zz)pZSh|EL29Au0AxikeFJ{FbN-u zE|^*|yNCs1fsyM#K}z64w>7u^+Q*ufzW|*B{EJE{IV7manb{sqT#2h8J7sut^!v7K zvU)$@>>1|53nom{jYgoluVuWNhvX6Y%qDj7xAfI!eJ`vy;W34ivEL&V6FijRYJZ^22kbQ*k5G=gM|HWazPqc1@UuJezrWXC zzV1iJoHpXWE33QN<;#ffQH#i9Cvss;xYTY~zhD0WPMdV(aFj@7h-SK&Uo)Kcw+@>o zrzdMea-h48z_1U3r7p=Y&`Ru;y_?csitB}RN>?Q_yZ*RPE-#f1F)xlK@1ma9whF*% z#zvGS%YnE9%CmzOzP|urH~ZRa=%KqB%QO9dUZjN#nI$+)qPv%>R~$-J64WfQrXj=9 z6PKlpdb-PiHPN0C*B&}$?AbiX`9{BKqoypGiPUJyzVqr{&ZlWc+EHXWMe$3N6=+bv zBJn&PnI%`>-IdL%D#wIdyVue8!QBGb;`feRPCC8%t_^im z@p^FUP$k~pcryM?GodZPT{Um?O=D|ZLF7-mDtTx|_R)&_R^+4I`%bAqDoWqb@UL&$y5X)Q%bX%OZPF0jwI(;NyCEApdP%&OO8K#!@|+n99<% zJ;u0w8+^ajCHVVF+G}}#Fj%g0w zyX0uUofCf_U!Gj-^$S-WG-eY_%r+b8u6hshCbFhylp7Tg1tFS;q-Bq40q1^ z>5P=C`c4e;MC8xM!1)RkIo~~X_1}zUbxn9b%>LN0hCZ-#I2$PwP$*$Ur?oNov2QA2z!(AwsBes5i!LK*JL6kX?ac$ISn#{gAm4{Mod_>wTWF1D*ENsqj|z z8z_7W?izSoIX`YUKGM24oRka7bIm<*3J3LRN3#f{$IYA`Qm=@=u(j?=pnVP&M%gBB zF<>|9xscbr1#|UET1O8c^K8N_4B{LJ=e4$FqRUDHumC`2JE+~*b4Ahy(UYazfaJLn z#jXalR$~=Xnx%IbJf|@vTcvI(jzgxDp3taj-!$!(UK1w5lI*H&wD6dv-4vzS%&R1p zjObgocvIt77~OY3a1uIrX%x*SXRrplB^^DPB56!@$8CX1cwTm`R0FtY>vw^<^B z**?nIDR?mnJk-5m6^N>OGVbnVRb!S}Q{`rqW#L`=)nUN~0n3cGW8+%-o~1hyndX?d z(JqAr+$?Pn9wPYSgQoSIjCr_RlEwMl{Ce0Teo)c!>Ib#*8{uxL{sa zOjebXhGV3cIJQh5Pl;Jk1e^2KTsW9Bjg6Z|qqLp6M( zqD~vg7en)-G6yIGizqPs;AHfkjfo)yptontBkt&az|g1V-qd#*s$t)sOEnB;UFr}S z40U8V;)=GDvAqP_3_f@j%;b^;mnJ{ZqGi(o*FU^nLPOq7*412p3Sp9ysD~+si)V^v zb{k?eqpJ#;w77mFbncmQE0%3Sk{Q~GJm-`|$hpgZI&}4`4kaV{m*>X;vpZ`=Ka2W8acqDQS21v_2XhezeVdW^J1+hKRjoKs%SwoU4FpI*I&$rNe_0og?PN* zGhfISkD>AZ1$>*s>nf`bkT>QsdqY@U280*LB^yepD(tM zH+Uby5p!SeEM&7A?k*nfB)?r>bM8=@U)QO_Qm&g^T5O1k$15@2mOLKM$f}L^!#TUi z?~2rzRUYXKr_^U-S{IC$^h6jjGr53yAIC0WO-;ZBEF%SzVmF+b`Nu_3?4>U6t~v~(El+;5TA z-y*l%uJ;)9Tpzifr}Vpe4(}uPG&q!0SYMg(q5o~LSf`eq_JgXF_9D$_bSn7A@HeYL z?FTsvr1CgRXLxrz8vLz(n)8FO1qA49#CT`$G=@af9FXGtY1O(30;gDGVXp7<8}1W+ z=}RqufAnu?3A=nR3ApgR$#hz^cL%(u9DYslswo?Wqe)scDNlov9o$vZm4GXXtn@0|Yaulu(nLnb(p zs~6Y4E90R-%WvjVCuzo`eDi3l1w;kRi5PHMU8%Ug)ovWD9P_&UvvS2_ZcbdDYr#_k zW^5epeoeCNaD$3DeS=%oeF&|I9f_ci4dCv#Ew-2!4+#M*PAoP#)DJ>VpL6nLc$=Wz zj@@{@G8pDPN!Z!awi_tv9aBmiP&4-=zcoDgShytu7oQZcWU<*w6`VeKb~60&t8xWH z%YDLP?u5mMA#y{q6`O&pCECQokkX6JGv2oBEC{pBRvKWD{b(^=5~k$I=6AAvr$b@P zWHBRuOa$BqHA4=Z;uG=owWI&7itKGg7lhd(n6Rz3=1iE6XZZ$@4@$yL$v2KdHU=!d zQM1*t-@&z7qfY36E>cipmEG^@DsFvD1vDEOGR-KM)IklBq@FM%d)ych@I2a0?4h1g z{TZvzGZC892p#ohmgz?$K577fb6sxcWT%$auH53o06Wo-MbRGb`3{?xaR>yZ2rKSG zAHzrbykxUSxTnnD1CKCf3WO*~fqxKZlJRPba+=^fOJ$js6Kcuxc%qD`N*TE<(mvY} zYsv)PW{Zcc=q=&^OO_pm&iEpkCJ0-U$HVhQH0b@@iS&g*Y^DEzXL`A`RbybLb8@5u zbBk;^+_f49XaM=01V#Mq&BrL!_^nc~V`W!&WfdwlKYoyeo6gF-s`^l%#)cMAlNq<^u1^t$jf7vmtwVwn@x1@Op54mMj+ z%@sRQzh%)5O&34)5JTK)3rg&2Q;U1%WCq#-=0Wn!otWx*zzpV5BSXQcY6F|3o0u5?#UD*&;TjB=xi>{uOfn1gm4VCT@}DzC=94# ztXEa^{wc`{rzq>i<`%VDOU?g%!8)Ge{2f%h9xp>Lh6URg(Af$S=byr&kG9NoHzs?4pzt%_md>c%X7laMKAn@w5gfm-j753D48{ zj=V6*_R7uMHoRabppDXh2@d+lr0d_GY-#HKU+<;nzw5n(!!))38%?%$nPmTWvh_b> zvXy+TK>)=lHs{X*aGAK`@@!0T*-3GFl8-a4P+y{*#jh!hWiF+E+<4v*;mN9oF(L2c z9D||#wUo_?lN7<=E`eG~aV^S;#CA$6v@p_s78mS`%c^vHs$4czu1B6WIW{{t!O37- z3%ov`a;+h%&{{HjG{Ug4IX`?0d6g`(zN%`Ty>g%Fh$0i(;?jMykn4z|`Vq&u?nQvH z46x_6!W$JD+Q_A&wjf6>WJ7}jMPz8p050^#^5&lCM?o{IoY&(^5<}Drg7j<@rmx&y z&{Pt_7{QOStP|KXM_C>sPJ@|N7ARL;A`WWzFC^xe$PR_#uE{p0QC!Fp84z5Fh@gij z(XA#e6_T7iA;tskmBwYgr)8uB25s3RsLHsgNc+{2(IO#&;7MQGXGKE+9|n}LNrt-o z!QJvC`@YiiRhVw(x~pJrnceSXPn)c2IA1)cRbDk*zz|+lQ)~w!q?s9%69LhF#wsnYtCok3Jp7RTe;HIZa*F9X(1qwUGWdo+*&1-*Vz{RcM4n?6q(}c8& zzfce(Eze$Yf}GsIV&{6As zq8TQtlS;r%Y{*%gYa6aI+4p=DlcC!oxU|!~lotcGr*TNrRYG_X3!|f9k4bPsfQS9Z z3%u{#X*q6kP|rNo>iSv;zrttf*iQi5+rVx|XNO5Wqjyd)3aCyBO>^+*+t)kCc7 z*5j|;jDN?kf7rm8gR(7by@F9Gl8&dIFFK^KE=|_RdQV1xF5gPp3ogNVfzsh>#~_Y2Mer*hHVp!4zHK!FsQT)$Rs|0m z%+gg5ipYWO2G`|zSvt5soNi7}wK@rM6M)7^(qDA~JA%VVT_8eLO2$KNe@1*xy;}5l z*PEs8#R`OHUB3{+oUgM1jbAGO^^ZI^QXc57?!FpYdDo$ivQjo>J7VmY7_S?8i4jDj zVWZa|yX&LGZ0pX|3dGX!0UhZ|zozD$x%%Fo1P7*XdF*a47wf@=Rs%m31&3b?-&X73 zD_wD4!XJ#$o?H;&ic+S$0KzwZ29Y1RYFJm<>>swMG+#c5Ui$ar0pj@=5WF65nT{I8FB2Q&qEJv!E$Q`)`wZ*NN ztx$g8TWyuHHTyp+u#BO28bSU+{gC@(juOT zMw?EP-RG@{Dc{XEQ9n;&hGB+pD=z39QEp6qnrr?GpkU*m=3wSN(F-r#~V5MAffY?Fv6fs)vuoJnW*RXeBEAZ0- zlvM&Ru9e#;f?z9uW)D?D64-F`db48gUQOiiDt;Z`!rOd^@?XL37$Qyo01*`DqBEY`v7zl(l&vFm|<&B~6W z0xF$VhN6UHnyr?n<0p%VOESXn_MocF^7DRAI@uLos#<%Jn~|SL>C1H%@M^w(W`s@;w=K$GP13y9>}|9BMk$NO_@KdS<{Zua zD^~2JAax|8FsH_l8YX<+sVe47-RWwf;y2;veqE>CG;y|WK+5D>#OlefmQ`uEW+vga z7`3Dj&IZN!SBli2Z#~*F2EDw@p3iVX6Kj}>IM?)L(M-o+mLS^ab4O`%8N~p#_B9SfXYRLny?&4K+ zqSkRLI(29*`1+B`8uogVGoj0>OE~s7^vR>s&s=`E9m0VUP0smK)XpP$wzXUyTaDf( zxBR%smPWn~J>6Z5s@qWV?s<`4WZvj4=hJwu) z!@%{5^FYqhf{K$QY^@mdcBQ`^NL*+};@K&c-C1#&VIVQwV!MF{RBh&RtVk^X_(kj9 zZte0f{0>}IL3v=NKA^rHRA$ciR*pV&=$R1LybOWnttSRsD{D;AaiOBL&LbEln_*PYI|l&>}9l~x{VnbHo`T2 zC<}%zM{}PSTQ$vb$p_3JcwPCRD4oY>*9YynbTHD*+c{N!f4tv%r8RunBYWdCG6`4_uTs9Qah@1)!uyHOT{0s zdvnFP$|5gAZ{7of=``44R3 zuG?M|HX$K4a7b8^)bMp7Bme574Mb97ZO)9nA!bqT_%g1r`^GKiy14qx!x;=94JM(9 zJ(U^HXY=0f#xCF+`FMXW=_Ex00(IOx$kZKBmm{JIaE=|S_g%ZQ&XX4KfSo5=3tfl@ z-gDAdBa1B7*?g|mDYe9u`DeK}Cq=MpT(}GG7t+2En#~Wpp!~Wcz zs4A~Pq1-1|Nvy5-9I17&0s{$$*RoNY-82gGOaw=;`gWbSpTq?-Wb`pzgg~wna?;RK>HUMI5?_1wR)j54 zCDZ|5j{(aZoLPVH;GM|33mxw-;Z|WoT2TbvLeY)SfGy8KzxX5~ffd!|;?7oA5I=@U z+V{5f#%~LU6}|-4Y~JWdmERIsTD?rG%U>v8aVWx`g!142C^$<9dmDvmU&^MZm8Oli z^%Bi5`7~-`7d@N(H9H+@YRpd>(|VH5U07`gSx7}6_eTJIQ6drQ6}%=WEw+`M1>-j= zyGtv*l0_Fh_!WL+uO2i$m^mBKz+6A=plZb-U%5OV(ZNH*+M&mp#rbR}2_*GF7+~xx zzEa9S^mfH>jHSP^(1{i z5T_RCzK9-402R|-*%nmyRFQgYSjB*zrlPk%?@RCwr& z(P}O?fk+@R&E?$zw@Vf>aWwd^fX9a^R=p@=eoML&K}zcvy8pR8jz&8u>#(l$mvNLT z%fSLh9;I0?bBGH0kAl{lkM%cM>@^3!Cn`6NwWP2ULZ@#gytdEQTr2Pd5Go0Ku0^~iddV90 zg)sS9*(9*xwcJUJ9IXmQJZMQ=EEoa*Fdp$%HG~F^JH|Fu1)eE)CPub@`OBII}wO40UTH~RFiGRv-(ci~G1t@tyNMv>z9LRDQQ@UD=w^kM;~2?(A6 z>7~46u5jch$TJ~lv}{XN#FVBWwwX?x^zQ7Jy>+FM1u<$7Z3@BUhkFPIU53%{dx(Sc zOF6wmh5H>l94a%0-7;b|=Q=*B`dw=~eyYc#_sQdx{R%9bHHGKIYKx@^jtR0kqpAUZ z7r~@E+%TheY0y}g`H_~aq5>X+5I!Wa2KbEUJr))Af2wd62XOOri8_VZu;Hn z`*OQTc{oQUz}qFO`YNn*PK-@kBSUQi^0pq5U^_{hv+-4Q-Hy_J5$%|7D3d zgZ?j&@7jO+9sc>K|KyI)`J2K1&!gJ9AnkuxBF><-bwJuW|8aS3ZIJdqp6UPPxcK|5 zf4`lqrJ?aJqlAW@=D%l@faz+f|2JwU_cH1HZ#(&aMmxDkO0M-rN6@*Va&Q@oZj-el z@ltf_!05HbtiGnZN;5awTa|^({O3|WH2(Un`>p<}!67jsI6>PI);kl8yhQf6j}1SO z_pv&jwQSF^gcMGUx_bn`a3;{tuB%`)cr_Dfr{2Zi>sl?;Sgl)9m^CrVLiD6em`YV) z2>ZxcyeWolP>8g~;Fa!JGi3TmcsX-!#W)Acp1PDLp)~bfyeUFwDH}7oY+QZz0 zOwoIn2KHEG`)g90|-oN>4ncmg5FKeO@2P6L8hmyka^#c(=tP#y{n1RZSHeZqx^W_DQZIy@^$bmd2v)R_NxXQSoVv~Lm* zD0~Dn&_JUc`1|0u~~C? z_y=&yiP#)6EOPG9)yhpqN7HC__$NBF@@FP*d>3Mez!Kvq-+3(H7XLAh5~y9_ z7qWfc5c0_;Dl?|W4|;Ie)cNf=9Gg9*_NT0=_LmFc66A_JYMSt|mpqmeUvgF4N$V6C zon7e2Uct{@zanT)^k)6rkLM756yhr|8eQhJaOdGcdW#hsR}($2s*9}K<7v9RTZmDto4!l^%{Opz zxp}+)QRD&k3HT>%C;U~;)%$yDtC-KfTcdPtesV$ovhM6mZ@UV-|28CePw-8MTg&O8 z^yusll#(;P4YGwba`WOjo=g-QNC(;xxcl*;i(;{^1#KaxZr^KHv=ZcIHtl!|Pl1ma z^3FrG`R$^!GF)X+V2r3oQWh|Z6=!X4J>3zm#IKR7ci13VIDd_pkR-5S<hA8z0IO@UX+`riHe5qJYKx+(6W^l0sJ?+MAlj-y@{d;x=HZK*~Gm~AoUrP08 zSa+9x#Sl)Z#??sjAer9iz?rkL0h^Gi;*0ISCa(B10><`&?kTO3)2!N8NKEz@NXh)s zI3;cbvtZz2)#>H|e3imct%m#9e&WXB1^vm(<$Lx5PJD#ZM@0T#lM(m|g`<^T3MW6e+V1ANljXy``K z>lu?(Z{`t!l_lBKQ;Gr3*M~;EX7W1Dhha?og)_Li3Vyw+vkvTJi3)dcY5Mj)mzs?T zJQsi2rFOJlL{+4c0i<%BAHSMI#Dkx$Tv#2VHSZz?N ztywDwu^UQ?*imY))~MMU6|1yrt6Ei5Df-L(ocsKq=bYdD&;9%FdCv1!&Pj6RrTUBL(MI#K(tY@ zQ@)W;TEk{B(ezJS?}o>{?DH6ZF!K8IDodwh zkVr9$S+IwT-D<&lnpLJ0x5x$&YLz&h6cs*c-924-N3bzKefdS+mk=TYFor0-NWQeR zqYIFvY)Ruje)$@!O-heKFtKYwM|IsMdHfCL%>sa04 zwp{+D`*(>{ymyVA(5C5M?c)*UQD&avEFbiqiRtLl@UVr(d-&=ls(y~J&|mJWsnTY9 z%xL$twIRs`TpH&@n`ok$!K+{ME_OAtHwM21-*n%xxA0;TW|EI)dr*$&Ii`AhYdPz- zfAagFcYzw4W-Polo_u;$_K3+RJZ1a@XO3g9%-<8bz2Nc{+_Dc?y0?zR_!yLuQ7+Q* zfR`NPzOdb-056LKkX%u8J-e}y4-G$dG_}USj9-_R68%AZqV6n1u*zR|sgCK*NZJ&3 zU)uy-RUI{jq?@~**Hki3L8Iw6a)@UJMGC%=ZK){3?7}AgWL%=vIgC;1p zQgbk%5>^5Hk5t<@-PSDw#mBY>ieb^o5l?IG$jZE&IGbBT`ce< zcxa>=LX2>885wu@6HqTr)RO~DcJ|XWGs|8Y=Kpook zvQwlqxd*S!{|$rGKrI0XQC~3hinf@bIUSKQ%M;66;|k;B^a~jeeN$j?ZbDk&DUMIE;Yw!KTf}p*;dcCZC8>HB# zI%tYh^5=9lHG+XT&oRhapR96Dj@h0vxtsaZtLJXpkz)VkN*!tG#$ds)n|eRu2sEk7 zT%bh}28{OXU+fZahNF3zk@RZTJtpn);=rs=$#nG1gu02E3>Nh?gS`Xhs?Z|G`Lj>U z%bI(-W9zEZP4eq{_q+_zNOm>}1%!($#vE4Wg3-CeYFVdy1He-za)9W-<7q#TwI6)9 zWu`M^fR(2mSkjE#$pdm2-didvAh_ar;t41IQbbFP6ixn_)EMv!M&XVCRY7RU541r( zna>;s!UJ-6N??6D>vbS!OLm8f5o)neIIQ23>mQ)rcz#66(Ai+4;DgbI%6C9%rDczW zGjHdZ4K&Z7B088TgSjpOh|BTdR+=;K7^i#5d-l@siiSeWpBb%X#M2Kq7N3#v>#t74 zZ3MJNf^3;(56R#BBMhfit9Z@y1LEd4_2zO*d9aHUE^lVXql$P3VbH_el@IxT0;y=T zzH9Ja`Zkm;`qQ>iO7{wQ%vysDin;C4Ecqwxh+E1U$D%v9+u7%QjQiFT8Pa{Ob|rh%a+Hrkq3xerug9jWiF9YRDkui5q1m3NSz^5 znJiK&huNF&{bua2)9JJ@oMNEG)Qz*GP2eM@!OBQmon^J~%a2qac^4AJ-8qAG&;~J> zaImx?fASGGi{7WEKUm0IHAUZ;PAgwLq_2TU-U&(bjo2{r96p$z!+$T?08M>RnYi}G zn*I4NM*8Lo8%5E|$>(^fKFDCLE&2k*z7Swk`iUO9deK@s_1sV6jGJhNp>y-@VOCZ(iKU6=g3s)jG8iegCPI zUCwJe*lcY(<3`l4{9oXDHA8{|*R~f4E$NbLANCr$O*Mx--z<;82?MCG4T1D|8JIAC zHVXiMj3H@oL@`bcDU$wWoQ@CzJWUL{GbuECg&Ler^S&lb z%{~s!Q^tH>Mcw?`qT6IbK%X8{pJ6PjMNSk7}zr~SrxUFv;9zi$H4Bw2Q;H{73HcVy8M zG3xQ1+H{mNxWSUXxv@m;Am3*GC?lj|`1ZUI!6^LlPUX=$Uc*i~)4YZDf&c7clds?%Sq z6Q7j~c}t!SzV#fsuuc^Lx-fPNR7A$$(dS-}uCmuqz>+C2v$702&H+GXU`+oIuu_*Y ze?9_NgEhWWVZ$Hxm#|IXZP8`4n+TU$o)OA~y!q=u*lnSga?J2s_wnH>l(JBsl52}p zNRd;k+k7}W8X+vKY-e!H%M%H&xJm#rQl~Un<*raJ`mr?Anb;$VUX0&2`;T?c-Ser6 z9~x#+@Se=!ki#;%^{hB>WbWW{7QGp?3ZudXXBWxg1?I1pQ0KByg7zSDPqwZS>Ht## z&mB{XQ7M2Q80e=c`^{e0(Hu|=JoBJVW5tJI1B{L9U6nuAOqf=3h)&uxHKJH?q^a^A z&cgC)g&E8Q`H1TwSFePT0?!ji^-f?$t%1(r{mP+{aR3f zyvBE#SXhnwKY(q=<+dIhxoSQ55P|(g!e=ac$Dm8FrG|dRZZalI*_3JnQ$0sI05wj& zJD!$q)eV@SXJ0|6%9@1ceRFL6;Aj}JsF&*}F8PAz+#YM*x><@KiP$~VeheKA$tYgG{-&t#D+D7^|XWYIi2My_9*vTe}q;Xg(NUR@Sw5f zD#-Eu%#ANrzRTaK@B4l!4C3zJn5Mk+n6!K}@WC_WDB~Z1Wc-k4P>-%M^^ed$fPJf% zSx=;@X1q0Kw_ueH|B45v{G zEiPb30W`pFHZfM21a7-!L6A;hoP!)XE40woYFw!T@sgo&cF&E9%Qp{U{F8lhVuRVcZdcA-kJqI@K>T z1{(@O9vu_t2Vq?*$2Hpj0Ewl52;PgwGqoD2I*vi*L0=tX(u47Uf!6Ns>kNKRrfhHw z5yRR0^_L67DtTN;@&+A!$7kgS`mf4^nU$GkY2QAqBYY_6FIoUATc9&S3;HuY{sVX% zl{Z_wO^UjSeW=r1ab}_K5S0|Q!$j6xMmH)`lzoKrS#za<@8DX zZ}0Z1l+Y^E+*(c>;-CRo`Xhub3SiK$UuX*6W_F=LG5LG|(TdHvG!S}3YK*eAh)EB? z&E;#U2yAMp)tR_r9ik8n9PQW@667!ETtOLwD9+$Garh8Mpk+JVpGZy%fwnH5BH5YF zDXl4mABX}hLOmHxdY-Poj#eo?>1f2Bi7Rdt1@HQb8}mY~E=LM>R1A1Aoz%idRgqLf z7lC<^t`rG&weV*#dO_3B+trg{3(=0C6(Ru)71AhC*VO_#IZ!}9ofK_>$_M~FicX`% z1%3D!1WfgwFmr%BUhBYFBmh4kJC07Ba?!g1$#FjD!H1X?0BB~3};XcU+-G#ZMe zwz{5L3SUU4<1aB530SADP)hI0UT1fTo{c~QiIhZj@_FCsfyo#!%W?2;!U$W`REV~3 zbB6Bu;n>>UC`mN$j-$}?;9J!^1>9`GaO$p@IbyQS(29oCDs{lXMD9p|*50P6w!S1D zu3_i;8d}-wad)AmbazOd71>WOXDUTC6v@PUimVvZU;`WtnAzW6#V#BIAlD+d5QGiE z{E34Z73gKH4I&LtP%mHv8q*$)l3VCteKoW}5xpLRWW*kF}BTh6P2#%OB^!21Bw z(G2$9SGqTV>`WUN%ZW&;bVwoT8ZF-9_)$p7*QhZlpja~&d;+JX#GPKoN(nGL9jDQ` z92N-l8yW@o#)+iGvfT&*^qt< z%s<~s7#Qb5zNXC0J0G7&{sTC*DdEn3(kr1eQtfqvzey|yE$*C2aXx*uItOq| z|FIu`w&|{!@DIQ|^)dQu5`>jeGggL45cWHJ*GzK>&Rg7TLsOo1Zcn_&f%-r}EEt^D zRgJZLkz@dYEM0Xr5UQ(}q^OHgd_FQQ^I)OG3R}b4bUEGXko)HgUJ;_hkyQXatsz*| zC0__NfM(pBfv#p&JoW^8{lrIEN~5z%nS1h2&vheT;oWM@oIf*44A8hs6}@O=a7Dte zp4aZ&Or?>J=CLSP2?MZo1>-Dklj&kcxj^1$c+pTQ{}6nDx75H^<qjpRkk0dqPzWI0Viz)`tW z*zOq5##}NEw})UF6h_1M3Jw9=iM`f|J{#MS%(7wNab`akp>Q2pRhIqe2v~dWB!ZtS9tJtt{8q=^(?V`diX^ZqH ztpm`+mnG|w0)w#PU?`2rV^)R(0^R*qIL$t^WYu4jnf(zxoH##UPM|d}E}-K6@aI)T z_}Nc$q3JeT24QLi$K%9^X>Rq4?Fa>Jnv8p$hp+XcZfB3T@(y!M+UDO}*u)?Dszgof z^6GB@>`O7@8zkY74?C>NfkbD~koQRqhefdW-i=|8%b2(V zZmL*h^if+$+j&qY0bG)qQ7>-aAMBC@;dD$IKLz=B1s8R(M@?3Yau99WlH7!31ldEY zZlM%%o1*?4Sm?8+-~KV6zMoM*u|VX8OD78`Ex_ft>rOChTzkyBPj#qNS>jep$)_{y zs-Nx`9aiNz&wlsH%(W55;X7M2io>Gra5Zh_eyZhqc+Xx(A^AXX8ZK4WO z&$p9ws{znh;aV#3s?5-mMcvr!Zx@#C!Fu!48&VD%$!RpNd3SZ8HKMF@re%Vb`xiqs zsXY|F*!6lub+O+k+;rQ6<__em;-oc|yz5l+^T1y@oK>N5lR)3GgVfe}A>zGymvx;t zR6IhCpV~E4k)`3|`$J;43tt%f;;@t3MJYss0T6Scd+!Uz$nw?X4I+PiI-TtI!M~&v zOR)#vTX~PTWtI4{1}YfJ?2Rvu#as5YSziO((_BSqDh?~8(ANSA(1r{jgnT-N zb)T?P%LLvr!-2`;s*9!H@tVqn>siJ9hCQ)MaCJ(+ z!hUXwguk7OP)J>7n9dbTmoql2tLvA!fka7)4}C2#s90|qJZyBxi(-Al?X++)HLb<^ zNbiawGaWki){xrSmpEF!t?jad#i1>%_id5o*CR8+7VVPMnc#Vg`dCe+fI|WkmHI}b zth~O3v5@?RdO_wZ2lb3CIQvt8Dw36TIhv{;oxgAB;3<~;*PPlzfFZ)raYGa+7#TI9 z$Z{1XAO!$<@RruOXzhGQecmdxN74BC8;ltOsMOdUGz~>Py07cq%KW+gLyP9&M4BKZ z*_?VM?X%+Op9C)9tz(suK(%)eyRg$jT;yT}ka1;v*>JBR_TW&)T(dpq58tBZ8Zmg` zs_&eb=wD*|mc#A1J9y0-uGf3lV1VONZt8O}bGhDwD&?U1*RO)1Vh*oq(*h#FZt?WjvekV@6;i`mDS!E_ zj>5x~&#*1ZGGFR&&A?$zRAoqXp~iwT!p4%W<`KV2R(qV-;*Vcj<8=Cm!#FX&hJYo> zWtHjDVwgn5h878hPf^tMh1rTKFqLwClF@ZvU;~osQ*tdgI)@5=SWdcBzmMsB%%aDc z2s$;V6J|3(fiX*VR+7St``Y<(x8ibB_8JZCSl`Js`~wvBlq4>|Tg7OyR5Ul{%1_=W zuRc0*pC1mk5FbqOH-Jg{>SRdwlQK?B(?egSeieQ!w4qpj%#cpMvg!CE6b$kOEv;S; zmQb}R%!@RW#75&Y>TX=U^-1!KLSq_;)ki!UJ}x8rwpaES+cEAC4VaVBI{irskBP9V{!6> z5FJ__)b4s_&2m@BUN*+k?W;&Z*_PGr?qxd+O%!H0dr#m;UEAV;;gY*+GneZ^djwGt0lkHz&7;xIPa_#&$Vk==jz=>$U$?;aC{PTBQH*Nbu@6~H$9@$WRG zsX!6#)?e}g${hA@jDVJ``!(__1)0!65LlhEb3e55mal&k`T3q7n06^MOCPqAY);!S z9f+inqx~&`a}zgU{EEgzud4BkLdH}EfQ)avKOTjgk!&_K#56}cl|i-ze~L73I^>-b z_z%nRvJx^@CeuV{PvZ->z|M+!&v^vXjW5M9`2qGbK4Ne5XhDKg7<%c$%X^LK@}V>$ zkuoC+L$Q*vi)dr*?l=xg;blqlT{3~f$a)0ej7P_qt!$j4%|tT{RRqHD(ebz88J#{S z-CANl>AkP1NEZC5>K>Hjg>6f5N&fX}{(8sZdmL^T)IXbe8Z2z(|SIU z->+$ysdQCyA`+k$WpyMY-g5WP$$*f3(}TtQnJRo|$EAyH?Xa%%yzDr>~U**L3)ZAFMi{9;8yy@lj`K#v7*i-!1>v!Uz z&o8m_@Y&FSP#Hpkt&1cXxlrwrpud%A6gfWhrEPt9Il+#I|zc>(--b! zF|O%)5`7K4HiASF=&9)WNh+72cPj}TT6PQ;g@3;hq2ER$uvK#zgMn(UD{G*@@&)TV zpOjK_1;euu`3L#y~o)_O%=mLn;%+JAUcGvEKx~ln9l2v;>W+(GQy9}8=BkxIy zu4wKT4HOIWcRie!W^C#ib4=;yYk=31=f#$2N;fPo_jr;FrE~H6L1BRDU&Zu%#>{;8 zq^MDkxhw~7H(Mit&MF8s_uvsX{i_EIpT!=hSZBI%_FbhZtP1mScX)3xU1<}S3bi?= zzmo`HWo13E%KG~JYl`*60~GKDb#&RS{z5@a*KMbJZS31&Q|IXi6jD2Z?}D6j1R-ktvRXM?-}63oz6JUh=dYABXVATjDJxE&gC^DB_xf&`W^!26gd}3zdqH zVP(5}JIVQE~K*iVhk3BPWDC8QJXgN8HmOqmr<-CmhJCIhUo6iK1dFuDS~$g&X)X_UBRF^qpR%wtmNrLz8jfZ zNn0P_I*sQNKqyN1GeXI+10W2*RZn%jIFKKW!(<*&LW11D4$x#R?Ad*7uYjoYAN8-A zPc2h_OS1*KTIc<|u$E2w2M{W>QoKv+)XMJ1NN*nToIQ>-7ky(=Y5O0bak|QQyZPn| zNTgD9=dCRF$$B_3H{*vMm=#aRIDdLC#l(E*;_Xce`jAR`4DOP6 zt$qYdL`tM&W#YJ4!$@orK<<=OO0e3=g;Vx$)|9II)$X0Uz}gRoJ$OJ!a+xYz;ee1`SiqAMvdvW%B9efGW;r!mSUXVJnX=tQ*8(zpGOu zZc5LvQn{;;F2R3zP4|c?aP>#<)xH5e=B5^@JF1w{Q`t1^1-WH_IL)};eo99rtGeI~ zx<`a1FE=f`v)9X`e&y652u^7^Eb6jX*0Nk5QP{boDMbM<*aZ^pW`EJ6SZ#9a21K$- zes7vyawBK6FHG)=K>a$NOzaMBnnD&i3lODQupS(xa&Hl^_Q+Fj)dPwF4_|Id)DlY1j9CY@T4RM+4z!d`+Gvx?N2Czx3KmmDrdOYM@91gD)^8;cc zVCK{SSPWfV#CTt}Wgy7_;9`fR@3c1I^l%&CIJ`>|Pve%qjAhzr1W1XNhC(Me7REjt zmh@BH@v(^lU6e7a3OM?a!ie4~Rv}H*GLfd>h~HmzvMxU&L334NW0LtU=pUd|vJHQa z)8nsx!FOp5;eUWK{X@-Rl8-?}!1I^6L(yHVenNv&NhWXMvj(6em2%nT8;|5IIl3gv zkE@jSbBmY}uw6RDkThwYTgqxNd8(4+-@c%DH1>{7_4HeoIpgm+9Y(*SGjf+M4-gzS-o)G!Wv_9x7M21s+pL~eVkaMTer z8C{@e$&ED;7FYMUK^elv6v&}o40XZQW4mlbTM10SWPen9>gzRQ2AR=NBC{C~K+ljm z8m}S*rk(U|9|Qa@%U|{A1PBYeeyc6W3* zb28_7%zgVk`l9Zgs;hmCfuuy#)rf{2&5g1PRaBXEqtN?-3u>>z&*^bZ#`rKQ&mX@p zuo29t>1+Q01^z-kRg7HFP$q1qC+$cz0d)KGv0~0+|6|M0)TmjixoQ*U6Jz+QHFF6~ z=7Y#%(wa^zO>MOrx-C$!T85b7uLYF5J${o$(N~LMtzW|g0%u9KBDk5;Og?QDFRm;reCNSUv=-NrU0xR9)9Y7nJqWb_6 zyAX`45)U;Dy0%KQiRhx{SVGX(XCdj$I@LaonMX+LjOrhhN-P~G$jn7$fQJU4^eOPgx<40W6EuF>cSZ~(zyUK2%KPYqB9ZFL3Fu9Ub~+Ke2yNsDq(g# z0s=mUF>A+&MS@p|D*8vIBA4SuX&NPZLMqHG4R~+eCol?%Sf$zz$r-f^I)qz~*YeyW z!J@E~Z$pA^^XHyE&L0bmO)F;*E08H+tc2h!y6BeR(tpH){`;|W3JF!gH7 zuim`LLv~z(6Wi+!xgXg|m=3Q&_z@wr>rLD0ngLJ_2%S=eG)LI?SLDD>dQQc&iuDzk zdd4AlQdP(s?@Z6Y*^Y#;hZ-i2rHHM=tMlU@@cTu{zCLI({IZdb_l7~LMlitaYvpNB z{){qWh9T;}_ctlxkN#_Q-SX=4I2rMiE0$!M3YyLbJf+*w_M$-t)~>I35yL*+PtSM1 z*uK0w>JGDb1No#IC@4`s*Z?bd3Pr*QE)S#H49@m=1J5}S#s3>GozT>)vk81*Rh zbg==KFjp$cbFT5tFL%dj{~$#hNxM-EK*jPsEyHw&!V|B;m-a~??*Ec+9-mS3`E2LO zF!7R1G`_TQ&Gc4g9!ntYBx_O-O2I5$NhgkuqEi=ZNP#(9%N@z9iY&^&ad~BRD@XFn zO7(LYtK@kNiDPpkJH9*E_fG4rs56gCY0slRKQnTvKf7D0xL$Rm!8hT?=oj|q$LHSJ zK|?iJ6@9L+JEw0PNlg{I2$)HI)wR4lqsA}a@?ccgt50c-c7MliGTyR?fs4KpNEdSinblrO>NzLCl9<3Sc`5Bd?>_eAT zonCnIy_Z>2Fl*95hYSzXD7h#h>D5+2FC+8_{`IRyGS;KP2W^hGVtZ*Kj2*&3$C zA8LBn*m3&&+(J3_h6Xp7raFyNf{y=sTcYlyrpGffl##T!s}Z-XxcQ{@Wv=@(0Rx>O z_=ZY5wBxS~4@Z}D-rsij_VnU^7XMY9Jc`wnuI2J9qc2~7aEDv-%?`)en}KnB`ob{3 zyQ|<*OF(uN0HX&DkXySO`(;?J=7&ZuIepn`QFEP6+e8Azk;OFx&dCwJ;C9lRM~p?8 z8%TI+d9wwrzjD=Sl*50zrUV%*b;&n_e!+j@RZt(CxK8Qx-4Hv)R~H9FZCSoP%`SJP ztelX$3{pQCRe($-dZPwq&g7ttPMX=;X0NcHUe+y?Xho3)ipbzqaND!8!SiJ6e91&v zN;APGNQzQ>tLgKB6jr<&?Zx#NTEhvGj0CK|;sJiieAKl#4aQ?+%d5~7HFO!BntXJh9Aj; ze9H3~g;I4#IEtlHmr6j_KH;y;Lmg`q`C-)<+~u2p>tfC}Glm_V6E&}_`~v=50qzXz z>JDswqRlaOVH8dPJzFj*oSgD8+_)ZKJBS2x)B8)U3yFwCG4^|%nKIZXc@q0?W!?Bv zVrs|7R2~mhu*$l>L4p>5UsbS}Q)ic6Ev>g=J)Gba)qw9I#w_ZpEW~SXm|RE2wo(`k zC|9LEVxRCTdEYpLmw#2Hn87>7kR8m|#(w|rh{TTvvQkvRe8v;8x3Wa$jlbV@39?>I z>tF^XL9KJES2HqxVOj<8h3^f@0}w>|kCp!Y6Cmjfhs67otv;Y4TTCmGV5M61s)&My zoF==Z^x_-WqUK5$k$inaO@TdEM42_D-Kgli2(&Ni={znh7FEg3!joA zqj=lSW4c0AX#h)a0$6{MPoB<=FRy@DkOId&{eJJ)>13Nn7+!9b&%)BOriP)ox0MPm zecG|BZ9d?MRuFaXIC#Gxn5Wm_1NOF6!J0kP*>m{P)zyc12?u4EbXNsk;*~_|50^>A zbscunXpz(V!GhDundRd79)^*k#6NF0`R@thjV{%wUpIe{5>s(mIxJ`MR8UudH0`7b(*U24`)n%D7GEOP-@bL#KP0m1$EVwGcbyIMJfT6}$b$_N zge;J&X>+&)ar7*C+Vz`a&FQoLTkw*<7=P3+s)K8i-@yUbWL}8)9G4~Plf2oKbk2mI za2j8HNK3^lo`C~yqv{n#1RFvNj*3ndT-Pj5CMAuYuJ}ZrE9fp?ePAY!e?UWWQneyH ztyb8Tu5R<4IH(UEC!1aif_rGh%C$FJ8h%m*sb<|eeC5?}rP|pEwS-#IsI*SNn`GiH z*LYbaPY$t}R$$^qCJ_^=8GdwXJV3srY`u_@EsEd%_s@ojSbMj6@1E?%Z=t&|t%2$G zS8{y;_P!bVm$zX9TlNueLB5KgSW5gSzetiNUoE%(ZRcWbpKcqHps(ME86D%!Cyjej zJY~OoZe0~ke_|Q$K-q`|^Dsb6U|$=xESLJOgiq`V25XFC>~a?X%N*rxG=Mmj_N8 z$0pwR>w3XwELm59dDRMvLBgWeKrXi^(hY@}6P7gyP4%a^)KfLI?3a6}7o<@{g;1T`#4T_NK zPIBoGI@J0Hc=iu)^n=thnEN0hc30W`<+xpmAK(4N8&;`kE5V@-avh`P{6v#2Yb&q> zt*;ox^UXu1n+LkY!yUGyryNXQwE{dzaV;Nj0XF*mS@o3VU$wH9q4&1IeGREl;nPPY+go{=A@3^*x>ORUls; z`v!P<@*bG+?~jlgV}#bKts7 zBto#K$aalSQKjrPXxipgwLT5ck}$3xJyd$<$H+CR6NUrs95IrAjraVwM&bt}&~rmZ zb4b5N#2Cr0sWo!J(JNT1VnQAxM!#{k>+FOK6wJK!Ld=)JwHub|A4 zAVL`<1zfnEq2ljRuKyo+Bd%~K0VT`_9+?-5;l1B~8meo{cNJjM^xzCoKsB!I`27PU zF{5T8Hov~xtGnQSp;&wy6vtM(6puC#XbEY~VP^4l#QpzBce4;uo%j$>>pqY zDN*y_QF5uq7ixZy`peWaf<})%cb|dBd~^otnq`{C!!CKQCft3=mZTsfES9#*OYwbN6)?F%Y{zo#bKBu9z#(#91B}1wrU-+fWGzKSVs&#s zwFUS(g?<<$PKKT+vfw~ZIhG%4IVF~$(ojF?67_bs!|)X)n{~7B@?zQWgRtqzr_7tr zef&plc^^G0t@VrBP;7k^ZfO?~(=j>4$a^&{j&}NCx`IOvOPaTOnPU2b`j%2nX4DZI z*(Wx&(eERc>;2_We3W2x^(LpwNbYfU`|-iUl83+R9DbwLP|yF`AR6mFjE(eC9DR4` z;_`FwXxl|x+B3F*v5zB1H8c8mvw1bYzPgrA_uKMexw=)Gv&=&kr?SH77vTyG=Uxk# zTLzT<7Z`O(5A?Hn&h6Wmsjo_-1{>Ohgvqm!S%7?m;av8p2>Yt7K>cL6BEO@&!#N&^ zSWy=!&e%4&iF!;pF}w=Ma%!c$uTB@5Sr{MJeqJ%kcyZ5It|-+h)I;#H)Y}_}1wn%M$sBVvO_Ve)2+t$>v$T zn)Jm^DtI2am6)z;tt*T*5G^D^DQFU6c=$(t=xh&wx2e$F#2P2I8A8vR*g6og_sol@ z6vEZNrlG4W^$Y#0Lf{-Vq3Xk2*&e^odeLA<9s0bcx~f*Hi_%J9D}kE2L%+y$V;&n8 zPF+EtLM6(E8^<)4$~xK7lrw8mBAe4h89VO)gYn9K#8RC8bRl! zm{h52ya1~Q0G2;o*Z+>7P2DI#354QSgKW#-UhmxY%8E^17SU^@~`2U45`t7RWUK`*9eOn8EZr_ zubo*3By`k<@AvsizQTRfE_J}|ey*updP=$}I2Bc_v;LI^OBbj*^x0XTP+_F~qVKhQ zYQSBq<9lwOYRfjzQH~v=3R1@;0e9EjqU|bt-ggvtkn0z2AHPjoXzkTUw1GQTdH6v2 z2DVJ0SfeSsPvmW{(LeT8%zNpC^zG*BEoWYeQ~87qkkgwv!ZWb=-0>a z>!_ZScN^)cqgWJ!h)l}$)qBD-v$?&L`&+!;(HUelVdw znO*a#*%<@nMf;#^8Gs|J)X|S;KhhV>W}^;)r9T3uMvVMjR~3g!6is^;eqTJKtQ1cQ zdfH8tduzKd{WU)*(FhnvrbrBBAU3w4y%okHtt(i?rUgYeZx*nv8TVTr%RJC-3?*jq7+pls0wGfoZE{5^tZ+5Pie$8 zizjeeo3xC$N(VovxGK=oZ|WUAq0M1LQE?oBWR#A&q6=I)T zQpW8e|HRgLeKRDJi|j~N9EKnEubw?op2(YJw;y-kWazxR&nhk+yZ`IWl#$S%Q!~=z zoF>Me7eX)j1+Z8k!B$0v}5pEE0g0@+*$_cpPT>H=_hHJY_vu9zj=zfbpE z1a?Vk_X)lcWA6=fYJ3CX#L~I_PzF3D998VyOczs8jI3AO`6d*|_ri!Ua;}-i<~ij6 zYtoaRx+5|XV_+!7(?B*tcv2-RSZr6ADCJ@~oTTf0?JLUW4X#H`2A0>9Dl3bp21MPp zNda2SCr3@ROjplPYzafoRCbS~v7{#(aND`&-D?;#!=5Q$ZWkBnm)l}4cR+Wq9oH<+ z>B_xU?0#=JSn_z}VJ}*`zXX{Ceo2e#lV8@g5nL`eEB-u4O0c$ziB_|=e)o6_DOlgZGge$V>Y zS^EAZfr=sCgGGy}5+E5k9s3f#7||6$vTn}0jS*vT4;3Xjv>DeqwE(Q|NfRM`cLh^l zZQ^fFd*66N>JO{`MG5DAvH98i-a>@qx1P+$KmpUc(kG5wYmna8E;64Y8j7TOIC8{?qlZt`||5^kGi)16l0M8-=4SsrLhgEti-JR zpWSiFipp3Q7ZA7v=4HJz-UaNS`Bln02dCs5^igNZ);P~We|A68R3cLbJvLy z8jQJuF=NLoqt#TydXO#_VzW{g{GH94M@i;I0fKV79#8ZuO_gEYhJJ>=;Ho6AYPZI( zu?ChvER*d<|hn9iSA7s^$tqkr?W8AfFbh} z>nseesEgvwYZ^9xJ9W(-vT4{QCq*D>0tqfjR9Cw7hBKqgtQja{(cyWp(&MTp075_5 zPSz5vrDcfNP z8*zfTr|HJPImN7n4RN;AnHWH_EO-{!&;pE;P|%YS2rvZ>0UFApC`_YiXg?H>DszRp zL@|O_@Vea6Bsn^JJgk|I+bd+2f}-V83M46tofHyCvpdU4yM$_ArSHk?Sxw?5glul4 zPv)&xFKKQX-fPg$r@_0uS)%|b-A(3VM_fm{1Q`??gR>bh?_b>V%W`)UZz=g&FnJz{ z&75f2f$zdV*vyXs6ZvJ_*PS8#Qrv?*msODo!}&XkRS!LxqyHcF-aDG@!2kCTYSwBS zirO=wMu-usRBb^LVs_XPd#`G36`NS0iU@*e6-8T$R*lvQLRGaji=tMwx_C> z`}=+Wxqse!?jO#HbG&oH8}GbdujljeFt${D9H0gCy{Jl$bqtX#!^8Ql%}&U!!#AVYj?m*LW?1ESdLwFk_K%{uq!?@N3x7M_?&R^H=|UbC^l zIjj(7yE{2-1e(b!M1yYoN}{TJ<*>2IRG|T&B4p5De!yv5 z!5L9A(6u6UZct@(pi}W^5W?bB=Ze{GPhi$#TtC+(Sy5uDF8w6VG0V>VBTxr$7>aq| zCyDPjlMpS^=3dRXtuyl`INRQNQ7E;>^9x*oOX&7FxMUmcGx76Ndwi+Za-p%TnX&95 z2NUWPSB&5XvpUBJQ_mq8a1aBicLE0+5sG3+K~7@8fFwN17*xe9n|EjkO-cZAMAs$S z04F(`#%{KEVA4YR8WDfCzW56wxrh{JnKs$z@A|WKRYS5JN&&Nm`W>ck)(NsFa-Dec z3T_&Qd|Buue|7d=3*$-sTLmGn{V`peg9AUU#TM-u?|nUNOuGBxG^ePah65+2$e-(*$Xr2-UU^1TVs8)A;n^h9xi0>M}dsX-R{`>Z@RFhZ6=QY(Vm3&I(zp)WiFSL1 z^5;>cP=A-oU?Rn5q#<=h{eIZpiUdC;rxDqt>=E@OZF`5=Ro!IAud8%tY+}P{ZT3>* zSmbzi;fzod!A}hThmJCn_uw2iji4azivN{zEWR7xTNF%CV#)oUQrSM;V0QN&?GD{G zdr|1r=(qg^SFcVLL6I?sJ^R2~*t~WG)RjH(p>qU8PQ22F0{3=aQta-RlO-Ep4$1AZ zjGZkdoli250y2c{aBZ7b4s|ykeVshB6c}$gT@$@jU!D_&MK~~!i2svr!!Mlwm3NF zQZSF?y$n`9^wO$!0(P`Q9p2YPK{DAU=Ub!uY7tT>cG5UT&ALxQcZy(rloB$g!?C}+x4D8YiKM^Uo}!g)ZPSOo4TsIUM?9B_c}p~0XCcm{7PPQTN@ z0xYnN$pZ=TsY+@#Y#2aN1!%!oIo9I>MdGL)DRjo<3*}@+$oLxSpaHl-ur1pe6F-lS zsQ>9RIc+wmavlfL12J#`kwSphAPH09eHY$d+pw`)Oi2pXG}i_e5O_f~SsE*D=msOlFLoy3V+&W%IG5<0yZ@V0%E z$yUmuU+oo|)GmlBv^=s`NwkY_iC9Z@uP38n8UnhL(R|SDv<4mYNP);^-F*`^E2Ev2 zrRC15X{J})u;w^@X}-C66-c5Je7-g;s@O!*L>nE(DYV_8HA5Z@Jvo~$d(Yz2l8^UhAX3Edre#2jyyw@n{OC=OH{%MD-)COMIygRN67kq_vkq}GvHt9F zUkbQrSHLN3ch_PuUk54V%mt7OaZrRKcjea}0!ydj%Na|(hGI=O?L~4h*90-Oqm|f- z#~WExK|SoVCve+@3MwMmnghVMv z;n&0`-%CLeW`0OxmS&gU5r#ec#QKLohB?O@pe)Xr*zDKG>Ju+Rr%vj}B0W)#Ph*Qh zFQvT^N`|ic6TJM3GTbb*QDGL~dj#2qzEkvZ_7^r5ze*IcHkF5^4$(E;`XVY+P@5*a zQw&vqc@CFa4kcdVdX^2vdlxk4$IUi5J?~^`FWWEw*{nTdqJ zW6pAS$n$%2UpS-@^)TzD@r|!!WE3Tq6B)Cf$p3jf%Qo~@&H2fjzS`INh=cV8b6UH% zn4*t4t$>k#Mg3xI93d#SN|+V6<}YNR)$m??lKIPe-?oh!=PbY)w1{zJ&kt?CfIIi( z30QXfxK1MLT}`>U!TBLtOJ8?maLcm7jRj>q(t~#(a{BZ5QgqY)%kB_cXq@oOjg{7- z24$2}!b?a~WF8ZG~WoZx6@d&(k>txI46!*wo#Zl~q6L4VsN(e_n}l zROM6;KfxUE8iz$Oofm3oRTTo&v`d5NhGrcqHIf8mLr|0SKq6Z8HM_bIPzL^K%k~qB z8FW4TgH=~MBng5FSJOq&kwomZjl2jP*q5P{=+;zBTX%RZ|C46WSO!wtdq!|ULcaq z#-QB341DHfz~GJcHdP$K?}ET4>TSA*8qh8$MHG`_&lVs9uB~DuU}CAZj6y;C?iH~} zo*sjXiuh#b$y_`-zF}O!TB5HZ->i(k`e}M-rTnV-AZ%s0dDm%l@s<5kdsT&+-Y3J- z9IptHwY1hKiJBJ{Z9%eJ4pP81Ey)JsceXu7-%)!gBNbht)^$Zj@a0t{HH1!y?j-Nb z)caz|#Qa*%N(Bq*M`=$KWe1Xln@;0>zFa+AoBooQks>~*Zoo)#PRj6bekK%{l8bHP zQNP2G17?``IN071I!Df6Yk6;%d#1uciYzNYXvipw*Pb!~QOr1WkW*%i_&6jgVZAh! zk>Vn*B>zaH@fBA`e--zW0daQ$J{RN@2J=B1(semJOHA#o^k@MO-{@Z0wNO-x@Qk|q zYOcx*AN7eu!g>XM5jBT%*9cE}Gk5hH6Yp?~k7d_63pMIfR49c_aA(jBp@YwfL#BYG z(MG{=|E=>Z6Y4pC;I0}h*L?S^iG0=KL^;06FZ*OBTp!{P{XJJTrw1$dXsSK}%Na9- zUEgz`Uw>Mjk(l*q4tA$MqnX?pT2^WbwT+$1fm}bsZew`J5eTuSb5*qAqL&|bU|km! zhNdgf8o7}TjF9zCnWxBlmhQE<;vD2(F(o5Awrv;fGBm6?nf4^@)nip~TCEfT!*^B4 z6iNlJhQR40TvB$Jg)!Yy%KYAb)A^AcW5Ytd6#ZMZR)AeRe@y_`%mTIn4lK?9jiudE zy_TGOq&enf^BUa7)T`7A2#eL5_V3JEYL=&5D$xGlXn8i;>k_p0GT0&VuwlfT&{Hy3JQ_0p9 zf1&9ox0eeAKA2olm2$mPFUr3BEG`k>a?>uIa_#~QEj+C=b0{nDE3(1Qosn*fr~9Cd zwIXX7E0_Tw;QkOasRDejEhu#Ik@yjLSNTo#jTBnE1R2AYd(jVGLGCF`x$oe@zh#bdl4B%O$$g3@`aEs|l2g&%o-|6V%HQ zqbt4gDbp9#Z$iCE#uAJ1S{%1@rw1LAeFrZEgO^KyY*P6|@toP9UxuU0nw!YLHum&vrs4h z?Gsvcaf;i!?gCtnK;NbiNdN>jf%n&pf5LY%`YepU_$XoT1>$r8YQ zpC%)6=prZdI_Y9S2$P2V4XPPLUR)|B^M{SJmEz;?JUkC29WqL|?Q5syaxC1+>;)p_73YQuWOX6s{d3@Fl_Q_}H9a^Z zw(`Yi1NI=D(N$g*RyQ=WhCqrL>z!lS1%NFE1E^0lI5*r6Yzt>3XJ)L9WNV2gt4Bt^ z&C_1x%sRAF+`R^}$5)23Rk2fcb*c7gLd_iYzP+Af5<_9R6xTt3mR%--Vn&y(aUlv$ zP4T3s8y^M7T=T@hecQ>n@#*_$Q%(cv5W+1>u9b{yQD>8)$04|`*kAPc(3eA{0d7`l zbkhCd`fkBmrl-@XP*h)?gzwOXwf&eD2OvG*6838Q58@*Ihb3vZk?71nb!)cNza-Gq zxlHo?LXB0eK6HWE>~$iwkgu$Yi4X|}qFN0&K!JGgyh;#5?+k-!Z18%500x3QXO08- zl7MNrGrEwvPT3?nT$Pn>5lgCN$>SQ7)gnX8aY_sqiqvBjlCy+}Iap&LXXQFXvOqyL z&i37M2k&>Nu3HX9?v@WkFB2?Hj~>g|Nb${?1N55o*N0WK_!{%?=R_+5zjg08I8Qc( zlchSo*M~S(KThbKt))eO;gWl&^+_no(4#Dzo$U65xox7yamMa!NQI9snzUP>lpy{! zkEaJ$M>s=DFW0b(WXw!-9<+H^qF>MFFUJ?|_|>*i1<*(0&)&57gglFj<_r2-Ppweo zAzfrl{%l`*#3cKe0vrpaY6jjF`r`c<;}(6`8B8aF*vG+TD9LLlyF)r5IHfd)cNP~G z9%dR@^Vd@|s~sm6;$igx-<#;}Cw=^9%uvro!HkAomq497F4Y0h!bctZ(#lXZ7uER; zTVhs{0<4`qSxm{T{S>Ff5^kXQcmD70@)eHRgEpiyhH-vZF0S&&Cv;Y1w+QGd6Uf9^ z5B(&yV1;z`yGtyGQmTih&uw%_XU9|gPbBXjGp2_d*Lj~DH@~?Lcuv|`eOFj$q6ZX}2IR1w#8@n{FGQ!fv|nE3@p<9eqY8#kp|!X9TX$J`=+zQS-#u(o0hA;>?XOKp`7Wj*jJn5CIr;wSf@BdVqw^H&?G^h`ZN$rIV!EW)2kfH4j9jHU-AEGLr0fJDPP5e zhuM0C8U+Oe2L*ZshKp-)D4SsX!@WY4uNm20^YRGt^isC+3iP2Ltfiu+@xRfAZtMSU z=-4^_&)CrAeR%Wd`^r+`4l*k2=WLicA?H>rto!bs*m&U%*Pj*J3+9EUDw&dzfA@cH zzK$GPQg;*ujS0V$R_zSM^tv6_5dg$e);;M6q8zO}2Q;R0@2rrfko8fzWM;xetv#zn zOYi$udcMyXY#u_(?~$r-N{m7J?Z<^nM9HiWt80IQdL&}An6}MKfgOUfbYmm@_eq^7 z{v$O(Mim)UhqOKO?9Ugj$__Dv^+*-#E)iBIOw9o?{QSLXgo>j-0*onP+H3N-$1ah% zpz)wbJhfxuL_%yz~Ok%2-YjC!{49v=(4Tx6Ji#N zz6HerNZY0s0C1Q&E|QMxAJgd&OO=53MaVD_f(5Hs+)FU(y1^xS3KkzN3T*XJKhRU8 zcqeW&#L9qWHzpkH!= zL_^oN^Kej3JN%*E3wiyw5Chk-_c&Ym6&JMfJ>~I|z$6t;YQaUl^e}_Kn|(ylj?sUB zSAPQZ7o2`q1a1V`T<x}QaJjE-(og$i+NU(VBU2=;|73Rh)bNhDTdapCE zU^ns&lNT~^Yi``JNC6f3BVXpQg%=rLt2>JoOfi8fcD%LB`t{Hj=nda{(AQTLGzU(i zF6Oy*yrqEA0H032_BVs7xULO?ytl6y4haYh?}!@VDOk+UdNZ@lEB z>-FoNt>9KvlX9#l20OnK^4jMpvkbQcpZI%DgzDgSg+A&vCH}|=3n2d>u(dC@4Yyvt zHaNa=bZU@cZtS!Z!qvF^#!sQ( z924yOuS^Y%NV78CNr|%@s?8jahNaG+I5W0w7ssa-M!z*+?Ah)0*oS}#C>7-zS~7lK1J=esH+w6l>g*`l{~Gp~uAA|EFyWht%S&g(BCe#ML8*Kf7o!FA@Hq^$f+=i^NOC4)2jxb}rwvu=0!rKBS-G;!rb7tz2gF5wl0L)m@sRRUoo#3z^xJR3i{|Zay_MME#I}~ZVU%!VBTlJFsNihwc=g}8 z+={Li_PxcEhQIG5c0(+S*!IdDGFjLEU|DBZM7V<2cdg>LFwgEfqYWaJo5jEQsX4`6 zcb^K_yuaXhhY z{LR2aS8`WqEWxJzN|ET`Q6$)?clX!4?CuSkI7t=n zy|UDNK|u&1bs4UD zof`7b>}``nDEw#3?*{HY z+cpcL_e+WDf8Fg-e*b68Lro}f#W?R05y|u)!uE%mC^XejO5`!8NIl{8 zB1Ti_GD~r(;?ZjUttg3Mxfrp}&gQXVJz@0w?M<+Aq(Qj1ZQQgjmCI`|Jo?OE*=F`A zpgDY0GNY0NdSyWwAg=z51C=xL0JOniwUW@!pB!l5(y^`x1HzsTv z=PoTrQG=1{Dq*#Z-brDIw&k+*$Q^^PHpbT;dmb*-3O~RCY;{m{=DaVR_Pb_v)jelrGH#ELW8wlbi@yv&&>>WdsL z)T5F0yf-e1q#ar#d(8HanbuxkK@~DE#Og+TqwBs^vB?Txn#ah-d%Y^Z3s%cimQc5Q z=D2Z34mu@qT;qzTrni|k>G zB0&>)__B``RU_7G`GB7J)H*&hfzPHLj9IeahHv>U!Qqk#{D@RRXw*I?2gZaE?%gSRIzN^j*#~P3 zg~>Ks-MOJXtFe7mAP`2Dl0Ip``lbS$tRFbv#bQwzgN(vFe8B8P>oH^cm@rZ=+r+tI zg%HR-$Ru`2c$xA#y1%g@T|H1;*H$5S$AWzfx^D^un9Vm9K-9f{Zqr}?Z>-WybHx|g;H+kT9&fc3zuFm)- zq%NAV`^Vl5iL9ggyV%%Hb#vaSH%=dT=UdWf@msJKGcPeIfw6#1Y6ZtAqWh^j$tr6$ zR0TT)vq&6LCkQN}3X|dW;QC-ilNexI7D-jVNQaXouI50|MwD&}xNR9FJ-2)OR)O?V z7}sc{wdbrkk|wv*c5l5i=e3nzs60znA+;Hm6h^4#EB+|kY#L~=iFyqnchWrvg`ut2 zYf7=^0(N#>>_1RWq2L)0THY{cgtW%9@erg3U*LR$?(|iE$FBxAFpsaDe+d235Yzm# zb`h?MCWX-ozpWRMA!d(s*NI+ZW*}g~J)`0#mG|5|WGQh`Y(y});8pZMZfs%>J6XC= zj)`RSfW&ll9cQ$VwR%(wVFM=VJ{Y)fBaGr*O<|bE72z2MO{DuyQP)Q{4N}6aphDWe zCT%OI?!~#=2JDZ{vp1={(vt@SV~tCI>@~Z54vF@jZrgB72H!dVV<@|Xi4CpANqLW% zzPGltIr9YTRih}hbtTH)(c2ok3lXtr+E7oiymn9C(25BcO+j2XvJZ4@tgt6i8$T$I z5Zoc&{v%nmB4TP*NdJm@zUCW=)7et5Pj@=5`c4)Hav@`K4wFxjI{eNFB#w`I;7XN%-lYSrg4`e`LP+f(q|kKIzC+NWuEM@6 z)}54i)$3JVWwHYDx~v#vIjyzS|g zaA13yEEw!N$jE&ZH6}vFBrN%!QjbJu?m*Ktig9WN%*t3RVIgOL_S6_XA_C#sGX@{m zQ3WDNwPWC#PZDDy;1CmV!h>wF1k%u&4f_vUCYG?*T>hAhk9?&U2=Av+0HN_XU^Y98 zlt^Q#nBMjBltI*uy2lyU@LPtK&aQc|K{F@oLpPH{D}ew+YW1hqyG8 zIiqjPhDD-f*96nJ_2eaC^{~aT%JvkrY>FpGAb6eN%YdS|CR6O3ThG1ZD2B{s9(Xs= z_t4{-*RWZ)g$jxXuGhKiI>16z)}N9~LWMSzQGWFGpMM6hzdkFLo?y8CK_Qem@PV@z z7*@5Mz&UN{u?Y{uC9bX~w0f%SVm|Hv1I#r_8dYLn1<=G-J@ zd#2ZiK67oe>)%kvDw$v)1-Rf^!FmRQua(W3`ShlZ6zdX^zBynN*oDxlRpX{T<+g1L z4UKCH>d+IhHMQ%_uj7OOk6`MuQ=3*c0}l$RNhTgFmCf27f_3W9h$^p!J|D);W`{Mt zWPkRMkA%(3h39e<Hf=v8`yCp)mYTBw!*sV8socBmWi|Q8+ z2_ew?CLlp;V|D%|?4c}XYGHSWMqtE&Ey|J-h{Uu~ks5Vf_v>x4JNuD%!!!>4x)$ zo6WqnWt;?Kw8QDWkyzBlM`U0q7o(Cvw?JcOE8owArsCJ6?#x(G`Aajk9^Z3OP-cw)vvWkR4Z3N{GH3o{T3 z4mjd-`*1ZYN|M0`UC=GyXyO1E? zq6dB{S?V|$gXiu*W1@uZV7kY(Llj0cBU%prPyHd$trl`Ywt0|$T@*imD^d#guC;ab zyu6nJm*jeRP=_gB?COru5m`J-@{jyk;$UcJq_gUx*CBmR`5HGPP`ZAf-bv&2#*4)U z(BEOdBSP_!+g5-h;{G2{E&Y}lB0pjC;5jE(h`&?$(*=xNRcjWD{r})Frz7sv}!8dW6QH=KUxk;bjfBgqE_&V z)=(_opC31|lrx%~VPO%;jS=$te<@<-xDrE|DUM8bu5_Z@p;4 zBSrM+#Jjj_{4fN2|EFo%hw@H7lMg|+4I4&8p7&Z=oMk9reE4~0`Y@(yYyZ9L$oi{! zX&-U2*6@V&KS0q;NOAbftPutvk@egj@G(_y!Ig}sc zN^~c7C}WfHYrStjB-Sf7`Bb+Mzk)X%W0x|>u1gB@7E4;#a%pWOyV ze&K9dU!2?(+SVVf#HY=wRoKP3&9503o}zkR{rJ@}6JMsiT=I2f({dplJetY>6;`iQ z`45m9A$pa^%HhK0xk|}d=cSR~P2nTLc^bLPTDutX6MiTQ;V*u_u9Jkoy?2~am$r9$ zs5pMsAMGV|Dzu~9{uOKy;Li`6owgxa5rR4b0&ZH^>M`52d$gLI<+HloQO)V5ZOi}Q znQuct&dd7=&g0$jLwuK~xyu@@-$~C(a|XqN=vE*nNyGw<$N3gZ7S)yupcPJ!R*8mK z=35z>=xxUPl7i)+_<9mwnUQ{bS_$hn;!hMqd)Ydk9?)m;-81|H=Efv^nw7tz&J5B; zJ`#f1B*2)bP2%vahYXWP*5N|MjjGT)BKwLh z_v_+|H$6XGI!|JWVw%`+D!v#HwLBmAWJh(8<^2~P`i?E;#Nu}N?Vc@wyEbpE*x^FivgL4xo`nSF*ISTP;z>@dgN@7i*mHSP>-GYU zwQS9yqg5BSts$|Cx8x(`5D(wjbwFZZ)#LOea8R24gL?HJK4DkdgQvH zYZ{|OX)-3g7t0r8o$L&~lYBbo%R=^B&Ga`P4t9sG@*Jo)hg(@y z>II>vj`@=9WX;CUGBRlC&ER&@1Q_eZvv8ku;dezT4gDhZdm7n^3BO)d7A^FH(w0Cc zKJKZ%Q>|zj^XL4$lmOfI&Ks2-mliK9wY7=736g&pOOgILF5hNh6YFihhpth`jhcwX z)J>r!!YnJnU^M~&Wd>Kmq*GLwOyUrx&VXprmCr&lD;NM@m)Qc(%hthHlT=&U7Eu45-yjLN~oWuBrMon9$kl7SyG)pxaH+uly9jfX2iP0!Y?0Pn#+Na=Hb7#iR=?nD%uIL{Tfk+? zSEIAO-&y;wKwv}G9k)863*bj$T~vNp-RfkR0rv+J%=0PZgvc#YT%GexjZNau(;!r` zg9<$^#9%#P)&4l(+u*P9^3qj0x}|Y<1^yZnXWPdPtEGo3fdKC;s(XoG6=O-&wh5?z z(}0M-=S(i7b>`v9^E-L*s$L>-9iBSW~HJQVCr=HSbtudy4eeFRG?L zPXenjhXZ4RQN{H0$JlR7)cc7!cvsHPg3w;4BMK*vg)65hv(hcK=XFQW82F~M0gnYh z6d%Swa1XKw!Y>sy^o0$o(SfhG`+R=FH%;+F9XF3ih%w_Ss@Q z7!#%fj>k`Z_i%WI^WC&5%OZdGuuyD6_keaWVGzfr?^yjY^q>T>EYZ#-jD~m4ik-#X zbQUh<>m8-@XzXU%Tl$i}HdXp+EZ6VB>myYq0^48sAZ(DnHD8Txr>>Bc3o7wtTH6*j zP%OhL1(eN-wW1I9Sif2z$p{|;7aMypky?0m2N6kxI`aINYk$~(U;F=;Wng8bsyc`2 z|EJEY^*_{k|Np&Ut^ct#tfkJO_1}(GMruJhw4nd#1=Am@acHUi&lTbS_ErDu0R&a3 z=6|mUtJBrA|0@9m4K1zzodO7_fRq1Q5&l0TfN;2A5g`Mhr|{|fRD>}=1}Fq#0M!&E z0FhMWB!jhcfSxa-J-ML9IUmCSg6@x9laEe=D{#h=m_yL{T6Gp(Ku3<+WdfW#rjE%t zA~f@xpDERn&E+j%p(PhX)A}97OPpFDI!;d>I2Jn zVP9Y^zYM6$zc?R{9r|B?Z@MoWPC=T7sa~QD!4%1@T8=c`^P1c?8??^f8m;QZo2C4I z`JEwOArCeX(HU+BQF4M|ry)+EYDPgq$?c{rE5{xW)^II;eRztL&@uj|HSh20@hjT* z^w3I{=VJ>AOf(kKqhrY)sJ7GHWQbhAy&Vo`%gEe+@+mR|OVuQ)}l#-WKO%-4qLaj$We zm(Po}W$rq)zqeHrNG^ev^1tD<*C`>N6}E?sK=a-^--BnjEF)fa#Hx1Wu zcT0=`kzzig_!@>y=X&d)pI@%XUuk>rYvrKX-+rou-eA|Q-gLI{kd*LG&Y86dr9R?~ zF{0+tN4TM1Sj+)-YS)d~-uN609acqlO(-l7-1)5IZ-pDMZej7A)39+i(PrN^g_7>N z&!!>vwSt@Ww5`+d`A!-9UBKN4MAH@ZCSlG7A0%w0YNkTXnKG zfYH3AJKVIW-_{}cL$0Ce_cN1MO6BgI8y89!c#U>@y8!cjRUB4E)c}hL3g78!DvVAt z4|v{TB=A~Ahl5@s@sTw9=!t_=c!~x616=pCtWV9;=%YLDOy#>*q^37rmd;0-#8QR> zx~I+M$}@`f<5}fS?a!_rw#+B?eL{DP#^}SJR{T6yEH_*F50EC`(qBQdzwrc`HV0CC z(V;Wk^emp71#w)YLAvQ^(u2l+H}ibBkT&*}C|uN`!*O^J`iOE~r8q_39{4>N)VLcstC~48JKap?G68UoS$d z?H?Qbd~FKbv{oRPb1MzXcFolNst%ZIWy1U(Qb#Y()CkI!t$Iw^MO<-y*FKZ~g7#We zW2N$Awqb*G2RX5po_(lIySISk8l0O>}bD{$o6)s)Kd~jKGXWC+2^Z>8CK}@E|`g zTAZeLoay2oov6~fbtPr8XRTqpCSGId)9w9)k4rbWyj^`SD31kb+<}WBN0{ChzdKcoGNL`+~UFO(I7V^l1fx|4H#p@awx#68)@y3hli@1S-vM(tpS3 z3a(R;M~)L%k$@Kod>2oZs+tE}&%-tZ=&=n{mjc#P@$jwX9l;iNzn@Zf^UGyh1HTfdB&Uap zjU@G#Qmxq=S`>5NIhto}_@WV&aU0)SbgcK8cb>DV76%T&1~G4%T+Mw?G`UU^<%wCh z?&e!-tHcSEw0IRq+LYf;0f}bzH4c~>r6cug9&YaIJiRy5W>PB6bK@?>*W4`_rOdLn zNv(lDK|-jG^P!N_X)g{F2bPC=DLz%c!zYagj#fOwM(g#4WT=-_FjfWb)Rme)EX5p) z%P^pPDoR;@y*h1;y#WHC(*hQo?X&s(K{c6))m>9v(>K=V?>6B_!KDXW@tYr`UJc{pW#{O>)ai9Ih*ueWCaj{Z>VviEN zgyY7n>&NHfn@Q7X$#I!9`!gDP*fmnWDablxdJ(ie*^9eZWA;r$N>Fw0MwOZwjS za!g&qw8I;ztRzE$7Ik$AySh)K-5*^R z?EIuJi5P(e#B;d37F>3>T{JE~%JK86E_=`rjfAns!E_(T%rEBl(QFFIo9AzDYuPxy zPyTVB(5@MBI@u`*6HnZ;rfbNv?|45sOE&+G$qAkiWO}cQ{>k3IBVf!RGgxAFs>yqYCBp&rC_^y1DJ}I8R za?&ukPUdKB!$|BeFeb!Iq58NbGCNogXwF*sHj z2=c)Bi>{nlp<9TSm|Aw#A8W`@2gTs`>pF3j%u%tPS4FfJWIkPZcEwu3@k_bPckwwN z|7JO{X8_^YIjz;s8?1ryf15(qU11ZK;Yhd1@ClM9hA-G!fZk&J?T0;_>94DdV@~kRQ~B82df@^7mbBVwD^ea*8i9@^5g5Mz2nN((EGuL)_m7z zj6NBRWcPGyQ1I|2a!hu*WU)IbHJq zbZg^B6Ivt3pI#K6seb4k#6iWi&GaYq*$mHrSH~;|yikP4*SjdW_@cI+qjkJBU!n4k zYkQjciitgfd(~L}gI)ZaY4whXD1XJjNVOfuV&hk}qf>9XJUFZV!nU0sWA;{?^Nj;! zwVQSYe;YRToInc9+j07q>Wh+Ipk~#x+*Kz{Xop9ROU04~WeblPvf?prPs{Mey5%#% zY)j%VzwMca)i*7+toPl0(H=}Zq|~%`mwP@PCwYW{{!W^N_c2rp=Z<&(I;Qf2ooO+e z2^Q&AbZ{w0xbTJjHIu^9n|cv^ohfemVYE1cQ*sA_X`Tysk^IJ*8S_rVZF>Nd6Eq`A|3 z``Y!^+&AZYx$k^hnJ&E6eCDy{iA&I*1IX{K#kbkR_$7o+X-CEVA>F@HQb$0% zML?N{ZT^cnV_^DRAea1v;2TN*;nfTI&WArjwLX6gYItw0qu^z;L4C9!i}SeT5g8nr zXSyz5VT;ckT78_K8BOpCDByH~tS-~K5WveVn3RXlEgKTe0`wm)3O zm~_{R{fxOe`uyZ8GI=TY@u&`AZ3DXIQ~eJRu=x*gcz{2qLBDTCh%Nh#b3G^0h;cDC z6lGuG=A+MKC(#nye}Iqf-8L7DIj7rRy^+*>8(HzkuZ(}1d%bxf=E=d@!SJFAu>$5K zbCO>2bvur|WH`ICl+idJX4>C3bRBKeAfs@NT4=lkHJM~++79n3~VrrrOC zz4r`ivJba@Lzk*xKtMVOBnVPM2~q+WdQGSSln$Xu5fBum2uP%NB27pLEl6*Qg3>XR z5D;l1Rf?cgMe%v_>^UFKnb~t@_WNz`*`G7R%zgiFlIyY^|1M!Bw2U#b*rtdlx8$KX3DE+w?h(j00G2EgaLJPLOQi#xL8_Z>n2wGGje zQ{1ih8VZaOElFSfSacm47}10vbzydR+v3`wY|o#^=Qi%B>B{1czg&CBXHkX-O*+SZJjf@fgQ7tp92?r1e@Q|Hzm*%Q_$(pBnbpu0#fq3C zI*eVr&(QVP;l32kSPK!(I7RUE>Y!DTA`5`(4EtfMpo$GlSf1YsZ?k#&C)tsC>yDNRZ<`F!k^%nIp-lP@F zxHlS$zIGEnIue?}~NXfkPgA_OtoLb;pk?c`DcB zWTiR|Gd5k#e*WS0c;rW?vYo3>dQ(cGVH?^i4@6A3r zULcjeYeW{>|K2D!C1aVH>1SHAp0*qWA3_I0w;Uuq2cm@h9608wo75|js~=0ZZdsZg ziDaaF__KDYG-mB@YoTPsQSDgxeD&UYsUMqXwvn173&cvQnaZ5(t*eoQgU(;UewXgSt$-}4BbHtgkY#PyH{ zpvpz_1!BKabW_-hVx8q;8SNYYa+Z!&+A`g%8#(3o>0N2Od;ODAtn*q%qM(fWMxWOG zT7**L<^dBEuXZj(eDg(pe@pIl^Er#%+`r%Cg6-FVoD@#@Ju+JScZ&@uA?;lXvJviK zIR~1>^#iW);_+ql{lJzSfLpCoPm`!xt@W_Q9tjZg(HEcM5sXdWO=Y_s)=J6D+{*k@ zbG#;KA698Ezci`6_(&_Uv167$3syi{7-R6(+4RR2O9QxTL?SOHaU;I zr`!?pj(jyJ=Cn5ttLW%h9ejg`CG2;){a=h3^?Mx{@~t#QJ=eLIYNGm*_s@>`w>I4o z#?S-6&3^zHVB(XQI^DcdqCAJr84#0~jx!ksRKRJW)Tu>y1e+%vu;jp- zpp%U;GCT|}eRVKFKcxrZ1iAMPR@J56@X!@)7YAv5KFuL(*4E_N8r(TCQ?!?ixu|vJ znWkzr-x-oaUeka(oc~(OuXPrN@Hq`f*}}%tG;Q$Oy{g{)2;aQ`_k(X0=3gSuD94f> zE#$JPsv42>QDCH>MH!ivC&7$c7D%Ic4fuo-(}JWz)Bsi{Mlc5IzK9knff#~SOP8?` zp2pbxs{7=wV9au|X8Y%>yqTAiL1*+fxgljSTvWNm?kQA2(`7h7rUIhS@}{QSuME5D z+0xdp$8`M70UdfGHKt|DD_L`9KLd2i&XRW6x^g4>N-0yW(Ef_J#JNl@b}*Qw;~j^L z`qGJ1hmk~)Yvc}Q+8HqzN~g-yZHljaQiI%eyK}1-GvlAB-k~NM4Xei*BECHwjbLLE zuzB1tqUM@gwIS3vQSBcmJ=r`DOwR9eTcl(7)AhHtLNlw^SCSq`C&7<*XC3C#>={18 zPQJaD)~>V{x~Zbna<9@L^txP=cuw%dOI~H%k4r&2*t(O<>#E7h%&rHO zMe3`(o=j)956Q`tY@kk89(?Xmfxx4jLl1@bQ(03Ck*gZh&^RmeualDj2bMIa1$0OI z&fzlR`tj^#6*tja)*r}HQ40s{wfc(}Mb2#D6iHPu+}rP_Ao5k}%$I-~XU8}0 zA=><3k3L`F{p(m|d*{*dU=>uHT$vnVa5ria7r6!PHm`BE4bbJ|ZfsnT21FID9@L&a z+@Wna@Ce$3vKZ2p{k2KdVz|8a9@jivE8S_IiG#ZtaJA6QVP0|#2tn82yeEF4G^Tfg-M z^C5m;K-tB3vJWc4vfJv#N-!NP($RBN9XMF=Bwg_p@N=K1rDibVwnRvk zh(M-w;PqKI!~BrnVI+t4j4r@}TjEhCrGC@P(nN0)DhMDkGb@5ml^@@CuwPB>z&~RT zeJgN7I~Nf>#s>#ynRuWUWMAZ&Pu5TV1E3LJMcroX@=jY>XaskJF|`xj@5oT`*}Grw z@STNelglSOv4i#rZqVz!jwKf~eGA701Jg~*F<{fUtUT&A_TNkG7yVbvEYHKZTmyEL z#|WAj>7xNH2rC#X9M}TL>7Wuo{-uBzql{62irN8>DM_21l)w5Njs+h=0tT4;?J6=Z z^nUfr>;8T|uf11z?G7TyS0dcCrpo67{X;gdimqHSv-f<;O(i_tSvH4!oJzy&*_iH{ z`{9eSHZM||2%qWKGIxx`BUjvV%R}Y$NxoTXYwK@0C_DE?RDa)+{&$)QT#qnl1cKAv z6>@R=P{IK1s}r`>z9FF~_G6ETQ!ll@V=-LsuSaVS(bnI8psTtkNATB8J$*nOrC2Hy z33JX}hcVGf+@F5>)8OX_S{V9W1!ECAKr4gng>mD-NSC>Qe5eo^ zSrL30ZCXo?C6j6`IsjO1;wh=B2G)K;b!u3Za9)TEk-uzzOYoiUtU3S+12Hg>DwxejY0BF+S4r&up%xHIij}R(E=CczhC5G8Z z&tJAOsvpn#}gg%aQeEBrK0qJ4?UgX2L=%VHEvF(Fj`A}zaq=FXufO_Wca%x z);d4$#dF!2Qrfsrnpd(-_Xr%;imU6EotxcuMGBm^VwzO}92>=;8&Xnv${}N6?XS5a zUDvDzR%0sOuIf%FIH1Juy5yTqiMEej>u@{ZoMj8PE<VE_Hn(Y0 zSmKt*(n{+uKSW_0+lb=hMV(2Ef*{xhQM?ruw*)T0B+EZ;itu+i#9Mh zL48(+9I>c^Pb4?T`+3vjV<~U-u&=vPTYH6^M#tTIEB6@QgzA_cLvDbfB=wAeIv0Vd zf*7BDV>@cxF~wK0Pr$n1S2Z6^u%TOgzw`!nlin@UoLye%KBQ=)Xi#G^?dXCxl;904 zKChCDO&KSdNhA_}6k$AysZ#42Vwa?F6%$d|ufUcWzLFoPkFNhj7zpX00%H`IcW#(3n(drtgik}v9HS0k@i`J zWQFS?MzyHi$5UMOzw9}2Nz6Q@c z+Ij|ZxZ&w@;J&2m{kwCeZuCjYji_pWSg$7NV6=nm)pC@4SpfU>-h;c~&mUY5wJq?W zRrqz@vyXRtA5WGK0lo>3)JSQfHIvo(BclA=p}0kCMNW7SI`t!D_wvlYMt-)*lp`E% zPMccU1Bzzq?zHI05`P{@QZ_!P4qR;x*CX0#om3TS07? z+W^SZ&|4MaK)tJ+IRZ-*Ld>R6Dy2QRh!cs|NR_+)orNA7ppo@=umj zH?$*@0M!#3XyTE%gPa@C_zV)hcD9mr%iMW1FFZZ$x=Q24j5h7QY0XDrozr~O7ALDf zdMlbKy0)_9vtNnR{tR(UMQmdRVt|%#B?)B>S}Mk`JcCxcd|4h3!J8DZ z=tfs(dGBibT))5&b=iUvu=2W@p@11#E^J|X_PAtW0gMY_Kz3VWcrrK)@N69V)(Xbf zYnL8_w=|SOKKrpSi%uj8n}^!lE%TkGuMj_9e68~SK~Wy>(nZ$e%EU08Cg~+6z8!1C z{LJg%kwcoek7q-AQ2k#yz6wAjcsyRio3wzUL?7dBOpYuKJ13WY@sn}o$yV6M%37iP-yli+j zgcM;2kI78m`7^$L%ZfMIKY8tzwLO4Q?W4<)7U8h&Dv?vQ+3`~6c4hn3*jRF5%Cta| zxK?gRk{Gqxox@kSX(4ap%4SMH{phH~p|LpaGpCO6e0Oa#jD1}eG=@#7=ctykQiQHw zpJM-fF{PIz2gMInKrZNlt`If8QzvskD2=`klUT-YOS-Q(r%X5i!8P@yXxbZd|IHtN z%^#**XH%SI5+uuMr)PocSqkQtFQV|(hV$G#3$YCrFL1Q)%bae5Thhc$qr8=CUCZa~ zxi<7e44@j1Y)p*aK1fm_54nZ^1F(&X|7J1W^1HPO>-Abf|5aOT%JiY5t9@r=jZWYj zYj_9~%S~JVsG{Cs-52RUII}>u@2*h%-LfT&SQUEr0LraA&%Fw0xwUWmdPh*m0=4(N z>MMem9+sZM9iCY|OjpoLw?erMOo>1^SI_5OKB(x?^0V{MUX&7R3d-BU{x;O)mq^?O zB@Oim>&@Uj9Dub|o|>sH>L#2wCt|ddqimi#eli%*j?%nIMxwVla;I0WZ6sXHzE%-w zalSP8M@H!WX4^w&STObbU76yzXmDe+NcBavGhGl&=Br;NH&!9IZBrZP%O>}_8RT=} z>!3umOu3yc%sLKCIPolWTVb%({D{HqK?7vx>~SOI2X!|e@FTObyEp?kLg^h(@_seO z+(dGj`1SS9eco+Hd3L`ab=jWMn0zY=`@(xHoCmE!^o(EDh&&Xh->eM&vz>dBcws|0 z*!6(1O;Yu?4l>@RayoF5O9rRd71Y#tv+?T#{#$Rcv%3X%g^BzLe-!Q8J}9a3YS!@k z>Dx>xh9$3d-G7arZQorRI<8YKg?_u}ZDxljF8~kBg1%1b4kYIR6z4v%MgH~btAHX|pt;clsLbuvY$;%lJ z&d5IXUdLYjd5!cx9Ud8+ZlNUM;xciXwW)cZGBOl3!H$lj&k>A&20v?1KE3!lM#NR_ zk*wRh95OB^NPSjz36btdfXo0pH*!iqu|go*m`J=vs3C(J?V)v`96-=Fvfx|YXs$As zC!B*naVll{_k-NbsE<&wO9OSYBO|ktd2=aSG`!`tdeSm*o1w-!r4)(+HD%o@wGn$0!(Le0_1z)s3RDUa5avX3KN`jtq?&#c%W`OT=#%dwE|zi*c}>v#mqA*tK`z3Cc3Sqf>X%D1!td+ ze7~GcJ?yZE^VVT;Q{72+)xhSjeC;ITNq95Qt}i;Dx$@TJ z;N7e7*?BwI(N`3~dX!T$=+5RSB71!N<3Cdd^ZiMm+^X3g$)YKm5Cf3crcW*6sV+~;n{y8I~a-dN3`&hDg zp4Gm+((%{FtFxYV?ZmK|r;Q2p-=R`VO-Ijk1WYm~0<|{D?X-&E^3uX_Qs!K(hxu*@ z`$4luaL*P=U9XUdSK`2kaEV(7ITp22&f*o?qsBz^?$q0p_^lxoD7b#rdQ(H-@XYpB zA=L*K-1C?4=gg+Ion0bLAuGI|!=T$b&FVtlmqhp25QExq;dJ3*+ab81>$3$NSK;p= zOMCCn*d9rIv|=pfep5;>!M?5|+1btb`I~Cxc8HN|R&?arM-%0_p##^XhH)KBtLG5} z{r(0oh8Z}e>zS{pT~mbpLRkMzY$1lx8Yf*f+Ecfk zK1s=ra}_x554Fo{a#SJXkdv{m(*!(_hnWs%j!M1bRO`6{n$LC%)Uf!p8V2-FDk_Ru03FQoXsP zvdQ#H6N!_N$`zfk-olc8PD6=s z!hV2P9y8N-?I>INF``kwm;xy@{Ps1E^ToADs(}3XUDs6yo^>umt)PDZ5rSLx5#kgs zcMezj294Evu%Acbx4D};&;9&f#Hq6FjdvR;Euuztf-i$NQ_^w@F)rr7HTMj5Cyx~q zqb!_4RscQ6$4h&66|VzUca|FV(zC@O&vTUyvMEt4uQcl>2iR-n!6AS^rZ41XliJ>E z#G^nHm4if&-edHO>GQNcv^4IYKcXXd35rd* zRUfU94f$T8FN?8-#&@i|e8-lsCe9}@ZOPaVDE>A)v}IS2V;QS+JWS$pdFsJ13y2g4 zEZfAr^=@;+RTv$t34JCP0ObsRymboat5P;fI%^fDTOTA4FWE7EcvZ;k7OBR2CkkJ6 z*E8PYS>ZKT@m0!^aK3h`#s(!(4a;-Qf;|?OeD-LS7bv^qbF@rSVQEdk+*{c}K`lEOd?HrpQ=tBTo z=VtIkN5yg9=Xc#fnFkG<>4%t3h9Qy5X@#qJI}?IJuKU3rQ=rzJ(L=oa+^@!O?kt&c zmL8#>nF!0ib&UOa5h)=S+A-XupEdWeKXlnE1Z8epC=MJLa#?}thh4X3I?K#XaAZ{x z0m`o8d5-Q?59CKaWzS$!-hSzojQ)Fq)doNU{+hg?m3koXd|?Gk!oaM3f~Ki$-PTV6 z#d4$|b&23fW18~V%bROu-oV0@xKMJz#oM6K1PzKu28cCqB}U4dKG@2ip~+Vx!&lb` zNHcyv$pR!bSI%eqdpTUIl`*|mIpY#3FQ(*TSbZ9N0VhACS)z0c;OmLmt-xnQA>e2Sf;b#RO-FTPO16&>E@eO?I6Y2<@^%P<4)`75v%(K#l~ z)VeKgSZC7|U!=$2`W!njC#*7|Qblh;-fXXOn?k_Ecd$!}rE*Rl31i^hvw@oD0|0G8_FrPL-`*n5}6aMy4en-P4r=jrJQd8@vd}(_@7LP56&`b2ztAgj-wsSS= z4;NfY6dVFANlSM=jPx{sljzd4$2aZU72~IJx3J_lg&2DJhTrj@OImXUE*)N~FN@$#~RId9MqH(Yl2Nsv4rO5a%Iq;!3f((2A64YJl#-YA1&( zZ)A2rdI;C*zNZXmto^}0UHdF@&B1W{LNC$ek^1SDEivnAa*0tQ;@awWs%zWL7kU2N zJj7z3I$fRYTer;KvJ4c@+x%YXs}%hf$w@e)qQ#DD%K&P)fuvw#c7qc1HWa7uizIYj ztwLTYV5gIUtf=8xF~}Yq9blul2vJ2+!vjQs$ey0^+?Z#O&PuOr$%5fiT2O2!j!vAY zRB>E(3tz>a26}TeqcK6-d}y4SjY;`UuHMLa=Vvd+_{rVwRIFKQ!VM~KJXxwYL`3u< zZPK>gptY%z2OP%CfW5?Qb2MTHj8ZJtVPe{Gw%VF0OgRB^tXbUOlF-{-u{;m?d}9Oj zk#pcem~G6x1sWOb3yBa%3yJwBncl&v&GFy*(de@eO0%+WzVmYRsjXiOAZW}qSUo5l zIlsWr*GTi4QST3I&GLt%bF~zo<{3X`IUg(@&@8`T;Kf}C8Bwhj%(~%RS!vlkfzAmu zbl_K(C@)b&&nPf^GrZY8Fd*8vX9X|JoTPily-GA!Rfe$5HN>;9a%LYYXx8c~Z7lN4 zCzvZ>b^bo{8XMvMoG>0dK{<j@^kP*lU`9k; zW634D%Qkyfa=EH&>H@VKHNN_iS+W6}VV9WQ?&iz(0`5TxqZRsOCG^J!_Ozx-58q~P zSqqT-q0U3l>#x&C2$=m3SKHI8&NixP(Ej_G=0{<0KKJ$*ZK7=##jNc)81xILM!MZb zk>JUK@fA84Wtp8PQRQ zz{>n@h8|@<%=>kT*g|Sj4irUpA;-qUE_C~%lGJ>2Ea`GKFo1sGg_@GeA|DMFKLIu@ zBh+xq@Ld5xvJ}Q3%8Ogf#u&IMz%E!oXyK|7Q{B?M2M@5Wp|gl0YyhobHnp*%2x)GJ zvng|n&$eoPZ5jfU2^*@OhT$Y=U`_*+>-DV6VqO8=v31oa%A-S7lUeeXMav(J9;@bi zi&8xvq!2Ox##7Dh%N877FTDTt=%I~$%-E^g{FsIAezOF>6^e3w#| zW}~$jB``E|;s@rz97-|&g8TDEB;_{-m+uZ$>)qeqI<9^+`PNSr@VJOfOR455#GBpB zMe}~MI6STowa^`#YDWZt1AM>LdnPVAiW*pil1#WRWLky;6O%h}>|>ywKdnOVP#MG4 zUOAFxVm}acnCrApSU@|bvYE!XOc;l+ei@mCm%&i$8$?#)1`rT4X-t*DIoExq5O8C- zDujl=Qk_!9qDM|^@uyP>?WgyqlF1A1LuiEE4J%9gA*&ET*`c0%1yK@O#z0+qY(n-x zPySE1I{ooS}6<-yNAcOOELJ~K^W8Uup+nI!zs zL^5RevGBWk$IP37X^NwlMmaj6b+z{c-8v%|b?lp-Mq5;!*_pWp2e^Kz4(yb0I+%Q5Ec;#Pfbv9MtN1uB{0@9>%*!&pSO= zL(JItlw5P+RYjPGmXcdmJH662LCF!8I)etW4pzh9N?&atb|_xf{50 z#rrSJ;UK4pD?q@YTloub$vSS5eAN+dAh9x-B)T@$B|xJyfPQKNOhCib@X!I!Q`eOW zDQu}1T%OP>nks;?GA`qH?u3Z&D_|wvwpxyWxQ7c!dw#%Bck6Xlk&Wgz_ncH9TGpZmVB z?`&%##LJ~jEX3etS&gY_z@J)%rok*`zECPp;qS{$2bJ%?zTl9FW84P*AwHB6lO&0v zlmmk(!qpZjnVtb{79IBhTfZT*k;+o~?CQ?dR%hTBlIVBY9{g-59#RDcI1Z*!Nut znC2ToRPZaU(+_iQUJXiIjBpCZQXLVSX-I{j716-dAceqEV;4hn9}#y*?+|_rE+Rl( zG9c~nK)_|Q9Sa!@OcM=w9s(-f`Z;c_GNI5>`E7U$;SS_XLqAO+aPv6{U<YAb>am$})9}rpU%((E;yrmQyTiq-m@@kWMb4 zBJg zs=Zdev~)Wt%9=Is6I26P@iZAAfQ{fpi!Xv3zg8&U3js@5#`A4Q@+v~mov%m{ENRlppi6h3vlvpAiib>$5JXy1(twr`$#Z&`UG63t1 z#)H78ZuX6pk;P8P zlNhirSjDsi9m}ev9%2EAnwU(?iHyI>$UGROFDhZHQTj!Arm`3OD%nO`K`Z8Q>AH31 z^+dOajlA1`vZ&jaBivU7GyMgWuDm0m0gueX%}$gd)A6d^&~zZ6RBplAG-e{y_;s2O zE#p(6IBe#wn+2+|#S8m>E;dC9o9UQ>4Btq_l}LARERF-uKUHCt5mgWxu@viK+X7}~ za0&~+Hy)D<7ggVt;wa+2{*r!VL@tBbdF6->nv>0(!&r(;uA zGK=W;VJtf&d1=PdY>aE54~@ZX^dJ-d8ecy^77mHE%qExkw)VMMg9lmvY&|6zjkdJ2 zm&&R?nErV~b>28{^={GVtKd;^nnmD7jR|dmEl^mjs5BIbg2|R^Jp49O+$&~DvkHuH ztsXHzF)eN2T+m88=40q?bPQP$ZI>pkiG~BD0A$W_pejlU77N=q)8J>`1uG6hXhb%N z(m)QlT38v=HEoR*EE8mZrIM~W-cVQy!y9ajVVcR{dTGqA3Mnt(=m$?xOSu4NPUOm) z6BdvjQ!8V0X}pW@TiU`gv;|5U1}Wl4+&`|u{eD-{!UkWP>c0lO5L~GMKxm^9jTtjV z{IR?oEqw%4V>{kX32RvKH2A2JOfMIOOkZ5dKql##n)+|XdYx$~dqeqcJjna_iPmpKiBK7GDyk3~#@`C@gDBwSG`~P*jkfI8;2*A)2?d@|< zMDf3x(^po4DE&7o3OJ)-`(L}z{|vj(Hy}Vp*tyh0g3eK}w(!U0BVf(VTU9d6tQur~ zn2%&f+V4xo;5T!vB2|sniF$3>0j6+K?psZ=Ezfmu__t?3o>+sMvc5>I% z&|G3#h@LJ23q;U*0{D9TI;PgM+i|8T}aGod`9`$5D32)P5{f~G-uP>>3FLFEc<+g za&DkfJrSU79Swe%y?M@=n{ZTC48H+4E2apO+%F@;lhER8Qmb^rq(&GGk(}w{Eh}QlaOb}5)uU`oul@vS)?)jxIgc>5 zsa8WI`IKiC;bzH35HISfSH()>%L^`I%&02DUIUYIt~q`DOst?lM9Hz+&9SJD^4W?d zt%{2cI3@?dyab$P% z!BVGL65S>1%x&-s#7(<$GoP$9YyPq4@PzTjx@$&9>fC{wmoX}r=cv%A-3!g+I)n0e zNqdwUgm9YyPa9bXgC+%jRUE~9n|lYj4P+U46({BPDlYBG^lzC!le#g7XW6a5Y&&90 zA@AK+cV&Z%yGcG8Gi`>qq**y4+V8w;e5ou|_!MEJd1yTBZ}Qx|zP`L&w?P{4W6$@A z`9WZ$BJdvYv!oGsq5g(I<~KXHb~$lf9Q&8%za&~7y#`KeIpHPZq9I$Ffv%aC`7cf1 zVUh4*lEF-F>NN#s>YDzGl1|D5oszx}7!LUX<0vo0I!)31!c&JDrwO`4>Z%Tlf*A{> z9eq*aNPI!!t7O1;xgv-=EH9{^%kU>Z9!C}237%T?P9an5rKk@tokR<6APcc8U`@S05A3@0^gu@wP5B^F0LKGtOWw|fA;I-6uAYOa%QCJ6TF2N*u*>Jg*s{iSL!-8`6~KupbFOZJR>{ z6FS+xNZnvL5`fT{>p@K?zsR4-4lNCVI?!mNOHc8XXJnNPcm@9zJ<*lO*90 zZ+FzqvuYL8$Nf~us5T`kUWw>0@w(u;q2Zn%E{)_*eBw8}=NBR)?Z3>-5<4i>S+~%XzJLvU0>2lvFyp9<`9<<(bai_5GRsTQTz|A0@e1~);X95y zzbnpW92LB-M`2B@8e6PPtVRE|*@H&S2tH<0(balYFh0haJFf{5-jaSY{PcfXxRUC}FC6NXl$b3;BqoQ}K*6cNdpaXddcn@OpxGSZp__jS^WQ7Ewz2An+48AJR1-U>nrZ0%$oBptw*n!^&8L2D8A+?L%AeqDb1- ziX<5aRo4o}2M<}wc3M7~gfcNU>|gfts*zhBvRtNop>X(CLC&XjA#7zHLZNmo(XfF5 zCT-AqbgJ9yZ3{Y#SiWCvTG<96Cqg~BlAb?}yyUkNWqE z9`scjfAz?8$YGqHq8%<#VXoF(ek58SjQ9i@?zD_%mqf@kjM#+pDto4nP(igdx(`yz z*suVCJ8e}aQwTb-G9v(f=eF;41PzFqZWAkD@8>1BQUB?Tjh(Du7r^#!zE^GiC{hLl z&bnjfQy%8VyG7alkpkHd`NXX&vWK4T%yc;nSkG{jz2>)a`Jkuo#GduuLVA|q2JK~JUeKqTko zG#SO?M@UqiTHWvdUuJsJtH*M@GuOu*u^j_`#W`8NmjM2jj!>bNG0KEFIt4j`eVOJv zyj)6zw_`aG{Iw(~<1g4QC^$iC0{MbBdA{=(I!pf_fYN15AlQ@|$f3Vq!7VwbGC^;T z6T|mQO4Evg6cD)^sVx_hs4w$VC**`J7{9F){vOXDSf-?TmHVwvNO@DnB&1@!&P+#5 zxoegBFpTzAJEm-S@`jrI0sB4a%jKa`Qp!zYBUf;-tRppyM#|S!$mYFbh`uvB*DwD7 zE?$i|+?(1IsKRBMewqwOt$faQ%e684=S)T=L%$(-lG4U1{`e<Wke(ntIs&c1XKlB{V*l7Cbu; zocKptCc6|>a-t1((X26axxvx~&fZqRDE?{W+(!RMUywePEPhyGZ?%JPto#W)v$>;t zA$+nO+vL^{8Sv>CQX#t$6tHHA&te(pbX&vx*L_l+%g1-_TR18*dhnhVAvW|HOWRUg zD}Lt)04y4)-jbKnpG93dfKIkD0Tlt}T=^rAJsx2{itX`>E&GYS5gjm0Q&D}UpWvIw zFvG`Pe7}&frDv!n->A2`L16mBV@;iP+uXiL-)AF4VB8=cedgSXq2Xd*oIS4ni37I2 z5XCr=txR<%jZCmEve$r?qU`#sm@Mo&e9CwSOsB3>jCwadj5?5ClAMk?aSn!kV96&o zWN_U9V4h~930_2Pl$EPEy|ZI`)M1(@(`q7+iK%_bt!k(<#zUB_|5G5Z9`7j2Q{Mc5 z`?Z1Z$;v{<{HqAzT#Fa8CSfkl02gA4^;|OMJY&qne+&Sb_2y~(6_oYtE4x9fZ4<=$ z+AAKDfI91xOHtNdvn6rZ(-98Scx6^!g?|8%=@ZsVcRlVj$1P@`XH#O0#S*pV)4LJT zw}hS!?pQ^)4u63o2nff7twDE(bw%APx#0U^wMKm55}VlSlTYb7u+HLF{BuBA$^df1 z32|0ihLLLzrVhvm^F3mjr z;`W>=H`dL3GWMJ8w~zGJar~L$y)Wc_iVe7Lf4Q%WR<}l`frk{l(j~ECLtD0Mw|xL^ zI9x>8RCQdjGd)LnR$c)EHRjr{z>Xtunn3_w8RW}mBty;-wYp#V*vTk@{6-U27U<E1z1SnFeWKH(J{MT2Ab+)Dk}L-HIwrAz;9W@#So_V+W8e zB`w-de^oGcxO=E#V()6rw=*nOkk2&XT6EHuvkEBd)=Nr=I{)Cjd}Cf0cNbfu*J~qCGycU6j*={68&V(jBv{b(g=-7_Zu2=(`O~@+X06?%3>`oL;#02OVnB!YwW|1 zh~#XyQR#8+D@6>pS*9hetR~~AH`WQ^QDt}>a62oG8uDUbECS_JeQA!LA}Vk|1_;>H zDi?jq!c;1R!lp;Ay7NKwX~|}+UBPmw(-J;((=_gAY6Uw52ot1N-{=(rWb`E`se z`XQJPFP<>+LP$iu5g|>msU-tsmq#F5qDZZmpy-}CbX=9<+MP}W-@FyH@REoQlO1k` zp}}{r8!A5WCf9y2HDFUfEKg99xEO97B-AuJCyXoWIyOC+X~2g#?cT}TtY=4Nt!i#R zH?@eu7{#R*d^B|_r%qK#c{QW*blEoeE-6vp4tCK!bSLetCa23&n563qhqhwPUTc_c z!2(utQz%G$Dwe>K!XNG%6Maq6r;N7X#~K%|R%itWv=n<;dR@a9pLCjsH_Ec2dWsQ> z(3%63{-*faU8{b83H5!d7&7&#gH}f+iW)Kqty;>CrPJ^JS?%vxjM^Mdaw{#Ss%uVb zsmO69!})@>Y3S9ZM*nhEWj;KWFPtdavtAogRU!d!(1q%f?Mf=F~-5v(mhL%Kn%1J^1=W$-qn5KqO!4U{6y17UB)2|n~u9K z9qE1vVMoe?i+7ZYKsA#KqgMkBM1J#crSN6@e5QO8JH*Tl$De=Hc*LEpp``P-mCxX% z`%emT`?4Y9=~@J^Z~EH6fEPHL9nC|gYe_QJ3cE=`byqXnM*|Ig4cD(sKN1i9_H{ff*%; zffwjgC3&M=B#f_eBV~$aC3BSK0ASHgTO>^@Ft(Wc7^RVa_bup;TJ_g5xRLCPq!Fi5 z!{N4{HtMw=ZNISX&NtiEo2Sh_LzW|h^meKdP^@>xKLE~^^1wM@=576z+GZrqHwN4H z0?k|jc^BDJ#w?OdD71>Cn&RkX*o>de+OYF~^ziZ$C}Hr;G)m><*9Cnus~b?o%gQRJ zN%IP+Pe*QCxCj}2mQi+SuR51*$?oJDtdi+<@JB9kqft%{OD!RfGeYTQp$q%(4S@Jm zgFl_(6odQqKbV=&vx{!^BVFWW4DS5 zj|4a#FYQu68@JLl-E^c&Mn;eWiL2#G?h@Qi$F&^yYt{}ONI7Y5@*%zEf;(<-JPr@+ zlO}i-fGB`nijv9tOFBv1H?v1MJsZakyhEx*je?poVg@@X{=$C%rujP#7Bijeoj&fZ z^8ETcIy;6gW@hezfq^zKYW6ym-1b_Faf<`muW(g5_7XS+pkNGF&nhcd0WMglk_*sm z?hRHBA0uLEHVChz7&}RZ#e{5gh0Ec$ROe#dY|Olrc%YKls0qJn8NS;qdHn`i1MxGs zr2Q${2aZV5;Vs9uyja*utpg2aCJFC#%zvx8O+n9M-_p>62=lSh3z026|H`#dLqH-p z;*!dqUEPYX7Apb^6p)2TR+q;i8&&f}uhGW;G@z;Wf5T{n{{J#sq5p42D^!UE`X4mb z8wjW(3smv{3ugU~kN)cmUx+*v#`^y(d=*rw%isSJm{nQvzf(T6i6-NJ7ry^97QUN< z#=*d8LRcNg6G<5Zv-qDwJJ#h$@tSnhVtWcW=B7VnzlvHgY`13dIWm?y~4m zsTgI5RbX6RK|*;fnVQ0u-hs=r+$5h?PoRZ4y+f7>s-|g85Jx`pn{+DYt~LM^Ht# zj3C1|b>UU*1i!MLnv)+-V4C0wA{P|5*N+Fr6@im!W{N;m^ao8aNe;x+Eh~Qo*ntDK zTmb3AuTewj#?oc9d0Es8L(xz@MIbZ?9rG`#R)i#79s`Q`Vhn28o7UyQm{Y>b0Fws3 z)Iz*}!3+R?V`-ei%}KZ*n$6f4#f+o1(xGPEv%6)P@FHC4c%WNss*CUIcx+Q7H+?xi z^%D1jf=vlj6e>V;U}D4%dG=OaUyCKmstEl3o{snGt2Clb+vt+H-{(_v(+cRcly_ZZ zr3A!qBdVEmX&^7_-`bB>%rKRqXQPkN5qw~$glz~t1YXz`8h7Ex+20cZg;< znLU9B>>3EZbTa(+UQZ)j@2+-Hig6RS8%`J%nI|9gf7pAkxF*)&&K92Mb^DE5LCmj1mC62TZz9K~{U)AFeNKM*L|B}xMi%f{A9<>VHHOeeAGETVBe|IP%jb~>d zT^Pr#Sf~&wKkj*V$UWiOtOp#lquj_j%zLq6miiZ=`z0J+^n`QiQoMvK!WTwnDGTM{ z3x5%QslhVhFX|SFh;9S*eNxT~v^i7!lWnW?t|~p4sebdb+e=$jcs$0rLJ51N9ya)F2 zvlAxSKW8 z<=yAduWZ`laZfkvORCgxFIsV-&U(P$SbHv%2>XK}IqC|^xV2b+ui9&&lUx8EV!x9_c zmA0F0@8+()_-dqieX%52_4c0lWvfFHrXN~PvCLZTe#}bvhcqsubSi=_CHbq*r)5`CY_-UXKKIX$>*?l=87 zZ%t@ULK|;$-nmm}7N4%0|51?8Hg>$bbb9c>+<2)it;J{0i)V{RVe&`3)YtOQ6R>il z^PRsv=BT0PP9>jNvv^!%!Sa5(>SBr7{ORA+k1UGK{RhV~p#|NlMeBLORv13o*n~jhBcktv|9zhwIa3}v z12Zi2eoW22E&T-r!wpuO9xU#7wz%kdvun!sC;Fw*v%AxuEvMdcru9zG-&l8#>vsD# zJ+?RozN#siiFhd@h|5&)AxCsElbN*PNMc zqF#*MEZ}}5;RoMsZv4`lOOF)zHOy_M)g1kQnbj`d!#f{x)8>r(wC6gK#T zzw9$#Zh0`ue$xuEolP^^dFD(7Xk}S?)^f8y$e5+xY+oY}Kf%+!vXEmc@fU$zJEeK$ zn=GflhdsWy{R&&xKvcGJ(%&}no-ygm!=DkKt#3?SyH}<5i@3Qd>kHY|#sP1YL2Oz3 zqI$PNS>UAO+cB$#l~jC zd#AQbMIY|euv=%%yryvWYQ+X2jn5L#Hka--D-7uzY&c74cx2WsD=B&8Li_3sE-I|I zwvxgTTIZh@iiJ>P*K!U?FK^BKf<2M)d_slZy0^B{1t}6ABN|C(M zT*W6Fb~{u)UY(O69oVmb5BJaI=7zmjtDZQNJ2aeH%0DbLl&J!sNylFTpxSJYDEk>jze|f_v<#k=J^>HsLMg>RW6PQnXOY zq2%3iul_kNGyU{{a+Znc?$1XW4xN!6+x|;mw%ap?)PGS%w_?uG>^`Sa;EMlW&P!7Uet31!IJxknd-nK}y;}^Vqk-^Rg~aG%*D?xvcy2Eqfp>!O)Me zeK7Kr&$D$0y_3A!^8)=>)n(9w!@mkIs#g^3_n`PH8WN_c^zdbj_gKQwK2=M?&Jkuj zR!(awg?XW}egBtR`6J6uq&xB_Jp-~o$F&`24xidPzSq@-mb#sEIM^;)RY*YD+vWUC z|5x>@kkjKgYusjT-EFAp=KJK@`G9_zt*Uz?XjfXBG|l&Kk5>pXEj%os%6y!p!HPM1 zICS4OC$l#p`&yOE_sWR)#E@b>#8R)9S5aMm>1;fUe>$~|Hnly{mfyYJI?E4xqi~Pj zYJ6K)y~3dtVP_r)hMo(jTkHAy_CJPiJPduk8jq~f&Tk=S>nj;L z)JfacWnb0czuZ`1TE22youNy3v!P}v<`g}s2vWNmi~)0Zlg9i#{$7vl+#gweqOXYd z4Ni7|B<>j__WE6psXE?+V+`1^doa%H!?lbq=|yr}_E6J4`v!t&iq%{3?x2(^@fS+d zez7u*vb)Lt^S4Z7KaTmhrb~W$6~3?UjKN^Wg((btJW!N)lbS##dVbc;;uRKzG-K-t z23=1xZhmhsxu5NO>c@r)s~m9$l_LGL_bAv(c2ImSj}Nl^PKf+*KJO&mHm^-NuJStZ z#9oa5Mk%I^X((HIesrbwd@}sYGKi{-%+oKZQg(vsV5^)&k`F^%=T# z%Cmw4gkxlXapH;Ja$_`mSkZ?k3pXyLy^2hk4FYR>l4oz)uwL_70OT)BWc^RfZH#d1 zvfP}dvpK*)S*oTgUDl@Og-uFA?97DIUqtMrEV8{bbMfh4WM{rM#+CK)_vw#b@B8-X z+)px31=A(AyLDfYr@#yQ#ioYgx{a3KCY#fUEEAswf&b2AT7=`B2jJ_|pFSEc)4^xbT05Cap_v-7@m4Uyy&@FzNa&>7!Bk_S+pN zYoEPpKVz9@v+iO-g>PqtSLx`DW;f^NAB#;YdBYLKtn>R$$i(FT4| zQ?{X_uvrSr{myn(L3!U}Cs%M3iv#%PlAPVK8>3!WB%cxzduZ~jO7o54$eYrQ2KrGV zxCc&|^B>NMDXt6N^2H;oopo%_@@F$;{%g9X$lG@X7)MaWvwnl7x{5w5VXm8Nv3e!Wzi!#E^o*y8^yv_RDiUxgSPQ`?cDi$L? zn;vC5x=t${cE7q9w966|-{ww!-n$)nzU_h;vno35&Q7(zh>x3~d$Zg*=^6grM{~Ce z1`AV-Ox>Rp?WSa=JF;HdiGDMyPRmMuc{9z%ZBNS-eKpOQ5f?eOP4jt9Pz6JK`q-;) ztkcwBaXay^vb%3D)E#Dj#9oQ1OL(ouK4?s`-4=JkSN3+86K(!suJLS(TxC$!b>)(u zM#<6gmyH!iD#KPB=2YPVikKNvQ3Pe3SAH7~?Imhe+!;^f#0?mc3VG%f=6izbGn@|e zOT9iv2_SY-k4pL0KVP*%5-Pi;&vc8)u_cNz*>>)V1qRjTVl`9jIa6ihSGM*_tz2(a zkxZs_))5mD!WqckfBfM`sher7)oQ8P3dx2Jqn7y}ros!mUwyOwjw!5@X{P#FcxK)1 z|6wGIpK`XnJ#P`4t7aL~Z{%se+aXW4{!MP{Ug4KMUZ=H^Dw!{A_$>m)+~B7{lTpTf zkI&c&e-tq8)~dfT@EA#X;&oWOz1VA3^)V?p@OV{3*B@_fUq_$Brr?EI)ltJOZ|1v_ zO@dVvvQK!JHy+ECOE>xBMN>IE>}|ZVxeAKIPJ}4$X>f{X96}IrMnRQrnYs zC%Ld^wAeUj?Gqx|z!#c7A`e!r{$-<*DD{<@m6tJFD3!VHmyPC&a?1xE!--shkNHt| zUzGnS|6F}k{wf(KHRRN~?en=QtEOEZ-l;gBOM5LoScjZWa!?u{O2G@Thx2jbqB*ac zWfE<0t8kOA0vW2WJZR8~^Fbhj?3=qYu-a7r{WmMRjvItGwIQr(j%gf z=7t*@=>P01$MTd*Z5?T>=eIt*c=F4cum?grZ?z;j9p+2lL-voz4%g(~V~fkT_=oRk zZcWzSF5P$V zPgM3S68<19S7DVKi9$}K_xAu3f12UunACp!o!hUo2cGnO@e99odLf$`et`npR*MS;cpT4FC9E%E7;^-q97P{R_D2!aNQ7aAhM>N1Uis^$VBE7JS~me> zq~o!v*779(T>s)&Re&yKrnYo{`W^c5*HSg})mO3qggG|+{A4xP`MqLIMkauINAG~` zWp(FT67CTGp`S^=gTIPB-k-Z>X#L{vis=!{4!lyKj`W(+b-%dAE^>=1vpq8FoG7z3 z3lKY=#r;KAaI_`4B>orw8C*yllw9DUudwo3(XQI8u{?h9=b?lb#&tPO`-BAf8#>=? zSNQb2N=egA6>9>(`XYo3H*7Qr)B26}pMHv%xmu)I-p`(sd7!i(qM1eMqqqRTdR=8C zCy8kF?&EcfxTl{@%{EQ#dAdKh9OfxK;f93%MFNK=J4-hnPs;e@{raLhL_{|95f;&{ z@Kk30!l?s8!)|kL6HL0Wo0+B0w>(Mg$xDX_q6TBxOB*up0M&5N=#MNV7(28U9Brw2(KX6xVl;Xwpn~w zk*<^@r)^IdQo+R*h}!5Hm*d8f{e+PUQeVcjL+XBALIi#MR)3db;YV|ExOKYC6nb=C;gnIC3lR;Jaw9t=@a+1K~Vt zYNIdFXKQfnal-xtE7vto7kWM0DzF9h{%aaaZxHT(J3Ciaix6BeK`(A8FZ4S7EK5kP znZbQYO7v;|S^AUy*y76o>?3AI*&8~x?R-Pz=U86bwvA`DmX1+z_lrHAGc(MRw9)Fr zy3=1wItzN-9y?PV$D*MnW3Q{r3W%wLY5f#?(aJH;kTNDM3b$G+X3mete#gHgoN>4&n#sa1`%=dvrTrJlmS9GG>F55HbVCS$swg4(u_o z|KpVl9}-u0_ViVkWr*I5s~}OFo&TTmQA-J;|MP?pQQzo)cMRQRLi|6=2pMiP);Icp z&mI7QHG<0je@f{88!4f_GN$%=F4}t=ZKk_r7~1b5cpP=OKnMqQZ5St8JapJa%`e(d zI2q5?!HGgH2Pff6fR1-iJ%x7nMF;8O%W)WT68cscniZGBe`$}FI*gDc8$?)osf91>6HeetO*yeza5MsO6CBQzU^d;^YR zOGDrkImqo#a7LslhZ@V?U`k4cld0o!+_Ak5EJxwZSxiSkI28T0EgmT+!O|&np29kW zBQ8v&qM}j-mJe3Smw+&+y^v_}B@-f{&wNe`%poK?!G$k}JqpSzsJ%|k=nw#RY!I|W z$G{TNV7YYu>+_wIxAd6GGK6sdt~gvbx+dkq`M4IgFzmR1-!wr#WJXX5wbx#d3)2q^ zgyDaNAB3j#A!RB2P=-vRgOj}wr!1uhme~XCx{irPZeqAC6f;4a&<#Z@-mOHUi%=#9>L{Ea+#USt-C`hcX=z|6Z0Odizv)1kb}!WkXXS zaU<@cjthd;nk=F%oCe)Hka(6wh_u3SBTcFDhwxlvBlA$NE&lRyuDTi1*mE;Z({d` zhjkLi^VF4c9AwVefoL0ccqx}L4axVJ zP^XVB>WZeE&}@=KL>X(jE)A*R@Z{J+WlIaSBwOg}@o-6?VJzof8${37(7^_gE6amv z#1to(MZO%$3RO&!p&ea70v4%V8&yj$2fZ|#) zCegJlaXD85K0<=BmqaNKBm#E7jN>r`P#on|OnfDJ!C25^24pU+;i?_+7&;#08+2#s zc9AA(C?rIkdtKPp)sV6?BzIEmm&;YI55re*LGqi}?$}_a^MBf02Fu*?uS9`>rBEp> zND@Q)aab}U4Hjz|3vN#zZS757N;86Vp^pT8-DeW;NChYy0!pd@Vr6Jc_ZOesEp~{2l;gpTmZq) zM&+E1I+h{Bbmp(NX*-0a#WLRSe3*;0&56E8HQ2iq7E~C5!ZgyD1yX8Yk3R@6=c+8f`U_Q z$5&J9q2n=DxJHRYssb#N$x{is}`Y7Cd2!-xR8-}JB5!-?Z% zDUSF`*zk~#t0$ro4h9&evn&}U*{VeN+n?sUqiGzExe1Q!1UWeK{%>vPe!@D=L4z(65XD)=qb!;#yd7ygd>64^{7UfR~hQS?U3{J7p^(E-R4Iu4Vn zr?yx5G^07fa_?qU_{^q**6X>A%1FOuxjAFkmV`5u2px*ooflHSPT_ByDc+CsUxxGC za`@>t@m)qz-^6tVbL2y3W^gx8H>|<*dswY4%UABh(CMwCd0=?KxP#jQ#ROsLfqO6R z!S=F1>v*UNq7Mn?1yn8>1AO`IrD+nPj=u0o5L1l9Q#pltxgHu%12t=oWW6u~e1+;D z!qYfX!BtU&Q{v^oG9{ztR-V=gCW{P$)?Zku0tRc`ku1yM!b6592m6sQHtNFv`VNpL zP_jgFQZ@;mmbfFTbEr=)%gX}nL8W5j2$4J;XfPC%Lva=WFw)CH@NAeLj9M;tLO&HF zq>C>r5M#PSfGdEbIFZGiP+0@{0mF};8(tM0QX9On29K2}BwNN5UJ|S(xTF6N2Y4ik zjlha$+QZ8OI*G{|WBtz@j^L999mG0>j-2nWq`$EqNTaLA1`^du9K<%XFB+}=Ib(T# zW7f4R%GpQbSY{oI-zq7rL)hK9owlmqYJ}P!a8hRn-0AnKuV8y_mNuo%_UP@$y|*9m zJ4CRiUcr7J&ktVomCubi*Eqku{(k@4`)Qu0tOx!#*57>1!@Rz!-R@b8IhAQ^qq}v@o~?J(_m79!e8YcP9&O@lfPZiGq`T&rW8r)G%wrB~ zq7t;;U%_{kXNnMCRGkS>+g-bB@@2wQL&S4jP`+}s((r`$$KTJUYlIsxi^SPyr70r~ zatEg5{Zo#0mg!btfK2G){?G(2dgnovd zn26iz2f8`(r+WS(d6oIv%Sz5@xJ`jDTHexrYFl^6GOcvs(jiM`n)e#J<7ytSs9)BW zwWtkV%$ebt$4q4Q3)mEVNt=q8;qW3x+6~j{Sh;2n%HyY}D?-=U?O_@EC;iU&<>9tg zUGBY+OyI$oLJlulpuHw7de)=!?E0r_i=Nk%dilLRV#9bT?{&GBi>sC;Ofd!b^Sw7u zT>tocu*9e?dVcS0p8z$*J8pdN-&?LiZ;#*d_@EahUTjh8@Xd2`{r<~9IJfEso6CCK zdcXLUEyC{)^0aIx#9pedij*uXYKdcR5_pr*Deue&bG?q`+(!cgD-0$P@B_d&(32HQ zCg)9Bzq^aTYE(?YEjb#Jx&I<8Fms?PSU?lzG&b@BEHhX~m}SylQ31{N!7hPyr+PHn zsATs#*$`2OC~5=vBtr-s07xzfDnLTiAZvm0zLQjr0W-Muz)E&r@ujtmS-8hVL z+@}76?t&LSy)K!NmSc;>io+OTaN=$G>+@BOBx$e7t3#-J-jwkaYA|}ZNcZ=>Ej@zs zp&5yk{iOYH6q7zdfx{UIt~sIQJUJ3ZV|-Jbd^%uwu@h_C(>wByrVm@5x6Za5M~YqW zW2#aer9WFcvEK9J7sq$>*E3q0e-Zf9uw9dWmuAPdzpQ?3r?rf=x9+vxx6sms=9tOt zel?rqP29im5-<9vu{}C&8;=VG?I)dN`B&?9Cz?Sm_2WPN99E9oU$lljuj`e%dymJ-vu@3(IC|T@4+Ro5h{w_@oW^R!NjKjOze__0MEt(G)c#U zSqGyFCKiwUYtYduIsh}5I!ni5M~%qOp7rb7liOtZ6GX`5E9t*5^dOA*9$RqivMbT(`qr<)CS z5HK1K>^(;dM_FclB{aL#i+=$k!m7OnO?$`Ho z^w~n?(rOz{Os)JqIC<+v95XMueSrSaEVIlx^r5uU2eS;7c>ccix z912{3bmWi_3JZ;20Cv(iQ%+=fV(8-_;4%FfC&@zQvgOH2HAy+{LIrn@2&^4# z3Z|qC?%P@|+@zDXO|wB+-BTfTvwpBn(@3nZyS|}qRGWu@+k^4r1H{iVH^e)>{#o8E zX?k5d=*rPN24DUVoV>}S1~2=H;>zJ5Fg2*0)V5rM-~a&u#Q{}ykfML1JyFyO1o1=j zig-ksYCz@??KR~{fSp0%8w5dY08+9LOA(hMOBxrX3qUWpWdK__p-iGZm=N@>xbGGk z1|mau3_6Wda4A3vgpJK0xhR0;DvLWpXsEBi@+Ct3=_?8oF7onnqkF%zrY7aH8OMEo zUmRMDJg{d&)fLvX(^-iu(~|o3Ug<-cjs7#hWHdOSQmiNt#1GC>!Vk-d* zT7zCZ2e9;nI(!~b`O4vZ+(J_jLzSybbbV<%gzU$^BI-Qn&X{#|J*7+ zxA#e+U7ALL*H%P+Kgbr}wL5<89!eZ`UX4-}b46hm2Y z$8n4|J;J1gf8GS`bu)5vJomUSaP5n_!}Tv{5ZNQ;I0;93)o?1@7))k@QDh!t1V&C! zUd~cnMWWCdmC0jN z+hm8}UEVm+iSUk>hoAM@nDH?T5jJ~p_cbeiZ^KR zmkgi-KnpM}@jUT7&Wp zK=1+F;L4VhS~*yhB!WN#BIy7fa5u1y=)%RQD~l5$Qp7HiBmc$rR0>Z(CY#ih%vf#Y zyZF{`yA$DamGoZe?!z}e*@fl3omP4H$MdrB?5mrG&E6)pGis+U*XZKqXi<-r`=y(M_r z&(AQ!3YVJ3pPu;M`JMTtLT&5E9{Fj%`!@Y2XEwMji!@KJ;Phd?Rlb|4EYfB~elT*9 zVfWgqelHI&&E%QHC@L0gn>M7HCLcdlHHcMnm&VLg=A?5_uCz`yvJk5$!I+KugXK3s}kb+7Zp5%MDP!~^kittF>OnS zHX6u0f3%#Z3k}A~Nl(B~9;fjPK@HZi44r}Y6M-#pKnnibvBQwOYBlwlwTwzOn2~l7@$WHcPl&sC-$a_a5-R5cJQD*X_inRt zeyBYc)c7EBhs+5vC#BB1Vtz(12gr6>HGT_9KD5z*1<3$f%^9UV{HfH@Y!b@7a0O(T zMBo}ZB-j})9BEa4O&$Kh)6oQ$fRgFZ;x1G?oYG?hgi1SK9%KPXXJ4|qF8(Rp5eNzz zl>pTQd;lTRS!l_DLP&zJ#R<_sIBTFpS)>h|PhZIaj6IMMu#_okFfx$os&^Llyc?Vo2AF_$c!^@Y!u6q53WL(PSA`t}A1kP6{~ z)2+MdF3b2?iKx1v#58J>fp1zu7$_SL>?;auC6x$Lu7o&oN}3^g<;Wnj=mSrMi`dvW zO4AQDAX|m$TJFO5=Xk8XSh-?9JGf%gZp6;U;VMhwFkAG~DCY$iL&Kz)aB9Sh`y5#S z1}7`C!-0#d0Hmgl`yA=;CNbHB%`~(c1t|jNM;Ta)#8Wuf6tWbOpxR&{DYP6p;_taAZMnQSuYFQUdYjL z<_R+{FZ37HTF`AUfpayRs4Kzf9~yV=iv%E52$w`)gtF-URO|ZK=b$_nMhJ54 zD6Pz<^3gO6ibg@1dFqHR9u}Sx2?4z zMV%(TnyJ8ExR&FDHGaPm%GpXzEd#h=021i0$6Osgw=Kqh*ST$L3TJRP&KAEh=5Q^q zZIUx;6cFVq<3=keV5rDK8*^{;(NL@kTqYPn%{cthT-BwV$G^`K?$|91uLQuf?1ViY z6DKb=3NVs^qZFfDc?tftJ>9fNAdysYg#Zk5v%E_OFk7(Re99Eq2@Sdw$z9+I-Wc~N z2GJ!~2zr3yk1(_qrUU4PtOn$m6zCgKs@0`Q@V&UNh%a*N+sObS8)oz>8V=z#g_Fji z%@1UP`a>b{g;X)&{!Rw)J$_$^BuiA_hEa=NuPH8M&CE6>vqMvxod-TB2VGh9F^r+* zc6~K7nK9J((f!QP(HrYuJu@j={66b<+4s{;PxHrTZdUV1;{H@TSSO%7aa3_C{S5H6 zV8|jJnC<{5KafgEYlYNnk$4CU%y90~5_y>5P&<8==*w^W>Y zDxJS}`&q7i_hYNu+g1IJeJ^X)etNLz?v?Rn1mm4Eed#Owpy5K88q@h@y~{TDqv4LC zcCYq@<}a=iwY;M(we5}{Z;MH`!fGY0RsFH1yFXZ6wC0X1sJmSY(>tT{DDifjx8&W! z&3!dn#1jXTuPyr&knMJIKTp^q%wE;>OoP4lrZ-hp(OWZ1^;4*s*CNR)S+E7X2V)lp z=2;wK31tXj{&!Tev^NbV1l(hb=y_PNBk;kBLKRB3^j7deqb8&rAZ#H0 zV?0q@i}lfwTgdJwh8YZCFHV@D)r0m!?w>4KN_bt1>LkR zyPt3>K`XH5-QuVD>Yss6B7c`l51z-WKKI;Xm2NC!SyNhegsFJS zSiZn-8(r@;Hu738>AwVi6OtcA{zW$M6zg@F{nv=sauNhQoDHPj9(a^n@Wqa0=tjIe zUiH25vqg@NFiXgkUM`FC5vI6;mjSFj{BNqv89*2xWD2&3!63G(X5(tEy{S94_F#?l z5gs0fFt8=hJ$Rh;^po~6`HrvO{~{OiW{fTh1^qJelM+q>nZ`)~=-Cg+SD6&1v%F}f z3M2=pvaq7C;jWcUjkY5ppTWI9tPo}>yNA5z1 zT&o7nhFjB*7JD*=gRAZDnC&|D3K z)Q}ZM)Db@16~+ply%n0`7FaF)7QTebq{SZlzkkXAVZM z&@DMWt4{Il+DNZYY_Sq5|7vkDE484RG=zpBj>333+@5RDfpp2)h=Z91QqmD2K!Rw= z>6Yb0JGgpvv4sM=q&Jr>>J=DplG-3+0iaJU>c!qBtCoTerCxJ zOmw$aa&1nLU4;(y zb_?x7(5(zR9Ogj451i~XetFWCws@_5JpyLee!$*K%lm{Yuhe#1nKic6c%3*%!mPZW z@)r@UEV57k%Dn2bVGZ(&E#C1+b)M8$b^oY%s}os{SGnb=cxuxbx3B4suHm_uXr(3} z^nH1_xa$1+W}*!y`g}OX6b=#kVFYqT2{A2h>@hc_Y)pD^!RT24H5^x;^m!!hl=7D_ z!?Gu)i@8H^wWmbb6^~9o=~n(Uo$i?0)Y>2a>RHT(OYF)5_Zf=addbiu^VhF*{>tbV z47!coE6Y(rE+%;Moda%&=Sy-4iVNoSiin7~zPu~=^Ks(7VLvLMnY3l{KO6VoeH}K0 zZT&}L6K`|8=*1Loy=a@ukR8Lz7Az&bsX^!MX^@x%$H0ZACZbT(ph$6LTN9le!7a;{ z(slk3?2u+AK$`U;UlL{=#k>T1Pz~&GMWMJF{ zpz8`+DFQq=Qc(%`Jd(o$Knp|<#5g({^hkg|=+W41+QSF(W)v1!<7XiZEiu2RaEA~h z()jpRRb=G>lMBB|PXNL)FukJGL`Z|9MQJ(6@bf78yR*3aCZi>r z-LaOh|MVMesLButOJl5Bnr#jc5M$%E{HCL^mdI_B1|NO*Pwju)g~A-0ent^GK0WQN zxf_ywS>ziIvy)jo^vLq`49=*&?QKUtMo3ySTf<@`AZDaOCH3@Ipg81g>@Rn{7)psS zY^z*x6s-_wf-JG?GM0D-4b#+A0PY-Hua#@l^{et_`|iTkbDh!`j@6#jVqlS`&ua`{ zUW^~NPF!g|b}~ir58wW68UeGil8**^5Zh5)aYGSrnS1CzEK?(274wKrxvLpLO)&Ztr?mhd(lOPnl zFVlC`-TY;i?ApNOHX8DF~UJn*zLW+^~p(Rk~zBiYaU-ezpLzd{steD2sqSH=>j zJbW*X#a{nBa$6;@D#uzZdZ@N>I%ogbVAW0X*LOE!YRh&Sn+UwbVM5=y`>@T@u9@n4 zsiz5fUiE+UJ!JQ7A)VhrXE4UEy9sBKhb=eSpXrvqx-Afqgnnw;>5ehy3=eFG5(tRL z%N@)R(WvpiGf@=L(56Y+X?i3RZ|srfq9P}U6TPwAyQPJo)qdNaCle*N{?!8!wV=YN z6HlbFB#D{iWgn&G)ZTiX30b8a5Cv@$_XKTBay|UsYi{cctR9;q#L`-=KYgq5*Ui2X zG9$D=sw_iab$!t&A-=o;v0xCEotkhehD4@vfU7D0{XsTlf|^1ZtECltH=OZGwyL4A zr7Zj3eb)Q+Sc~VWoFkWCgT#5HgPpGsC=t}gtjgf?4?_A~m;n_kz}G=4 zl@1{rfu;zYw3TZm6HU=#PmpECXq;L#pz={>&H-S@zqKrV(N1WD z*#}IqzX-L@(8>Ogk`n~Il`1dFNsxuW#8N}Epa_RlNE&yh%J#7yJ_|H>Nl>cWCB5^z z-bP`{GaTcsM!JZ!tXtS%Nr!h%twyAm@1U2OY>3E0pPx?33%lJ4T94Zw{>scB7p?AM zi$h~L93RaYcpJ;i=5HtE|w7Wk>QN=DY zn_Otss!`;4q>Qnm7j7e`EDM@1ZP;e8g(%0>8~QLU@MZS2H8b&)I^w%`%s=a;gXL#_ zd}HG;kMFfj?m`!0r?C{{pH=3cg4)~5Elz&({KVei@5fn|blRlb+9P#1yDcMfVf=y( za!@8eBXzS+enOFk$j%eD-Sh18sF?lcHtv$!E^t+e!C6Px8)!}>wLqT;Q}zT!K*kpE z?LS7)wwBR&XuGO_*yWGCk(4|4WR0nA$G&Sp2Og{q(%*YuEkOUskJ{D>39Gl6WQD;@ zt5tGwnfJ3jrzA&8J$Tf#P+5hR32*g%_fPh<)O#JcMHg{YXwVC@mW}ImTza+;zQv`y zmHde7^%%N1QN2yc-^1^ODG2LPw(WcWXRtU^j94&)CcizUuQ5v>1@3-86j*EU$*%#ws_whe(7PRa~o)gK^ zmqcX+6w=9IjoY*gZYOA6HIw{hKT=kMn^M1-KFCnocR>|_Av(+d;jLFTD;Wq=8!8y{ z8a=sC#rxUGhgQHg`sp;ClwwxT$qzyvSq5M@u}@mo4(#V|OnWVTcEe_twYI%kU4C}< z%@*9_v-8iH0!eX-p3VEL1LFn`o+?b-x2RDdzhZeK{;Abqt?jX*v&+`{Eat|DbZMRM z#WXUYVbZE`@7>t-0`I-r?A`8P4cyW#n`TkaV6;vh@oYNe-eLVv^J_&(kb3$al{Beq zc9GZoXP!1zzkTc|_Eh8#U4xIXninY`}gdX#>b?bLkm_Hr8YaP zp)P3sL)m`)MOK6xrDwRQZ8#&%j!U?{pfJ~^Eq46t#UgGa?6AH$x6;4sU83}PYx~cR zx8!4e!xULDp_FLn1U*XgzL8Pxq1$_bZGEgD`DA%)?F-6}`j4%VYLh_t_(EGUh-+;G zAvESfq6e}8a=_Xw5zzuHU&xCm<#^EV|I0Y4s}ndlfOeZHO8B7Kg8x%_xV z4X>#FY#OgS9y+uUSdF6U*UtCKg&AvN@L_b{EqJU;|H(dKur4oatax@O;H;m4rAvjL=_R8XtkYMQiQR2GSzCrY8Y8g}OBxEphkYH8P?J>g+$bRTo_C0kB z1Tch?Y-->MC^(VPun=G`>ZsA`86n`h(3iNR*89`HR;JB3$JB{@5f|JV*LOplHrGEw zUQQZ9LrbVCK(58wyBT_3-}UpV=c&DiV>X3-iu~ots{W$c_)^Et;!xyZ#m?O2PfC0g zSC`yxHqcIe@lm*<`HYya+pwy%L<;7fgcMtG;M^9+;zqMyN_cGdQjJp)9VM8T3K=L& z540>7t$ZqgN~-@WEyPhZujzLe*a8VpW(*FaU|Utq`JT@QP$s`dKzjAd@{RVRRb>qA za}k?YQ(^Ng4&yRuy>U3&)i0hCEL-Op#E?rfu63hzzi)iXZzA$!+2WB_ms50MV>HH< z3j+a%IlLT~PaUn|lk@gPO+X>-PP~ZsbZ$v=ZTb_G7G|Bachv)9ZfxFP#OPM|cv*|# zFPB4qf~Wf4T2yOkcsh|i8eLFs-Pb?T<+bB-M3;a^%biHn)ns;XH3#0WfC9|@@dPUl zVxtQjJ1bxl4l>-37zJks0ig>i4am(K|5XP1q170a!F+(I0pK`QglUil(kJCW?GmI{ zDBX}^M5`B}atUfkV7=O4tq}1oh15@9(J37d>xZEm^+elTCEi zD+iVLtQ46UqcDln6xC|^l;chB;^n6N`Pyqw4z#ES9jW^Ky!Fd|qoGr3UUCBG92@h~=UZvP56;`pC#k6u6Sgxm7k$F0R|7%@9`8Ntzdx8+;(eMI zeN_2J{p+ZauD+0avz%F*4Vy$FmcMD7cZ0Afhu7y=%K z6q_UDTyr4)#Ua<^Ca4~=Q21Mx_CsR1`ce@fWcYy8{lCAk^{eL^y~g*=mnDjp#^u)F zsM)A+Q|Wl9=*ToDU}3cerSE zbw#wLH`qnDUOaS44O7y>iRxJ2Et~Er=(d|!V(@-tp0a>;UhN(+STJy6|hxALNkbY|_Fa0T47T}Gkr;*UokR($jFmfU1y zurj+f)#Au>+t`kk=~^ZqG&O^+rX8;8;PjEz2C7%&NkLudjX&`#k-)!(2Mu zRJUtH_n7%H=60`LN+-4%Mbw9ASqUnx+}XG@c35;E=G^%c07tC1oX^M})$F#qNc%2! zX5#iN!&SBA#vhrNpKbVdvV-X8_@UFwdnw}sAzU#>^XKdD*l+m;6 z_Jy}7;x(oBt}Ha3yI;3kgS9*O`vvIOI4L=Ca9^;h@elT^{WrdEyZq2d3-5^>#MU^> z)t!#0k5$YPaYR}-l=y}ei+e_Vl09g&<;auXrXzv3f^)h4%~pz{C(173vGsh@*9D!g z$d;S81)cE;87U6Rnh0~;6-+eS9k!l(hjO#@OOL@!eMyMu@3{wNy+-#tm92iA;cXCK zr7pmhrf$_fqE-~UN8pm9pwH@(_s6|98%Jh(s>gS28#PgCH45!@^s`kkWqc%IOq65R z=Ns9aPh&?fHXxn1-AD}EhzBs6==i{vcjqtulxnG!8mwx{c)UMrW$FWEdFEvB>((~S zHw@YK+N@S%>7Z_p4dU-tw(JqU8rkwrnhZYa%3jwOf)TZ84+aynd%Z$hxcvK@M>K~j zGkPpj7{`~UOa%dy*^z}7JiJO(HrhrDlG8<*( zAMDFJs~}}Z4T-6kuowNHa3LeEX3=YupJM-@=UL^<+h3P9-P+Miy;LqweO{e$DXhR# zn_ua{jb{5% zgN+d36Sg$AfEjFEfU;jXwz%k0nK>>N=w}WVN+BHKb7=3&(4n4Ks&I!?GJ!6nBOva~ zXF)#tgp-3Kfk7S3fE;lW6R@5&T8rGbQu;}W|5nzAJsG@+qtkwypUkZv(w65N@NU$K ze|g_^)Yi*(b5GufR-=7(t+O>h&iqjl>n7Kh2kdyGE0{Bq;BC=~ofj%p;_qU#gY zQa)B#JPQe*elHbvk!Ojo^)Y~)gcVj~~E z^$fonAy890>@C(rS-aEfnMTv7#)C^;TYd6tOpFRu9@cHsyA!(atFg38Yc>8r7}Ts| zVS0o+#)JF4eQK<&TI)f^_3HAvVit1A0T?Oq&3qPZ!j*(PaH(SL28ZV~lz0}lBM^Zc z4$3~GLUGQ^uH$xnsg`cqxPI&DDruIET=4FD8(z#NHdxteb>UxfGRst6cM1+X ziFD-}O*b|^Q*;;J`O!AhX z!FM)$UfDaJRMuSR^Cd^R5LFgel2f`asGrz4#l7lFGsY$1et^4>b3XR6CQ8i9cx_Iv zR-@L<+{8`+R`15KEL+Eg6rzLV zE**Yv-QVx;y1svOP1n_7YM=M}b$C7>&pr=dHYO=8NA?XNwxfX`o%{U! z>GN3@Iv*0Ti=ybqOCE>Q>qiMs+^$n8fo+g+l`|#-UY>)((e7r!RMMm5$fnHT)`+ zHPKQ}_3mbF(L(-el_}2$Wi9)Z<^C-e=T$}y-O=CjRj>5L=`A#imp&E+h`p1$jwJFD z=bYaXIy8<|zI)^Gcx-H`6voQv?*S3KEQ&*_O)lm%morEnM3Z*`dBG03XeVWWX#yXInjPYe3Ml<2et9cw|B zaJ&edj@|=$wAKiDF?4!e0qyQ^+);Y{9_OsvGw1lS?& z!pL4qAn%oiGw#}3{W{EDB-HTDoB7I}o*_}!C6-kb zX5K|Rc|W_onD-UM>t~TZh(F1-`~6#o*njNEc67Ss8lP)G=U{qq8@%+1f%vYCo1VXT zR?^LAqh-ds(v_IR_k1{zv7n+rt=^MAE>*3=6p+SaY=Ne2dae4qUzlo1p3_Y91a+G# z`Ap@K^&IBRJsNbZkgPAAcdAM&kss0xhVj5wvTD`r{O*1hWYq$qGb7B?ShHpr2YRL$ zwBJ&eqfLo<;G95sxP;%v;J3F`EVhCSZfS0g@BbS6&{Zrj2Ocz-^{qa{6aE?}iRuo& z{+)4)`v+<*AMj!d&+e8QAd%3u%77ct0zGdDaO3e{XkaS+>jJI31%xs{*tgkXg9-Zo z=pMEVfYwy1F#%{a?eJ+$@KeyJY5wo`oN#8a$9}qSNOs)?4P9Cx4ezyK{7w0+9#*yQ zeylTSU>|S2oN3!<-FDS{Mevmu2%Xv9+vQbudt7$NSsq642IaBn+ZJq$`}H5=9q!2k zASyx=QfS!QC)Dn)w(&qLzPQ1mk8|n$^f>?4!1^J+qmg@BzAm_Awqn0F1iOyCpAJc% zrDHmnU)f6Rw0N1-RIlLTocok>JCrOX-znJGkEDbbKD(fhL6&Ngv8f;MXIFL>JBTDd zMJ_OuM^)p{heL&#Ylz#}^IW^P9cNZOS<&9tS&se&qNj+Y-L-N~Du)ZqmK^l@&7_{l zUcAd>r0Z!B><%9l%uu|3&ig|){HUL;WKf9ASdbYp%)-~eFQ)nAc5>~LjxM7SsW_rK%Q zHh1eeCc-u~zJ@2aU)Ybee^W7DHpOQ<4RDg)hbV+{lb>UTOU#DjEnfP17cc)?>+H~Z zI%T6c8~rA}!;c556($qNKA;NbjZ)wJA*SEBM`~?;I((NV8#FeMpSawO%1do3Te;2& zHALzKW;G=B7H&QJi5vWeuXLjNTgL6E-FiqbJ4I(D)K?^9L@SzMUKldrV>^&xhdZLL zJ7xK9-|q!GXd_II7jDn~J#QtmeIjdDg+6^FQ#&DHtnI^=RbNgwpE#SF$f4dhViWG7 zV0w1x(K$^{1h|_x#n>JyeiS`b5V^%{QP^HfAUjq=rBktacbeYWDHnNcB86VLLmCR) z6wW5NNyq$}I^u#LY_`stK$nQ_pLfN!)0tf2mFb+Nf+6UkjDWvY$)NEA% zH5SH71r;9N(dWY?Wy`6>NGI zM~w<_g3V{l%r((-53W24mM^8ZiFr3A?X!+JpST`M-TMR&CeA>`@Sn8%KSLLIx_~Nt zb58W%x;DQh4ZIDY{r*o=`~T$*VBugtZ|Z+XuPdp^X6cYo!->Ay-xI>=<1qJ$i* z`5IbQ{mNw#nhEbS4UMP(DzS&QGi4R6JD%xJ_~%3kluJvj$5@bVYvE;&oSeF^^?JV5 z^Gi?G+{$0y~Lc;+ewPeDrYFLTSpE`zv13`U9ok) zB}lI|tVa0kG%v+m=EUN~S@6pY7qCjP$8=UBZ293p=-LScG6-;NKtOe;``5SaYAa+- zjv`Njr{z>7BM~VYhKpcn@M{k)5Ul57Y@^u{nO}K!l~T1X3PWyROH|7^ZW;#}tw@Kw z5EJsj(7G+%OU@58U1)PkPTNKqu2aQfRf?8dR*o3B!=m_o$&c&9{5#|4E3A}+E_}=g zC-n~PGxj*tSw7VzyYrC*{{IW_urWGBYB( zPttHE=17^H&t+)*4+!Z6KcMpGmVVzm(I;PyUTUm6{%zMEDC}IDfzAgfZ0om%)jgL5 zjKlP<1fEb3J(pWK=|R~4iry9Yt4v$&v8eb`X=aF$ zkr~CeV>!6~iC$XT?As2L%TkXOYZs@go)%hTB(<$))XSSoE85KncJEeZ%s39Nm8yY* z-?;O2kF)RBO6-RLV}f)5n4ey$fj#K+mOEf)uup<;_4|CX7%nB%38=kHKebBDmyJsS z{q3fr=D!i@|9vHay8zl0H3|b$;a}+|rYE=bRyd;OQ_7k4y(>F!P}R#nF@l|Qz$JAZwjIu`fJ7EmEhASiudBZ!R)L;qP57tHMeqS~tE-EjU5UZ~ z45rdq>(UYTpn)Huigep4Y-CuqO5Es4-de$Es2@oM4W9C6JU>dZVCw;=8Iw)Js$1Bm zIT{1R^kB{c?27+qD)zqHJ0a5$j&-+(K-G5kot-tZ`^NtlBV1^w|uG;cy z{Dd}2so|OasN&qo)e-63*piE~OM;y>=Ylf7mJGwQrKfC$&V`5?BurxV2uL~K3S3Ya zqDw5Etd9;;H8kY99wk&ci`{s5-|mNJ;@vNAkM9TH==j|u`{)+}5;HWUPuojPn?>i% zUMt8OqJMwcl^(uf>9gLwR)?&GRcV`-<^YyGTFQdH~SpsFPlE}}S zehVB}TFc9zAEDuN7oBb%n3+j31yk+H!Vxq-;6uB@0JEoUz>Y?B8{y{yY9#%3evkKf z&5k!09jQc-JX<8AKtZjQl%g=06EK=0;pw@}m{)jk!Q;q|gN=F4U&d{46Xmj4!E&?r z@WD7zU^$P|(z@Hh{-y7!)!7PN52B{_!(sKzzDiB)K@WP%Jx%a6JGa(;I>SnN5(T&Q z>EtA2h$%_Do49cZQ{3$p4Sn_&E!U=uHs>>C<{I`oAT%g#_S~DLj3HmQT}JgH-`5NH z-oa}%s8rqkuus$4M#FKp<=hGn%6;_0Hm%-mXts=)u=u3pYe79kFa~?pZe|s$Mr(fO zx7?wA7?J_KinIIq%l~b%awGs3Vm$(W(h6r^8xWLMJMtV%uMYHW@lt7yqCe}O!xqew zJmq2KmR>=S>c@W)I5^tA@Bo@<6^0uzs8{22rbGw?#;Kjar8&c|(8&Wv6kES7>70PL zhwpf4{32y+4&zqzV?DbYBh&~LOhxgzO_L&IznfW+T?&*1W;V*BSgTj&Ezr5K19!yPUX<;w{lq*d4DIPj7Go%>s~L(AzUzQLPod9D-`i$0G<-F4DMc2y(rsIIx$@SUc-0eeiAz6X^UEgZ!rrpae8F*vbBU=3N zRmp8z&B)){Q{rZ-)d5{z%x!%1Y+j7TvtfUkv0V>u^t?(8#!*)bUw(FYbZW`=wJ2DP z%*1*>jCD6pcAEYY$`G?1mQ@WD{a8Nd=Q;P{wTzcuc+%O*iMGO-Z1cz%K__;D?sYLg zo^PL0jvH$ZyX;>w94hH!Y4n4*M@nh;w7m44aA$=hUQwS?OajK@FC52Gs&Y$$a-5F} zmlGmJa%Q9-)ZW0QTt6e)1^eT8ScG59ob zn-2F)iJk5ByeYP~8D;VWcZJ*@fUwD9H3`-ZLY%dW#mM_w}C>%*pM{qIX*jKuHzouNx-8_{{NG*+SM z7i^^h&ioXTX~cb%zh0vyOPXOCEDKO*5Wb8_^@!jTDZm2*NbAYw=qvE%O*)v zI@o@#$^JbBg?F#dHtX>PurdyICJ0n2oGHV)7Ans-U(L>3Gc3)-yceiv@6p$C5@dzV z20Yk5pCfxEs%kXkn8umsWNn3`=~Fdf%H#cc=-IXXc~UsFHx{G>8G)K03k=IGh79Qp z#kpS4ixTZg)1K!O=&>;eleX*@ceOpql@j=;eH{I6~1f4C91 zIGY9GW-+)~pe}KesXK@5-}~3Ufmb^mF?5)sfUn;)D}A9>4RD?fqsZ{w&^7 z`UhH$jYD4wc_s?67t(7j!D)7ZUwL|Js9e`x2XKG6lc@@i0scH?#?1XiAd@@u&-(%+Cd?o z@d5Yb=YiHtchml&jJ@KeHc2wM<41XateAO(mnP4B+Y>R=_W z;O*fQJ#6cxBv4pbj3TrNpc>8d-!JDN(X!YCAjQekdVhFNO;Uj!K}kN#B^&{sjGPO% zbYh9KTGJ)Fo@99Wubl(xRf#v*0%Wv*zB@g4=QLLTltA0WqLpi!nxL7<#Ewr7*W?~` zNiHi*gT*O5(jgvW7te!`GO*c8mr|p0n1{M{3C@6GPEqeGN3%X?$4NdHI(IOFm;6IW8wci*Y|k-9yW1@AQ$seJR|Ix^#P=A*bVm`yeGp;lz6}%DsTvb?(&u zizC8b($WknN7W4<{UEIa2hS`%(yGepd0@%?YcLRhDgHil51*5HV z`9dw$K+~)9P=k4^hI8K*DYtJsY~al|s|8t+gJ~$Cj6`gHow}5QNZCA8$UAeb3lrca72`bk43zVF%vUw!@l+neS0CYWi>>MRCsQZ zg`78k#&*z&&GY)*jnxfgoEgw?QIn@NxWA)~>np=4)rE-dG$-2~^2tuNxaI1z5U0{| ze!JTTSf850gO1~g*4%SV&+U&oU@2|#>WW4X#c!XEm zhlzwQ(Y|MQ6Q*vSNgP)mzZY$mIZW=!7LHesRRACqNzmhf=MK;g0L8%Q&iI`TcGGdh z?+mqH$MtFregI_h@d>XBf1uaTfRqVGeI}4{vI;33q~n_PQ#poS8d1+YS!eYJ%E|m^ zT|FXv_s;8U94V~`{p+yeuosL;y-N)MLf>qj^(!0^xE1+fRB5B-2c9@CTRA#^-0-k0 z`GzCgVauURJAd*N17uyweHc#!828?`y)1|lO6Lh5a1`y@-GAAoGvkKBTx)Wji1YKM zbjGiwx0J z(pmXKH|l2Ro40+jsi_O=tczE1Jo+=7ea)UU6tsroseD`+d-GN9L1%0ICG^h$7}u?l z(Rp~KBugNF*0^C@c`n;`z0c&sT*tuyMe2j5xVF&!k1stryHkAhN+&cVy8MV0t3g+5l^^CXCwDk zu3&H4B$Hyb))brdi)T_W3b{Pu_z7YC?Ni0TJgH3~umPg0lBKCngW^=cwx=E&6hOga zLS!*`;15NfBYpk-JaV=pjb=7HXoO&Mv|zKd8UCx*|9AoZmQ>}#hG zV{WJR%w>k`)YaOxz9Z>IQo-SW6O*3o{%zC3RLw&R+7 z%zFO~BlhJO6Jm$=Jp6TUOj4(>{Y?*r$fQ>)(OKWaeBp=%tDe3?tr^$$?yO%>IUb7e zo>e%P9`X2>9-tdVXXO(=6P4A%=gQy8*`Giduf>LG|A7L=Wf515%r45+ANA`Yv{e2| z^|`%=e#JEU$*_8I5^{T=^V?C!&?~*ML;5ER`q%S*svq_A7(0E&PN;v@dBN8~s&ALn z9(13>+b2zz(rI+}%VN95w3YfKIr?r9KnRgrHEq{Mm7-y$!>7Vw;2muK%$EF?yoG6_ zFjxFJ=}t3RFM0MxIja9R>z5_!;p-e9#|foTmN6s$#{iQw`{YqX=4l;Nin@*S<%gnX zt9V&y#r0)du1HX`)vGm*(v61*2E6b46A!`q!$ZYgm*i#z>dhV(8*g|VHfgB*A#E%a z8IE||YPbimh`T*iD;HvIG2JdY9vLRlRS4WmH0*8@#!4OuzQCMzn**|;C%jZ(jfX*G*RT4|FpLyI_2rIU>04c!`M)fEbhSJac=OCRY%LObnNLa790G6#3!< zpcg;;xm4Tz6^SBFx+vx9>u!A|m(2c^8*uhjL(Ba;&*ci#a?771(_)ei7biW`CFp<2 z`W`wy@qIfuD%=vwELLbiMtc>VR}9_~zLW;PIriYjAE?>-H1X`iU00c5%C8y$1d0~< zg0gtHnNB-+ot|tf?t6@dCM{-`OMU&xxj?uiyXy;EsaV~5YQd>!*Sgmi_7zq02WY8B zN2{J465>g0RAeuREc_TzDt~4@>f3KCoBVU3+V-p9DpM5S`s8H1H4PJG`_O|}mGivT z#;H~RbEEQ`(ov`GCv|(3e}AqPc_#Q-nnS~WAAGANvS4wOyp$yW8++BtJm7kjo{?a} z$*~tQj0aUmb3l%g^lNv(-_iAcAWVxV$P9SmR`g7L9aherEg;^TO20&Kx0nt7F)qTk z2+R95>Tx{9sv;}aYUD#af@pu@8!h3fspN>?ljG{U`0g2YK}x)Mt4xli8E=m(PNbsvjk$4F6QTPj`j_u-JDeNt~pc6AXzu(v3<#$*)us^L#E@FN8GAx}*>3U|QstQ*p)Xv2y3aD7R#{xMA zfR8@aUd)COW$L!+bJxW&M|4hu-7Z@p99c5A=@(~@h(X>}I4bajqwlhSh9tlW)aWf+ zpw05qe+-Bt;clD0bU+lqg=~@rbo-!9F5oBt9Z0UU@R)1JNKn(?PbOGL6jl!_9CcCb zY(tT(rY37QnmyhU`W3Suw6v-fl1-cO+qZk~8g1FtFPM5riaw!rwR$l6xNzoH(vfJh ziy9yI94m-9g4am7B%<7s9=)0{&JH9rTDkFrgB>?)^>iC+d@ium&(j?Sq*y98q&ODm zdFPVdx3Y?gPy`Ft(_?H?3iJd4_wgLrML{Ds3@k_fJEuV7o;XE%d>g2=wE+vh<^_@2w(%3whv*ek()d7>kZ7<(-zJXsK_XmGQMrdZs5{ zs1qh@S5xXUkXX}rs4Zu!CHSRfWHICH(RmRm??+9Eg{`o;=KA};oL=1$P`4E}O6dUv zf)?UDDis%5)rXAb-+Zk^eoyK48>!p>g{(seZngVbSqy3wIg;t)a!`Yz3fzenaC&D5exjG(Z{C@g{lQLmrMPTNykP5Rcj{R3K2b(0np z8U_}KN|wrA3Y3Rq&KJSyLCG-od^!C|8+G>$D%l=j4JAu?^wH~<$SwB!$YAncf@^UJ zm%M)^0s zSk1GVZFS?@O?icE2}fZsB{7d--!7Rq9!_iFg~$_C6~!X<7>qSJ`5LoLt2Ckh`2NmB z*|ryI9er_1EPVh(pdA1pRhkdqkv#kkSC78?N#{m+hlc6WP$4a(Y0Jp<_t=&bRzHFl z@Vn4Jk6%l55;8=Ye=Jf3VUR9~EN3N_NYri?TM^Y zULndj2QLn`CR_K583U#yXpX_Ekt$5C2KeEj;NJzRF?cg>uX5yTqxBk=#ez6u-;dW5 ztaGw6U2?(roqe0E&P`7s>e!vvynk2*&U3uIEG=eqm>S5V_GRKM*j>4_f0X*oP=g$0FY7PBk(lz#vLrkFf>v3jSY znG^PO;H8s)pywzrFN^o@EpE;=^lH=0_#r!6f~MXhWH|+TGlo^^1+ zEx(EE%@%cYHww&-u6RkDG-OXZ{Cu}o0^OZmduT}h+;ygCU+O?{oAHl{l!`&g89~Jw z<*eAeOzb~8bBp3=i1EDAB#-6U+#Y;V>IR(Pce?e9R9CX=LQ_e|S@UIxOcRrwOYK%` zoX>uA%p-A~x9486hoB4Q%kA${Suq4%)6#hEw$tCLp4&P@#PDsOW+vDvx;45<@wz^W z?WTrIz1|DI3Q+qd!`~ON)c5E(ir;RTh;nWX^&Wh2G_F`KH*xXw_p>fAE``k0RCni6 zZb%mpASW?f_Emu@BDg1<1u6w;QL0oGfl@JR%v|>Lzsvda?-$$^~q! zouHMZyM1NLBai@(1Z>{Gv?eU3N*1a@)Ue;tA{PVf7=&@Dgunzmp~JPqBk}8~3gqO^ z;6=MgVbbiO(m}_)E;x|SC=7plO?Q?Nvd)b#JNOg{J307~u#d)kijpcFg@0!-LJ_yZ zqz2g~1StG+@)E%SG12^x5joEksgM5XdYM)`SjoqO$Crbr2Ez^*wPgyHh-tU-Nt2P? zLRG3MV!EY(3d4Q6Z&^}+ZKiJg>S98bs(0{h{$rFnO0VfuRtAsEbjs*D?2NB zr9vI$!_Em8HS@K$NYxsGSXzg$TO(^8Mzva(E3t+HeZc(gnmH74cfjIN?%Ygv?N0Z1 zx!B)eETpqbSdit>LECRf>as>7P`uYeR(>*!vGc-A!Fs#59HZ`GO>OLY_q@tZM#1Cnj zm2w|wp*2Y(<)1ha0-CQk3u1VJwG{G|C0oEF`%6g9*7#vEqR->T1;HWLfhDID7q2|L zL>IpsA#@6%e--x!x=TkmF+6Wv9=x=Yx+;B(&tV6@D}IMChAak!Qf?OS8eg(X@QlB@ z>QB11;nNp>4X{`;W79({J}?Sv{jap;mVXO}-_Gr55gcQTpqvSQKK);Z{Q$ZJjLZx+ z)kOfisRF5Zb)`G(8TF)Gd71q>%pT&1YD!?Ux)?X!H+0B*5{HfVcqx{(i@TTEAgNjr z-?7!Hp2xeAR1F@hFq)U=3+-%|d_7-&4`>G;{jptHZ>Jv2(xN@pEqoH&l#@6j2vQy~w-aUWB6+e^aRv&*o0oSoD?n1_zTX3j{_lhr5Kv?!*a zFeyS4?C);D!KxSn6L~2LEh`#%{{40U_;%gJF6x7vJA}yz4I%I9bpScHDFk^>(<5x1 zEoHU`WaDU^|vD{nSj6w5{(-ZE||e5+0mm%{J2t4>ekeo80y9^Xz6Xj+-H(m&p0y8ojk)d>rJUPG157^PSa3lUrIy=&sGE*! z2^&9>A$z2bSDu(3HdV{qRa248gGr@iQk0Cp4gT=(j4%5VJGRmaxBg0j zx){3dH|H#F*_0*veqoBVv>x76Lc zbf1y~+aFT`{KbW;$Gx{cULX9XSO-uE((OM_wNKPdWzDEJ)xvkT@a z*%H9H!bbS=#d^29AxmCg$XQzOIu;q9gFG`ZlZZ|k_EdfTuw8is@gc~2PI57U(S|*z z6_ghoU;7{i1AQP8KnjGwp%=!irXQjc*>%s(MjWg#u z92lg#+6EWZI~712&+MHoGNqRA(G@qgrS0%KyQS3*EK3-%OZZ*%$(pHX zcTx~VR{^LOR-IjOYhKYfrUZTmu9tDFm>|EOVnr(!ogqLH#4TJ8S~jXj!g+gWUESGn z`K&1_woXqzt?nH1Q$EbkYT0?aM}d9(V+vHKRDCKgkjOZcFM91QFFnJ1`)CSJ1l8;Q z3I&plgz%`Jw=tq|0rfiPAupY=!&W5q9G6C>@P~?u0PHjzU?F*=3;TNAae&+7IrLF%S*W!jSvMD+x|9c(h9e7}GV!xis-1714xc3xf zM3MjSu)Ns*)en=xLaH1q4)~ANk0u$!r@Rci74`=T$$f5%97XsG@zw0EsW}$u`OG?@ zoKiNmT@;(z>UF1O^?o86p1X)CvsSkkup`O~_x&EqJ0Y0GitxVs2EVPeoCF=e?MLyU zLLP`j@eiUw4gVZGOs%Qg)l}g7R*ES$Niwp=bEI)D&X(>imrp5*hFDlGcz#4No~J|+ zM1_}46&klL5p9~B&i#&iJjhq`OQ>E}C3N=0yRf5An9|nrg39CZC+~Kj8CySnduYS_ zvt&bzRf+ez6B8NG3oCJRPr*+$ZwaN1{T-*xBpKL1NA zfE_L8>Ss|Ta%bI|Lg9c8(cvpo_(q6-(B+Fpp{AZ?ST;lF@Gf413%^N6Q`ggvnmc2K zf(I6ObY!&exriv$cI?ijpQ6oVPmw8a8yn{659y)6%`%9AjnLXY| z+eyt)I}gff!?Te`8+=yI+>BoGRbsg|XX<62gL1~kKjUEyUam>|euVykj-bYxBlz#! z5Na?#&^frKJPO-(=H68CFDv^>A;$SkQnp|MKeCdgt0P%r z$wQwg?lmxuI}iRqy2M%Ukcs=C?cwu!=tv4b$350IqC6k`0G# zsvqL2lkp->03-q8Cy+1)2mIe82QXZmC>;w8B3~6VwZV(d64X@dH2lXE@7W4p6>C*!*H62rfR41Lal<`Dy7ld8;)F3&r%;_vAZ>TQBnx?LC-(Y} zhaEQ5guJ!~l`5jlG0`*u>+7_CG(yWT;f-lXWU@7RJ{j!5MP2x{Kp`JU18O1a{uW-v z6~+M`RZ+1bkSHB2I>H}@lF;;4cMO@MVmoSNDGQEc5weg=++6Jq&r3EgH;-?5e0Ytk z%Xw@+dGZ#wr7`3<*U@o6B$d%@_}y|1rPPaj^Z8)6WSWU^lfBvds~tEZ08fJE!E=H- zS!TJYF5PlGY&xNGjJV&Ji$=DjS;mxwXqeTSWd_--TwqKD=J>GmA8LfHlvybh1x5^D z9X(786d*J1d<-VNHuhxUJ5g&2x|J{cla<$4y|kSO?Q!OVh?nAK?+Gv-M^x8!*m%Er zuv4<|LFSj};lqoKcFHAuFXNdaoKw3?;n=8}dxof?D&5*M%+%#WvfQTbuHWB`D)BO3 zln;~&2hAu&Gaik5dgi@VLp0V+P92X#gq{yD{zui|9rEQ49Wdx=eg1|MDI`N& zHvf+Bk75m^koO{Xm(F#*?JV%+{5+E69G?q)&|zrsE$p~&?n``LUL4vUEH`m7h$>XB~25U_qh0w)LBezGJbTky>2^3(OMi&FQEiPHKT zj&yC9X=vSk@s+4>xXr7RTw$S-dpn$xuskJNWe&2zd$p_urlEZ7KEa3U+1v7=_e#f0 z=`Oq!qyIm4NHsS)So09qnDYm+OzNR3Uzco6Pin#r zAE4+Qll zr}58jqKv_m`25i_s_@xTYb}|tFPwr7)|-Syp6r9R)9sm^kFO&A&P=fyf4^5{oUgj# zJ1_Fl`Tlb7Go>nBD{?rpWfRb!zZv5Jc;28ZaK95&*x>bX4}XY{)(8o2r*`Y8{~xFp zA;mYYH)#wo11G(Wi|-;i%1yyh@}BA5&ZKPL-tZ2wM*P)u*@W?_5ZAgR=c`BfkF0f3 zMzpK?HW>iGz(#`t;SA3zTyd2mJfBw(K#QCWm-1sB9P|<<3cK*@XJr;hSa}T{zlVbB zGWK9qQ>R*n&W??4`^pSO4Rhq@ICi_0y_HyTVq270VT+zGeRuHVKB&t){Bn{#mK&!h zmoSzLHesNvCbd?ZPY+}ro#T!*$~Im71BDau@ekLnH1|o|&@->7x=JnZKY3!?y_#BF zP_|T`{dKH`u&cT__w}dRdg*po!WTgfl3EkG_WWNOAJ<6mYpuVH8CmSk#y>1=g?j2+2=5m{#3(1mgm*S&6bDkivDNxOs)Wxr- zG>lDnQX1`&#FibWJ%Dn;swL(uIYe!hGqDqVProSM%V{qk4TR9#Mv+87iAa% ztYIBn{MF1SjBDRAPrL9{iH)s{^SOP`jh?Cwo!S=;Z^`8^iZuF#3CuhFwVT=09J7xc zi1l7xz)LWOihr-ASsTPMMirYtr&E^>gEiR!yRNlLaOvm%)GhXnH0shWvRrQ;Z}peeor6G<6v-?t>5qBEiQ$wyy`ewM3TvUUP8GVetFkF&u`- z-8wt6DEVXB9cV}oFm2fE=)-$?c}|i|mwru!*1hz;V_Jr8FIKrp5wHa$kc%~8C2so4 z-)c?_D!k5O8AUiG0_0a+AX!5uAmihW>Yc0yoB_*Wf7>1{LHn~9(Z@UA%v6e=^RJvJ z5gg{u$l=uwe)egT(_5a7e@^2g3zPUYK|l~dX8i3GKnPPfEUR5kU&o^)P>si>#17=1 zv+S?eaMf)%aApi<@N9K`x1Pku^i{$OWzAI&hoyG1hs)<~rr3aZklSfmZppS@irIN{ zs?JYf=~c$8>0Ok3E{|e0+&%{X14ZMx+Y-N!skW~{H0f-)nraC?r7Ts8e;c|V$ z80ECAw5sr9z{*3A1hNkJZCj`%ChiL^Do*)nj;;GZ``!=^4|FC4EV!Y;WQ=r@z1RLE z8*$!LI=osO0~!c6Ee;o4OIZ0BC_#i4!#e08ZooupB5cE}_)cSl$6A7l)Aij>ogFs^@9e=mmXjo~#AT zu_MN8QEQE|7XPS+J8^w-_&k97)eeKiMiQM6^_aAQznx&~9Xcgt( zj4}CpzJjKgU2^W%JtlNZH$liD1%4_#fzi?1sg|CC3s+Q+zqexXZ>$nR>V^whE$GpK| zAAp^2_1Jb)1HTx{Xs4m!$;~rElk#oY#RdV)Q=yAj%a{Aym*?G@Dl%ZIGrg}bK0XuaHUUmOE&mC zj^)d8tR%m(;Mwrer}gs4HNfDCGj_Md9!FAhteh$;T#1^9J^Z%DME7WCI90}&*oPCx z^ki=Z7Rl~9z;D`XcbzlhWL+k+Yd1w&dD_;%V zpkx!Ciw@aJMRPM^%nXCxwy0w_1?~yJ*Z{mpf#i!oH$k)&;PHYPBnXc=4L&>|w#)&a ziUhZPPabk*3^sfcQtH(-5 z8v^$+_pAlcprO-ywQJr$iIi~72akNObabO)fgd(#GZW};7ei=E`j+pb@d>of+1| zKU(rdatHauY6{Yl@eAY=1&T<~t1k z(J6aQPcFme;JH%bcDXYnXeE&82df?INgk!uq-qJ?@LA0Pl7Y)j#uUg4sL=QMvZAO*O)4`k=WGsMP;u9N+fV_E2%azT@ z9UyEJ6t>r~WW&Ez4WmKM9SM!RvOon_1NgYOgbyR7`9KmNJ$f^d4%`udI1KKPB4C?> zTF!wFKExyf#WRe}d#74RHFB2dzlgd%(OEgswN=8V_`p;7U*zr*Q4krs--?AyDWvM* z)TU2lxgN4@(7OMR>cVaylo*hO3F0PqJh4IoV%pGbyx?-;efpvg=er!WQi+UP=rFPYK4-yx+}i*r?so`1C!!V^Pdl@?g?GBrTZ6 zW&Mp(SB={w_-UTseLpP|nbA=CO~a4&FR}KdRDHji<%wJsdFtsCRqp5yiB2E@$c@mC zOp8*Uo~>-pNF7)nDZ@%t9BY-Wtf_c;$POVRoOs~a*8H2Lc@x!O+qAif2XjP$cKfQ& zg+*$L*S7cV4-N{4!=zVsU!1S6pfbU_IMvnKGD9OQybPNHXR@)w zP0J}dzX!Mp{Xf#5Zal*NJg^0XeF%bo@4pz_{QM3O1Lhbc2;`ITY#tV!bq5CvPU!5O z=TgKywUIC9ne8PN7u!XzSEXSZByX0&MqK#2LjO^*G}1G^hRVVlioF8 zV7pTUQCZwbZ)zlc{0=o?V&`pOe52`%Xc2G%*60B~2_7SsVXazxF0w@!ST}QFCD?Jx zNaOOJYEJNh^Je6fGK^?}m6<1_6}#$&$akl;q*RdvjKC-a*|+4TDZhu`G}aOM*-;Qd zJE?fNtrXnN;^gj8sJb39l#apy6`Tt^))|_kV(!(;gRB6SVo|I1X8!MN-Yv)iWT@3^ zDqONFBZGJXsFQV{Y|NwaNisotLSGfDQU+*BcyqbgLQYKA%{)r>e7-mu2HFMC&M^R{ zOdi;l08B-{h_M-HpumjAivuz&xG>PTnGsB~3UYXCCsV@$N3^VD9FV<1=LO{p^C2VW z@@eo9UG+nRZwG&PZI!<#{Z*4-;M4J~0UmvEOSSAkj+lxjilcxBwNw;{p1M-=JwU1K z%95m8Dvg{xWpz9gHo&>ZSy8`~Iq&^@NxFqmdT%xZT3i?Qd#a^JHldvyf6;;S7B9ki z8S3TTx2(ApRdiG4=!mIi>sq<> z^QM#>xjCe_$iJ20kD`a&r0Jk%S?Kw#JLA^4OUKG%*Y&cwe1DrIr*2YJ4gVORh{ej) ztHU%=l2^7Sn7&yOG!w}NovA{*!E{E_UIEp2q~3%6=U!;(*_aIUp~*&#sRGOZI7t-i`(2jcyQR;POHl_AzyFUM*QsJA`T92cv%ZI=M*R3 z{fJvlmChpeFiLu?7Js3J1F?m35=IbX#O}@QTX3I|6;7PIgg=jbg+~I5@CAEU!h#c! zQP&#^M;Iqx0&)tFZA#w^QV{`xZe%iu^vy)$;y@7Fd>+tEh2x6BFb$mNMBwHIFdY$^ z(^p}gO+pOA4{TT6c+y}kOXuz2mzTjfVa|iRy8z>&sG2WiJdXcDh-)^c3Z!sY#3`8P z!+>Pek`WIkV-PjgsUMgB3NI{x#+~EQ0?;6yC*K9Z!B{CUw?wABmpScKKHKnY=JeAF z!v}J#DC4GxuIP_;k!shk*x85Ir|-yj1>AM!Z4BlbAZX6J&d0h++Xpz$yM0f&ifp0g z8?wZ)(j=(Vkf~h*l&OjLriv7qET)hh@)lQy_vT5I>f>8d=Ijb7)?md;d#O7&lZ+32 z{I&Xh4A1+2w7msfRZG`6ObbZLp+N~j`Vfci4(aZW0}|4qAl)S)E!|QA5`uz+NVk-t zpoAz0B8Y_FZ1mp8=id7~-~0c+-}gIb?>#enX7yZcz-=_+ z)1@CMfmIy2z?e#_VXm2~h;aEuu;2Qr-b0{*Ryee;@YYSq*a!2=Du+D9_i@%58~Yu1 zl^@DmO=}Ia)27^w^|_H_rgsebR?hf1U*QO8$mxSXd?BZ0W0Y6L{L%bYJ1YFZUW4I6 zS@sL6s_)sp2SownWaPE=fhmAYcPH-3uMTQpSnAD8r%r2K0ke{ zN7t@(i{pW!7%p1>TnWFb#q$rWK}%7s1swXpt~2WrUHSzNDy}6s+}-1yaW(_W4>604 zctRJ3qaK#Ay?v}Mv=<}6Cgkz(PS?lsQlGQx6bW33!z-gi|88TMVIz|ZC)y9_v6-FQH(1#+8E*`_PC zm{hA)Sk+liDFt!J0sWCD10~5X*upUA`M@Srkm#5W8|)`tstV)f%7XA-_b)*V_lB z(;_r4wv<&~IkH=$g#cC=_Pl(OxDQ3n5tAM0(gPbIaJ7`IAv?e;!9=*gXc=Iv(tvtO zU_JzVc@C5cvgr-Z)AXI&u?It0F^wiS43|g!$|yLug9g+Cg6W468aVhy(NqM^sF+T! zWjjJ9rAH`$P>r&Hp90KbT}wy6W1EN9bM`*P_bG7NsWrIaD*}tL5Qx7o_$QsNUSE59 zn7|wBi~3AKTS+Y2cL8kUtpHq)Di?4Rf8xF4H;vG`*&w;_{z{+XBGcEZec*HWlmgB) zYz9^}Gm&2;J9~Al8NT?g%1fs;?&$*Irux~qn@XWP`9-QL3!IzkR0;OkU?<^m^|A|ntGvFVOgYr9W9%68fa>N4x8xX5-PA19{6eL!1HYPf4Hn44l6+-af$|c3)i3lB=V-saRWNk~UB zWEmF${B#UX^C<jEpIFAqh52f%|Z#8!z7?{ ziBs1fHDMO+mmbqUSK%V#do=k8=$W;XNXrM8DTh{fF{#($6%~y}DlRfMn^+$Gv(Z3S ziP1ooR#JBr)M~7y@7n$sCgUQad9Ldm;m2xRO`JBxM)C`$Aon!f<-4M_w4)Q?X~WX&+RegJNK82KL8*WkBsoa3D<-v@fvL zr!^Y_=Ei_UeGPH}eL*)g7}Gdio}sc*OSyz+5Fki&9-CeKI7)G+YEimPC7LE0ss>ta zr8XuwmXV98M3%;h!VO0}cKlXu6U%|lqe7M+E22Y`gDl;;4mKLz3k4fxQ|KN7w7{o&L0j9qxEXL4p}@L3 z&?W?CTPpb6WcPBUguy;Dp!yXU&;us4#!;n;lD)ynDS5gzU{n>HOTDhFJU)&FEc~s3 zL+{m2#7Fmf^|Ei^_rNm8Bs;^O^P%zRHJC*fmf@&Ntu@$9Ud4E$6W`8j%Wquf|t3EU`adVe!BDApk(-DO%xPT}b|DUsJGOewrDepKu{=Kx!d z^|Ru&F<{uk0%z0t_G3=dEPRt86#E5uPahs@x&&5h78DP`P}2`IoHQO1s>~7t@f2Vt zZ3B}7bb>@Xzird{!QWQ@iw6~W?Z#lT*B2r_x}VeLCM+iQl?k^v2fTVKQ}y|AEVCCFY}BS~qz+ z8aI_RXDgczN(Amto8on*<={J=W-O$Byg$9o2zO!bG0wL=CrwaStE30$rIT!NR&~Q5n#3hiKaSf zpBC#1c6fj#E?`sT9?*Z!vX+`{upP3Jmx%16PXOd=ZUq?m69TP;Qikph>}sV2y8?lmbs`Ju zW9b4Wk&I3hL`B&r%JNiYDf~HBAE*%?V^U*Egh}Dev6ceajk^@l$IEGvJUYOtiY5Dz zm%q0qQ0+^3A%*pcn(-$EOi}Ebcd;6b+0C&k9GGsPOVFV`n26=Tw4l>^7u%=+)Z2H2 zC|Mp<>$*$9hGG8blQjT-rSEirlEcm>Ensut%C&_g#)aCCFqgGpR)5$IL(QjBAW#Aw z87xsR07dq4h$6NIAciKUfV~Nuybor-T}b1b#z4Oo3eR;V0CMF%%CcnSa~Min!9=X7 zttPrGI7h)g>L^u!wY`?N5R54b!yM>B6bqNHWIN7r(Nn^#b6G{l(OimQZzsbh)5DqQ zzz#@Da-g+3Ru)%eA{N*sgG8#}WIQ-6hJx@ZT?s`31JIa4poO)^Swm6431P4dK|(Xm z@@j-0n5dlA5!9p#Nh*d-BG*C)%d*uS-KF|2#F|dIj|iaxL9PsBcZF!;x&~Ujr<7@u z3k&Q-E0%+t3X`H-OFme|7)Y=IzXa|j<=Qrgk3g4H04@+}+J~}=YNCS^B;4AuSQ7C% zp1@)S8fgi;MhPO=enC|?vlxa-#_Fzd5lnHCV6Ekl{iP(JFgyrAjrgu|Y=#T9BX)Ew zHa|U#SZbgPykO~P4IXDH_ZHLs1jd?FQgDht8Ly8?l18gB8^z5@C1_AU6T?e4$I)jT z!@`(nQ`@E3g$#|mWAan^3OEEitcj`o2s{^f`h+0co7VTzz@!Y@5tw`e_CAZ!aIv8S zv5}CqU;LuHSSi2`Dms~h)l)~XJbEuAp^u_m6G_ws#1TN{cu6sHDi&Cc(G)6Sgv52F zT7492nfT1fI=fP^V0%Yl#2#3OAzq2ME_q%`K~ZW+fypV7k{7xHSb{#VT#celtWKlN zkHQ2@Ofk^`MoONWNP8_rIa`VoF*)g5hBm29r31S27Dq5|uD2?7NZ<^rt~qq?({Zi1m-dm?@c5Q?HODFU=uDS!hJMIkESY&sWf z*}Y&iR!q1P53tV(Pzo)BMpLK&C@jXr0tzA>S&EW@Ui)lI79joyD%Od#<8d9qqE!$m z;uxZ2lHxlX_w-vSf?~v^hLdzQO0t$(IjX7*6($#}BT7^aMQJJM5l{mIn|atHoPcK; zZ)z8f&0wK|o8h9uLIy1JT=jNz2{3OQ%LArG040h`xmXy2 zsg>11Y=M+qMWFGSu$hTvQwd3wrqfy?jzrm!UP}QMV9P?39QmaBfR!@Pm()f$1%aJW zbT#HQ0wkR#8oI(q(CIBT(LL3RJ7K|&FG|qS@)THu->^V>ddOk8EG4M1U zf(^=eE;|ecEBlrhlZk0sKuIr436Fa$5RYLKsKHf$KJtl4z|v`fh(+-e@@V9UHXz*s zYCFMM40|wPNrTvEEiw|mz!VRn< z!?2+n9*;7}9h|xXMv$RuT%#zPkVhx_T9yh#*r)?Vpx#r`z~(8%i(;AyV6e0q1LVX6 z4*UMb^?mN=(y=1hnN^# zo0kulmk;>0;o3X`xI6+sox%uQVZ=`-9|D)}my?$tmzN(3m5}%&uk*CO@{+Ogv{P_% z^@7V8s>rG8vdgN;81nGKp&&UsPa6-%n_g}nbi6+^)Ahe;cm4_&uHfk5=_QM_@}NWT z!&R+*xp{c`;0BJiUPw<9IzB;uIzApyOk8d{egVF}UEH8hfBAu!Lj2(31{X*vB*052 z$Oly%`XP9P&z}N<0(3mw0)oIJgy6>&6o7(-_=M>MKs^P8ctJ9#zC1i2_22X7M+lxr zv&sxL5&BsAkV)b@$>aBP@K2!A1UDwVE*(NIJ!!^dOH5; zmvgkYxAU-bwXyRw!G#(fV2PC{((JdKA*A>#jHOjI4CNshYx8jb6~sJHgKD1_@NXdI z;rV9}^9zBB^9!6`LVQ0#{g);Onf~?z0Ol1GqJtX$k00dc6B0hZps;g4$m>@;Tqy4U z7?yusWHwA-a*%S-rU^(hGRTXQT{WIoxlFy;usIy z-X3o62)B0z4o5&;;O^dTUUs(D&K`~qNH1JI;hzCNeZstdzIL{=_retx_~}3Q{4>5n z-RH0Ps()Smx{?vVS6$`5(sNaX?I|JJ13|046}$o*G@ggVcE zK}hKJ{}v%Zd8|FGZ0sPE`sq4Hz28Y7)Y5-#01X2reHHn068N`Kj^}5w|FQo6hEcpc ze_|A`Ak@s~cU*)pfb6g99Lm7`?;()?{0EUIFhUCm19HR-$PNOKAOQh70WggHd;?(% z1P%cnFrW!Tw3!N3B&d`9`2(?_<`>`xU=RSK1OS5o zAh18*^Zj!117-taNdQoIe|Ad&A<(n{Q=l|Z`akpgmkZ}M$u zU=)H}f&c{PF@KdC%8w6}={yX?0jbaL=Xw6t{D8rMs{3Dh*>C;-|5MiDoYVPhzmk{M zR5CXBNvi+GTL}L*QZ4+?Foo*>4{iHL*g1^e6{sOC?SR(LGdGLb4`aJw+95DO> znD9aOpFafX9Oqc@@9_9ZKK~OrJ}2k@TdMa@tRCVwK>yjpjAfLR3=|=F=>DD1pEt#S z;Pw8Uok#ph=)fQZ)fr4D&hL=xzg~Z|6?mSv;veyU3;)%cf4qV6hTKq$pU*#hf28@- zf1cytWBq$7$Oo?f`gQRBHyHj;ht_kt`_~?zEvu|(s07h8p}&$eK!yJ^Z~gnY`WsE- zKOa1VpuYdBwtuw3-=2SY&kMR6#60|DAi&@R{18Qfp8R|~AU3%Fzg|%6KfeUh2nq`T zwin{01;LO3_06Bu4+`f4^8hHW0N}EP1;LO8!i0DQa0Sn2n$VmKstuG9dINFM!hh@B ze-sNuL_j3**YlkJfr<h=9`QJF@e`JQwJHcP^OGQam?;O9t1pRLm zmKSQ)|InlP{==xr_xorFlK<=X3!b?AU<&_F*B>$Yeoe{G{Q!VMU@k7i15Ioo@CpJd zDtInA5QZ3EFqeYj34jR>fIlxC6euKsz!f|vrb0kM@RR#FM|l7iFai4GJHMU~ihwZ` ziUy4i=TBZifZG7LprnxhXNd&BSPr>_`N0?s#TMkpg`QA2LJ*q7g9{P_fG|jQ0P=!H ze{g{>2>wnHKskQ)-T#Ol(Chy{sQP)s{hsl^i)7A8jJlPJ-9HF!WMtg@Ot|SddAWH& z`9U280e=oxaJF*rq(k7sr9ExzT)m(`T)3>&O(i>M0{7DkiF}}UP*PmDvX_;!qm8ty zgR>nVLU0`~I~RRA9zoz#bM*8C;*E1r4AV3Rk#{l z1Fi`NObT2Vt_L@OTfwd2HgH?G-7kp+=odbAaCgz(FQkW^9o);;4eky1f&0S!SkK!-!O__ch;7a} z$bX4K&i%hy62$Pb^MKmI%TCS?2x;sPQK*8}Q337rB8b=(vxHCs6k zeDD{ksEIeO5WVLf^ll1EjT_R9GNKP64xtW|pT`b`(HCwFjsCkzpccns{FWl(auoW}6EG3~m7hk;5 zU@K2*=G$T3{us(`Ki)4{?}yRsaT`O8288(7vtDNM#FIB>`sW$-wemG)%?vNbv-2fv z4s|^HtSZ@mZ?kWX$7&dZim5+a!bu;`V53H^8m~HPFnzG@0lBeYWn}e=-g2cwRou+L zljle729G1WZ#>kRqp3gYJTBUf+?M=0u;KWsv22}lapqA{z~-&y!`ZJvvkq?gJD;>a z;eLAk>BcMHf7ryg|)E4d)u^y? zMg~UOqL8?mibHD2VB?CAu>$SqS@X!xVf81&rrcD%EtXGF4QrpsF<18An2w5f8ApkF zLtar9xoYTP5xaVqF@fz;-J?&M6E_w!VHI+iwTcniBEjTGS8gxU>(_3h@}Xmj8&|&A zH)F#;))H{O^rGCA>d~YhI>Gpi_akbohXYGaZMU1mJR+r>&Rn||R46OIYX1n3M?dKD zM;51{)l*v}W4v$=2(->Fc=g2lOzurI6nsK6%pv}4aAnU8)b8?n=G0x_pb(-EMViPKg+JicD zSRa+?626o2%WZvqyV=n0^4;)F5#oc&s=>YEAeS~b*ke*JqAbdG6SrVobrA>4hW0O; z_e&nUv#y6nKIjlX@~iK03YNywG_!Gz>hWrp#Sfgic>Hq09_h&dJyBzP8CA(aG)q5V7ezoq~O=Yt8yYiuhEGqpd zjNH$2DmXHWoJCDr&C9`b!a0OH?h@veAuch8z5s!CFWDOEh?@h^ti2(4f%_s0`J!e{ zBFq5|8}~|i8@G*xm{l%ahvgCa=eHOzebd=`9ULfGSZ;ub_FjkE>&YAI6S$;TO5&9d*5NrV5BH>n}KBD=EJOSD@a}{?~O=~ zg(5ZgDk}#M-m9B^Fy6$^=IZrCWodrqxJYb~3oKn45&3x%caGLpJNRyr)R&J*^FGf^ zxro`N7uujwB9WSIPve^6zo_2G7^eVBN^a<&<}xr)%#Z$tB1ChtPfZi@EZpsdRFd9e zs6ecP5${%#^XBl;4c=Degp&zAPWk7-$KQ%BP)bEUt~D;1(9I>dN37eSMl3gGe7pK$ zZ<>B-6K>DZAV-BnMQ7V~)5g@hHeXi!rIMFXB%&*yx31E}*=R_xaxLLhx_^%k*X6nW zHk886iN`bveJrkdwqK#AVek8-tRma+XPAdFVULq=N1RDkZ)D=@ulKsRy%3jcP#pS?JXCq zf0vDOC0q6)i+p%t-CcUyjn$X#QnH?-q7JM!KMGax)2k11F5{R4n>4*+Am}Bw z$bIr{=7r#_mUCLXzWVAjEa%NVRE?;+ zcT%yc?#Yh2D#lF_^S}YtViqzYedrx_mmg%4;;w01Fb)50^2Agp!ihSFLZaZr>8T!cmjJLex=B)(u;@Dkud^JLk=zlqTD- z3@;B^9df*;tj!a_e7U`Rp~ZWvYs5%QqvL2yLhUmywxP-w*We#VkwX~;$uiYKQ_sft z)^2J}+$3GCWh=cuiT4Ed(6{UZon3kI{ktV4X<=^M3gPn5m?eoUAb(3>qx z&+9B%X;CXqerA#PJM*VSz6VZZ6{ulAxBXQ;;;?kwj`2DQoHJrH~qeAxP2cKecV zq0ZL}FBdsYf7HZn`K5ijb?I?+Qcq!T?B}o$-KOF4p%&rK&Rw*Dm^Yuo#Fh*?*!ip; zo97gePw8KH9^TC`ZazPgy-;+T%gxM&HRv~qzqQFF#6Q(%)Al;+vR-iS?`v%-`X^DPce}KyeK343swF5P>3-%}*!MinjOY?o2S%-~ zc4a~4y{p&qrcd|?bPB4>V(!waJaNDNih22sl;qR)u6~=cc7>2(`isca$KSLsn-&*s zp_o2;7xEZ!uXOHew&>hyY|`Zw2g3ABPR=z&J=>+=K-0!eYm>#(=8`*Y$&~2dC)bfh z7uXxG=M-wF6C-Xg3>sXamc21OPN^=(^EBww6TjUDFGHpeDxObZw#R06;xt>;$4>Qj zC_gAC+NDdJW7@b*=ec+>(%*|`*m7WmWbcdTp}v8Iq3<IDNct zZZmy)xJWqtliPp!M2gi)xzkH4T&R%+FELBu%r|QlUB9I1|FLc=1U~T4mGV_^O{LP*2kHEK94W3> zlRo2>3{vq{X&X3HA$62$wOs{20 zl6;=R-o0NpN592KUAw428YJW=lXhEMTCcx$f7&Zg{p!UR*y$x!KkgUt7CXIJ_yP+| z=VW79GSLbZe^G)u|9B()tLdIVG&#aKeV4>(4)3@?dG^G;9zO+dH)}IX`S=|fP|6pp zoYHPj7SW_lF;p2NR?BW~k??cm_@hJ+~iUnR3L?LS%39m;c z8mc%)-w=5cAe~$$&eK>Za=|$IwEOMR^h$3Eszx+vt?c1rU8i{*Gp8E%?fv2Vw|(60 z4={zd3)?Zi7s0O@2HSWphhR`0?%TR!&tErm*6eiCSNtG`oHNi;G|e8scUZ}92KZqO{xUla9dd4%@yi(}_7>#b0xeINO@ zi9N+*+=1aiuD9k_JEmus(m&DDUOalr=>96S_p78+;Y{+aCcXkUe32Yjl;ekQgWd*V z4o9=|SBMogtWyPM)-|0+x)=5$wOw8$-tJB_k$+6&+dMHQzcetp={AT}lpDVE=!V6U zDX${cCA{qX2zzgT0^RYLtLCQ8!3-7eqF2NugPfelsVt@{cakfQ9g{v^dI|eR6f)|J z%zr8@SZZV7PtP?Q6NOW{kr2BP^#OpWYf|1V->HmHSl0^B6ef*$6VH# z0s6sv`qEC?FLrHDHsRbqmU_uDz%QM@PAtRAl#E4Vdos)U^S3D5`sWLuq@S!@b~_u$ zYGhK|H*%v3B!3WPcQ>cca;N!)G&i9@eoS3~?ZeqcZr1m-uSQ~jOe>Fl`*_J_)+}qg znw4#cg{_f(GUbGj&YZA)A9lB6zAb(@HB?VBb4I!y$IFl~l83DLu`{F9z#H|*)`{oK zIWvXr69~IdOBy-D%Qk~Mrn8BvS#Q#Y=Z)lrO!g>)Yx5+G-0!(vw;J32s9k&gF6zP? zyCydQ_R(VTfH&+aFQTP&mF;_x;y%nflj>1^;pV|mi z#e(oKn?yaxEgY*1Zb#^EaK)_#`eod6qxjHynFfcXk?u=<3v!h6L0Fin4YHxwe}#Ff{n=`q_MKXgzIKRMF65zG9xkiQqSn z;CS-{vn4rs-y2rl&V(OjJ{bt2;z5a27gK2lwJ5J7@|mEly)@A?CQx)C?$80$j{Hc21=l>~?lzzkkji zp*OL9DRM`g^zmx=Bew>@1@*@oSZ@2TNlS=bO1Fi|^|XRHRZb|@Ki8DlF&uZSX$5+c zN3pseQstP+zXV)#V=g7mWo@^Y*{=9DgJ*KOhMj%38o<5KMSV#fynCL1yg){|0tMJfGfh4fOtv; ze*IiTrT!NomC-LTm5rOTn=9PL&Bev)r^pHtl>H&Nvh%ZXwsL`kO%c!^Y>a^ZkSq&q zkocQ8%jr*nma8L>XZ6{@7q~9^ntq&p7A4e}(@HghXSW zb}o)Ti|uLW10-plj(%`YXRtNspM+*`e|P{qz|O<%cj*~`3y^63wp;9H!2hxQOc22> z_?!H!#{Yts?)%w;EW9kw3YmVJOI>`yEVRWgoMYckJvZ zv%;^2hhJ*fm97nr4u(lD=wV3jitmn`o-C*0Y@F5^?6fbpJk-}8WIcX$JU{m3qc}rV z1}W2}n5!4{YwwFGf7|2?ijKbG)c2I@;MsQzSYGAqxCY*706%`&$7I`y7?My0S}6(DO3-F#I`^@DEH6M=My1%M-H% z0{g$c<-0bV{cU@3M=kp!Z;{0hjKe4BEKX?rp$kgF+7~Nhrm3fyKQMkk|6umP#p!Bu ztg)P0(d!a@ow&*u(Y52_% zv4x?PL~LmuL|=)&mg=XR=pf#!ydv&1HZnOfJY`cSwb=y&__jaU1|5+Xng6=5w!oc+7#u&lKb|R zhxiZSk?uWsJyH0Qe9zqER-#GVSQN|7*o-$-@i&^V`1W`|=Ng4azLvKzh&#Gb5uA`b zu&nwl?6Zuey|U@FZ~||TXeWB?)Av*(mn3Jde#UUiL_Z5)u84h7lzRN4y$UJWd=kjT z8x7CE+fZdndS$tmK_!QuM_?T!w~i}Ntdy6Ef>WSvd)2D0*6q{E>@6md8<}+N+K)|M z;@Jy5a2@Bi50I7fPB71@n|X0SZ*l`8h0!lmzfvc7QeqD0Su0(;(H&HuXRdSQjs|>d zLJPzx9`6$H1a^-&9`+m5xHs8$)#=ye7S%^po{(K}A=6vB^hIaf?9tjVy$fq{i(I8F zLW}4ES38n3ruzYFLKOB~nU+IIM+Co*VZ7?#ZEt4Vg_liIm=0w<{MTo8iLlHUENR=U zBz2`4B&ime9u6s~<7!@2tiv&DqT!{(wH_MDYGY=xbF#i(Y+aNZX0~`raNkihs3Vq9 zD`85CSs#PMGk?m)8GP#{`SzYdKpV^!%kYZtD`Fmqks#kBvF_6kXr?OuGU^qMlkg2exc(3mR0A}hlN zmHu-BGjc}xbqax*5(Xpd&$$I`F_>a(B6y|>KKX0GwZv3!gWHvbMwB)x(sxIUsaVgf z($jO(vk4C{3&ut`q_RiPd=_fsQZ7#`8}H{!vmbq@ZmOX0yn6biy}+p7U}B^_l-)F) za_nw6I&yOLCh{e)#}&CcdX?8}G~9SZK*@(B&kykq@ zVH}*{PUDLEs|PXH$!c@>A6`4s9C_+=X=b;x@5J&67B2eHl{Q0p-b9l zOd@qdnzPR6IM;*Yf86b7w2&dVFfoZfLch&FDtj}Z*oHfsXK^{R>Paea*H|0fH=_H?Rye8?v>l}vvrdhm- z$xkvj%wFM!ZR13y$&6^Q|GlIrzl$Za$1qZ}Dd9$ArMg8v_j1C3E(Tw*L|b=C^Z09T zD(6UU6~y>mG7i62=#Iqoc>nq3H)_d&UVhi9FbyCMt*x5y{VpIPxDxu}7;DO=DMYY!B7`BAU z8aR(`^EZLoQ_JrQZ)wULE|~Qgm}4wfeHx$X=Gq80E4kJ(Nq}~onmT*YO-A&_c-D4D zQP@~73s#=P1P#uIsERF(Cs$7KgUllHeDvfW#kYns@zc^MqU;ry{|j#M6FU~*A|iP{W!P{y}0NZA|!_R zVN+U#CfrhC{b5a^OBJr=<@=I%N|_3oinM1tiiN99>8!?Yyc@(5F5%vlXDvM<6;8Kf z#edD?imO35T09|p1%J3#KJK+I-;u6cI@7g&%wS2zPvHd&S3KiwZWoC9@m#!ICylO| ze}&M@MMb3PNur5K3$Db~$N}2P=8!Ctk#UqPO(T2DWY~|vC(RqhpvJ*pVg)&wk5=*86|KW+Fa!3QRt*x7{g2)y2t-V!@-iVs)W z47_uEqV)M7O~yzn%(qsNi?MS>x4vYf_f1*$qs0NX8y?AtQ)O#+d->#(_2`d7$S@dW z@mXKws_k4%o_2UP0ot%LXmt?%pz zI|S$0gkC9@mQ)IIKxrR5tK;CpS=}nsZHh_z5RF62%$2y`f@L%ocwm-LgSaeTxX!^= zQg{hh?fY#raf;x!r~ua8oH&N%zG6F#lzBxx1C1WNHBpYX2u1gAZg-^6esCO!Uk!ff zxG61nU8RsV`_adJMgkig4)i*Ke1WG)q>CYK#y-Vd)VR^{Wo0*PV`#@zROOilMSCW6C0vUGL#j?IR3^Ja%^Y&j<}(m z<7&ir$(FX06Z935D@BCg2#v&4yZXxgai58ok&P547#{t5v_tGCxgq ziRO;Pl8=gr%6c~9J<}g~-!axOPuW}Gxzn?;qOs9hrsk*N_xF4_f@V4%_8zn3)<3@Sf%c5cXqCV9SVOzg?*~CCb|9uwxqTPz+X&Yj3 z@2Qm|zBJk>;eGG1JGG%7XelpW9}7`No-~Mi=TCc*on8y`-xR!UD|ofzGR>JIC2Ajh zzyPJs?`=Q3KbjF*$z zMedsFb4(U4x}h{h6e+!&$%xP|xG7DW`OhTwzTzz?g?4NZYj(&|u;FCDG91W=^s7)j zZYfLg+_$&d(Gp1h$lV1zjfux1DjZ*v*q2dXXWaHroEAm@UuQnAXj zn{II_2#K56v10Mu@L-gj=8wbljFVn3}d{AH9FLgj;~Go zjCr)Vr&BYmC|a{)^hp`%AWk60jofLir=Pe-rOJv}uoHR*xI~pRv@qn8vof-lZHSfk zHUeO;xdMXJ<9!OX^^1oFu*7Z6#nSU{t!X|UW$7gW6${GO+ZgT#4ZDMe9(s8PC8OA1HR~$L zYxg3MpM@DzZ`ei}53AKfB}z^H;LZQEDPjGge8J<2R^_gs*ABgQ|_DBLfO~TKYC@5ZQsZ z!lsP-tcBh_r{!8QpQ3TXPI#U2Ztdp8?)KDmaxU_LrnV9yQHnFh_8N-OQrci{1LcIwConzf5Q^2W^`2 zMe5D_uaMIP9MjleoL$%{2H0f~TQhfw@aXS(v`AHoND5!qBFZHZ#dnxXP>hV1v3mP? zCE%i1TD|_(HPbspxOx#G16V(tGtx^mNZu3ZY=?D)r=aBmAkqs)~NmT|*dZcks7oeq{=K=vP9pLsNiA>4k- zl(VU~HGvwx>$U4W-++BBKrdY8a=}tgA3b?C@@BO~obOiTq*~Xo@wROn-jEnaFMSjzOhBA+YV;%1N$1ZF1|ya#AhJOj9#ef=M&J8YF22oEADx?$csQaP3mhXiRpku_P} zw}Q4zZ!}gUzr+p9dFHy@_C-oBp{=c^L{>_xRm6})U9&+ygQH-eVpJ^>En;<2IP}0t*8|i^f_Xj%s!V8A3^GT;_HrRA%MVh6Rq<+pB<+S$)uifCC znGe@~lpmbEO*+5gO7wV3EJ8Ffj2QP+^~#);Q3m?`{vrMVHG+*FBQqKFe8uDBZC>6B zn>t??V+$y}gtO$4WchYcuRjewI+=LAXAqf;W-2Xtx*ulb_4(R6AB$np;v?I8quA=c zi}y0`KT3;64a-ovFDaW!2A~iVL zoVZ8QwX}S?{oqhw*t}6Y^5q+pwtBUMrgg`dh;F|u;*nciGVH3>?_Mn1YshbVA0}PA zNC>}pLjbn!KysmS%Bi_)gHD+;^ND4jijfMge|W6&n6^FX(#fT-Zj zlS4X|>j@sAj6evIv;Ze~ZAb3Q1UpjmZUJEcvtp%zb4~}vb;*@kn`#&bGbeXB%HaL3_(;%&K;pHnLW8eMsU*p`i@nyekp_433-RvdB-t%wSP@Si5;x%e zv(qAHJ^l7bF@9OH)OH?woU9Rn^;U|heWyJ(d+HLVfzPNS1e39zUf(~e))q9q-|!Z~ zo5}H9RSEQdT_1AyOvW_QrbMx%#qFE@vuo8!z4_Cr5)3vfHb&lhdbho$Qto_Tb6kIZ z>2bH%DS@)xtBE~EHn-Qy^5fow{*s11WBLmbAIH5P#VX7rEx#02`Sg*IWNcv8O6$dx zO@8vPDPKAm>#bX%&+L24y9u8Q&Ws?u`)%=Q>T$`=?Wn%Ez?W{ZZ#6A$XPKdPm&2Ic zX+M+F->t^i*iPRLOSi9GBA-oF_91bOKD_9&q?+sRyB2>^Zh)(-MJ7S?#p=XUKqENe zZnp}~Wt0yLc9O9-M6lP8HJIq*;+8!hf14Y@_**c5lfI6ABAB_*`dt4*6w!Y zy)urOB^uCtE+moyC`o>bxjFfFt(?O@^?2`9|SK8YKV7LibX|Kc${XS6@ zjVV0x??f(6KKrJxt=d zNq^Id^2ev@q%yBXE$D?MDVi_Le2fu6vUi5sf6kd7Sxgr#h!;L}Jnp;h@RHN;Q|F6` zd_Ja!`7Ja;cu%h<72@UQpYrR_cr`(P~^`c}5z>UF!(6xnT$FLFKeb)w;`54_5fS8=pZ z*~p6n-VNOEdSAVbZE+e#oMiAdxtr&;{xE#Y%c?OJgUtq4`^!7!L6=2cnzQ2{!(&R!t8EMB z_cM$&bF=d6)`OBtB?E6bXJj(uw1u#FJsy?Zx{K3|yp(EWkOt5>?_COw7Cb*F+YIH>#B4K+-`I6q3sQc=#> zaqb)mcM6XLZ#*7(7C>9$NB4l0peW}=$;U$dVL6_`*}QH~oTGDUb^)=vOC2-AU5xmB z=IyWtOi6A#-)(PwdBlRgUa220gGQp6YN};q)PDLd+b1ffbtiyhrT$&M#LBl~!2BV%xr{bGrMS)2H7%`n}_R z{IC5bJ7cW9)_k5h=kGv`1fIR=ygA6Z_XR^wKrBrx7ky~$72ECoA}-(f9a|c=`H_sV zDH^4yoKCmjz!Vn#P^TKikrbTRm1;0yC~VfmeS_;zk87Zj#< zinkl$;%gB2#j}JZ)u~T^9A^b-St&tz32d6iD*b)e@f`O*954(}EI|FAXx_n654l;-$*sGSng9CmKkv*xnneC>Xa3vr{hwhDJ%^99#vcpte=WBE2x$Bx zm|^#8zx-PqD=t)8F!i4(uZMDAHLk?~vU~%xRC@~{aq+4VXb7blo7Eu#se=OYZF!ze1CcC(a z!q)Mdxc-p@ZF};=H*_5;Hui_#~gPH;uFw6)2UX6;*V6&0ZG@wBWmdF@o&G}r9wDF8EOsZ#A&h-x_BXXWEXxOzJ z&*nx2gn}f6&bv`ETW^NS+|ldbRFS-LFnCJ|kG$9m#sA-X9MY7C>wVexWAtUi47 z+|wOPR(sKu$hpO~*@$y{HRzz_Oh#eJM^&C{Jd9Qbn-|6)Wn{hZGFg19XoC&ezt_$I*mMZQF z-bfH3U%@tT@xvysuj&|JN}Mf@Jrkt_yC|qjQ)1c%GeGKZZq)*?4ueJ@AyB=BQgtMg z%cq#^?}-ZWBUNv6a^l=+xMc5HCDs<&*%rtJ0-D204b%Md&mu+i3ckXoDw*80s5|=U<{x1tGeEfi5+1)FfPK-ZEJ&yKD z)oZ@Td)2<(HD;qQ-YRjq@9 zg&bVW<`7hIQKJ1lK*;itn8q$B&NWM@(ItDX44C}Y?uJafUX|Lqnxv`zbBL zLLQ6YLJ40t%9`XxnDju=O?|fE;ovDv)6FfCx>Z(HZkMI`q=LAf-Y`r9M6*4eF61(R z16HcGe?ZF+ALY1=*3aCi{iZgSW)*c6IoeX=`YwltK(h49A44;WegLyOnQ_d1S??y! z$R%pLEM%t{`0t{}?5WLznwG5xXSFTa30ykUS`V7w+7&9TUF(KsH!EZdya#WsyiVTv zIsBw^^EEFHRMK=eCz30`){97<;U?F9$d-n@hswcB`pq%o0|w=jiXuCTS@Y%@Myd3gLTVq#o zdA2b!P4d@6Kdyg%z7LHx5p&uDR4clVOLv7=bULY#la{kFdbzbiS)mAjTQ)B=#jP#M{(V}X@(UMzrv>qw zPhUO@i#HX%Tk*pv9OB8PLWSSkz1jm8#w6zVYy)g-ronLYzR!m=UH3tTtE(kKE&I9q z?P&88p!2y|Z?HbMPE#EO;?A$K7kDQ=fZe%`UXm`%%$(??Mz`s_7Fb$$Fe0t(J@zjM zq0L`(%%nZ2TMHuBBQ;cs!ga+>zmmTtIQOSoXoCPRP8vA2*I@QBkR1ZjJaL-uI6iV} zaAG#S#l`i_gKuMZX(U+n4_|_p_DBMH-n}=Kk0trk6mB3 z7K?H~6Gh^VY-mA=28vtdUD!u5Jo9HDb5h~(JSBHltlm=a?ss{ca2}ved=%_kIyKd@ z5wUqd!6Yu5;$sn}il7?#Tp&_e!8*tsuT1hoELA>0>u20bXxfolae*#C{p0G=edW5K ztxle!0U0(|zQ}P>u!DXg?-Zl^%V60Z`KNv}L<^F_?QOZj;PEf{O= zgyk?xD3eU<8<8wteS9$+c2n!0WS*uswVFlZ%TrVpp;VW}0!vZpfXXrZ5t27mFXsW7)sgc1)0_Mi1$IpB!yMQB8nn_i^4XHUqAYYlP4jg}u z4_47t>i6?FY)wOyn{DT0JlIq-|Cv{3%IMCwH3a%iyW{K5(OTNU@S(=d;9MP_viI8l z4(38fV44GhdSX^k)(d;It-ZO^Je5Ir$h8cN_~D~D2)MDVJghSfbNWc#A{C4ie@nfr zOh_JaookK&?-ttKdq_8>if8im=50yIyz;mE_?Fj3gN3O;_~CUUTz^l53UL9f7pCzp z*CvdSiwT|{Ia8(g^7>bW(h;9QJ+NpRY*8bU$>9|>h zXy|+g9m&M>iC)P|l<_TE?+Jfo^|kdp=yif*-Wq4m8YhwX3xj`$2AC)7-g_nOj~}Ch z2YZO8={mA%@hO>dx!IfLCAy|&W|cpa)70Zr(vypRrm4opq^79??Cg*M?UR}mCMq70 zv+aExd>oJ{feKKHP!b9XdCQ%~C#cD&#i->k#$?2(hYfUfb;V^2bb}3o^>jfvVthjM zAo4Iaq9QjuAUzGK9%7okFWtu3_s);KR#8rQmfKm}1-c>5$(Po!A|lqHBM@7QoQ5{c zSKwHQ+pBU~>p1|JXEf9_rR7xQPF6O@ z<~HZnyQay@+_$fB9!YMy9d32bohO;?4v(WLBZ(PD`^iitCP%aLXZ<*j{ycTSYv=6Q zG~yaBg!Vk6LIXmrA31K#Hp8=3p)lGznS;ag^UOi|isn}BHL~tzg)`Pk$+fei?w93d zUw|y9$i&1-;oz`FM=r8s<^2cjzIE)yjOH&^8fPhcN^4j%q|P#asvpE_E0LL}NVB!} zwPUsp!1nL8ZaVw3Ep_V>3WXl~>MI^4ZtS2shuv9skV~GBlDZqCx853&VSVmAu={&z zTwG94pAv1SJO9HC@h1uMuco43dh7ST#6QCMf2*7N*Zn~E(O>baPJ{kGsX6+;s<~gs zKdHHoxc&d2=2-t-&3%+`{Beu?5zQC=@IQPNUVE!Lc@3&Hb-yO}rg86?4 zzJGa_e^2E9ZaV&DHU6gnboym0{+p@zw{Dz2GWqnsm0SIdd6f7P{r9uLII2V zibV5d&B9W-d_3#&5+>&dyq&V=9}WA#yQy?pc%29S?=bXKU^rm>fT3adcHas zSzK5=OQ}qccD75dScwi~Sp!*3>}>?l(fUx2X&zu#Tzbo_c_{nSqFz`7Ly9 zK1?Nlz1fJJsCT|Hh(!Pe3jKqGeOnKb-;xN@dhW~(7&%DHU5je9u(RrG03ii+G`GAE zf~B9S-4VtW#JA2|y43X8(!tT#h=FDl)o>@1_!u%p0}D*P0rUf~08W1&+@+u9%U>}d z7$gLu9naw)X(?q53y1>)pIreE5vo4pVAx|=Y)K#@7#PWSzP=5})H^xMT@ewji|WGn z9|{H^3G=M!>oE`OZ{o}foyV}a?Ew2gKa7cm8N|yFyJ&_s$9JekpN(&0EHeTp#sw{u z%0!!B{uKP8Oc|S#AwqLgCs8z>LAmm?dvm8#wHcm(Pi-RnMQN5HB~}T)rvgzaw;yN6 zRU`aOBD#9$t(v)%pr%k=!?@|O1EP>|n1 zeg|IE{qCiUS9ILZ;7nAQQq%a$k;(MRg4}DSswIgIK0}3T0_Myp?f{*;4+f@18YP&2A~(Lc5K|@z z?#v1%GCjyUpEQL5HISLd3&@+pIm ztDD6t@*c1-ONAjrw@iSKy0F~5rT3ue&=v3{B-;R51LMQVk=$5*IpQ)3Xu*`fFI&_Q zt|LiUMqm%vPDI`5hw7P|bgyj?0=FYZFXy9Cfaw$RLlIuxxjw(ZoVLos)a=0De)2%= zdpl8#D1Mj2BRM9;yzY1AVChxFT=PC*iS5>M5IZAu@c=46d#{1(*;rvvv@jK2&MT`f z9#fFa(8L_}`$3J!k7=Q_*=UZJF3jz&~2|&LC(kQsFe#tkOutGOBqoGGg zrah_Jmh_~vzI%}O5>*rkAu3ZoB~9&(^&IX`qqmF-HRw1EhW);9W+g0HgiKXC2`cRw?HT5iGcY2%_ns6? zt^aV5DHaHGp{|&&1vXvQlEQw0a$OWhHsrt4Td?PTeGR-AX5DJ|Qb6^Mg712&Y!HN< zko5(lw(r{IWtg_=o>AWPc>kDj$m(IS$Wg78Q1TP5YF_$D3)!OE?);Jm(6W)qw1@`u z(OD~0MjNTHyx`(nB~bgtbp&aY<=NJP%gb$cAgE2!Y_Sde!Ohh zWxp*_hNgk+M7C4LtPIgo#8{{(H1C4# z@JAl1;ExQ)^FhQZ#%pS44^>PP%>h^5uQd>cKvuv|5ffxJI1B+S2*2kl^0T=gTbWmah1ak9udN@CcP+~Sg*JJ9DH1To}nHmX|s2BT(wuR<0?A3&4 zz{r#`Ppaqa*9Si3itC{ud@dU`G1E*B z^mIK83RtfQL01L-*>nnO+*%*9_?G@H(U%Z zJr3J+6=>5)>6`DE5oHK@&i>$3wG6tHJ4l3b(lE(vO5?pAKA5Id9Vi}c7U#`nt3mV@ zW}qdF=Lk(IT`>y6x2ZTi-?QnX1Vsg3dbJOXEDXwe2=w)P1T3~JFqrC8)r=XCPD>8fY9Xlfh?iWgmuVDjch46Q9T6oe2pBWc zBnd`XA=Y30m`B}?vG!d!P;njhm2pQ}N>|IML5}DJ^E0Tm9V&~Fb3i6j0H<9GDpU^_1((+@+T%;n{z)-<%`rFo=X8odskj1^Z75jm zFxcX!sX{`^c;b@kjF2!1S-a$$(LH{u*P>~blH5#pksNE;lJ5sXLfM2Unjq_rMGdEJ9Sj0Uy`<)X-gQ^?B+MesdP;FVzF)R zzW->6VZw<@UYJ7b-QeBs*!PdQS(16K4wY?+0T+R=hSU4D2zUXuF9HEq#`&x$$`Z`u z5>B%I@d^g%_OKt4v$=XVhxPo38ms&P9+Xb8PY1vkpgLQVs`T ztJ5=lo*Rhin*5LCAv5UNCDk>6ab?_!T?tD`OJQzqA@e7vi#aP1X6heUZ-X`%=K|Yf zR{?c;pRdOoV@$qS+pw4J+Hqk3zyK(?wwy4&DUM<+GgD9x!A72MB|2Bn-*suMHnLy~ zp_uZC#ierbTRvaof^furidcV_zux!0A3p66%W6?#f9)J|euvC^=$X7QK%I^z`S#Xn zxXFi{p&+}E5~p+OHF+L|UGGvMlJ5*x?lhhOXB20MvtfL+aZY}4nFY7}j2VX38YBXxyVBWD z5uOFQiR4ckqO`THu5R6=&7oXIG<3*MxgL&}yD{MKB^`A%sezxb2VjE%g2udFTFO)m zReL|>8Bhj{sEC85V1ZNU3BzkdFq(1!AQh;olL#aDa*KA2%_C(}Qqv5!!Wa=<@P;5~ zBAs!5p7`8mZVB=5y@Ai3d_fGbwvul&22!$fwpxSuTa;?EpLF=VNzJ}~nn%GUJ^bc! z@{?BIW3#KKQ$uJxhcL8Q3MGN^H>9gdA9q7B|RTmt!_D%^K5pbe5@U|HsQYNq0p#)@k)GcUU`40 zE^B>r9daRRxfTsi=TP-KzX6AAWV8Xf zv1~t;-GwRZk~{iBIx4mYl?;&P{!B8k7m$=2*@b<;Wz4qbp!JHKZaf(NEn*F1g!xi5 z-VWrO=(`(aWrCNY?WSL#pCQo~?1~JvBZ%`K2&xc}3YuG&a77QiF5}jIllp9ev1m?W z;p!1o8qlR|G!*W6?`gcl=FBCAq!uaK(Aan~nd1SX#NTcS7bQA^vPl7;bBad9qPQ3u zrkkn}7S8zfgb+@&BryY>V7CKP$L68E_*B^3U7Q~;;E`@Opq;2z|2{MN)k^r^%uxT< zjs1IWp5-Gp&-9U)|5d}v#Qq-~08H$EaRB@}{xLK9b^6aUBl?d|{+gQqRsHyXsdM~i znd3hvM!z!hf7ChtE&BdPljB!Q$B%&eKf~z%=x+Q=b0a<7Z(Xc^9uxhkef7Ve(K0fz zvHxXE1g?mr(o&h5Q-;(iNC`Nl*obZ$@|oFu)s882s<;cdtEnyuPq%J`np0}V;dSjq z3Q($!jC!!p7X+D4lTLV`XbR3gR@XhQSI{8bxZk{a*U^P+;oz z-SPeW`Rx8ZsW3f*EVZy;ou{L2Z|OaiDzc~#TzZQV0h(noa*;tx*B?ljtx+27`Z#Rx z3g8MeqOD&RAyvD^xU7*t7#X#Ol8cXL&Mnn_-WT|KMa?QcMyoEbf_%zh~=C7K!<=y}*s% zJ(0YvXP(;2M5W1wzqenoQ%Nl5O^$E);3w;z>vVM;DniAss%tleQ5%ZD95%-bQaFDvN)km0oeO5IzPgpju_;MCaoX-^w zi!AVER_1voC}Z80gW6R|p5n1@Y2wj;gegg<;5k_>Jhpk*xcZ&l^0az*(;&#XrDL-c zZIdC_Cf|BTM+7*EgJs$5W+aa_avWFdJ^t<`72|f+Y{*Max4v23>?WuTp#~b+j-uq7 zIR;Kp(x+o$=qcpygT1iHJs{iE9rF~>^HzSk!M+jI13&s179{kFEPs;KF#;-I)NIiN z8gg}H8VbfJ+j=rbWG*Y)u^Y9tNe%*OSxaNU;JW-Qyn!7814Xc=|1N+$%g2c|S)**+ zir)$@DXULLhjf>1W?jtxgs-g`4Z|_nG63Wo8)bw6Ws(hFKDi6F1Vkaq*}VmE2^1u} z2};AJ!f{0YdYohkox3Xe<%lnb8^M;P<%grmdVkLbgf?buH)K@4i%Xycm3@t1om3!Z z3Z2zBM(m4sj$eL5H@L_Z^YRM|`jtTkr`PLt$ClEHOZl6#OzeFkh^#qeY5SB(PFhuV zb{fJB+UqDeGF;_i6%D2NphbJl)yY;!T_L>t+WDA!cs~C9Inm9HMUQClj(S54b89jq;IhZhVN}Y1rV? z9cCn==J8Lqlg26=`1I1a5R)4y@%LxQ#}p7L`X*Gr9J-BQ1}oa;L(q;`4l+X+jB$Rz z=J75*x1XUnm!sQr@+p10|quP;6b4&C<1((QT<}LPE=QFwNBuL zhByxz*0P?($d7bioX0d9MxAjAPw8|T;F9~;jh}uZ&wdpm_?EYZg|UB&SV(`$9H9HW zbw2|iad7U%OMB%)3bWH7AnL)du^O^^J^6V6+N7McG;Jld1>8$y8^)j2I!H-yHmAjr zeg%mWAVKd(?A9m=#gciNb%D$}!gd)k%W^|-9oV-BWw`0OM{ie+FY3-N^iA8uE+Cna zezs((J~{$6gcHxET>9bBSp|WsRD6Z~SLF8ez~!Ks&WH&)cHb|yK?e)GFcOu9paj>5 zeLUBP}PR?gn_>oY<;?eLy%esQPsj`28ohfb7EXGM?dr(Mf>17dgPDj}ctrqP%z zuz2iE@Pt1XzyrbwJ`6qz4Eq{7r}9ehQ9v86dW`GNQroYM7CoFFg1DWq&)O=ooj8jfHI(^RURDA}~NJhC(Oq;DDGSMr? zY{(WDswe&#gGU+T$lQn}E6A6-UO54nP^n>Tx#zd0fH-06KducIPtS2+D*Gz&iP2=98Gmcv6zmJ$O@&E^mB z?|IuR;`tB3mDaRNQ4LxrmPvTv-;&D2&DIxSPWBggTC9{BMOcTAV6hp`g51gceKjkh z3jz#TDu~L;a~D;W6Xdbc5h}x#E~Y@8(FuJ#ED9#vH}b;+5d2=Kz_PnJ=BoH!XP=ADLg>-Y$5Tw7U&0 zSf(JqN2Jx}?rRzt2~?;ltC$hp)V+#AXnRt!NX2lQM2p()WO3Q?4VJDQws}V*wZ0k0 z0=}D&9L~bY5T}6$C5;{k9ES-~6kpE+j^Oqeh9FLIpLx!qs{Dk!Tkqvm9p7FyN#}~2 z_&`_sGfrNl@!>Nv-XUR-w11KU-!(hUfdi!6)Cy)pvSn)0(15hmIXoTaCmWWB#HgS$ zxy|e)y8s+B8Y@`E&l z@-=@N!0FW>GHqc?5U`_6B*aZnWF>c>Pvc;Dq-_e218@>P=}TPadGj?VtRpZMnaqqn zYJDj#imw=tY&(X(5&!bqq~U8E45(RAN`Ws|A};!!?0!L6?e5wIZJpO?{Bdiez6dtB z0N2|9MnR{Fl8XwlAly${UnvvxATHxzMmnVF+h8dZhgD)?ls2-HwZNL&&$Alc91%r1 zUWw?F!ARv>RI#90Ei>WMfCqtNUBcsb*GsI&c-R=OG}KXF9!%AGypx2@jBs&UBouTA zj1gB49JJC%r-~i*M1C>(2qo3?cHdAIpfO&lPiHD!B!PEj4N~F^>HH!RKqNuo;**GsPARf z*f734{(YWMdMuNrWD;dz?cmPYkH)spW%scJ3;L+OV#<0&P_Nx=Cuzy>E4+DiD#R?L zD;lf3Sq`|7jy0kqligP!JHRN@2cZF_nxa8KPT3Jl32F3MD!t;Iw^~m#Uol$zrG4rt zk{_E3fDTze%)1PSXy;j@MR&lF-G(ptw{Y@P6ZZD|$-WCAH6xNV4QZr^t{Dg8Ef@!X zhm~ZN63~|hwdppE%fVD1oP(Bf5^kRfNfv9ckybduux(3V3C%&U<+|LDRkwGm^5M!w z+5#db>at$6m{2LAlnGKD1jrysX!@Fm=_JIR$}mlRwFb*10IbH>M)PTFFf!Oz(5+Xl z__G4i6gvro4O3^;aJy8D-ul z=#>!2_~!(L^zYLgCkkQ%*Ylgbnw_h)1x6Ov#?EoW z$q;7c;t6SQX{*#<1&fhRX7CN;1)ZxS!Q+ZOUhozVf-pi{fJ)e2uF_d`Hrlp-+5+P) zmArzft4&#%TI$^$u*6*D>CRj$9IJxJ@ZT8r<|gq7oqf65Lfdn9)&q3q;zJdL3nSbm zUc`L|Xc!pEJk{jny0bbq(-?bA!>D-A>(7bl3y&R}WBtN9bDAXkbt0*k7bH5wuWS-y z_O57;*8u1ctb?cQ%|TQ}wV|`ALt3pxCXEoRxi)pggu3E~QwC%*DJ0&rXY)6M8@J6; zYPf!yHsK|-09DjQZkSGwbv9n##Z4R)M(=l7ilnG?cD)h8vJqCU5m?$ z8bi*xTxdFnE-<&Z$S5mNm6oUS#i0|&#L3vWx!As{kG8kb2U}c!Ar7- zM+b+rj}BQd>D3JFd;py3&?6G=yj`?@W-k+9n{z^vocfsd{xq`&(eeSYr^??xJ4-@F;zP;HMY0-(eAcIo4Dco}hOW@Y^S|p;A2mTTHbBpr;a0(J0 zfl6bq6}cL=Smxo3#UvjoCV)~?4FbtgG3*pHD8H$pm78`9 zVM86mi&NOMb8JzL%ey04MF>j3v3`E&&v=t)XRYiKK!Lt*yQ6UWc3-cS1IPVQ36j!yeCeg(+#G#95K#+Zaw8Cgbb6Omt&e&KZ_!TLx1%Ov z-yEntbU+Jmil(O60i#YL=@F(XJb@*~AZQJ20tO=|)>XuWi|YBZX3p;tk=@$62cw_9 zxw3@swxZa_ux*0^UL+R@MlF9gLDozx5DC3u@jTlu3nEs*#j*>9#1Z#IAti@Da4>@j z`A$jwhbA9K&FiP|7tRCscv`-`!K~vSkDo^;dCo>u5w#@&$+5A-RK zE+{S}AG^E^K4!hKGLd7LdoIaJWg%q{Z8@w+SN^c>1DTIk5``nd#qqi;bC$-akna(YuB~kCb4y=d(66T5MQn6@tEy8l9^e3Mhege1W6l*;FS^ub;fc zrY|V76ddy*m8arae?wgUqi6r0u*?6}E&q4w&|mx&9~=!9_W$6o__+9It^C{Z53Nl1 zKl>~G?w0>>T>MKbtA4-@eg`pr&XMy{tulnB$+z)EVpM4Ms zvBx$Fj%WiDYK>=~Mvz1apP(ntS@bb_FbX|j+XVA=!7PM4tXhd^4Ps75(CIVI&>d>RysLB@D_$!t9{nq&)0v)TNt>QQ(g z%d@bQt9@PJH?v$N1uIkLMGmMZ(q;9qq2+bsYBLJzZ+>IpdT4rIOf4*U)VF?AH`Xwe zgRDd;>8o2J8+RoRRo1v$;&dj~5t}I2@X=?rvfpP2tzLjDHwAzBNiUYvW_vELu9=lP zQ--t7x*@jy&H8qOj5CKp)M)n{2Ozh>grwJ2GdYhT$43l}NEq99t>k_lt4a6epehT8 z8;kTEPOLHumXDXZDQ-Xtr>-?>l}2k^tTe4~IMF9#?b4wuC^ z($X?Iw5<}&e+w%MEH-9z$EMK-4ydqT&ggVXff|{5_pA4!`-=OuyfGCHDI}`B=Xw+$ zNtnrn#Zo?he%~C0VrVIdz5(JsjXS11q$ZSZa_~0*?XZx~jAs4@KEily(g*o@mfjF` z3Ld(^tO6^X`2=Risi(y#Y+g`o%>D|5`v8KXKLdea&*^9Bvx~wfFI+lMIWp))SD{*# z31;^H`r?!(=K91=O4&=w2|NT&j8~?i zE8lR&YMHai;C3=1VP?l64H_rn@%vOmba?F>h0onk87iFtJWEZN0wz%F6;6Q^H7KSd zoo7(THvEpJ*7@MoEd+@)(iG{-r^V5FZ4n=qm;-&#=T%y%j2@0HB^;|prnrP5(wP#L znZhql!3E;Z!0hO`cLN1?U2{Z|p`@<2F2!yoLIDGSU*&0=;r^aW?011ggEL;5$r0k> zr%gNJ#5q)POvz>3-?&p~aTxDARQ75@6E}SYT-Q2ux(r}`j|c_;L^}@plYkjCDVZIw z+ZH`bqJLlcjvsYlq#m>lizquQ%C77EyBtx(I{}Vz@Oe%!1v((#S3cJIi`d!~;O|)6 zV#p0ebvF40VxQ};#KlN=OcFP=_-H1mrI4v4L?9vPPIMT(o#g*MJN*q<_TLOo|BgNT z=L6vvs`djD_^0Q=$ItvfP&ohB=KSLbzTi56xbeuntaja?oR3iF^ z|L#v!pZ}!e{PofE8zSn@kDgx_{?`^f1~xjjKh0LH62WB^_E83Gz*aRsvu;&LoVI_j z=dnvz*Pz@@@W0(X61Yks&?W*qFSFnW;I@5nUSFbEr zQ+Yb$TzNf};!J4j&NwDX@@U-goN@i0@y@=14A;Qo&x;2)1`7e5acKVd41V9?oo3qO zfhUNQ{-)%OZHGi4vT_&FbDF`+h>;i$lqBabi+2I3$*q%`OcE9u9?L0{@?LT+DKpVL z&U1;Nb`y9DKF)W%D;N84Yv&2Sk43NsM;%i%_Vq3#%pRtJE9L}?N-S{@DK^3{XJ29) zQDFxm#Xj00PcV@et``&>)7QN~VoxHGCXQGnsFx;dm&GmeSu^S|lZJ7@5TRFI|1-Vc zL$a!H6I>kFm+pjQF@Lxm!B6yQU_`6n^z?z*A@{*Gy=?ki^uEcw;RNZyw88a2Jr*RE zA(C5dcxo4m{e6XeY?@7Ciw2xa4TEQdt(JBWW=Iim1#&&bL`Or_@p|od>vssxMKE#L zNHD@dBbwV_mGCLq14!m}-z)=VuT?K6e)dJ=aLSE=^e2r*=QKT_D30OuavzsdekCl^ zkaY`!GO9k-#V6-^IJr7AAT2GBKrde<`_^7HS8Mas`phu2PkBF~frOKhI(%U}NAj>l z)MOaA!-L-l4&_A$a>qB%!i>n;MfhjA}3T0G_ZwRzpJ}i+7!l;;xx4Pr70hO{h z$7Ks+Y#(HXCbe!26&ezJn>8#=pw}FKX2tat>sB@?akZBpgi=%qA~#VpFa{$6EyAcpXl)U819kP;18TS37w>nV_GMtk}Rn$q_C++p6&4 zeetSmkniZ(08}QeMdzbEn4ZyE{G@YnZWQKnPE9x*Sf`K;N6WzHDmDqJ`S?uv#;?+& ziTbFRc1n2>E$P7@Xy%gxegb2J<$1R_RCR9bKGP|1a|8QV@SVO1e0b@|*|H5?*7RV?x^v#Gd7X!M! zBJjimhZ402IIvd#T3RmXn+B7gRk?PPk6T+gWpM*YAOBUvmkgRzycHx93`$R!fo$Kz zB(gB00&rrTqe*8)36lYv#?tM$(3ISpibHIH1jaC`Lecedib=X-jQJeJb(pLXZbB{X z{4cUKTW^&w$7+-$mdi-nEhPCzrQzh|E1C)Z#bo)iwF*M$qVw8n8s8-b9E36_zvDv~ zJFatF;YzahCf3?~-*DLjiZ$_cueuX}W%a?Cy^BF6TinFqdcn>YDL>*N=$l}Vu+k9E zQ%sE|NMI@aUeCF|Ozn;Dm0hqVq|;gI%}h%i>z-J#7Q(^8u62w2zQc+F## zpy93msMpP7LDo9&TRWg3idEV~Js3oaI+9Uik2hVF{`=!A2(ibXAp&ys;3>Vc} zy|~vZt(mbdJJ?Ak6K7oBF{3|SwkN)=U@!>s^QfcC@N-tq|Xxb*q zwSH@xx7sYNdJ$M!kk>s{8=?N1ZDWQ@l*)Rs{%sU|6K3tTszKqv?Wp!VO4T15wel{^ zOc|XjNU5yRirkokgC<*C@YR8dfs2Qcf<7QZD%OmExhstkUOc)oB-8>GefLnEv>Xm>9(BiK*7#;>fF zIoGw(Amk;*YkI!yZHLdw$$S=a(5I^|91sg#MTl1_G%#V_oNC2v$n4T4 zg1fN6nDo+qrCEI90q%;^`2jE5$YY6!l86I8?#;L^0h%45B_3BOsnPEx(T}WT{?P`c z$kVZZGUc_wRx@Z4>2>k4;L7y1Rnix5PoXU==$fXVhm8({l)zG;L^fQms_H3`JV1*M z+g-{8%2A^+*L=9!ud7ki(F$W&M3G5c%xED@UT#>LuoO3yxOxuA!c`k$RrRenSz6>(fFzV2itmKo*ptR&aA3wW?(=Z_k(z}vx(2x<@QrMC^}b(|DF2f z_AV!C3+~RVbV|YAo0KX|3@kU%Lgyvul^3^KgZ_&nF;!p2>Kn^`R_D@Kl?oXJsd@I8n59p8z%vbQ6$e~bdH1AXXy}#kKsPUepgy^{ygIKb^ECBuu z%4fB&$b7s=$U^xC6fV{;Tj%dq#ftK6#tj6b;3-voA>I84i`Ok76U29_uiwkgbn zlD8=)=q4sbC#aQE_(QhXwB{!xtCO?k47_-&Is{N4E6{dqs2^lpvhG&db>!C6xVYEmg9?e20HO8)s zPw5Ufo@X3ME*S+eW@ijq8Z6h{W0*<)3^ni);u^V`k~zw23}-OGHNi&bk=!Mzvj<#= zJCg;j>ucDKW`dy*SP-unU$BpG?NQs369$I!{*^pSbzm=tN zxjL2E!QFYHGct}#)h?rroXcNz2q}IV8^Qh_m^_* zzN{FsZB=T%0AIT#@V`zwO(#(STc>vmrKwdRQ7(ZDc9Nddl4~;C>oQUSP)jn~dG4Nw z1Pam`xzQgNNTm}CK7@cGd3eTjevLQ_!L;0JlTTsGvx3h`EE)<8K%30Z?~ALxn>dN{ zC2W)g9gkWw;`-cI4Qaj^99UOl{S+-<>?28+Y_Bmnj#GwIG(=X1G0k@jSB>Kf^yRK$ z>Qm7NH^wQECd4R-Pd@P*sz_?DCeCwg8aLRaghSfbM0}0%t!EasB@??#sTcn$j+tbu znHdFlCiSmH8kK&$PhbtgX}F-9)dESWg-%3fcm6%TvjBA7Lpin5IvxIQkhnpayGjATy$MhnCK}ZEl)zA|;?43HV0gJraEeAiZPIhBH~JN#$(3?d zqJZWsrN9ZT9&ZafdK8)KtZ$iEEW?i0$?B79D$(#E+%JnGoC>VuV))0Ufdw}epy8l7 zsUZ2_Fru4krGdu8G{(3aTy|%gU5Q2jA&+?}AOAuRrUzf?$?kXrTOP>TuLa%_osgOKza0zgl+fLB{nz`M~gsZUbosWf7Q`NAM$Sm3Ky zVnMb@Fz**T3FU}zGradnI_?ipJbA}`h>bhRODv%>1)wHEbD2CmkI4WFUaZJvo_Rap z&1wQ45IZ=C-QkC?8ftyw$5=JtZZ-7+FS8BfNbr9u`|7x=y5`>p2^FLSK^l?Ha}FnI z>6R`*y1N^sQ;Dj% zOcTb!MV1$hhGPc5gP!U!spkd5{k)15;>h?nh{*)wVS29f3K_Kbr|WVUEi2z`5qv-w zyLa=6xwDdAC7ixhtnOVSIK6>h8{aL!M1@k?wK1UIbtx0e+r5G!>d_ableUKODY#!9{pOk&YqP}I%^9SX@HouxWu6uZ}@zT-Axs9C85KcB7hgP-R(f`@6ts_9I*Sw>0PaM;hkL=ppIm-Y@9fY4Oab+aqFV5Jp(U0_qQmrQ%K zJW;k2MTyfx+!%L0I+cjqrR1Vm|ESpp-#lvj^-UsQleO{41#a&lyL~M2lJ_B=t8v}x z?uP$YjUM$a-f1_q>S#{+oIT@JdC&f?ocX*aB^?Y8=7m~%!$QnlXFc}Aa_!X6VJ~+q zm7h~bfsYuj#qpW0A4GqbEFeaYy3x=dF=C>(Po3#>qov)mB&zGsQv~&0D^|aCRdx)Jsfckmfp196?+v3C=@pNvVpQ+Uj

QXMX1i#1W|3zalW zNBgAi+L_IblbfBtLqvApE%ds$Cr!IFC_fwPbzK8AZ|go$4mjsabZOkbkI91`Q&Wq! zE}qJ;%(~9RAAyiuaK&6E_USV_Sg@c1o#OJ2#3|9HDyw!TsUWRx)>(+opWNB1coa~U*s2cTk?zd{^ki{f!0-5G}O}PxuQC2@s zr{#uCPXpH=&G_@0s`BR-PI6l0?e;+ThaKl)noqDq4ERsL zUU~Iq#uH|++z?<<=M)@F9`94nGzWdSytb&2;N5cB>Xf==Y@%Bzu9cg|&|ZnYf>-O# znpF|UvqrEM)r>WJ@K6j0{6z{BJ^}2K``s!Sm zaU{i}txfGuW6(**oe*2g`?!(>==+v89_!cKdt|4fkIs_e50^TdXosfo{<;koda(6| zWUKUy!0PpT7RU_&E{;B#mH7eByfaTRR`pA1+c6WN*V=sapEu&o`@HD<^*FZR!~y6^ zgY*p&wPTKf9N7>eZeqRRRTc8DM|GcwtGR}$yCvy9E^y?(FLEna+5Grzp+bqwr7l=x zW2str zytJWhyo?e<*RcVwF4604(x;Dic9n_D&6x|oJTL-lzSz91)8u6iitx$VGiQFo$4ZB* zWR#Ts;gnS@cw3fzY;U--d>rR&&!6(Qm{u+}lqSIOXU(`Y$rY{H+ZM zEo+U5;g$Ii*JW$}vryj+iYLnEf_scqz7s#*X&gN3Ecb=4&arSHIp|lTSDiGA8+DGF z2Rjft;+A;4#@FSr&)GC^)_Ep&vggA~{vS*|lE2_Y5ka5qUPgXOS zyf)EBfiUIe>s{i8z=FAof@D#m>aJvOk-Q2PlcA;Wxgt2+W)7@V6rJ=hSrF+d+3$su zKQ1!jUg@p_n&mvyp7JWkHAqZNJ!eb^3$OxB)A)Q>PcIp?^ctt}5CTDhSbK<}W?$)O zNn$I^*L!~Ge%O|JS@bjJKAE0f-n3kC?b~0%)<#FAxQhtDF7sZ;@KTKT%E=>(y@O|t zxrn4qJ|z!P3HOBGQbmilx;K6MjE)JjEuF#Ui|Z{PXkYJ|e42@0lYLl*PM2k%?DB3Q z@GEJ+)ZAE4LuZ_V=<#p(*0xg9{jKFV@v<{wab99k67eVE%MuAe%`Ti!t*jk_?tLrY0Zr>23ql^v{>hM^_@^5ZO2C*MHbg2a5~zWhm~&O@J{@w>vabtCn@x;1(y z6>iiRoR?MWY|AWT$eb2_!+E{RvLX!f}n+OAmS63+d zRV&9T6H_b%3wXKXZPp^!%RBp&Wz41%oYH zZs(%mM{ZH*tg)tED#2k(!3YC@T$_X*!|`@oB9TIZQ~Uc=*~(mX7{M|dTF;y{Dw#&uRp9$n%O6!R!+y` z@mi?zC7)+4XNh52OU909S1pTg(+<1$i*zQB%3CwrD41g7vWR#h3;t>t@3#GG&(AEw z*_>N?+KGsdn@f*=w%XDNR`kg8b?(_NO}=?`*6PprO8@4ZyEu2A4bSuKRp?~QEH{(v zbOj93R8*ojxc~MOiA9Na0grI;)x!JIMsU~rBl5MSx zsl2G!n8io-KRCD)oJO>rnA@ge&9#h?=O6oM`0}%yHaiv9LvIpg2B!4~n!M3HtAeSf zwnz!d2^2_16w(snVxBq8BFYo16slJ*zmiOa_=@09R~yf-UcJp?3n8p?f4wTV-S7xj^MPove(7vl+O)I)E~8`a zE|=x&6ZqPU=Q!reQ+Qux{K6snuiwAp(F*Lg!;j2#!lSA_>}ytloINBB*e}hU^S3S| z9Ihgto~PBkvm99`I*4BqTk^KYoOf%!p2X3GyD$sBEWOWdDnBS2K2!Y+Ax0YzW=Nok zkqvvd=V?TU=f12dZUygVtW~nSXi=?Uu4rgZY8~jtNaGZcqNS;@-ChX69o68%g$ORB zt*kzxN?Tz{P0PtxS&d_=%GjbXz;A50-(z&UQjvPnA!-av)2V z-Wm+aNX1wYb`H@X-nXCAOrCwy8~ie3M_!;)o*7Y(%UOn7?_?S9GZVe4V7%qAMy=pg zree~I_uZO(5u4=bhnWUfaaFSQ0%)2Qo(F$jK0Dnw&0g*7w{J}EHJu=)Dx#VDWg0`} z_2#pu1M!|RwLnjO`K9*uu;C@wP`QJo^1|-|xziv~&QEkz<<*R)gS;gYjE@<}q_@Jt zRSa&$@bPE{d574yW?s!XZxrneNmsdIaL&t%(pvW=hTd_h9O zQp8I-5X7bR7j$TWWSMGl@$e|%lT#t+%Q4AYijsOJ(zlC50&F2GUsIpI4_8oF7s1_> zt7VsamaBC3*mmO{E+%4kdG|X|H-`!%L?C=YlolJr7%A)j9#3k1WaM6dO{+eMog2dm zpToYnJ;P>t`Hoy~Eeyx)!JGAgLohij9WRe$(rJ(LmN)Ch*^Ce2Grz~{y@!r(J2^)x zkF)i815BfP_n|l6KbACl5tlg5MG7En*5VO{4F_I@_kuDd<4&%iBersTlp6gpHq5%g zpsmZbI3`lB4~yY}lfr2}y;4z;OcXfSTe_bV%e3->1PE9&wf zfv*p#Q+E40p1CD6k+;^AMrzv@;gH~^L_)h)EZQPk4ek-~lct|kM{q3)QTqENOH5j} zNeyQF?xAfJd>X+&D>&p;6no(GZ1Vw|2>DeQIU}v$~a@>gG7w{wW=u73Fdl z6VJjw)EIxyHr08Cd!Q5FH@r=(OQTJ_L_tVN55YWMu3%Y9@lV$oZGU~s7p=X1!)wVa zuKZJ350tY`!L{Q6{is&srK05iIHv$a!F5LWQHWWx$FkuG;E#xK6Nue=5G!RmMN!n@3GJS#H< z*Su}=@p(5@Hi*9QEjyD!SZ?Oq;ynRH37NDgyid3cWTBvrtWt`>iSf_k>JO)_S*ULk zs}HU&imsW)Y0@`Dv20=+&s;A)GiX| zwzV$BGpMWYx3#63w%@PvyIt=1MM7U!q|m8RHO7u*175g2R1drvoSpKK=+BDuK2rT1 zG(8=kEbY;wa=Q2PtW`xTd`jR)5F{z4zP%E{igtnDwp~{T1^}M z&xf@C(_Z>tO{MRIRQ~6)+CPcLc3k$zWMjuaHQ4?u_lwIJSx?XHKh|P{qsB%45dOd8 zB47jn@VB@~n#My7;)%qPs+>X<(Hssm$gk>%@JxfphuVq&MLSXj3e3PanY4v(usJ^b z@~)jCBs3y|RpAvX7^p0g6ESfDdyL!%Ifg}v7DrR*l4Ms%%pU6=m^8jG6);N%tpR;@OmHV1+c6+Y|XERg}Pf%-%|6@G}A~suQu}y z`Cxk^anNS6@poYp5O=udKs87?dH6ea=UaONHBbaH+M!|c9=ph2-x{v7zz8`QVpR41$3HPc0cE--|!*Ec^cWv(5^g zXKqrtdZm{?U(PqNT{@fuu^fX?y0-~mTDBlI*hy1Nd4oZX3*Nh@eH*7?%k+I*m!2nr zQ%!vZdT)NcNkp5&|B2`}8G5)$Ha?M1(t8=O`sgOsbxG%(|7t=6`LD@dA-g@U;jv|D zurwCNemZTNJ^V2j_JKSFU#lf?kIlXjxhBR>vwdnjB4P?>Q7q)=Sdl@^PVxb=6a1}a z?UqGjr3cO1M^tb%0@9>za^C3fjv;x|*Pd{~#b=LB7<1bR4JS^k^6Q*>9Q`7OnKvSt zOO~C~(^?h;JRki62IT(la*XM+}!Oc2(IcEQz zl8{r(bDZg39bGLuN~k#91lEmI@lFSPAJ6-g#KmeA&%tr8R6m-WD`jI1k83TO9NvP9 zt{MN!#Efu^?*^ z0RQwtEhJzV^M214nbhvC?H^r2kH39^o=6(2nvYty8W+<>tc>b7wC^m?r$&}iOK{fd z!M4J<*N8?`7Irob8~mPIG}{;NqT#)0tdh)~DXqGwJoTTe2HZrR;iL&$iN8wE4h^Y% zq7{n8`}i4}uOiwomPj(EQf_X`Z#w$yf#C*li@900q*$3ffo&vr&}WKBh0ZYln2zw0 zt{UEh(Gx$Nhf9>*-5snkljL>C=9jsGZ^S+LF}S@`0P%K_LakF~L;g_zEQ}8(EMm1C zkz)Rk<$T=qj+np>d#E%aTZa!H$$~-E?|Jr*h)sURJVnC6=gL!O=J*e4wIsUkb@x-CX=tmQMKp;>qpUh6$Es}ZFQ=rK!3a0>|5 zF;7$-E;IeDSECV~!H1VN^5XULQr@@ET#V*_*`L8uopaIe=Skw(uZBH-S2KEVmt-t2 zV$Ph^IxE9`T9ZV(mQ1b9V}R^|NcdL^=HiYoY|iJb=8b>mH$qq?0!bKor15d zDOdbW>&GlT1>X`qQ#}sn>3SuI?CJ5^ zqtBjQixP2);84D?k_rb3JbSo^yFmYf4 z@U4lzaCD)T!-~lelx-%17oTemw`fR4Oyq9Ms&*CWl9eY%J=GVga~&INkUQ@DJhIV- zi+kSn*X5hA$)^E1vNLWUhM~@^9eWc^bUW;}Zqb2ReUByxQm^`r-Vl%d-bBOb z)lX=3wRkDoPEGJ>ySrXnRBV#+ykLhWJT?SAv>iTG@$*$3EX{o5v z!f6{j3yp;4;%oX>_W0;&e|0Kd@k4_naP0sg)j*z&C5xF^j@035SugZLCi6hFd0VCF z@(Pai-V@#|e*WO{LH!4DMN2DSr7)FFL$>t58HT1`&b^T)5x)k3p5pHB7~WMDNl*ld z0b*`?vaPF7n&N}MmI*IGXS7CM=fLRC*lH_&l@!KY!kOAiOE{VQrqvT3X>N!o5B^7zIEMV9pBu!1)3!|{9LM$NTm>n&%|Pf zMd`vqe~ozY<%u$fPmEOIS$Ik2XbQ=zDbt{lnbY5SW7|qlJ`pwwt=s{;j2O-4*M&lb zG%8pkKjj}RUlqDg@~Wv$+nMwOxhCW+e`Trkl2qvRQ1~*N5l1C0%BUuuCEJge zSyNF4)<>diB7Pc|2X_gCOIQ3A{pk(F=)o85iD{30Z{~LjHTFW`uWH^H4=TQ=n`a|_ zIy0c@H4)8aARDvuhG+bL>fvVC<29Ho& zg`i#hfoY7NP!L&Y|L53khW(A;`Pv^ZT^)NpSAM*D*cUSJ;ok7`R$C}j!3g$<9?UN0 z9eEBT2uc!*XYyfQC_lXS*3U`VvfG>)t>iHidX)97B88UI(HF?tRKJgo7MHf)G%Gh9`aZbCynK%-hVNLO(sE8b=e5RK}#^yPKA7|&! z&*S6WD_%p?e})sCFqwq>I(14$y=BwrGdWY|UN@ERDf-#FP1=SV`NYCnteeCbla!c> z;1;=WW%X8|H# z!F=kYa4upg^|yCLb#Jqmf69%Ky@k~=(}S!qwOMi#g`u$euJ~CIrp>{ju%m?dBQ)`_ zbUyo-MfZhokBY!m?^EXC^@XreGmo;~D87AGU%I@`K^S~;;v2NOrbpXxvF2sQ@mW(! zacRW`Uu!gVzxfx%S>mqnQ8&U zFG7qG7HEycoAiDy+Kex!$W9>&#>ep|_$93|cvIcUICvCpI!Wa_Hf(eQj_<7q?pg?R z#vBa9%QH9!#a`R}rR#y<+clIFIDdM$PIaQY>-2o!rVz`J-$!=ib_4ISbr>@(Zcg6EDwNFKtUNL~H5}*PugMUk*(IQGmxLH6S90Zwin^cB0JU5h z$l8zRQk=-rIvt+=bnWvwbK;~crqfbg+Ilh*{?w1k)X8BHMO9Q`m)ZI^9=-vBRzYt+ z_y1}e`ci1?;?Xfdf!*d(7^e)CwW!2y&r+TElB=fpb z^t+mO|KX>T6ocVk=JVyh*UYL)S_K^K2zX=`DW0EP$IoF4+^VFh#4ojF9AHQ)a6wvq zm{$RT4d3?A7t3Nbw$pAhyZGcse`NEds2YF2zoS+>r+sXq#=`z1W{VzVvL;IT^mKSt z*iiXBD|PNc++>*YW4e0SSh^5a?vqq$^=m($a?pMzWs?MY@kh9k?+djP^~WLp$FGCI z({-hgASp%8H(uU8y|XGqyT2||vWn5mNpSt?e$JQR`w>jn*=7Wkd{x=_8HP(nN<)F6 zqLYBsDs3dCVJX{cLS z{ybZ{+9f`9VoPz!Yn^1->+=14v-8H6>fNBgz76H}Qsp?4cIEGu_#+{^-~l3WjuUBR2#clxM=DR;B~8iG3f4w&&WEM=L)~0 zBA?}zzB$y4+0zsgS2p$t%O}RpA)c~%FmC%sXzvYeilG%|YM`MOsMIon!~O|O!;8td z7I}-SPL{xn(SDAxytB(EXpPJ7sE&cwS(m&XvN}Ev z6Bz};<;uC&*sjKTQB(yprdT^Jo0;x5ei7QF1!4I6GLqTr^=+K;se>admHj_@vc#@& zy>d!sFX*?0FGq(8_MTiwQ3-Ucum~&*vNpKm**Jb2Xpmi9hk5qQd9i()s8msDaP;YK zY!Fx79wtI0GP~-1^u6m6gZZA-@*hEq`$mQ_bIN52bYzP58Syf)#oT{B zD-mM4i2=Mw&4*_WK8gT7bzvyzj@Gf&G%Jf?HL=Yv_x|O5;Iew&^Wgx^dpwNklTh<1 zM=i`J%p-qzXhZQG_)LgPdjrr5(9%A3U-kR~D+ogY0^C+i+c6k<{`N=V=G2Gzx~od5iuJ~2q04PQx2cl>Dj3>|MpW3*`oulNY^I1#nknYXW5HvDai8p zU2JyBR|l}QXEjyIW3guy6kNoPI+&ux`Y*Euv(h9f_%_YOwiq%EOEj?-oon2v9Nir! zj%mlG>q4+sE& z13(}c5Dq{<5L!qEIa{Ou{wQJdLPn}rs_i7X^2Vr%FAuN-Syq&x_% zlD?6-p}rNZn7c8pvaN}etGEqq(7_ldY|lfvp>dk}?Mv1mZ-BV-XPe z-!&WD9E?q{0e{X{u>t>m(Lx~*WM;ex?Z0W<5a6FY`9Bw}&A(|N5D*4JcGLJf4ZsZn z0FljE{z>BoB9O%Z|3O3k0HVl4Qh?ld#zKI|&wu|h76^kOfXH*tzsp0O4}(A`W08Ci zWZRm5@BtA}2=p!=2${N%!UuuDP{+cc2vq%m2yVcgd%&O|Fv@&^a0q}KMII6>5D10u z4-ImM#?5_)hQtclg5)1M1CUnrrwZer>%X265C(xkQRjvD!;z&g z|1J-yA2$dE`#&_u9U9VLkjMW27>m^J&U^t71Q>NJ7`Zf1X-EX%DE0zGngImGHb4Lb z9D#}pa_n83gn+@Qd=LQij?UcNFaRnaQfDYCE&wU@!WsLu@uM2bS?;|3!gAc{N?1ZkD1 zGz7BR>py8g5EKkXnHvxYL%MPlKIBC1_*kSacYGa^hCr2v+>Y+xht%Xh>33(Hb8`b> zDEI-9$fL?bZe#!ms?JDnaMvF|?$|gGsUI8#zd!PTs5BS^dWR2=gaGxvaO6&oIu^N; zq3+2*CtPoK6U7e9`7X?$~Y`M8nYzXP=5D1j#3qp2}LS5&`eFld5ZUIE@MyPup zk_JOvgGj>wquMjl?}AX*Ad+^+Pa^jZq_Lsc6&$%h{)V5EgTA?yu>&?AA1#-%xrgze zmn2#)C0ko3TBH}ERifpRvN5rxMS6Z(C1jLYl=c-L3?T-D0L4U*@hmV*907&B5Cw>f sg2Cc&2oNF+hY0+?Idrg*wLTo3^c|f3^=gKE(Lx|=lrS)ey%fj(U$#9W^8f$< literal 0 HcmV?d00001 diff --git a/sitl_config/ugv/sicktoolbox/manuals/sicktoolbox-quickstart.pdf b/sitl_config/ugv/sicktoolbox/manuals/sicktoolbox-quickstart.pdf new file mode 100644 index 0000000000000000000000000000000000000000..449dce61485627edff342a21ded6c100f9f411a0 GIT binary patch literal 795749 zcma%?Q+Q@ux26sZ=VaP`>=Oc<*f2%hfBnKEL>5&3oyW3%FQ1L6`q| z9q;gNQ4ilV0vRCMdOv`nbdCWw#taQm_3wNito{HdE|DC+@&bv!EZ%qq^$v`<+>V<_ z*`#bNL8)((QvjESn$ycB7uws`e*qO5Baiqv5}P3q9m{=z8=6|v%P<2*=>J+q+y;x? z-PTdvD{ApZMU1SxkH(U;Lq?oilaWX$k0S+tRj2;$}P%Zgwb=#fhy>XgCaXt^Xt3+{U@ z6aluVIl-0>VwoYbO#Z+c0o|IvmW@k!cK4>b6^$C>r5RIF3~l7As7pmuvuQ!hn*^zC z=uj{fC*IhF@m&a42rn4K2nrdXen>36pMZ0fOF^F`HF>Lu;+fkZR|{k^uTd=1#7jb7 zx_06;P>8(38n?CA4D3_sf`*cIFppLTF>`I=T`X(7 zBtWD5p%e3_NE9EOobole+r>djO^}GQvIR|1gVDq*Qri5dzZ2WujKm{pyaME-(;_fQ zQ&0`he!3!0qL3Y<9nE=5+lO} znPO7T_eju=eM8IB-PS_s(n%_4=Oi8S7+MsWHlSpdv&^l*GM)6;v*-BJpOBZ*D z0g3sJ3rF1ed2_$sJOJTemg229T$4HnV=I!Yv=q6LN|l?suHW9{NGY8d_rdd5!Hj#0 zVrp~o;1>g{11mx4u=8*hoskEHlYX1_%fIQm%bQjwNCfl{Q2Ea{{j)OSOBL&*zO@7P zVR6*?J(U>!>7FD4_l9~fo}9Y9iu3(}yR1g$%%3 z|4=py)Bi@=SGqgSiyTOPy=R1u@ou~r+Ez~&^+-GmY4SQwe9XQ?&>;v?FeOcUy*D*x zIt?>Dlc8Z!3_Nt z-U!!X^ab?iU}4e%gp1WCm$Jdx4nU!Lo3>#hCzsy#&F)ITfY-I?zG+eu5auv20j2VF zil1`65a?O^t`(t8E#6cQ;pqUh@-B&&(Q`_DodtW*1Yi%lP!K(b$)(2O^Nn=y6g9<1 zw$uI5hWP==l(7Zn1>U?go?MBm=yS}8F@^o=)xZ$!zK89Ez?38iJ z*JRGHd0q+BSx8AB?Z};a=?8r!YT&dub64T;z(+CSSrI=~_8FS(-gKn!@}>_;Gcz!p zBMrcB)&24?h(DuLeJR-g0YlYsVNniO#lUG;*{dgbPPdl;cw?h`g0wx+cXu`&xYkko?NWoUs3U5)K{k=wOO11M*WnlY)sN< z0KGxd-i4kgPY6u#etVl$2?orRi}S@QBOy{YPb|L6^{tOBl}QM))T!;ANPK_T`>mYS z`Nw=*xspi`p-^l`WjS}mZ`SH7AgGR-0WMdWV;{*~>~}b0A|!}`0AE+*9X0F-lHdk@ z>q{)g7m&9A)MIrrk&PH#R-9N=&5TUSIRpQ9Ak56_v{Y9+@%AABBztQ##uP}`9(;p~u=ZxOLO0PM)BET)A zSQJZ8S1%f>B(ueEr37m)vsj}3~eCi+G%P<4l_QZ<&>+&P7h)+Ya?ja@4T<@5n4{ zvaxEWYV$|lK#A$j6){23b{tix#grI0&u-BYqy@9K6*WH-?J0fPw`SQWf!pkXwelQ7 zrA-9l*o}#lqC9TO|D@T4Sy86jaT3vQghBo_^(8l<$XO*IrV}fHCe;GMNk?T>A#rkGg-&GGT2?jE`eGy6kFnOyN_^5kkrT82kJ#RX(zT zgrRr6;q;R*=X`}vU4F$~74w6Qsekm)du1Fl<%t*Pb$D3M9r2WtsKOjYo+2ZTGdc@V zIPDAeyb#Brc7RjEW3b-5oGZGzCAA7oSx*etx{5fcMxouCY;tjS2j=8^G!So$~;^U<3t)(*Pb%%6LuU zVGPFyk_QYQXclxsi9>r7371>#9G4j>pJa{|teuacZHVl`V(2@4KUus_y!M%c(Lz;~ zuM)oU^00eRgxc9w-GlNu(QIS!Kty;w`lig27?l zuorl7KFk%>DjZKH15lkI!jUkp&0a&CjJ810I-kiTtJ;?dnMD!0M`~3`Cxm{8r8U)6 zPy3s#ML!wE2E9c~>^k@Asx4{}mBtAJ>Sb-!UX~~(nMeLx^^64jC0myyBN5m7sHtEV z$S}D;u~hw~^%a*3T{l-eSE-RYK67vM=Fx_{HC-$$SpN+(#Ajp( z(kIZ=vQM{1Brll^Q~(w5gHzeju3xC+8Z% zP3XqoC-BMVkPBhCYKQvk+i{g+?S6IfBlhQzyJSD0Fz8w$XP1mT4~=D&!#9s7zq;Na z!2Sd5|Ap*-$hjc2ULS%S zHk}t=@6QG)1s&_&Y;A>XOn7*M!`aR)ePbYOK4c|v>-2bBocCn7Ak~W?)cK~#=Og|xIG2)8OHO8jfz>@2{;z_ICx&bUoy%#h4EXz)lE>FFlycbx~CbxMP z1@YuE*PBpv@uBigjcyELkLu2yi4Ri0-=WQmSE*&mfM9)ZqZIco6&E(Ll+5H`&C!ZDyqJ0J>KdghZMu79Gb>HMmE?6<7soiKnDm2_U1m|(Q>c$YZ7clPCzfh zGM`Jr(nVf95^xg4CWoyYnZ64qdOVW(n_}uAb6OoIk<1E|qv~#(e8}~ERI-+sC84g$ zv3`|K3DO7xr)s$#7f$EoofFzOs;Md;buYG;eC+DsjZ$uzcdK4)OysP@uUHiyS=rLm zC(0@Zuz20U3E_sZxSl{9;|h|VK?`}!erx~HGFPmK4#AJNdzyjsTe2= zNrFX?}h|{IcNCW{A0mV2~<15oQXJ9bP_9Sr|lWTv^ruX1j`$ctXktiW>#?Sm31W3utjZlEz9dph37~YNDfz=b3Wk zI^%`S!z)Z9jmPzx z=|hALLTU|`fyV0i(J(X2<50iuq!M$c+wTB3THmgs90d>SaI9E1F=_Y|PFsle^b$Rh zF4hM5FUb%<_?AqMA@k&yVl@*_nfMJlX_w)g{Z4(|%*v8nX&|H(Lvf#oJ z=ujHl03(Pjk=#OLs|)1JqM*TPbE2XVW*&yncD_Ab{d16x3G!iY^c6KD+F2U@6$2t! z66R%O{&l{*Io-G2rnqgI(N%0G+7D25B}}Aj?B`|3>|lUz)qQ!C4g0$hC;iKc+`K15 zMMHP(h{R4ztkW#cJU&hFM?K+Qni#9!qeo#K zN^~-l|3BB)hw1w~J!)i?Xz=>Wxo}k83%f%j+fswpOkX3w7~QSVSB8pzEPq)m;>gAu~#0{cHt=G$9b z)QP?&*zM<|LJ_tL9jTRII)i@w${cC#(o0J;tf{*AGkMu*ra*_z2H>5s`IzZ%_B5VT zXc#hm3}MQHxjKCJ{%dfls$l(}Ap9RY%go92e?iE~`X3-Lm4SFgX>2=6b&csGqcX+?21-0}9Fe<9P%8 z^|_8=zi!|E>}N(l-}kMXx68*}+#PZMcE;)HVQqso@mq6YA-s0lC;$zz5ED?%m($CI zdiF+y;a|7SP$`hpEAU~2@}LBDhEZ7BJ9DuggQln3S&|NPS`0C*>BWV$el}F~7el+I<3tV^E<{TRlT<(4)Od-Ujw}5%a*gfBp|> z8a*3SLkK&RZVMQ+>}~i%?acJg>!1rltzHghWfsFpu~yS^zwC?=%#op$o0sm*H(0I1 zG_@woXE|VLVdl0#DH_e~9fv{4P`3o}_L0=UL|UftY?Fl&F;PR#_U_<^yEMeh(4e$)kI0iAuHPu>dVLy>uFe zm8RE{RB45V-%)49pu{`;g$;@jGvb_$i)q?jugp`xMzcuOa5;z3rt`f=oEMN5aQ1OCzQyoK>82*&7SCF6}`Q_O{bE za4vFbWip@GgKAgxvb##6G7;uxd2?WIp*G3P^g#@UY6<)f@Jr-UgSlw(Dt=RPh+;

RI_@ zvfh)A&e`HM-yx+pe(fR9sRzIPL)@=O)aQ(aiVyz8o*v%j{FR?(8&VIuesGE_fLOq_ zD4nS!YzSvK-$KEdI>^jsfC4cbhw~7k79tL=V{9L_kO`DtP?cZh`C6_XMXB|19eZ_M)g4jvxt}~;+mH*9;QOn9VZ%R~iT8GdMC-`X zQm3G%dSf}(P%}{ZVF&=JW63guKQ@1=2NrBamRZPP;?I<>LfoSN1tYcRSX)Hk`ygs2 zrZI<|D(2HHh&0tS&`as;iH0`;CC8k~CtVdc5@5taVc?KlggOQUrPtNlbsdLJh0v(6 z^t^;=>N&)9JyejnfTmt;J&=xt`a=$Bg>H5Ao)Z5dUJC{yO zE|@+MjHV0|xw5~+!`m1q|YOUE|)XMEhn_sp_d`+U0_b$TdKqj*S%uaSa3b2%BoD zX6!v--31!^|CS2`SXUuk#M{l)1c>ZL@j%x?68Hov&>Dl{`b98IfzQ0?JM#2X;FpG; zZidamse*Uu4+S#b&Sb3Nj0vSgki)filN-AQZR#Rm21qNPnjwIYgky^H6|~cVvsxx6 zuU{w?da6mAe^x^D>vLC@tj(a0GhN!}LV)+;k;mv2EhPZ%RbxU*S~*mh{P9+xD1&$Z zfM1SS)Ax8$lJ;2B(BF;E9H+8CKec7Wjfnk4Vuvj>_@n93@~l#?-^FM)9{mMMYOjcH z@+gYWLwVhIZQssL{=Irm0@&O2{4Bs5LAF`9!*w<4sC>(Sa8N~ne3l;ay24(j^lBOg zp95sdrNi;t)yk#Otpo9aXHf$TM{l*VMh!?P7mSBirF2kgQjfICtvK(f6fzWWteAWE zzs#NwfCQT6dR1Kue6mE4tp z3I}TYrp#|1&_IW6TNeE2y?pF;)CC%Bu zXkt2ltd46nLcMXEAo>FCY zO}^s@7OZW8V$Tj^UoTuw<#Dm8Ivu@DqM#E73J7p`EQL32oY0A>H&vF+${W`~klg)e zFiWOSqQ^3F&03uiLk#R`Cld6LF3us-nKmgG8{!=;-R`Z=D>Uo=Igi=1-Xr{c($?$c zz#gUL6<)F5P`}#5fGR&Um$TsN`;f$qgiDL@CNTFX z{EboxDt|JPyQHA-0y5k}d?%CYD7e_>vu}ix;x=U6XWLP;^M-}$?%?Kv{h00f3|j4Hj4cE; zY=B~rKCRAfSkr|Oc83J6_I49d=csQD8Gk8diIasH_&jUSDF=$z_B%5)(61N(C|qKU zD2^R28V@mhV{M&?i$?^ulyzXzTjVyXT+r1>|;`k*j6>G7w{#J$4DONa08C&OM zUS;nzd82QGY&vY;Xsr$Bj0kHA=Tzi29N%dXQ5}<9@lUp2@ksP+JDcSA|AV4~d12Sz~(=l_&J<1-@1r#4` zl+0d5toLb2Y;*qR|FWLlosLaxk`f>TJu^*mqIFHap@36=5q$GUf!LlDzX~L^(>Ik{ znXbPx)gtAp0L|_k#B>GL6-@}4QBF|$+(Tialm1p1!w20QuG6ktHCwJ?C*2S7IujD)$SzfXljiErz82i$Za;Q35TL886d8^7Z7j&D!j_@_&DmwED}jAV>iU5Bmo zWa)!Yh2n9n3cE;Q7OmjFj=61mT*Pu#k}#P|@vKukMFO=G54sOlRnR}i@;IFR9$$p@ZN1M;vClVQ77G4lqQTlo z`-j&AToqg6SNx=-2eRvin(oU5ild36uL;>dQ1e+IJD?}Bir2xG8 z`0h!ie`+0$368DArp872e%U)u9hToxxd-{qE_7mXU7B@_M^2u)f&_w>@{~>9MNg@rDDZAa{$dIX zE32gu`lt!udJ#Zl5xtRqs!LgxDQUj0tuNA}Nb?-6m5E=RG>W_R$P$#3qQp$X?j|I|v)+j>ioc?;GF z0&TVxI1E~hv5gfte5ai_bYWxj5WdZdqdpV!s$g;ty4@bBK@X@-uo{HAJi5)`6ln9} z{=&}aRw^Kz7)@|5{8q_Gc<{gjBw`Zb9cQ2A(ij4wK5&;8AT`?5&~$ z#YiapyRa@0xB>SE00`#7%i+I2bpbK;+Z@pnvTZb|iPrjzan7Grd(%!VDbeun*-Q%FZA#<`9XL)v<69uRTQ z1Abh2rVCI(IX426jGBw?6V}}g>2`M!=|1 zN5l!O=vdSsklntX$)^)rpzn>uPnx@avslHv+El!Tw! zU!|MaU2tmXCzG{WS3R?e8`Mrf4f!x(ozRW6Uh`7bZ8a4Xe_!G^=Bd;jbVhYOD5BU{ za)qo`wNmQfW^vEQxbDg~(K_faU_N98#}k39t$L5B2$F81Kb3v=AP{PzT96v~6R9|# zG!QRz99(_rM54)U3A(riwIHCZ-cxK^$4#Itk($Ne7-a2+w{ z&^7LmxQ4kU(3fyFls9__WHrY70!26Ep{$z|OFFCjQ5;jV`^A+I;hY9>u$wqMc=%v) z+;_z%(yu+dAB^J#b~^tNsr*+|@^81m#>&R>KivY`zxm0(!~eGs#P;uw(Eq<%(B5z& z7)I{V_(ba1g#Vn(LEJ>fQIHJL6$jTUV$xZ-lDw$PHuD!b{_r$h0(yM`OE?P%IDXRFEqz#SLI{Hv+Z?>*WGDvqzT= z9({lWB&;{EvWKn^?jD}_E3i62&`Jk;Utl3=Ofwd}k;u8j&OuR=+kj!Q7!)=e?jBAF zw5JcC0^Sx8?hq5O3MOmK@j7|`mdzt*k0oNrD75BRFYn3W{NV-sAhoJqSw<+8E+D>E zYOlxOEOPLku6r^cFfEdN>9q_zwdi6(SkSsGT{#D{J&m&s{ulGsNnAuxi5^Dx^b#cJ zIGTfTgYpWq*oQ?6_?Q+y<5DQGnTL`c+eW_%MDHi02R!R}E-`lk>WA8eyNR0o?<0W# z4Yp~41aW!4Sk~6yM%Um(D4k@J8M4x97Zh=QZkqL+c)c6v?ok^n$vz08RVXCVEKlLQ zu>0Q^*TzNsMjswF^g6Dbg(H088SI-DC*(_RCv+SOrEr>nVo;a@1hMZgL;0UF_d1LK z0l|0)Tni>8vmH=_H%IjXXW);(XhV8MMaHqLB#!R%DKgE;648s?bq~|E62!vhrn-2y zcg$V6n0`?doKQV!NA);o{rr%fm%B!LJ*^2`V^XSF0Jo9OnF-_^N zWDkrh$Und4e|BG5PHoJzwG4JyL_$5!{s0om&DzIO=z_?jG#*c#b=dw?6CjsMcn#r; z^3y;rjGpZ@{;{sW8ESq#G;VwO&|aKJ9>{$;Fd*w>K5Q||=c%?XynSE>e6#2vAhKM% z1Yece{#o}BJiaAT0iS8szsj&~Kx-X?F_5rLQ@7MjM1?P0VFd}Fh5%)j2by3KyXey0 z>Jg~eB8!9mB+fXycy}7lhDkiF0ycnfQ%hH-k6x}vR0cwTzGHl!1-cH{%K(Q{J%Dcj zg*6}>KnH_0Ni}(1%Tr`$KyqnK$L>o7EjAC(++(2T1UltFhBVaJ_=!mwOAL-TCf{i3 zRy;>F-^Q1A9^6uteur6Tjd*SQld&d5Pz75*c$Q(nukbLu3#nTcT_~5+wTv}(RV{tH zHmnyl0W9p-d?5hlEuvU|G1)_G8cEWdaK=&9*UMle&a8ZlMW1vnw>kQ~$q2qd=7E?9 zAH!)Fn6w(Bj}T)IrmwAI93Zg@Eoz^l7>y^kT*wZO948f23m3dKl=NW>S|FX|O_9bo z#k~0A5qF1WKw=j4GlO@X&26arg^voEg6np^7YX`jbBz}z+~BzIa#R^2=lYu)^!_IZ zH$GYQ-hCRf324(@;CFR`&4$c4>TGHb^DM}RWsW0c>ij!>G3@#L$nPQc6D~ z!~FMbOfIuU7O~+DPu5(^uV~+3QNFuq%2+^+ zCQ=tInWTj#k@tn2>YC(%L)iu~Z;CN?BROv*Gzf1?z2;Ha^X}M^Y>hTaqFY~(?{Y1@ zKb|kW?RwaAoJChH?y$F(TtfKbW?8p&audR@11BZtCHq+gabFz3lq|~`aO}z{N?@<$ zNasO`_&&$h!lN|Tl^i03V@ly>;Eo7K6MX0H?TFIqQb_}j8@rfhuOwR~(r&G|G;Gr* zuv%}wQzlG5QIGJqVM_g5qsZj-b{qee0Fu z;yunbbo{r^5>Dw{H=COzBitCOiO$I!iaE^L`YA?ZEfO-Qxn651#$wW*h;eIuUKFl7 z3ll1q#3${wJrpy^S%5e(2%SG$GCMY+ISrkO6@R&UdH+h)VUXan<6zQ@cGNS$^mPRf zxVn+D{CHi-!5bWbw(KW$WGLyQ))_p49krvSAM9bo+jZxm0{sCO8vk=AyNy#+~=Iq@;gqE0tZSbl@ zq}Kwp;Qb$>Ot*oJM3Dg#a&?2CGA8M{KpN{wD0|6P_*A_=p1$l$@%d9o^+ZPLbmIn< zwApFFF2G$NDsJgM#O@RZShEtPn6mqDud(LYfmNi3E)SL1xP3^>cv26a;-9^Js6fTg zy3m7E_s(&q0Rhzumc6V%r&KH1AASPV3HI*Dp8IoogqDzqNL@M999}p03V|zX8U1!% zJOP_kyl}1MOr;eMdCU52502d3-L&-7Aq1*AYg9Uu-Ay}? zv!M36PVGq*#fF1|>-Uc?=jNhgo?KBw4Ld2W2Q^J>-6e;lsdzI%spJTq6Wsn{5fifX z5>&<3{WDZJZ#jqqJ|8@^+_%EJoruQkG-x-R%Wtzq3*(ay+)6=8d)2rRNZ?p2ei(2W zVNsrvf8*!%5$ER7O#Jg8FyZk?i?81l&az3ktqA6k8i=L;Al4klVa|AM{ct@K}9@sqy$Qj_{i9+XG%@%+>7D!VAe#h>6%wUUzV;qUX3R`^I8u7JzdS2mW@5&hykPDD~v zH$X;gO8r5EqlonCT-J+(H1T!hQ@w4_`Fz4Gpox{k=@OYr*}srymCp_LnRbBa>)y{O zv5LCgd)je2_+jtAJQcaG6i;PBA~s7Ib?Q1tTtEjR55+KtB-7>RXBIS}9@B$gqlD|` zv;*OCt@Vg)p2}27fEU$WU`9o4D%>FDDp`odFLUSTS@G17VhUCKqd(Guei+WzhPG}P zX6$BAmG?0Kx8#n&kph1ty7J59iNihw4QQqXt5~Wy2Isj~!9h{&{sfX&1aG2`WpvP1 zOpbBEWwH;^Gd1?>5Y^$>QG0j@4UgrbmGc%Avp-VerUyTonDNuE)(ofvNhta0c@2kM zJjnZKWOwH)Y;_JcEo~Q9Xg(n&Aah|_}OHB`nK zmk7psp*bhjxbfQJ#2Bn8D%bVNTc<2$mr-rdyebCf-zOh*+U02~A%mk+6S_wog$r0} zyJ&0HZc`yG@l`fYmTKLstJG_-6N+ppwvbVPyf$jKjUUDOY0nIpo zH3X|~=#o@i$xPjKle4h7LNf6e#>CTU$m?Vnq(WC$(cLMQ9-G!?ZL^$a;b1GdhAFvm z&78yP(aXW-F{E7g#uA~|c~WkW0W|x_!$B)kx?I+5IHPXakGqy(3M#W6P3Q2SqG;(G z4ux|wwYdnuqGC^v+r!B!whht~cu3{U+Qs9l_Vm)x>W3lq9{jhfgJ5-m&11#FVZe_! z!pjzB=r>)4n4C-D8lOreIgco?#w4)A9+nMjY7VDwew=Mnjk)!{S50YU_hq0OanwaB zk9MmLntaRCQlUF@t<@b{E?bcNSeQ3TSWM~fx3D=C3a?bNqi15h?Ji9bFf3mE$!HY4N=I@`>%GD_ zHm+nzhigcT-inN+`-4}}T|~`ai!idTW~muVm9vC}JFdr>kqI1WHPmp-u7hz7{)*?y z6z)zdZ7XorI(r0q$)@E)Hw=pHD0GHuytFo)KG%0}I-O?&^HJ^8ofs{Z^u}i@XJ1?? zw7#|X?5Ta{t}73v_E4u}YO5m@)14ZZz-El(qu-@{tORh$atBu(mswwN{rj9$Qw^;>J-wT+TPOiFwHE`DgDs&$fNKdz~tSe`xq;?F zvg5CD;G}DVQ^aPyiG-sy7UM+K}nsT z66A$kiGRt6I$=*o`#W#5#zgz@%Cj*2HbF|fIrIS}g+Gzg;GlnVS-QrK-uOLZk?hIs zFzCB@c(6ecrZNEmUw0C~H|2DFVi=FW$NTBm=uZBSao61(zCq5kTV%h7ua6r`G>mlT zL1(hQr~?aL@2}i1V?e_wWmzM$y^=Jcnl)7rkDnh;XF)|Ezn?Q-`|zBO^XG#U!vJsX zDX9$TnPr?p#gTFF-1BP-`{%J}u2-idc08iIMZG3*5Xb0=olng9VUesU<75uI+>cha z^!J*#=O>`sdkObB^V4JA>rQELEwO%f)?*#g^K;Kd{c#?~-^XX(&5^`w+5P8GhYb!n z%zG7XC0+g4lHOIsw^QuG9L(Cg%W5YfG8Q0L2K_Yi7O@6GjCa$T-sPTE;>t{5P(;jr z+hZF*uCfInNL`l4@8ziw3~oEPVR8(j`|`SZoPqT3P!?B41WSQj35o43u&J#-YINw{|hjCRc&{M{&2X)_;Gc9yV-r?|RqMxa>`H8<|6B1K=n2T{vkqIc?3x7A{wca^$V+fmu&hndRWCt8=u_Qs|*3ZTad_FQ3#H)F>2=Tcw;dJo*a z=be?vcx*(JQjZYL(9%ZTM@igYoRC@~YUl=>(+=$I%x*P|`6|m}w(hyQT`z;vLOas* zknp1BvAZo#^z*_PD3gSMj#!pNHcEc^s%A#n(wWcUndlkSr0^>vq~0O~lxLxYCAPGJ zJU>0HqnyDXcVAmNhg8Hbwp|KP1p^nai%M=Ywrekyrk%J{e8hKe8akom)s+pu@C*1X ztIp#l=?2&}nB#2jRfBTCHst=)FCJR!RCtiu5I;IUMx@^(!cH=bIJr8FP@{homUK4}4^>2uT$Xh4{KkhvcMPm48?u zms~xrOVVHhEROFR@2)nqa*^c_h%n2MNw}o!!lgoyiZX1Foqh5 z#OYh)j%|MBu~VO|dy5Gn>{6&pg<~HWYq4^UnV1&YSRgRI1yuh9`e_=sG)h#la&y-x z54pNVTW?{#V}V)2B%Z(M8Ld-{b#&me548zYKsu~!`>!g2%S&ZMS;beA3iK*X08im< z;OT|9bLwojI;I)U(j~5E;(>vLKInsNn-IO0bQ?5eW9eI9 z3Abccctph^C_`dm%3gjg!6!x}aWngfHk|3Hl+~fQsiBxKqm{4|kb?ay*Ox4CFWV4m z>>+v;Ag-5}c#g&{5rMRAOt)Lmj`aR!`%o#@;VYX%@wfN|TUN_DkzJjMhQ-7_rj63G zly9b`O7Y52fd(=m|MQ zWQvGC**-CJ7uX2Ak2~g4^eUT6#_Dc|$7ybwdu~MwMiUH)(lW4CNb=Ccu0~f-7c0X#JTX_jCT!z^-$j8w&1@Mf z)({^jTk%`bgP)=~STGNr9SaOdYa30_nHx5gH?A{G2?>Jx$d7Sq1u*^SD(voe0TJ0RC$TG z<_GBP!7u2Wq)U;r_y&Yz<-#h)`KKSY#AI=i(GDwG7o$OxVlZNu zp_^TCVz~yFX~tU&NEnM2>QFY+@9ZP^ln6LfCkfD^I;4TLE81r45ix^~L)+Di9a>Ka?GuRvOsu@j(80mA*jW2j}Pm8a_zK#K@=fWz1aL zJ@hq#ojpIHoe=4^I(%yArOs?L%@SFkQG3{=wvSR_g~cu{0}i);r(G+;pbO!t3mtUP zPaOW#5TFYYHC)fi_;+wynMR4H1EHkI7H*DZ42?l*q1m|RaduhZkW^cc%_GF@&q_=G zLjS{ACRCjZZ&su^USrrqgg*#wGRL7-$TuFYuh=Ln#1!wrb*-FlLz7;qYeEolOm0G+ z6Ogzu0PNfrp8$ta5}z8aYqGGHVwEHm2_mKO3MKYax8^ zoQ_eq;C~bO*XyNh`L_dt+7_oAnG$oUXm_#fcnM#v>DU zWl6Y6>U5d;2+`&nk5xUT%Fr!LrL^xIkKlJ>5cJvn;7@ay?uUgXuA8a(Z%t-ofA4Z31Or#ztz?0?=%Qd7)*rQ5F`16zZndxl^@?=ronu=eW=-tO0S` zM!Jltbk&i7DbbPv-nbZ}uqhBY=p00(%V6o{F>OyBpK&SFml}H9;xlQyDNCQQM?xoK zC}m6Z*!Tzx_Q@^NX8A$qncJiJZb=5Vx)aJ&#w&~E@{Duxxeb>UUlK#1R zBeu!mt#X7NZ*;31M}Uq0-1k$Zi5FH`CsMmBE#j;I?8`~_A|IejQ)Hp48&DiV;2@ui z1#Ii6vI?wW_rCbM|@SIEj`PaAH_)dM?5GY{%2eD10R9MoA^tL+2%(q(@U40 zQoHz#ed6vMnYg`(x;X+NYdl8up0hfa9z1K?4c0N*Fn}m42=}}#P?r$j+|leVn{DRUEGV-?zwn6(4t<5kbJ5-MiVqKpU;S}p1kkWOZ= zfmPw4)B>U-C5mMLIDT)y!-62eXc^j11noG8IYe!mu)$ZfXDlSKM8__F(q^b%Qq z3yQEZjD~;r^!svl%09BYxSiRXp3G2Aik$_u8HSZlJADGL7yI;x_6p@|hy0tCxliHw zk=&J7!stwS;R**oz@@KvK*UA1ZOTQ$Sc=z5I{h>Uj4~8qop>GG3p16o%P5=P_U9?s zg)-}TmVseQL*Rg+5?fxsvzCH$lVwJL2bU|F^;X zuWLWo*Z9iX8-iKP9tC{xd&1F9kZ%D%Wv}B7))%$s%c%2t z78&lcBJN8o%WP`!-(t@g+9H#F%|#o;wmEks(Pz-ub5XSAtr~g}jf7|95wYVi@ppk`l__#%5YU;Z+k6s;3e&5@9doCDkAExtQ+TOL8E>;Qo`s@(SbpId5 z-l1C%U{RCZwr$(CZQHhO+qP}Hwr$(C?Rs_YTDRZe47#WJ4>B^oNLzpIr-2aJ1+y5t{7UH9&_>-@Z0~Hm>UTo<%vq zQJN8&%khkwmM=>p>6kuV%jK|`Jp4l=kkrTgQHhidZ0|yps^;-t-_?QY?%ghzkiM$N zGT@h7P8d}^oYt+vUNzsjrp>uOvx?UZNr-w$&b2i*$$WC6l$0Nsx9np#AO2Hz$l>we z1sq;T)>t^R?b57P+LP|PPgq{}PbieSdg?Wcq^X;gK&8>ne5^ZYe2bC^U+zoFRB2KD z%w1rqjSPMDKk6q`90H%%)P;(adTS3s8shuz*kSdpa4j!aAgOF7snXA)b8H5#IQ*r% z843hgM>++3QCt^BS81PSnp(VrUmea0gOM8f!EW<4NofZ}Y&MLsv1@H+nZIm3WmcuJw-rJ6R%=urA&n@;Ha14aX`w zZ4;X|Q(y6ggQVxfXfZ1@6IKq{w0&7_yzbu3v_6HLs&%Wz{3Zpx_)(ehtm8cy6bJd_J5PBgm00*bN~MZqxz-);$}D3!GCVjFjtzPaN8-pRcA07i_DE-SNz(T3 z`$VrYI_UT>X7@iV?tf$sPFBYMl{wh{o7u7bKQcRQ`<+olKlDf9=QQWdh|}G4KkKNH zb5x6JzE)8~$+(-%G+b^uo98)qvsbo1IFC4-fq+^hSclf;i2HomaP4TZ*r=#!bSNzjM_IkfRv9LJ6-OEh%mQP;X(W(0Cmzic>7sccM z>h|@%pBZxLWeyR4J4W;G_QzZ1rE+Z_)$bj|qrV?v{=NtB@2;rl4X*Un|8*$5KAu6M zum9`f_*3nVr+1_+e?KPu{m{~#ukUK5Iaz&YUGM&JB{z5Pgu+EBZ^6OBW%VPB3)fv+ zZW_6OujiV6^A!JEMx&oWjY}3Q+_&h}ESenmUlQC48O5R}O#xzQo#noi!BzJ^@q61Q|ng5~6ubokoClo;6 zYs-5OBb$-J_q{x-sqeEww@(c%L*GB?BK&b+QHBxB$nr`3K7(P)68laWD}+5|zGBy; zX;5BEo|CLkW{!K4^|AyM{Z|{yKm!ew>GZw6Z&bS0R_As|D%TDLb6ziSKQpH`$^ zHPclGti8cDi7uW3)RQq`IS;XE!!~DbX{<1*mCaLDV6@Yr;AX96s{7!mhjVjfs=ycT zE*1-9>8uC7DTqxD%5Kdslh9C4Bf&*MCo!bHiPqscp{$>S`#DIdf5NFx`94=zcewn( ztKj%PZL-sp=bYx1V7{qA7VO&NP5BP@0=EaT%#M7#_CEZzPn(s4a9CnEzPC@N84dmU z;K5o9^N#SCR7k~Aig40?>((AgSNUlGESuxA@wAq-;4uNK-AjoHyFL=YM)UTfjBKR{ zNqb%e#@S&hY~rlR-Z=ysKBi}DAK};#eR=O*n7>8r1AiQLYMcuM+}|2b>0tYKw9vo8 z6dwgAW$A+AawT?sC%NUA@3cPz1!2(6lGd=uM7xkyZouFH+d4^hh^$t%@3pu+P z;+$p@`t9b?*ZU2;u~~hw^jsiDo6J60@8ghP&5cuQXDUQGtn-c7enLRQ;ssI=Y@niQqI-2KC(_nm)w%JuG>yhrCkBVKB>XrMUn=t)Zc6>>8{pITH9o2Zd zs>S;f_x=jredO!e!A_F_{A=qdgLF~X@--JgW_0tBHP)FsXY_WRT{g(Hk+j;o=-1ny zs_;Tg>^0qT1@1q9MtmO{rxB|=!6Qo}T!mij+75f)TCTn$d=k_irf9sB{2X<2!r_p} z3-FeBg6!Z6g{?)!d*tY*gNLHXbZmo$9s)gdPV$7A2e$2D(ishs z1*nR>wd#w?AcuT%t28=@ZD$=TN7xhCAitzx^SwdwVzAbK0EIZJnCUQC5cgYm_f9uNNE>a;R|?o4yG|3byZYT=(z2zx86K zgbw??Ea2atNfE9S%|_Za}f(f%u|bUq2DA2XIca==YOB?Qj1nj!uS0 z!{iBHr5Zu@0_nL3fc3 z`m^XL0NKY`<^f|Qik?I}?&d}9Le2Cm=nyUo#^|G%harnLGvLk>$ktXaKR-#oV7bi% zAz2}7&XJ6Jmns|8GR#4xKM3BDa8$!*O0%Q5HLduvj}mUId))M=?5nwNBlH_9@=xhn zAeu-%=@*L#N?5B`^Q&fEWQ|3RtkD-bhD%}+J?Ez|r-Rje{c!~13j8msGk;n&>L@Qk z{7z5TO>Si6q}uB0JEMS|UC+J}x~cwO65?eXBnSf{=3kb(-4T{EhI=#pI49`WlN6=y zgHyib@yWX*O?Y}nZ=n#F&b{ox4HhbfQWAZ&!_(H|!urjb_?J_adW~-7PRT?i9j>yv z_Pe2h&95n(fYc8p(QhE z6C#TvVY&6Dro?l0WZ+>%y*m#5@WtcPbt+B6*Co+h~Z^NqYf#_5OIm=h_7AzhnGf5+yyJps)Q40vm*@lz@@#4-MYoBQS#H4JaeBWbq zTquf%34zWaiaBU~M#|0lT&~_l3^}Q5>B8g~e}(y=Q)Vnd7q59{q|nl>F`5Q!SM949 ze&qq_2V+j&2mD(&B)nuO`$g*bL?2m1wjT@4c6W?rF$bV961;Zv8!wIT&z5fc z%sWFKC1|g^l01#+Z<;q0;3tW>(!5>QeES_`7CFS}I(A?8qB*v%Rqm&LQ&jVpryVvs zjv!L|%o{opt9Z2xX8QE19`4pZ&SyuVc)K}PuN}dF>Yf3_a5OsOz8{Kjc?<>{FrPoR zr_xDGCo)@KH2R(Sy)-d*=E<{ZD*gd7v@soBbX1*SpJecg1afMK#60x)E3J)+>HOsHEv*W4M+210;0wf{< zYVQC@OTtV|OQTaRSRO(odX~*jSH3rQM&Mt8y(;i6A;%E1sb8D&O{O(>eba79g;R7lV_yU4hm~St-a=^{+KRVvB+mU zR#sU$wKDA0F%_Tlv9YahKTqbqBk56h>teP`MZjDCOUcPBXEdF`Pt~Sc6%B44O~iI` z6A&N^wldkk3%jnHU+zSYKJhIb=E&s{)Iy(+l~n0<5DWC0LZTTp6@k9(n@~5q94n7e8dKoe=K+seglN4J#FJ3-at&^^T%OIYgmRO$oHr zgBhWJ-=>HWW@!=$10vz3#2!CRi_?24cARYo+)XDuf*^_kFgc!UNTW(ry*4-bFJ||do`3l87^{w513ft>J1Lk7f|s;Re%H0+QZLuPVA*nD_H{`Byaqn zPx+SV&x~_~{6u0%y|SVx-kP(QqDGog%VcCX<= ziN$Ajbh$g#i0={xRtDG#mYXwfiqGXKWtkW&_6X^Hkv3(-?>JzKL9Nnl(m}s^>@I%2 zF@CvMsiu*vUck>YvXmY*dLw=xiQ6_#tk~kp*%tiQs#8I{M1fb)R07`6nU?92I6rur z-Di##PR(lrZfligMU(yT#J!(1242?o;ns7c0&kF0;In4`W2<$R=hhC%QU-TaoeRia z6R7^OlE(W(02^nTryUnV%IkH5u@J%`7tyStx}-j)(#j*!c?q+KezeL_BiYghxD;x5VxLXh@<5?!KJ=)uvS|+g z$n$Bly*+Eb^q|9SL2$+TFYjSJXyi?qVUDF@lXme;VR#*i`*a=W;gmd|i&H|Y>#?c} zalB6X1V@o>JoZOm2Ym7?zm}bYs2wrhBLeFiIN5f8nbC!BGE$tJpXh z{tvGD@2(l!|5MkjRcj*-w;j4@2>}C0jCV)2NyGJWnez3!DOu=-H(R5Z4%i@Rp@O^%bYaJEn0m_WqQjSFC&SB6nJbK7TK&8+~; z>!iGN#?25bQa(SMczgpl_^npF80Ut#X2Va2=r0V^>{Gnjh=~doUehHZ1s}ofO!vV| z4&51VdL0mYnyUi#e(+5(L(;tw+3ZR#GFki0o)NvXvgnQeWxmo2+}`p~I7=^HYQkV( zc+`5#`f~N=I3a2NAIuq5wSgskM+pS1?>F9A3>dM)8cng&?N-o>3s2@V(?4%F-RXmp z9WG02PyTX$9gAEM27u+{=m9bH(@}fWmo9LUBSyI#K(|p8CC9pjsPl%72uhmJ@UW?6 z9Ka3}f{k11f5jtGIRN>do<^{bX$0aBwcO+Agk_pgqnSdn$kB)@F8QqVrf4VUhx2#&~0bo>>K1Q zjoVGNa%-Pebm(!%u7tIJne-{q8Rx%97r#J0s7z@9^>Jty0(v3=+D6D^$nvaN%loX< z*KRJHwG-ciO0S0u#-TN6K^=579HQd$*C1Pp!lqtN&D?NYV4cCnbJK`>PSQIDC}eOj z)QvMgXun88`UgZE%B$fztg+#eLL>2r+&E|%AP778xo81WGr9h1YY31wbT;+V8Yl1l z!8O9x>hgRxbL@G-=`q3F0W zI?@bL#^+Auki&`g>6^Y{*91q*gN5l%6oRWBd}FYeb!3BQs$D?@$bkY}FDK}4kaWN@%B-~L*%G{$hvnA z-T^rv6(-%1Lq|IV-}%}2j{Vt14Oifg&}QnTfr}usLQzxF-|0#A(C#EiCGK&0*w1Qd zyI|kc7Gc0()~Udp*zX6_xWMbhUxVBs#@(m9)3TY)1y7_9=Q>6UT$H@nf)cDaLw~I! zSHzl;1Ja+=P&;{&Os7xm&{k-V_m_!_e7_(nxGAgJ)IpL(pzV0N35R4)#bFT!Flojb zD_bYjxY;h@Ia(dcT-_>wOU89Jh*NwxAcG+4nDn$*^WfQwmFA6=%-}hqfgo(cjgOsZ zo=CQ~SsUknV*($lX3z*g%^@*kOu!z1yg()(cVnd{g#1uPx%jvFGVzjNCGkHKaj6^j zTfh_qY*ZT80oGZ4wAnYFM_k+cPM9g?PyEyU3$s@VON#)B6v31NX2eP{DXecBAuQ0e zx-l*SQ}NA5(td-sLt+Kg@gZ`U;A~q^@3}|&dq;S0Q0r^bx~l8D1hobQ``|2F35rb6p*<5lvLBA&{Igf} zC#Wbp1U0W^Iz7YqZ|_Gn`6qR|Q^?2Q#mgbHx)w^|uoN8x^JY@v2Y{Z*2M;Rh{#7rC1kbrTdEC%L| zf|A`CN*6xKL5aUlk>$!E??%B!kFq20CRZsK84n$lB>IplS#$I{WF8TSC~Lv9Ymm&j z-iYvgL{&vhC%U=#L->h&3dPwcvGJinuz6L6?$o#jKLE{fuN$|#^WH=2d5+4r5!WAD z*y`s(HQAwteRpbbdJ4+6?*aB$0a_T%yUK{TfNb{Emvdfx7q-GV(jX9Epu{M$(G{vrlKTNOvFOVlSNR#h~-4xdUUO?y*Y&f z&UN2W-dZqrm;zug3AC}}qCzQxDNi%Ojp7D>{Tt~;RaNb`P_Xu_=U23F>(r9|aE#%m zQw2npL1+o2J<(3o$Z(#mCz!z>VXC#a?-oOiT#N@tHhR#emn?hI;tS&&ptdl9Ps{oT zp9zv;m;28^Rbb5R|Hj5Y{0n@0&_&4Q;l?;AIZ#JIR4lR-L)1icegILPa|+N~wHiZo z+X}N8fhBH7W8QHy0@LiW*$bihG$0hjy}&R(Vw#rEfk=2z zp9JD$l#=`Ho%=-c0&zK90nq=f1BO~tKdma>#8w5qoT466d@F$@#Vn8%9uUWV;}+<* zN<(A5momi7t9hdvBnJOpX%}pYWR4fVs+1(ol;dut6>rSS2$gGOjvzT6gfC825YQYn z*tN$o1UjEq(HmD3S!R-T)a^9hrs-l)vtPR7Z5o|e0B8I45J{*VCz8~k!Leko6Y={tzYCd{SMECia^>N>eUZEK}(t#%m%$??3AdL&EK8hQXC~t?w~uMFu+N?9dSlA$>1s? zN7H#RYg`(!c|@SypZCdtP<~ zmm=PQ+*iOAIt(mIEzSR|2{wfc*xoHxpZ9U7ho5HWPJ}qR$moE}vB4~P3UeZjg)V|7IAfTfm_uyldESa;Ca-|`FFf7G?`E}BYbfBB zRU?$mTEEYUA~yBr!`JUdN{G+QO-p`SpibgA%GjwimsT-XUVXcsCHUN!&i<|m-UkJk z`=aZ^cG>TVKC>Dy$VFK+@+Rql~bVQx{#k#9QuLLs#1HUmhXQf;Z%X^ zORoCGS5u~Z9_N~AW;d1|yxh-GPxWzM3@$y_>0R~(Qs{k+jL8}L5KyAH`|1lAYx zC|?B+Y_<#@u^_dETPY`ft(_H8U&AU%N+*X8A&UPmuSF=Y3ez`roSFw-@0M`VD23{S z7LDw=zP!9&fd60Mg5Zek|GxPAZ^x3EiRu4zEZN!rYg@zqpS#fiHM-EFqv?zz?)1uh zjUTvPo|#&v_*U3n>c*ayhT@IzxM}za2qGawodf`{aC|t&&0JkYUESpc7GMDmJX}yd zTf@`KQ?-W|Er|#Ho$jCC$H(=N&F}Z|8RY`^(r~3@# zFI+DkA1{aZ*WvqMXXdFmxetG;IGO*zKmPZT_S@_G>&Tz;bLi-(Z%|`BA1q2wJ_`2a z8s(N*MRVU>+&Kho39dmjYJ4jG~B#&)1Q}*}HP)c)AhV4(as$`DMZ1-miVd zi)nOnCj3TDo(}_eQrwz-uALi0j1o|O&tM6`XX&}THsD{Ky{~iA%A#3$Ku&3WCSIG_ zlk)HslLc~svZu39exQR%qbB*lfPJ2u>-@&*?oFE@iGh*D+7q0Z^FYR-Gw{*u3AR>L z+Vbz&^IjmtB8$kpW0OZxIeNq0*j8@HN9lbwIzx3U^5XuJTJ?nY`r*pzqLWPk{qw2U zpI|hw48tcYY1!vfn5^yz*_dEo1lN|Z-g^c)pwZsSpWUOFRj+afaw%_(*kHlaHh#Mk z6k`U*r;=AM5SMu^z!5vcF8fF|KC#XZWY*MDu*&{03$FKt$49CLe>>zbGIcM`6 zAfks^b8TEQ!r0w!rAWvtb^>fMaV`%Xx`y)Ar`bz4hfV!9Dmf{tR|@25k=73^zQM#n z$RjaUCIp&O&Ln{GGgN(=Ek9DuR#h;ILan;Na9s7qmziM?W%;gBX*|d{{4hp_`RYu= zQ+Y|3nv`t_I4`7^tSVIzOLOKC>6ayr%g4vv}eQ5U^yXQ6}-U+NRj(Oil5r zElX3ud?fcEvJCY~M_(-Uvg9;GA+nRu=!I#12QC`_WyQA z0_K4-Xun*7Vcq?I8?H`|rhCX$3;b&E^QZUtv-o{CsqN8f^5dFi*nzP%<=?GwXl5Mt*B!N>t+3;MPF9^}qM8eIwB^wZV~1KFO3c+^ zsBlA@9X(ZYiRz~Vk&Cey`|qe6l)0F9#f^M0S?}ESdQZL~VPs7@>WYsg6VIKecF<@O z5CYd329sjXQ@6)5N2u##r!DGZ6A`;9b>djm-8n_jId+pBj-MuACdOY9QGPTOKsV%$LV zo7w2QWC1C{g|)1fLI09KC3LYy-J(ihklODX;IW=ctwzy~88}h2I|16O~ z>LBt|MpZkRxXhQs$@)2Xwm?v26b$HlPpFvmY8V@>xZ_;a(h}A;Qz+<{>)=K~69M79WyGjBx~bgqjHJli8C_e@COJq0RO1%nB32b&9KQc6jwT z#KX{8N}QU2gsmgHWbrsfv6O^0P!{h|WJtcR=;uH9ECu7E!cSczoFGtwRjFweVGT_r z6gV#5!_WOivkVm$wFhbdri_!-Y&$AbVq|Eh1=Al?N+Z*ER z=LgRY$Dsn`4{e!c@GMvK2X-}F5wz=K2_hn$Dk4*1AHd z03;L;3y8U=G3vO~C8_{s{5oR8iV=ILpA)bPya**vw@xBc>L$1gn^F2>Kmmip%nL?M zL^v+fwp8*{s_`CfpeV?GhiuL9mcOtd!cXng$=0tUpOhXApc^>*p3+k2w0mTJS>nPL z!SbWNLf{v=6iiT{~K&A*g)MMw)QKYhh`TThl6tn_R1|<(1j zO6wXMMR^W|&v#UWbNSPyasHf!_-j^jjpy2adi2B@gK$b^zUt90RAc-lCQ-Z>Rd{5t#c-8Pwt4DH<1&CPj?~((3f|qsV?k`Cp5FQ`g%8mBI=f~P^A(5~Z1Zms+bQk5E||I& z62pce*jT`GHyJni!FYYR^fB>r+eKvzCnid02D|a*$Z>gGP%`Nl@V6qtS9X^Ar`fDH zth2yCGtRu_$zfV@KN=!9o=BS%x`{SV|K%c~1W=p^%FHzZWv_fExdF^6Mw=T#*5Ld> zuN%XO9SVVU$SI7bx*hI>pzrIP==ddXSp`fq@WLOw8TU?ou8int*{X&T z1tBg*rKd6xB(qqS&P z?EO``*#T6Nlcs5@eQ%7x@#VreF1CU}3&HTgPuf;K=PI#>R3m=|^U`sxyS<&Bk46Iw zQM=I|_Pmxpyb@hBlUmKqq(c+M6~wo>jAJtsfG$8OCHYNN!h&Z!fcPoe3TWq|_f-pk}m>Afa57nuMzCiwbJ7)!T*6m`|Lp(B0cGq(@{!&mb8Cbka zXT7U=D_DZ@lqnpiVa#Z5s5RqqO$tX#rlc$#P*4mD(2kjq$Ew(hV^4-cSAqzQd{drt zYX=o~I>2mu6>f#_PXV4fA_s>9r?9|vt~u-lkK`fpC}$T=wKsy->NzujD~|Vx?oz>Z zq%aLP9*{^4k8;S9e@t!5y4;-`UR01y8msHG-gIlcwk$r}k5NjJBpb`E@s=skH6 zWl_mD>@|#LTZ_O%k?_8Wc1c6|MX;vYOT~@u7s^6V6Qk!4ksXbmB!P=gTfpL6IS)n$ zYw)zyP_v{NT-gpE+AOnMtHGt75Xr2e3WTynJOUCNa$c_3eAuIg3oo5D+92MQAmMB1ClL6zb(%8?8NU)l-KJ9vj(h1wMj$-C*QQ5qf(4a5~ zuC84B%=w<0G*0(bakS>0aTJpS*c7kPK6rMkKTGVZd=4X&prWYoECP?D>z`go9^JW- zZj~~?adph9Z&N~2v|-PD13{=W15>Q?mcQ$x94ip<@uO$E`^ITehoal(!b+ojsjgzv zUWx+zC-(aL%-ozBGEwQ4nnKzYV$L*@pfi_|nygIOy>42uDxmVKC}uDiTn5aCkj1sm zY~b@aowB9wx!(R6Qif@-1}RjY$L`~OSVcNIVU+lJg<_}G#R3dbXiC`P}rkI_ju*&8j z^xpd7rCMK(x;#s~8;@3nUg|9eI;hH(Hw`9stn1^~XI{IpEh`Z|^wcebXYE^n;jVfr z$tK3wr|an*IZ)2V*{!+J=3Q7tgtAzFk5s{mxExx&XM2Fq$|wm*kIWrnDrPT7xhH+M z4jDsN5}fN%(zPfGPGZ_aPoCPsMML_?hNL-bBB)BG5#r#A-He&1IhOe9CL=(s8$=ErkhDMDw+))s7)rV?K)jXS+|L7#_TU;C> ze_LS?IsO^pwvs9Jm;4fY*NX~!(X4pfF!CAZG>6WW;iSi=#9ijV9M&-76%UZH%^bl* z(``BRh@&DM+#Ud)TX4n*vLmS(MH&Fo{Of;ITE3;y6x$~o6MFS%;Lq+1zbxdi5!^FcEz&BsQPO(lu;DJNB1~*u%D+KZYgT~BcF<^cG zv}v@wH6VS&ebWVCar?!yb~2Y*{jXEo?LjL1M_o2%&1eiYF;_(XYft~X?LF8>gOiE* zN!lfgF12DYwRXkIRR+u&d%9MVZ1Rro91@PE6tuGV4=S__JFm68kI#@H%DZ9BqS{T> z@kFg!d93OMhk7eHNIEd*)xa2ARU3bf>sHnK6;4!;>AMEA(G>9&L0`Qqu6e@ls zt>q0Ld%k`IA5Sv4l z`agJ13N}$!)aIEfbwyX;O~*{S0YJ$+sbS@4mHP`pOmT&_ZC2gY3fLhvPA_8xbsXfV zXkH*2jpLqOEbSl?z|p^np=6yyP!VDhV~om_6PESiT!`8c%hcOjH-|vj@@~_RiQFlQ zIOEzPq%M-W>$STP&&iL#dk1{ENkUiOd`M|C1@S4bz?iU1H1+;&w0kw+| z-61zv-`m`kz(j6eM}^9v#a3YtB2`NeFchNaHwWU!`RCABt}owvX93XIC<}RC)xE#m z3Cf?-fm=b+qL-7x?18>BzF@Wkg=>g5jk7AC)+WP)gpJQ>Szx(r?o`Syi)Ot@lT9~h zL%c)QnqHWgn(jB#ndKc83yzn2ySZ=?0^&GXOaMJfF`F`rYFlq#@m8l@EzIH^HDnd0 zhVs$;ep^(t{ZG{bDloRRMlttP`J;LeEm9>PtA3<@wCcJ*n&zt^)jq~bHdBT)m%c9x zSclU*`2Ky7<@}9|V2BWr%zY!}dlRG^h5*+Gp55d^DbtkmLdRo7%KffT0x%5FNS_~foJG8 z)%rFq{}Ty}=tHbFOkFd@2>HlmuZ=}aC64tMc8*2lAe4H?;jUdX{PLMQ-6Y2ZwBk|z zgFC^Ygk3Mf(I$rxAbJjG()i^9_k`Ny&)XC*!%{@|C~-Sg$@opwTNc#rVTl<}-?)=I z`)3UDHak<{!ckJrU%sns?da6R8*< z-rrrz_LI_8vOis6_*nqnbfB7Qbo0=2{dKp7uA|GDE0WZ}{L(9r&Xkmzup+<4=X@}C z3wTmYF?&o)6@Poy>{f5vP?GiUqH#gcKXM&Wbz0JEKKGGDZ||y94eL7wzI4lQS66W2 zyk|2E9%lP~>_H#vlnZrJ0eVM9s)pF7TyyB*($yQsdF#C=hniX&*CBgtZA&h@un97n z5xuKFo_HRk)j|)cwTOb8`jpOANah>3)@e{alxRzwB&{+)SrgYJ^tij-#Qi4T-@0h? zFT*NM;V9VDCTg^RFxxs=>x8`k`=?J*$4PG`aR@UoF?DS?5%xtO-MZSy^We#PLLI_? zS8Mi-fykeG6Z`Of=;dCdZvKnp{tu!3kHW&r!om8#3Jb@7=2ibW{QvX09RK;G=>JM` zTXnRZbw&_pnAMXHP{|blwMpRngJ~f%n-W7}Z6N&lc6i(KoKLSO z!Kh9eyxne>eqPqni}BfwlCT5+PW|QmIyfFM?(6jN6_RIndaD1t7@3GCXYxnvd^tU! zbV&fqlTj4uGdv2)4%x{0b$EPvy^$M{ghXzWcjuB3!s_`kZD${pm%6x- z=jILlxA@Szd*vDoP_(CaGh-5?YVFy)q4i-|5OV+Ho7T&9&_?fW^|)(nj3Fbt+IjP| z`uX+vMC#(b+w}vbuYdRI)U?Xo+7l=_WYR*DOl7-X{?tNNJoH+_*BwUaw|=v7oZ}A0 zXT@jrQNPpAA(o8YU-cXO{W_wjS z{9h>|*Wm9Kxord6ASPal;;yZJOYq>#?UUV`QtzIVg`oD*Q6^Ng4iX*^@K_J6#*5JWFYj1qoo zzOiCipsV3Vr^^7gU=w&oEYNQgi>1_K7tGlFbww`K5~boncs*H7P%`WOC`5esZ%^72nvvMP3KI2(5kj)$094eU$Bg1x52q5bnf}S}<0v%8uH#m}nQwtJ<1P1Y{ zCdz>KV2kWTSX0zQ{k}9@z{}(s!|Wj^B~-Km4_md(YK_}%XfDaH5el?)y(j;G5CeMq zeo3!q(#a(!6H+Io%_ML=;bgLV(=R*?f*tD&i65J9%Cdcj=kd}_as^18)occgfs-49 zfdfG0o^b=J!<{hN1fTbx&NPYl_qSj}pLR-eP-k_plZpGiWfvTZG%7)QixYoCk7hHBBwJ3>wgFEmwl5*WOnrwMtSXpBZ|Fn zlozW&D9r_r4&Ckz_QUYuhK;0m7nz2{aRT%FmWn}ftmtcICgaG_LxlZB>t8*G^Jz3fe<(8G9 z_gWJ#c}H>zTIP!qy${*B-zo62_X%R z0@Xuo|HVg4{NIBmb*3=v*(-=Ynu-51%%k5d@4-Evo%OqR^WZ(=J)j306Yw+kCUUqfy8Xf1)pn9<&1nRhwB0ZtAm z*{bU%o8Z@SS5ew>S+FBS?o;h+w+S4>IO9^Y!7@ZdS96v8U-gCeh;(z@ruf1OS>6Fe z76Sq%I#9~z0A=8DtOnw9DgGNmy8*=ze1}3jyRByCSL$g4$+0z$pu|W%Jk-Bbp#FwT zW&#_u60^;}0CwD;N;yVkOFtiNrNFh%`$~t2Ib;-YR!U_|@rXr7Od5S8FpS)LjXRYyGdS*Q})1o*m=MHc_@M=CEREDFj}dk3@^UI zygHLTX=_eaQv$h!j_90={wcD<9$C^2+G7*isDX1<=h$XJeGy+X#nhwEvRL9@?&W}x zC_(VoYf}9EFlYO)Y=X#h!kIyhOwZPUwd}ZX2PE;SOUuzeqE`Fk0?lh^{dQ-ztDxZQ zIx24e1gKjKOfP`l50QCj2gu{ZF0mi_EK#-?_9Y@1?J!+(maEKA?s>BDX`7;R_W0ute>tNN6);rZ>pFeBb zTg{7UxteT6=H8g6ZGNtjdPzs1j~4M~+FUk|`#{a`oLU7`m12N4(`&q-ZD9n$lQ!X} z#dH)$E`8gcG!XK||Hs%n@QN0$Tbj$ZZQHhO+qP|EFWWZuvTfV8ZPq@wQ`PC*O8WkX znapqCeMU#MempOBlvoc2YubZ&U%i2mJnV~xfTQHS`0y|Y@vLH7tyR2<( zqi-3HixFNowL(GXA^Yyhjr}u}co3IzbN=cF>VZMs;XnAnx3o(n@Uw7(Z;zlr@DM!c zmj2Uvo+c-{hH+e)=Df9!On|W>S7WfJ3%aR5yoOI8>tbsxjSkz4^`x`?E^NIvT;X)$ zFA>{@QA(NPlT@eF=F>Lh(-$6E?g;6apmXN0oCxPWL(Q`^OMWB*d84bMcu`r?KF_5z zoV+P7JHnqa%cs_`I}Dm5%x-~i-!wPbxWzz*D|I6t4x@C5#}^{8!w-`~t-w!~#;HSL zk^+NEhNSr3tQ{MVFl`-^6w}3z;Mo&$bQDqyeGl``IAM4GCR`4kMAE(=wZ-=53PO%i z4tzYP_C4q8#~A0_+>fU&(r*d(*@;m~r4Zi^-|EDFEzPF`e>!l7D{W3?zu69eiQ}24 z8|rK_4#(tnE^;{hRr{M`R8sD-D8^lam@W+nM>Mi^jevPKQh1{&#pGY z$A+htzHPdW(q-@qhQP<~5cR`gxXX)hhgSB0e&KXQ|~= zHH%o3^H{CkbCP=;p@~`Hv{bqjqY<>OOrRgu!l~Ec__WdwK8(R__h` z%2A47AB2}475pSVcjNJyfULKU3ce7Q?Le8OJKfLo`6#N3D;(W5h@f#&aU3H;s756m zMln{B%06*dgdr2E{d?MX-genIO#0lzMgFL=Mx81_jxX$rV92D^z@D=_FWp|#VqIE( zvh$wJl-sF!B3u$<;;+El5BIlY@YeNyAo#RKpwbvqWHjrQR$-6!pHMq2CA!s%$7f)8 zOd7A#Jmm^W{Z?zdhyZ%vgk;2F{=DXHwe>-1aorW5ETdu7jkmz8-F5Lb98T5SM7LZ?{H>`4By(Q`%X_(CX4{ifT8({9Wx;*T6ITn^4MRU8Q4zO;pSOaeg`oQ z>%>m@^JxqY_E9hL;oeD%c>-!JLY-oult>12(`Oikp)L6PV2Y3{gW;mq^=4sa*ODZX z2REsj45EJ(z}wY=&ouf<4M$cvo(h(iaqKfJmA#>)lcdAH+($nt2J=5+&;yXLz8tTq zWCg-J!taM3^T2tAE@OUO9X-|QA70#3Ro_Sf>kk4r$Rwhlb=%_I>E9AG#Z)1lggzYt42>rLbZ&f++h}EWB*Ivfm8Ry zgKtYt6?qOL>N)Bbsgq1*=>s?m z9e>C0+>F9_SX3#nH%ucTP;kQP8lGtHcJGimID5-Cc!G_&9WzFT3biJ*!)z~Q`+j&? z2}=P(($BGs`hx0Nt2`b{)hYCy9?4*Yrnw#kYX=@5#3LErqKg3Oi7FBgHp^FG3QAu5_CyJVq(J*l***G;%kseT42c>fk* zH#_o+$)u=O5+VJ$x9#0Zslg=XLQLr)ky|E$aO8#w} zgevAZQQ;FbgMBe`<}U)%5WV+U``6JO84tA|efijE=!HAx+c+VlD8?2g$9px&S&78lS0JC>b`WJXNNI5{;0dcoCv#CCZo< z)N4{Wyp$-UA6Dju3Ng7(`z|5aM=bzn#Jghr{bE6aBn3I)+L0u2F`5M*22woQ9s;sR z(}@s`cTa?>tDkcGM8Nk3mBYaA0o-z?L7XR`d3hDUtO-O2#T+a4PNww9eD&E``pVxb z%+*(ul?$Ri8?GtY(*h&r4gDK1s)DJ>)f`4oQ5a3iVp;Z2E?d#`$;g|iD5BhKZ;eYvp|K%St zaQ+`+6DQk$^A9=yQx5(A_Ybw!?Qlj>ruJF}>tTh7 zD3#(_h!YBF*7@_Ct?P2JydZ%9RT?`kR&-}{v+UJuPN>Cx7k8s*K|rEzG|&CFvxR%#wEMVT6T{4`T$Q9QzAI}+Tjn`!R??Q} zhIFicQl0bWHQ0{Ee7M;CEH*0zeObEgMf`QuedLk6i28zETJm=h6ECMx>HXZZq@kut zUcljHg_^rt*Z#;RXJwHyH#@f*Vezozc@T@c#LcNg4_YU`YtlT~#U)}MG3-=*jjF`u zAUw%m$fZ_m9<(iKr$!DBFURL=+XYF|fvjwjAW@00o}eqenbDx2ns0P?MT;}1wj?Ko z!OAP}aB4az>zr^#CT_)vO$<}^lmxkvNue-z2iaQ)0{DFw*^wLij6K^^K+0j}Fzi!g z&6Bj0o21qq;cL?))ZEJ}?0RpQVIey#`)wHmnh(mF{&6sT2(!tfd53~R#1pU|1p=ZX zpBqz!x-5&zaKn;trlnTz5YOCvds~ANk$RORcx5F*X2yxV$3w!n6Rl04A1bBJI`|zm@d3stYL4_@H^yZ=GBoT(rHA%IweYC0`25M73o6 zB7_q?mLyg-S^*Z|g)Y8f(Y**2u>cif)3S|yeoxV*z{(*MQ;)-4LChiTIaYGX?Gz=c z95IexJ6SG`2CY5)3YI(dR?lq>Vkd_!5I@w_G-eoM{!62q{tG<1MAwJ zj73Uf7*f@Hkz@kj{Sk3yM&&Is{SezpdtAmNL5mZ(;}?mkjg{S?p(59^+(Y zTRKeBcR2kNP0Qr0f8S!s?YVTu%s-kN9%zIcC3D%MvXy#-Ob^*6ke8NS90lE zw2@HR5SM=Q;H5c$&`C6M-$V-!jT0(_*hpfj<}BXpS1RrpexXd5Y`8{N;zsUxSe)mCx@1J7HaS0Ful^Qz=1_mf!<IKvEa^RkLEBC0(zhdjM z^CEE11&J_z@yUN7Q_|(fsn=)Mui8<((ohu}l+~w3$`gpc%4N3Qjuq_~AT*%|wIH;* zEwrsRQkCuin{*DZ_$V%nQS}f?h4pp`1ld(}D(jUKSj3*oOo$=p+E$!zmLK!xh>vN6 zVmrq$g8rc8Kq^hujj`KsxJeNzqS zN3UlIC{s%4!eJOzQD(x0d`z~l&1Ja!rL|GUPsu0rgLGEeJqpoz^MUSQX*8qKg__}^ z3qlrd;N9MikU@XFN$T0GN~HbmH=}~fbC1JDn%r&0Z|1W*x{oSTi*_$QW;2GTtX=ZT z8+$}5-w8C65im+sX#(!!SUcV!`!PawG1hSGD(0E#>^^9p{hjpA74RTdSI>%61p7~# z23aH_x__I{{Ls#-rBrXP+eXWRiupoAjF?_{h>b9({}ENBXm*N*)ar z5SUNF2M{4ojmvLGq3e`^`x*}C4i*KIH9~@g->7Q=YVr}msy+6eFfGwVfs;|3%aJWI zjo^;qs0ziQ<;5HIESjh|bb;D(#J3lGNRW&F1kl#+5Og`th?ex?L!#RbX0I4y+jjgb z=`%Z5A02Xo@QT2i;0&agS*!@#(y_*h(AHNdB2wT!60j)>6L>&~2Tkaq2oE7>pt0;B z&f&8{qEOc4nkJLP0>odiAf<=VE3YuK zuFZ2`6ItgTuH>YJzS+fQWuz4^cZoGA>N}1n#h`#4B2EICEsT(~DmEl!Z9)8nE(2Jh zk&VFVAY8@iF8rh9jlo8>R(OZK^LN#suU<_j%j!j1K@m-ne*R%t^uiR*vx5ycgt)E5hAs>a2Sqw;YzItK$ zM#z-~NJ!RNW7v)z|MTGJEUSo}+D-vf6Q8ds|13S_kUG%L0*xBfV1~+XOwiQLUmP6H zr!~RO)Er*$rFT=|>Y2!|^*!;#nn72B$wAP9A4HqQT@EA|7;0uHCN_Rr6vj7d8m=WEli~Z=W^=#v3B`b*6m_@N%^IBCQY(JpWIiDb zvjZ1yp?N7s4`^68sRl52Yu78_}oe&oeI-@d!|8B~nDcG57*FD-tGZn8{Qxp=juooRNKD?718(_l1uav}+ zDds%yRFX|05G&Wc*3)GQvFf={P!IuAB6a6ERM8?>9tj)zpfPlY+D3W7HlaY({I|OiE=Zx|`gX4YmYlhqw zx}kzkt)gPfYu8rkPi}=v>o{q`&(Kj=EtSX#)&xrFjn)*xd+#oE<|#i}?X5{B1XH!# znq^G0LFqvJP-CvN$Z|8cFEt&kkC3w_RnpYF!CkHm&aKPi<+ZQcqV)}pc79cnN-SnU zQ~Nk^=FyKCuFL0#q3AEpXoge)m3n%NtuFpG?I{S#g3%t^T@A5Yd8z@XL%!6$ zF|$V_wd)va-aQ7xhXB{-CA{rj`Rj?LVRnbQ7zc|a8yz2dcILa=WDv{ji#^4)cjc@9 zI&(d4IwVy8HGgkloot3V$T+#9z;cTRFIv-XOR=HXW1`^VE^A;a7cr4A|NxsX({ zBok>L8(xbbv|+*-<-WYO7?A~6EXD1$fBrsLysA~5{ZxGPSM$E;(0?wjQ-62RAO5E9 z$K`1_czGX5?lRclOV}SIo~o@^Kp|>T@rdCtDo?P2pODZvR#uA0|I>P1&R4wNbW3gx zl9IEWnPfK}t*rNymc%myYNR*loj6TDjoFo(wAJH8b-kegzsn{A5@+mbMy8quFRg6! z`T4QILknF$c{tqlUeVj#>16 z+go=hSFO3gEn-`@Nm1eKG;}gh^(W7V=cZcRYI=iT<%EyJG);rX*7oNR_d-ai=eaw6g>8ZR`DtYd~HIxXcdx#>L>wTLW!+Az86 zscO|j*IO-(pE|mKIZjP; zCZGPcBAA<(eq%MDM}izip1i!$2mfG^>vIxpU>A$RdkM9>Ae zI`8kMiNb+D;ZdBa@~|s`qo&|JyOKpVh9AowNqkK7DRDGj+>=Tk-_q(YUTAfv>EDr- zI5-cHd7;zL^SQWS0jw1+;iiK3(JR~;FwvvI_nXU9H@z=dGtk6ev>HX@%g2uP=x@(^ zLrotQ^vnC%jk51m_=|(?hPUO2@5&o);=!%DXjHBSp7sx|X17gwdEaC@J)DHDr^8Rs zrdhDD8A6QQhbD|W%^$`1jI9GMP%rb$)lNFTguvPrUSt0p#ofNX>jLB9m5dSLVdEFrKG zKqN=;*X|;3>&<#j3PMzL<)9TEFYlthyFYKIeVQ+MD({c51PA~B|@seNJf1knh$xj6>C}^lRMGcNYsE3~&xw z6?e(CIp3UXFnhNaFV%J@?Q$+U=aO3-*p8vpNnq!tzS~cWLibHFi1IB?kgb0q`W3?J3| zFMz=tHw2V|&kW#*LK^<7)Gv-oS$TDSX0BYtXLj_`3`p}`xe7ks=YoD-q)QIMVEvY7 z{o4D(xfS&CFH#vK#xv{Q3ZO2>e>`r5r|&Hbmh%hOzYZ9$HYpB_%WuN0 zjC|i!pa5t_dZ{Dk)>hwat!&k(e^BQeKHzbwIYOaM3Alod*-eoOyD>Cg_GH5_--=uC zG@o40ztd^T!Ce#;rzQw;o7)aly&1kvpitk>ImVRV1B?I4)eB zV5-2w0Y8?kz&di?+=$M<>pHd~(Tp-?4X}zziWI!m;x@`taQLCmRQyS}mte(r(2tEu>$K;nJzB|%upLDwm#rIIH@vX+oLgkVbAdA**f%)|ATKxs? zl&$Mn`&IOh3>n6v;~*leM>zn8HS)G^QH zBxP2oTS2NJ<%=`CtF_Ui%cFB?;nKmgejWh_e4pz!&FRk9oL5hFYg^C8mR~2gx06H5 z=G&PPP1}Dsuk-f}?`QMJ@V#uf`}+8B-5RQ3a}}k>*@+Uj8mW#lfE`N1GXM&$pw708 zRg4BSRt^-+CSOwccU;SDru|G%%WY)8!r}~7sn$>1{zFd6G6y(5GhMp+dB!L(-n46m z$%5#F8(KNVnm!u5&c?jS?ll-O|3lR)Ub0*T(QqTs(pGIq6BdHCoM&x^gF2WMHC@YV z0~;IGiW>eQ1|E5xs~G&|$pzMfaRby7D;t)|gDfoBsuErg_!3_Un0veX*~0sngs$@5 zQ@BYb@ib&qAisYHN#~XRm~L<_yUNjeo+^0$>fEL#e%+$^gZ*IJ6H~(YhA$Rc0{s@b z8Xkn>2I25qT8UtDV7$00g&`p9fbN{0EfbgM&w3w52?5D4H#{WW3ArN7RYfeLr?0Vy z(uQ?LN(O;M~?VFYjZWG|xQ2v4H zjl%$%_yb-V6e$|Pg2bdu>;%fR9JP+bEzqAAVxdn3d1?Fp^}X_jfNs{u$%i>4Na_9c zIC{bUOKw#FRjPT8CODB&=N5F+E6YQNa|mhW5<|=Hu`XVI!nJ--L<9F#kEjK&m2aTf z(&mS-PL^DkkzmKIvc*Wi-UKDbvP#BIbn;gsd~5nd6btZlD#a|if&TIqev%rAM-p2k zWv>KPAods;Z7&G(qG~i!V;ws#(7|yN(3n|diK5Tsa#BLWK#_E);bNp2HlZYUE|e*~ zAg6nu*R0@~www$cr9c_U1S(@Mr!jkMKVD zp?s1_qG9c*&kVPYeN3oSK<}r2m zVNo*zxibICNCl2IqaB0mGhEE_jyyrCVeC}d$=?B()9_HcJ`g0sUVW?Z2>to0O9{H1 zxB#D?1-?aLe7aWbsxnN*Dy@}L01_|IP`86V(3TtfJqr@!&@$tEnty2t$n06_HT&^Mvxv>C=AG zFlB^Ov6u@35n?$i&L5Yq&qJ)pG_}707Hai-IWPu+(LtvoD;HscEXFQ89wmp?$1Yv$ zvJ_(v%}`s;FFXA(x+J>JT&4^hF{1iY=q97on+4*?Se;GwgzXQs=_81iX$^ad7Be^OyqqJf zBQT{$Vna43{4g}!A_G%(y(kYER&}@!fFYaZ^qJ_dA&Gc^sj-z6|2>M<*}uQdUU};I z;mw$M>ki^#_-$n;&_|bhrKF9JfH| zcI?|29o&tcX+ADGN`Yz>2}!p0F8H(xdWsBPfhEl*ruSj6C_9m&gW9ZyB zT&Gla(g%gSFO`%%Wa*pEiG!;6*gX`m*1-dp(GwQ!i7ULbu&U^Z%5H1VKZm)O-khyX zo+Xb|T3L{KseCkgaLaomO}tJDI**G2F0>_T_3*svV0=ZsxoInET&Uxt%$S#!Lm+R- zGk;Wispfq7zj+>@3&mN(VT;$G0owS%b1k&%(2UO1-kkJcC`Uxl^iJ>}Y8oF2*SN)e75mp^vc-QQFV`;DUgL{tcx6)_PXL^3fBcMWv;`i|Uc=^g&7yVV!ZC3Z z96jsSZFMj=R!WoDT^@`N%XsLr6GT8HuRxO_Oz4@NvWbli97uy0XjznW^-caWMG!!xa899 zU*t5SR|M@pN{+D1(jL>HTipTS8-3+I?x4v0VRbX?h0;{hj*baPVvj6whG^i4MFk8kjWp(smlwC|7J4GZ8@_icR0%0dLer#2*kC-xX2CN$lFPk z4xQdcgZb@1!kG{HP~qjE@%L^9RpiE-%!-B6t&J=_b+i}m8d!K9%kbSx$)w$3OWGQ@ zkcd)`PnUIv6WTEZ%khX)9CK!R`#dp#J(t3+oM*!l``K(M};j_5|tvDK(FtM7$gb~tUGY>JN2mXM#s;8_{sReI1$UWV2 z(eO7;0hP|83YX&Nu+u08S9{sTb=C!brXQ#t_=K43okmK^gC;Z7#@>Gce8^%7&Sk|X z-0?9vhv+Mi>&YWUr63a#g*k;z_S?1L2ViQLcMm)|<$L3)YZ$xA_ZO*w+NBJrF@I7T zKtxqJgC>vZ-B*Gj3s0I_j5J%ju32GLsF-tf0?Hn z3^bH>&Vtgo$k#+mr){~3ox?I6>l$PK=lf1^iHj@1UDgS5;(=f>9qXK)*@FaXviN~) z1i9HI1M~;tYwQwGj!Ly1qN1xP9{gYjTH0z0A&%JYj68(WO{o1IZM)DKlrg~&vOtB zZ?Z*u6B8F(NzCO}=V7}0Lh0Kve6(R28=5@9yur|LwaW{w6;f6YpCgffwF1ax6zK0+ zbcP2{+_CjM)W#Y_N)_L%uR5X@c;$+A+$6;AUo2BBb4n<{^XG>g18oVLudd4*m)Th| zS=y^A0Fy;4f=DfZs*ZJ0z(Yh9IDpeCD9eBw&ZW)4a}!MT;I>HXq69}*pu1@nYrl2( zb6RQ+jTXO{DW(^+ORhWuOAT~FK6i&}3NyV4{&UABhoJm>1>(Qw7~+QRn#Ah|3Wm)4 zz63XRtCM;92{>kn!Gj!mvLg<{7zY+wIFWwlWMR%kA8!{;1PUH^+dEK{tOW4#1)4Sm z7>a}11b}&$xAu*T22P-X6JWMhD;$0)2%k3y>=1uS^Igx~_ce8&&gnj$jOws)Ci>5~ zhav03N7+(b@m2P5eP|ji_lU{{bU7Q6TE1j_v@s-oTRA436wj4C=B4@wxH>&PY`kMk zSA9Q^J3fqlxL17l(CNrIDdXkagf0>cTmiEl`bMzUf`JxUKfi{di~~|{InhPhXM_=t zBnn9KC>;cao`vfcm0~xG{QMEMl^{wHLTjeTEDF*>3=)8}B7MENF`vVLlb^SP=N7U5 zA{tnJJy^pl!_tsedntU^<^KF;c-tb74*T}er6>`4FM!`5G?;gAq#g%wP&Fu|2Pgin zEY{gkJ48sFkA!@k&-`WAbDD3E!%5yVD9-#$lq1n$II6>mIv_?_r5Rb>48+{vOv$o{lYVYZqtx*U9_w;J9ddez(QO`3d~%eq23o zpzbrz*1!4v>*wWixJ$i=!e}R&Qotu&v}oflvW~N;rW|@MOhgiSoaFv%#BBm7Z_4$~ zyz)!}B4Ip~z>l6Ll4)bHx{T81_MiakR0A*;3U7xtP;q$vkM*3yOsNxR2s01@EwZj-D*Ez^DL)6*uZ1A9L~qNJcff z0~k&Gm;6Ub__jQyCb~ZEQQHIl`mg%4Aj=d}8yIj@_eP8*mps=i+gZ#7vrc$Hj;nUO ze{2wtSI$}(43T{J>;oghKc?An*`*vSjYxvff$VqDu45fkIurD049aKm?!aa^gFuYm zURs(`kmB5J%MEmI2)V9R3|N13m@u794s|{u*2+Y0eKEFN0iVQX0rL^BM_%Fd9gl6> zpF_vYo*8`=Ol_(}^rQj_3L&5LFLXqZ6_7@-wWCY*Q`8QFydR(QU+&7teg5zyd@kpc zwAJGfa+x&mQJ3BSqz0(I1Gg=OeeQvP;{)W(m#eh(?S)WDNC(G?kV2XzDp7hSPz`6X zQCP;*rlF9*%}C_SmEJr~fUx-N( z!W53l)UKX9+enjxcNdoUdOBJk>xw2}ys5&>nK?2)c$Tf=3PAYB2N`(6DO(0k<;9oP zC={jk!nD(=tBs081L8r9+>WrLMV@-Ih(8TB=@RGf^!$20x!pe$QVMYky!9wda5Je* zC-+3rQN7F^a-5UKrK_K#&XV(eRs_2XpMjLzyHn5~TL+OT02>RF-QSCiU@w>Q4lALd zw;E^BcZu$JNU^t78_*wYVp!X5alkr8U*;+)DEpY=t(7ofp-jrN6exXk0_TeQx)n$O z+%t%$160wFje|lm>23w;fhw(TU_!=;k;{TMGbBr2M0CWxk;66!EwOL{1{`X$eLQel zvwA6lNUPbJqT~2BzA%Ho_;VCswn=8qL931})p%SF+8{rbFK$3p{YbbnDqd_geB~~) zLM=X$j?2cT!=yp22gsbsC}%Y&%c@qKr-rp!qt=|MCW1`9$-<1!;RM1cCbcpOa#-|? z#~gPUDGw!uk9#_^d{m9>#I)#~!x7l47>fJhWMD_VQH7eKtD#sQh9E~ioVHNma&Gv$Ica=SzQ5V0{UK&WTnfS}6{O+Y&Pdpi$ zXk3e;crUJ;V=%`*?a%t3Og=OVD*lirvoJ-%<(YI2iv!@B6PH1$%_L4$OPTfJ`XoG# zzDd71zhzv21P5YCciL+cC<)rr;AN}Jg=HqYQ*6l&A4#VW@(F@YUa5qId;-Z*G)l!c zyB0*XK2_*e=}5z+u7T@2{2t@fF5r>sO$ZI7aHN(4k4umpykFg;WC2s%9??5y;e|mnphSg-U?cZ^U0*l6HfJx$F%xO5!ruq_8oIIqcz5iYUn|2xwbDvCjos-gyIKm!x&y2q+^2yX6d=~cw z)1hZ85r{Rq2F8qLH^#J^@M_OoiV{_Y_V;EJJVowjSKR+xG432!fSc@m}tQ?aGo{W#Z|%LP>WthbV`#_SCC&Bsd;Aj(YrtWAh8N zYFXmh+1S_SuNV6qJh-U>>Pfkjv7~KjL5cQN=HXN}zEhZz=}dE+x#XjUecXSiI6RR((*eYioUse>Ea&MYL&VI>pn*tos8N|6Uu-9B6?tuJB;l=T(a17e* zaeJks^8R4o;CuuX$u^EBOMW@p9{HkM&GegEXLcVox|}t*h6|IY{2P2!d%zO70njkA zYi?0!w65R+koWagx^d?;k%wkFqd_@kl2oSbftQJ^UcB@Fa0ESS{O)t1M`b5y`c8+cx4vr{g8FpsTx~y zYbV)iETp^hJ}kFNyuM6NsM68Q^u@1jG>uN<(F zqII0xBmZDLTvyLreRhHm+ERJGJ6gor91kN*INg#E4~8DL(`=7&7Bzf_)jeF9RIS!8 zR9SYQY|lU>FZt$BnHS>bq0taVug6_1xp}9%r4uJb4Z=3|<(G~}=u3dF&f-N zfWU{75X`lmp$td#8SW2Q7+|B4i!05+HObyrC7t*(h!>>RMT`n>y+o{ve}TY~HVtwc zOuRhXq)a-suq!=ul^zkSg-bBlVod}v?%O8KvkzK1aHv1QmugnXw~M$3%m-! zj??wM+YM*o?sK&hJkNqm*YY$6l=9EaCE@AeOCqgF{MBoxm`Dv^7#|BqXMivfw&>U; z(Os-NMeoiRcp{!QQ%frh&tp^vULh2Y*=ea>i>dV2^ zQT0yG<~b!uog)J{|0|X3nT5Va{?^SK!ehxo%Yk(6{Ry>&&^IJvdK#R_RE1XI-}? zv=Rla`uoIgcTeT}=+~{`!+>0dSc-nTmL5?K0q5DpO4;$sc4-`S=<&RcA9|VN6Bvt5 zJ@F=8gZTDQJS3DJ>(V1xANyGTI?Hu&3ED<5eIK?<(Jv1jJv?`alc(%Ofw@a*^lo@N zlJ@DvdM#nM6O#$$Qsx01p+LQM)OEk&T%5-^<_lC9_1j_ha&!7(6z$&z6JvG#Kod;V?9gtz<7YG5XD0KepgXm%>P=#ojm%yh6cc$MQI=nb71SYC+nG}1B)^nO_oJI*ZASuK2(KRkn^9u&`1S-~zb>TcA zj^9V2>k8!fG|=HNQ-pAyQ#+#ITaQvc9B5x}Bsx%IFfoeItt$!i<;HZa-M=U0;E zi}BDX7Kc=YV-;vunhMg*H9AV0;%~TZwuuXVbc58^XCn66gQ2verK{K6IQV~^Hiogt z`H#y$8bENYugtNa@^Li|`f93ye2s>XfTm=ixkE=@J<6{=e&ecVX@5MLSePotRT-s; zQE#7z3ex{da`W0W=~9GIaBqL2c~cJXT5}Bnj07d!x<&vN69J4pHTg^rT{gk>Gggb2 zD5%ePwB|?~yBdj(vXjnjk}AA-c6e-N!tOBqt%nk;Gx-hg-i}$yik|Tf%DH zIGZ7_1kh5D5k{Iu5J#PP(VG`u0wWC6Qi7Q+-Q^31@z808y?pa(FAP&r81{%7LMOA@ zOAasB>~S*;dVExUOpx7Zn2wqcR!pc55&mQRiki`PuBJ$G}vNB^||QgayR=&ZmHsvULZJ(ubei z$4n_374L~D?<48QiX3%B+Of)8W_723>d|abmCn=Wielefb-X*H34XDrauO0DuSt z-OkSZKId)b6@;UXCAM-4Is;Ahl!}+R_!Xwj?jf2*&fm8Z{I0wmg#iEx9`e=X1PZB* zQU=+ziK8@3fIFbFA}nh^VbUUCbncGc)Ds5dQ3m+lIVrXvzJdepy^wZ+{4yDM0?aprjfHQD^37 zkXe`6u~v*h0g4wqXh)J0kafn;nqsp>gD}j}VTVluVM}TjPuAB_x;wXC3kq^@P1G8~iJ_be4S*UG$ zJv{?az@MF6^U|@_W};pFSPT;?WZ%{NkH`?$Fc?7T(2skrf^f84U9omx`cq;V$Z{4I zdt?`gA3CK&M1l;0cJp{d3U*hC8}R}{A1Ki$PD2o&b2?829tG^l$YNKQcxc1IY`;2A z70w{33imx1lH6Q%xV-F_K71Pkz^BBFI3f5iFldYrU_=8!^qQP^W|GJ;%=S?&GHfL^ z(g{-g1Th+8h{4#5kYpYy#gG=bZ8kDT_9f-M0-Ck-X} zffB|{z^D{XKx9qary>d!&TkG|yaFmJ3K+P56TRI!;>7`6SVMBBCV{%93g{1L)dbkc zFf-&?aq)nb)Pw_dbd_R;8ti->TEc>#ca%+qtSQka19hrqP~7J70 z;sp2J;3VRIQ0`>&1oRFEfCp%w&EEFbRNybU3nKIE&%a_XmR!|DJoSH_-+y4uK@@lS7HAguK886E8gAq z=;)=FK2jzutMX88Xy=Za>{Dsz1brNqR%jIzbIxWFX_zVBxEg>ffPR4O%tR}4dIelw z@+}_~%^@=6UCt{m6s=#n?GDW)_B7wqo11ZQD-1*k8;_#kOtRwrx~wTNT?C zO-;{C&qen||A%w&p1q&FmH<*AnizAb>WAF`%`9Yg;2{$$Lv!fIeJPvA+1dQ*!~3)2 ztl^(BzM}CyYo8Zb0UBiy{{>!L8Wc}Vv3Jv@ks^1Gswv-w zo|H3NJ;PY}48)ZS(y<}<*^wn-=WCMHhXVL1dJ{c}zHjY_a9F=|6`HD-P%=n%a?P%p zaYOKlaR%YOH5wr>vGy8+HzZ*xMBRV<)Mm2C2$*5`@l_ZW5GdFrZ2={iCKf2y9+20~ z0f*Us)O!+Uj`~S@>3^>QLRJOwij@~?(a^mFh=P_ zbD}SPBbI}!f}(cBd7Iv56LQ-Ap1Pd<4MzgYgm0t!et7gUJL}8q)ia-YE;9@n%x+uE zmR~dknM}#^JB?}fT9CWzVJ~dDi>obe_WI*QGI#rp@2ma&P~i1sz%9#o|04yt7{Wy!2=daMPI zbWI~E6LdFEG&)B<1m=H03(m1pB!#&zMQva0Mf3gaD248i_sAzA4fne&JQb18>DJ)* zZKN)C=~S!!L)&MJxEKih$#KOa{bpL(MuV!jf*nxZt9Bs}4t+qs5{O1|;_qtvKHvo- zmqsV53FRm8HE9fn>N_%P{h>Wn2lAEq)r1o2C@8m254+fi_`#H&>XN{FqEoGbq$i6n zS%Rvs@B>MSDe%ol1@)T3->Y&P{^Jj9fY}Ny)ML4*qkw$299`^*2H7NgAZ`&o1V#ySw%J&8n5FkwJb_pavn6&ZcG*ibf&CfV1b9^Resmq~lUQ z6CIzNO9+vgrX{lN&qo$jIDb5an#E$OR1QHkqy2P4mqjPeC?0m(C7n7D^t8s=oO4{l zrq~+PD@6#qp0gPyugM(4=TN@B59Yx}1ezBOFM>VK<>Q*r{&Ug<=EPje%OK^?H2n$z zbEzbHywQO90;Mzi$`TWovxfPy^LC|TentX`QcMSDR7b;qaFuNih zjjOqgf#J`e5axKDmHvPX)t>I1;_g#twkfU(wO=bA%zpw(MbEOYgw=kccf>c@gFVbu znL+HE#zN77zW>n@ZG6$ol+p^?te#5jjvA1_PHn0-F!nD7%pB!Q? zXxAhme%KprBB5D_To#1=Ryg@Fu@clMxtu?Pv3m`5kM3=j(>lsdP(7164a=N#pl2b% zcnqjT;YiI~-lpaT-oIXG)L+5$43)41 zqugQbs@nlVBF*KTxvDG(2(P%DSn=QvH*YnO9xJG~oWJ=vA*K7u_84_jjw9tpDc1%%wGmjeCXLaC#4^T8y@0 z4R!WpZBj!b-Aal?f`@e2!B&D)srl#_j$p@}|m35|vlW$A@;m3Ksj?q|sQLLl>6 zEqwjf!tIu(#MnO?;<1Pd3^$>rMVk8ES~x_e+^9Y^;i(b_D|2stVwOrQtkQ#(>+_mI zsB?%6$5`vb5%0dvojhI>S1g?thbB|^xeAJ0cN{O(UFb|^HaVpkL8%eyLMC|}o8i@- zWe>8P4XuC|FHB}N^B(efe78}jh!CEM>t^z72 zkbH@cuEGJqrc_~?|ro;AjXh$%*R1|I1%So>_yerT-^kgh~^^Oke#AcdK3 z>)8c+_g4PWROlo{{-N#Y`yEpdDCYO-p%4~xrf-BQmBTITs) z?Rey*R-zcM<@h<#h@zzWE2AivaVpok#idJJH?@X6YI8>Ib`XfUCRjOGiyw!ATb+R7 zz2vB4j@+WM)#)0FCQ!dgn)Z;qfB?)9;b!q0PiA$@eY2&C z=HvKhzzb95Dp|4TOcD0B%Fg*J3fTWvp{)^)C1`9(C(3SVH>F zOXsWyH))SWz&^M;BIt(eqg*uMGl)V<@{Z5^75uzTX?TU!q=*pj%Cq~$xFPuKR~}=@ zKIS%}P0VQ{jzR9ilV;}y1q-X$T`k-#-F>3U5yzoE6ovorZv|q?a*p*HHh-f_S4}V3 zv_5b4+-*<3r7}+hTZ+r1+Q72<*)|&T&0R&UB{B~lhRSru>Nj`79iM=s{vR&NL>O&R zviGPG*L34DrO~-XbwiE=F|6BOyygu zosg-p<`_2ix7)iwi}~~z@azS?GJX2pd*1BLG0yB>hpa#tezfrSY`lBKl?iE`_qaQQ zGg%@q^jPFF#Ts1RE$u$+FhsKns74j7dI{0*y1qMl1Q1cZ-oXlbj&d6s9OTvAkvYFP zMC8TY9eSKSfPZ`Y6CvFlA`A8Q$KA-L5%IZyjLjSRlh#s8h(79gwQ>KozBxq_qW2r% zsy>uwG<1FM)Rgt;;lDuVcOXgS+U`9sQ8QQ?<-Uwpq47MyZuD}7y~GFvt3h)P-+C`Z z>uKSvuVzOsU%J<)G7_iLJPo}0SyvNiHc4*ahKnWtII2~2ddTAKgt6PY#h`TeGe|69 zzRsk`&0H8VOubQZZfuhmb)i7MZu(q$^eMWIgwQbXOi43MN4mv(_o~SN+Dd@rxY*kV zGi+71)r&B!C4-G)eUo+K9np2cQxay#ck~g!g^5lSa?BtNePR@HPbf6}^KNH=muO{- z>7XbPu^~$*%f6u}>BlDf2F*5HanhYUwlW$q3YI9Fp%-y?GQWx%%7K}Gcb3LMmgyjgh+$B&us zQdZEog(q3ogcr+pbZAy=aV=!wtJ3&3CVV7N&&2tS9j@`KX6#T8ep;BcQ_ey~bP6$@ zc-HHtKUn#-wUCb8d9O&nkxGs8iwc^O=Lp1~%bj3br6Yvrm0VmVc5;m@)c8HeyP)Zg zJwXO&lih&e!ch_KvM#b_RxRG;(x?Ug4721yS@^6$4bpUBjySi zc6W6MZ1TOn2i_2PM-avJdcc1Rcs0Im?<`ut;lu4BfjO)p28mhyz=R(WpsmFbn|3q< z*RgA1<}V-Ho8o7*8+)kS$UBl8{GuJlor+u+7zflFM1hPW!HtXAB;$sSmMioar;hYw zDSWacri)$GW8gDic(sb*|5#n17Z&ly9+v2#zHn2=YT@kN1ggN1yDId65O5Lq?zy}* zqkj8Xd28SiwRwIuvHPm#hR-^w;r8iWocMc@&TmSOo`9&3R8?bNjz$rM7^*rE7&*K6;m*U?84gVl1^P62wu zsTsm&!MNc%p*QmTaK+bedyre?d9~yYZsHGZJ;?`% ziExt{MsrLsg0Qu_yzyc1UI8vcXnJmFv&a`Z%sP_?oEPl8@0uG>_Hq9syF4ss4cPTZ zm8V00bRwry$*QZF0d$Q$i%ItIDf?;z_vxZ7O4%>(DpTpWc&xaknN6S+Cbs0C6~okM zoMsH4o|TcFIUYNdyZ=QImmTu7nT<-g7}%5zW5h5F@h?~w<<3V@gAL5vdWb^?)t>X2 zn8}7CoK78Gbt{sPaet=7hHGvPj_?0a}Z z2Qp49ZX#dnOxvE)`1~Sfh4dFGKLFASYvrQ;%!EWz(}FI%7k{!5h4SEM+%?3ARJt2y z!yBZvBB%x}3*Jh-*-dua0mj3puhOCKPYjn6vdmrSd zAGG1-ktbB57QkGdd#1Lf6BrN~f|1=hZ9Bc$%C2D(FvaY*dPrUaG$fjlq;fE!Yzr_PKn(&IXuZKPHv)}hMF&?4xqcInPO=l zUmwiDVu2leScG@#HZg9xMK=EaHFZ~AJnK4r=c6L%*G8pMD*|=NDlJ1jR=rm_88`SdwNa9OLMU~$f2k*wj51;X5;m?R&Z(); zaV?dnbz(QEcYfoF&23yZcSSrr}7@P7D~rph7TXxj=Axy0f?BOXBZU_GfL5XCnULO2jJ3K3Sf*s81ZO~ zpIPY)NLC@@Q52_z46-`V^O?eO49GsIkC=%XjxzGDA`W0-aA*n}5A)F|SH3%M#TW&k zszlW)F0SEDi`15hmCLm1P^d$87BSQHO$CHvIQ7(3%RVJLQ-E42h(&HavHV5ez*4eLMzV#TtDiI=Z!KVZ zx?pm71F%zd=nlQG#7YsB!i%{4aP{z+C#2F;MYUD#)k>>5&drMTvKSRD6uJOethi0E zR=tML;j3O@YsZ|Q)R9Ofw-!9H^bIlQjN;~asdK-S!Idg)WgLDr{s2JQDjhOZmq~N0 zP+|^qKDt!mijzf-B;jRd7AJ%q=dSNXKRv3;9WRIu2Z@n{sc-mbhl#n1u~pmii&0z+ zpd>KD2LSu4Rbuc;kyBI8Vk4kHP8Zzi(^O6P5tP@JD^L9 zgt^6MPuIW%rPkf5_5ZPm5YsDDy?wcf>x!{A=q3t;{)pOC;W@4jQm^Ki1CbG0W z@}(dT*@d7QL%%d4Rut~0l^O5-7fNZ;_yi<hK8o}8c#5|j=Dm!06UxKuML2Kxa zb2t_>AeqzNXt9(#%WA06mlOqjgbEK%s-dqJW|O3Ms0P9}?6ADTLTjXAFI@{?&%K&n zGjkaK7;#w{v39`~siDO&!MLdkqS2>C7}mlum-Z+X9f_rfdBw*zRsBvGfyPx&e{>*5 z8BQc}@@uOg9~T!v@dk!|t@E-9wxU)4!GB$oWp7_5tff^aqcxP*>a1~)A%cE|kBxZ8 zhBY1eef7yUZ}`h%7jny%;ZKZMZaKm}|J>G)RL$+}@oJ(FGmG*l_q(I^gfNPA!z= z5sC08?J#mdWAo_Vu6jv^T|7m}dh^?n>*_>K-->>HwMmRthww%_sjPw(n<(KnrOCy_ zOq2J_*nF{kfK%rpTEoBZLG2Mze#iBSwVKvg<-p(FP)D~4rv$XXP=0{HXLS+-`% z8lFNW_#=}AiA)cyY(7)FMG>o^YTn2nVpr=XGVZi98nVBwJ@XX|aPbYmdf$`x#-Zlv zPI@7c^bC)SUOnv-`0AB6=VA?HTSRDR$j`vx!`>gx()9fD!{ssryzBY z;9?yT{xQ0YQ)+D{lL5APdh`M!f+96iVJ(nQkg^n|(DIlWL(n9Z^&9r|hI*F|F7 zR!C#?Ig|YFfwsg+r^kSF<@s!Gb}jF-$yLZ*L<=h7=MEHx7?2pspYZ}AlCXt|A1=8G za-wq(m8dY6`2cCQUReSPq!D6R`4ZVaIeJGydfr}_; zA7*9b2jVVnUZ^}qOI#ZA*{Xo`)`$Big)p-;QJjAk$XOsUzhosi#e@n^&&XDUgDhI_ z_^M{WragFsEyX8JdTo>&S|7wZxPopPeUds=&0bUVJUjW z-fZ4!EoFJ{_B#_c@xgzUPqX|-r0^f%0}JbaI!jns|K9=7|Cg4qurdEnpcc!z+Q0C} zP!R9iZ~cBBk=!aC5Ip;=-3FQR#iGL1E8u!Cg9YmV(8&x6rL|?hyet2v*BU&>cRjMY zB5Pefr?d@e;B?YMO+fLwK$eELB! zs>_KT=9DX#b;a+sqi?v4KkfRpbGJTYc$-(Y>kHzS>$Co8{=D3D&8G!(5*E_F6f{tB zly6Uima6Ah;oaRgy))(hcOVgZdr=_%9~lyd|Dk)+i|5da->tsxJh}-CYkOz?a_lY7 zi$}|*IXCYSR7Ybb&Xa?BBqTlWPwkLzL4lITXIxL;Oz%b($1sX$r3k-x_H;1vV9`MZ zvf*Gv&f-LI(~!)cU+)k^&8?DCX(lJ?NRr6_50&8_e6uXWAlB?AKx!FQPj22AN@|zY zS&H$8(P*}KdJ_Co2SPB95hwUXuuQYv;e^}hL_mink}}&M^cM)7FxR0s!j|n-yxU=D z_JhnU)J@L)`Y?2$N&TzB8_(Zc0 zt9$L+mpA_4-gtZ%%xl4ZpAxVfHYPgQg$Gf|5au9nC$Z9S0l&tC$PJ6^8zRYwfEXpYBbg=@~DdaOv+NaXtT%qrH|kPFV_1_LO*Y1o2;XGcw|I*KJ9K3d9>aYt#NI ztX3(}#B-Nck}S_=mP~RFo?ywp6jHlX6ocQs#XYpmzAHnvS2j%kf>a}}gBPRiBr9TD z2qOdkBDMGRgKRouSwa18`(IQ!VMjohZERG9xE^SW)n^>n>uc^s&IF5J%c1`%0 zL?R}y`q+@9gn(n3j6gooAn>FZanG}~$w(Ky4Gt+;aM8r1_q5z>A`Iu$K!Jz{z zIh9pTY8Df>7;}(Qk-oS110idW3;v2P#`X}i>cmaE;&i=e|7f&DC$}Uk!}uVaY*v+& z|8O=Q<^9sJ)-jnG_%^ml%!C3|$CfNmT#RKdOYiQgvQS&PcB5I6tUl*ZFxD0!7nw6G9d$maZVhcWUNgqPAp8{Exk5x+(!9G2D~i4X=(kLQ zlS?R}zdf>DwDcjG@l(T1H&(v8+O#`io+&dZ>*qywkOc#%)sBV_Fp$4q(2&z@2L%ZV zoERkM_kKR@%>hqRX3JLIq7F;o4ZysUH6hI&Wob75lnvC2z{A|1ThGXEL5Wx^iq-xFCRlc&$U z8CRcoV;yG{(Ick=AOpzc4@yVW(kxinV)l?p-f-EI8FQ!k@a_PZ5C~1#kyx*czb)*T zccH#x%}C7`7>S_b=$Ma{-tr6djzk$QXt{X(yR5cRJsW>BcG!DB6(F2Tqvq9OHW%38mv}q5>Yy)qM#;(0 zeoV|)S`+Z#H#v9QA((gbfR2O*I4QlwRyUusa>Go@K`papx#I0h5EpDiJ}}I44Rj%Z z>tkcnJZAal+AF9G?Z6h`IjRax{H<^8^E(AIS;>mSP43@>ryEC9_9O17tA34`W{xGd`eWQJURBbV}40sbHsW3X`r}#%>GqMkWYfveMP0ld|y41XQ zf0Z>b!YNQ|OJqwMKOzFC#RM1nqkqdQD9U?#$>l6#Y(!#X0$O$85&^Esm{ zivE^RQ^70jkkIH&;ZJ~$%~cT(??qEEmd9%}+w2V1B|ii8W?6?9H8{|2z~>M#08QVp zQSr#&QPBte1+ESbt+~&h)`lGH?1j<@h6J=VhYI5u4JuM9cJiQu_8jlQKu22^__SjA z<#-KVuAUd^CKE3}4fNAhUHk0?<#N9bx<%b zkV1>Fi>kl}haYdNBb}2Ep-?QY)!Y594?=)RJ`w0r#RUScUs0co3y@+cBS6F)*b0>P z-a+mir8uH{jV!2Ly5DSgr)weK%uLBVCfQvpu0&AWZ}7y;InY>$SVU6w$$u=u)GnHv zm`mnF#9^>^=NeK~qE~eAXMZ)Kkn$&(H2&AcvYyY`tIF~x9?7#-AX;XDqwcJUMPO?K zGSvHP8_C~_jh=EL7DH^g*im*^B#yvA+b+!s9`4^SAgvg=*|o;hb$)9iz5iSca;6vX*N&<44G$L2Q+de4s@UaJZ>OJLRdC5m`LmgO2#9C9 zp4HW28+2zt5hv{q0vl7;V?k@+e0v1ZazgBDF7$lWSM7W#EvYNQ-ze7JtyalE`Qd{v_w1wcb6>H7!UPN^VeVN>{eXlL#jt*=w+d*g4WJzMmJ68jTLy)6^p zy6})Egxh~aQEKY5SA^HUX{!oADM0L^2kCP(_^w=1u#47zwZ?4ZVVpOCrbt1K8!B=* zJ1o~fV1h;uD+yFxDMgkF&6XY=VJp@&0#GdY=9OFm~cVT8x>ZlqKG>$SHX|^mIt_aR^m1w;vDV z)}^{f>Q1V6+=Mf0#wD2vL3WBU&_wrp$N$E$9&bHi&}8U%%1=tJd$Zr%t<9XKMgG!> zL@l}7Mnwr)B3Gh4iL&d=NG2O(%=8t>ydp2lxxs%1jU7x+|L%1b1OVrO=9Rf;bBzk+ zbfJ0Qs9F%^yJCkDqt6ua$jI-Uf06sB?VFUAC`?|hthN}X19ok*dOr+9db2*Uq+VcA z|7%zIA3p*A2Ux-S|Ca%5|4moP_CM+>d-OIF@wptI9@d2R+I*ebg7oRPKzbrNhaDM0 zD6E@(wRky0*_z0MhHxUe5(f?w`)vQn*qVQ& zeGB?|IDRK=^7}a5PfAjADCvy8i*obPw4pSyCoSL|4)WvVY`_Wp>h0xuyX)rzK*Y30 zxeYhCB{w(GJRb2h)J711UGE@}*VmZmMCCpxsoA|YbzC}O$=kbP$v<=Dl9?xW| z`18->@wj2z?zJ>znSTA|Nmoxs;Hu)!yz58u9yQl@yRy=C-Tk&YH!m(6lIds1Hcdi> z&y~^8rnF6_)1Oyuacz8j+MPvhyH~^Pd>7jCf#q*TC-_urlzpSVT(u|Z; zDK3yfs)VCZzDrYlZ*PyjhHkii8TNJYcYF)sIXHeRy&euA8O|Fb{hN$Tj&mV#2@&eu zmBf3Dmn0`lQ6lfI&h9L_#!m zt&NPj<(h>CpBi-={!Tp>=gZ=9g6}fcLqA`uwsSx1Id%Tpjub;qMW^aPk4Lw!ySpay zaGS5YzFW3oC85^pFiIZt7J40h!d{nHWHzdpDi^C01-Ep3uRpXkElgjo$=2_0@(slv zum|V;%ngNgAmFGV;hx^wm$~BSbe?gb$-Mzm0%nsKT<1%dCA<7-KfsN47fmh%4Bs{g z{*t2n#y&PjnoS>HG%jN%klI7m>}zKNi?HQy#$*D>mH*pbvc|^@x@Q-TK(D+1z%DR| z@O;wku_kLR<6SRL##h2tV_C<%h+ZB0Eeco12ZTwKrv>@P@n-C2RfTQ2Qf z<&ke1<%UtOw1gM_ja!pX0mpp7ak}IY<1d+5DBUN4w@BMh9+%j(G!?IN>dAQv;4Z!= z*L(Q)oGK9NilgMw%mu%x6@H0iq=uhj-^~gTGKAk_5JYHlLP05Fun`1`rH|EN5e8?S zJXI=`yX0n1D05xyZ00nwYvQyLpnhD2fI=T; z@UkGCP~FHIM4{m8E?~Fnat|I91y%nZL;Yc4oWasf_rGq}A{K6I&CuO>_=^!JoxPw;uXW#QX3GwSJW% zKDYPujw$TdINRX!9PH1x)5xFiw6aXW7R`}hZWzBYWF0Q^Ralm~lT2j@hV{?S9=t?ebKFXK*V z@wPpF=J%C?oX&fj>>(27CDT!{a=OyrWJS<|_>?$G{)AfQ)O;VzhbeYWk9s}N^Hr^TP zEKM2JDDux$9Sftf%v@D#NjRxlf;)81z6$~tIIu}u{Z_8VOJ3>prfA3D^45oq(w5TK zqH?Z(U0s%U&H{O1v0`KoZJkI%A`qxOzP{+x6?5759LS>da@LlBO(*xuk|NdK1+JM=JHNB_y^m?noAz zB#l4iEi^LP@d*-~ThommWj0_r&9TH#`CRwPe##N?Ji08QT}^IgGzHB0d4&=sLh*hS zd+mV}XpY^sX}=~OP^9CzITD%Q%@;fD(xyWZO+>Baq~+~#uh_}rh}*jraYG=n1%WN; zc?i6}$oh0Q62YFB(}AQqBj9_HN9@7OZS=W&XgBz`mD36sdG;jXDGm8T*in*^2VUK8 zpNa)4+0A-<=~zdUgHT!4*N)q~d`$Y)_)??dG{!+u!`yXV1doL+?}gpj(V>lsgwhFH z*su&eh183BM{x{3{%B)dw zmK1Utt_>vYL4}N(Cl)fw#!wR$rx|_{D<2zyb0Zv|fYlCqb9`bnNa0WUrdqg}zt=(9 z6MvPnQ{}wdA1k3JH%BCw_bciP}Y5rdQGsy;igBDIa6{7X&2E3AEY~lRi^}AgXYHbZ6S8*8(-j)AglLSBY@4gS^|&dSKNC$&f*Q0 zMY0*=b{=suZ@w0f;)2&W2!`=$gi~;&z{8+K8yUS*qd-oPhAmdu&>uxL+~mUNtROiL z4c*K8Tg;CH^Mr(kl;?rms(FLqDd8`$?q+eN(4ZZYySed7or^)g%`TXUn2j zZT&Q@$TIn}F=aPi8n4}7-L(pcED|=VC1nAXvYQza1Mq>4R-)i`AtMOXmUWrt-fGlT zE)MsU5}v>pBhL&NnaUz0OJLYBDC1&DPukQ@;rrCS{d562Zy%aY5eZIPKR@NgKNg_m zNg;3}$#4~Zl8%S?SAw8c9*ab|#Pd#l$_OL2xkZeZ6m33ql4Bxl*zR>b_X=}1wo}~E zAx{gd?xy7=5re7A6tj_aTOvYOnEhfc_Pa@)n>kOReFgF)+SZ_3%h6*rhqVdj`*W=Z zGdir0lq~~QSsUd*beFTZ^R!tD;gTk=@3h(jdr%R@5{<9lJYie*o1q&U&E{G@E`4l% zq6PIo(qA1jKQ!!!331dnyqJ_k^H6&ywQkWA?@;|`GTW8Z+IWtG`My3KhvAr9wpF_w zS6Td6h^A{0gUo9#IFeay_v|62J)7t!Vqx4XvlALkQ}d4wcn zeb-btF<%rkkGcg7h{9YBlRj*$=mkQm^T!SJ33NXV|L~QDN_$Yg`EG5Dzn+*^OVndm z$skOVO!EVEd=dGi$Bq5Y32^T^ZmjEOu+!vv=vqmrWK1<9BpMhs6Yh?4?*XAN%5+qp z4_+15v5lcDrKtr!2Pn@z8_sD3uvAuShLGU9aX39JevMH^(5{Kt>Tn4pzDsj44Gn_Q zOwI(fgvq_ZJ(%XZgP;IkZ5he3s(BYCk^90kJ*cyXy5v2k__-)y#fA+ob)BimnheA8 zjlyrEtAmWa0w={B%etdVJ?$TW z`bS+A(kijI;+&Y)1}XBdNE@cl*u_bSC$8I+^Xfn6C=8oopC*(d8kk3i(198#utK`} zImrYIR{5mMQlm7DJrKE`IVHU2z=;?oDFN-o^7-`v$2Fj~L+NVd)d+~Ri@|Y2ou+X#+XdxyC(rvc ze%dk4zC76%h6PR$JU@Y`p4)#m6}t(=04nXqD$qAHDgeGr4iZxSUHOqW8;BoI{-SA( zf%q7c^#hLa<^*>fvTT?9s|@o{%VEBZ?I|l9o@+%jLwlZ5{UC;*KctX6a4>Hf4N}qe zcP8bx_;@eP%FhXDE8>hlXulqx?l(gcAZJ&q@G%?9T^(lpR#atEi-X=!5F}DQ zn7Wu>$U|4PjLRf_tT_lzkOqoZ*ArM%=LQKlzpLj3yW3VmxWmV5UsmV)9;kV%xt_H3 ziB9egThYtXjlv3(N!Vq+SCb^I=}xH#Cr3Ig=C?X<( z$juzCr?}r(dC7SdGNuvl6IeHzz3%H=9fsEbPsXUTl%ankm~o z`0V)mZT6veVe_Ml$O}^MB2^=!T%fo3+-WclUC)#HJh?1_8y2qvl&xV;6*FP2o(`}o zGHkiYI_~mV>$Sjv_k&z|ZeU+Kb95*WE z#I3E9x-oKWuHV;0aK3EL?4&l44C1?vIl6QQm!iv1-sp(p;d?3^H}YHXxSbWJ^UG0v zli{M`oL)*5VgvnGy%CCVD1D!LC+z!T@xNcS*mn8U**#&fCKD-=cf$Cj-Roj4Ufu7S zA$W`kI?^Sn5cM%!v4jL_SpO)wg^&q1UL9@|a2>VG;LP@IW3ctQ zZ$KBillb-0$pDo0)Zul{W6Hub-X51%@P+O+%8*h_X$Y{B1r8GIS%pCH_RwMxU_+El zZWVHt-VCFOy`@ho4h$lc46guoQB0S&Be)20H{f*uR(Tk@1R1gNd?%<^d;r;CvH_W4 zE4VT-sF}OBN67%<0##kH+Toh;U6o+sus;f;TmThhjkmbMfkI6p<15!{$Oi$2NB%G|mxI&|dl)i|<15GOao3!u$odIw#GjskY z2ZV#=zZx$%SpO%-0nv zDLDp*lq<6v)c8Noj4}B#+OY+PGIqQW5}l1Juj4F}9t2Z3Nhoz$=+55RIgeosOisnC z(Xs8v#32OtWB$=dHo}gu&oeZJ8?~ED2`i)XVp10USj&>xZ50h)nrBU^>YFgMpvS4N zEV4pF+iA-3WOQKTisZ29s#@f6MPKd`A4>_fu@aG=LoU23WVS`kzhp8=QfQ-Tx2%G= zh<_Ue%%aU;9WX=sS;CB1EA7U2YTijRNDa!|6*2O$FMxH5&iMm!6ARLh13B|J`_9jJjH)p0O8F|>czd{f(tz1_33Kns#G8~ngN==o{ zHfU&t3@lYWUhicQ0Cugcqn(;8g5cHbxJ`(Z+gN!Gzyh$g@|kFqV=oLe+;zH<56*4> z@YRURVP*l_Vk^hUp9VVd+dDH zj}*#&HCxR&ajRn=53E`*wHZxokgUiTS2bmU~STd zY!!;u^`ebqj3)qGtDcB|ZFUWMHBht#h2>)A?oZcr6$AU)3}b=B97ZcZ4jH+XbB#Mo z82I>5G+k3v*Y+=$_Ui6<8q%<{^N|n|{CLXLpZZ+*M@?$rH-uzCs>fjO2=7%}qj1!~6@1X}HJ z+-c`(^@8zQuqTaXhE91bVQto|!gaCE15+fyi=9k-zrfPXQtFhj{5AHvF4@uUudikt zjS=Y&{ZupB!L)j_OLtdDCsKHxSW;&{*O_(rWKcS^*y&(3RK03P-GdP^c}klWbC3nT zYp>aKj&K{F1H*+$AZqA*!d(1;9&qT_gYpp1_NIti$*sd*3k$onEqUFNu|)^XUW_*p z@|zrzbQDjR6=b(&R?i3>8+gy09%yf+g;Of_Fkwr4i3gI~snP_VX68L%yLq&fP%OC zHO}dkC%^%66>m+Ih7**XFLr5+2H15Uonq3rx_PUt9)(K^+*iy<#!w4U8_M+kYXb|| zi_n*1-3e6az{=ae1#}+40mN%$;G76fH~-L0T#Q+&w=GGJ~^vNagH zYgX9IG1piCM}WBg{JfbB>?G1<4E|XCisBE_4!B854LAv-$xwj1Gd0aWcBEGYL5}Xj zP5?fRu!e5G=NYkvFV-?$*m7Xs$;B=(!Rr+P8>R)cL^E5n>X9)Er@%OnYoZI%N}2h9 zm^%K!z2D_wwEKrFKFcX82=UwwG}pyd^gTQ{FSd@=%cS6;?W+pF}El%<3RbpeXPor|r}^j3B^c(Y1+`ORuv1 z^xcvnNvs$b^~VWJ;Z;}q!NfArq4DV4H>lV`!vaY*Wm7mpO`i2NCj7hzMb}zaTD!u2 zLd9HoGQlXiW6uG*P0BSFw4?bce1j`rz^l(`8B88H}v4uPb*-ttDXnAy`MUIr?|@&XAnmXngCZE7uo=uCm9hQJS; zoa3L}(4rh8$J7)$P5M{K3`v#YBsY6*?nwm2x;YvGlo-J;=NjtxzsRk*$)gggX#1J* zwECM=0z1Vk{!#vVMC%$wPBeX4-NBVu$**pSlIt4T~>IFqe|gIK88S_$NJ-)m9{(%+XXF*GOLls%qEE#YtM@z;{b)`)dI)f;@) zF*~L?c`SoZj=>Q^g%h!74m3mikCp-3^DfEMrPYBKP*j+?zLtesn`){Gck-m3Lv6|K6Dxfz zAV_j&$ts{F04kc330Y{=!K!sX6?kbkK2TrnWp>4Qlvh$=3mK{0>#Y-zM3Z~OX^bO* zE?y@F9N|1BYwXh*<+@M>r4VEv9sf!yn=bhNWJ_1y>;9+_65`e^Rrj2c@9v8gO0x3! z`r{3#!8bw!2=h(T>28q8QMsw!2#n@c_a%s#LM!`-Ut z1yR?g{L@a_n;-PU+pe_B3hJ`}&n{(D(=I<*%JU|YdtKHT<%DDJ1<3>N?f2BLzj3Zq z*OS>hc5Q71lv8g`^eXH7c6}4uh5xtz47vgkkDOl?AD+iaz4Ag89@kM_h+OR(rHp%# zvi~BE7h4QF_m<@s*i^nW^uJ%~{_CptUkC>i)BhvBng0XA!Tdi$IHt8U9kE;EcT7|M z)fo03O>JQ9`;2E=8&gVLZAVX4a|xAGrzeStpiU$Z>%Pp|x&osy(WMOvN~~{4uw%@m z1I|VFczO4Kwf$|}g8b6`dHq@*4;=MzeZL91xjDL-o%}~*;K~~P2p*NX>gM)CFZ5-z zN07Oi&dM73@Jz5@Y1uW>bvCM!`fmC%mwyjCS(qAT*&Qzkb@t{gU3IU1=8|xS?lsr^ zTU>SeYU6rC`SwutQls|D^w08~)%`kfEX&VIuoUK4z!OzOx7w0mo8U+9{KCi%uqm8< zbG8Ky|I3OvNy|!TOnJWb2d}I3Y+-hxo8o`{jGik^Ntoke^K=&6doAGH47d6A=NJ|B zb)`VO_4(-P__Cn8X_^a0I@`R=Gz4ocqvsYgt7GcTJRoY$Z=NqrX=Ij76sN{S|9U9+ zw8*#{G{MhYP8-7^`M3{J|?AYa)YI5dSw ztKQPf54~2<^~Z`mkt=vpFxPQ~2zlXbYK*TbyF!Py>5LObfgTDg} zlO^m_e>hw~P-kN7gMa#D7QF@9VR#5AZLSN84v=A}`m*zS^4)hL}ID zp`iJlo-2k0FajAj5C~%0(bSB&-7Grd7iR=Oo9+P&8cP%ItlUw70#MDrJ`1Mjeov#} zz|oZle|^KOnEbL`Ni;(46(B@t8U-;`97BURV;Z+X_G(NXQT#A=BE{SQcEctjz$UY0 zy3&nvIAHG;ia^+C6mxKvrS<$9m}D!Mh>GKmF+b5!e@p)E9{zug&`6_U#t`Usa+jkK zptXsumr|m|hD0z6mF#ugD**p$JOps;&QK>2bN&d9Gi(L=oB3QK6a0ym8S?8VdLNmj z3{VzZ`n2d?Z#(nAa8a)fPbE zh0)Q{io2kzYsj8A4gghQh!eHG!Vf@Uh5=i9QEg|(W&1*wlQ+K^K8-b^DooBL4Tf8| z2$T|d13kzsiffTAT5oXePG_NK8zdN(tO|m_=1Q~^DnLcolY1K?O4i?L@RV^-jR;6x zF>5|0NYP?nLr?bRf!*%#68Y_eq@~)AS(xq*oGXHWL5ESW#oGY7-{KVz5Dc3~Sq;S> za*lPZ-h$I>I%IQeW;Y&16=Q^GhC&p$5-1Z4sD~mkVJo8U)&dF0$6+vpzS!4G zWW~G)2(p3@57of<@pBdZ;N3u>=2t|i;;Z3-UYROPy8`2k(+dEQ??e?_8==w5(_jB( z>f=X;fPmufOBDSMNi+R77CUu;Ir(b=%fCg@V2_O+CvkzF4Ln?GwgsU{pg%Q*i5Ue& zo7M(mvJ6ZKAbNy`7K7{OiOcB+XGY6?hW-`95$eNnfefA#J$&tzMr#(P%X+>bmM$O$ z)hZPMbDO@#JwzGFGYAo5FwoQ8Y3El)8qnVWxRPp`V3MPl-;?6groKG8R}Pg1NTgzT zcviZCyU1EZLypq^bW{R!;uegv7hn*L-B;>D8{S7Es<&u?j-BDO-Ibp?f*K z$f^aecx+%ZYW006lBd0MqcDweAcLv+Fv$Mp5Bw?7IGBy+U>)6S^Y%&Ps++HoWQuE- z@toJV95Jmm_+T*-X!84~e8|Y&O?malYYoH#hx+MqnVZ9VQa{3PhJ&|^cIqX;#H;J%Q)sN z*SaJVrQcznZcjz(?E-?F~mzi8j!0bhnIMDS8WZ^ zd?@?9kPqDjOQb*;`qz4*w`wV$b>{oa>~IFv&pn^mj2#FNxzgXt@g}?->T)88Vdu|M z^Is}Z219aweM&xTwHy7HX@3*SoN#G=rOv>2lTQDCpYQw0<8j4y_w`XuqTX8&6(u_9 z5v@o05hTW%WWakSNiape>w|b?M{{t-g*HayY!Dc9e;xN|NB+aoDcxaW_$M6YpXiQn zUug^Lcl4YAP@R=+TnY#8@|YyXga$`;SxrD6MdD_0Tul{erUcABTKa(nBj=ldvX%fC zx=aXtb#&)$Z8KlKh`Dc9e?Y4*6$9_2UaPiqXVa}-I>6D zLdMko3Hu@VD-F{BS*=JkS^$u{Ks^^nNTNuoEIX!#HNYHT3W6^LZtZRP3MtuN#H`GU zc?mE3Tx0oZK~yiPtt_7_HJEp<0&9>wRuc9DM>($a{w?do8p4(CIUUOE2J02RK1&l z*pQO%Qf-27ZYfApz}L^v?{qI-z&{s zM4_61xf}hnmSH+(Q3fif1&r{OpbXcRBskJKS+f$ZRPBmtGKX&Ghyq7q@lskku#^+p zi>LBbtIL$AAEF(2l^3>y{#b#VHKErOg(eNlxAaSyEKx||Z|PRFNsp@9^81d`bNsp4 z{%*dadlIKIn|2K55k*r+EWxqHjHk%G9CqFp94}*AEz$Smh|mw|j#g5U)L^^XnCvAH z49#y6Z;~)>q_qu0*WEmL*Iu-snhGn1f}v&d^8wrY<8|~9l3TBf!reJ@m@_5 zMN22$9}ft$W?l|pJ&8}j5>(|Q!yLGJgdnv-|LB^u*q#I&lILVmyxJJgVk|IjAM^ol znuDpgc^5P;4{8Yqbr6->Y;C@2*tr;?mXW}=UgId*PP+drU?amnJ82~~{r!-w2{g1L zr@lQK>}E9r=F3VoeFRpr7}T!@tD2=;DHp>DBAx>?nw{CyNB$b$G+y^M-%`AMYe>2* z-h-8*QNFv>u=x#F*dnj@){58ihnpaNRQ}$_BSHhmE^K zv8?Qpd$`=GX*LsATdm9YEOFsrH80a`3{H^Fs&5!wN)k|av@+Hh{aFVgGEHpjo?*y_ zN3y`udL2(Yva!CBHcaGbkTh2 zGgmUlQRP&~L5WPI(q$bISI={<^H#B7L_)`5_eZ96ldJ^Zzw0Y}HivAlIRPqrU6Ie- zd?n;n3|*tSJYk~LvU+u}v(k5}=%JT)4|G**HGV7-_YRP~KaD1EEbY~nu67bKVE^04 zhLfZ&I(z)BbiOq5)IT7sy`w_QWF@Cag!L2?C623XgxRIdAz&C~8H~2>uU|}3;2HI6 zTVX9T9l(6gC`!K&x+y_Y1&KUhO)*|dvQ*Z5#SA$cIJ{h+%Bmc=c2f9^1MxGr&XkNx zf~iY_74(wX%7>}eljPC%OC0lHv!?c8c>$*c?CCbzQq`g@G(xQK(*%p#aQT<26UVzRVt%M%O!T-G%*r{5;NT$h#fYm`SCl&lrsi~nQ`Z+-uQU9H!f{_hIrZe=vcZR z>q=GJ*E7~OgCl6cP-c>((2#M5w|BaymuVYWt2I0nCgQ0J ze6$wTLtud9n)|Q2+D2^cC1HMas=;r8y z8edG=uU)uh$ZdS}SUFb&J+{G+m{$kl`UTJG&mw6_KFeBi5(tFh7UC$nA5r<>Pv!3< zdxXjngw#GqZH$@6q>__Z8^j~dsR?BU7S;C&em4y2dn*)ODyMUrKv%}~mxFEuen{Rh zOUp7_tn=SR$n6XB_woU(1s3#c)+N$+&1--szl3ohBP%N~6n4shC~ZKI?B**Alm<)b z>n`)MU;{Z}i{q%{2g^qLeJB6t4)J-hY-EbBGARj|R?u~4jc;EVoDrjXq_bzw{E!W| zE4zZnDRU~}mMafaPg9m3`p2}RLS7R>-y_bpT%P=8kkU^-$t#YOuCZh1!sOZi^8{2B zO(L1m+gG2yQ^gy_o7n(DLq(xo_^O}Z$w|N3lD6sOVBWc0sB52|)EO0IG>7+!+-c&g z8ZY`+lO_FoVNMGbMno^p&WsXn3f%fN$HRi)_pNUqNu`E)?2s#` zw6G0$H$FCW_oY8XK?2P;(3~(mLiECx6WcqsaTZ>&TOq=Zt1aE}2MR_9RGM{>K6lB& zaLGA$zJs*T>!74us*2|z!CLvVx&CVq~78!e6ph~qcg-bfjd9Z1E&-GOxajv3$0~&%Zirz_e&BMjYreRqq6Q3 zw^DX@8T=zD9b!Yk-6J6un-C%0tUr&uM$^$YVmXy2bldZ|2mD?X7*1F)(jpD!a{An<@A3@;2K?>{-P90UI_R!bk-ao=dUh5@`+R)lj8UJyVRa75w^BGHd6&IuP7 zTOPg$tN3%n$Q1Uob)-jC-ndPQ-PfIpZPuoKwr3?Dp(YfVvc%Kbm7Y5mXp z@LVwZ-*}*y-T|kbO}eQ{mfb3~Y#U5TXVp6yDxG%m<`JXI3M^IECR3S z5A*M?CTI7$4zO*&l-&ML0ARo9JmPXl@-U=EAi{WMw8i9HWNmdjI+FrL&o}YD%wtm_ zkTr4%W!)(`PKz6A-bVb(g&KZY6WE~q;t9uIF>{ir!=CKA#t|W47j)VDc7Ta@Z>S>> zv2+cQUt=IA8)lH5-Xb>nKv|AVufD=ge}g+bqWlX*F6UC?edvqH)yE-U>yrvaF^hn{9Z_5q+l)I-5Bm01g9|D6N&AC~`7u}`&@W-68_?1}sMJ}V5@vtO(BE41wp zoSqmS(aD{k``Q(WOIUYj%r(ehuBgJc()KcUr?|{axM@kJ4MlR%ZK8!P?hq9`(C_50 zP7jCYTRJb7ucJsW&e48m<0`myK{occoz00|oJPfZaA2g)Uhmw+AgL*Qu9t(`=XEFT zEY8m%-oN9|@9TbP>|QQuEIcpg=h^ta?Hp=LX-tuV4NDcR>8V|A&jie`*UN|02`xeG z!QH;1TG+zfB$jYeXsK@Y_*c)8iOb1eKz1}cm$&oF>^ZJzIdarZ$u9P=Ra2|Q$Ca50 zWzh1XZp^8LhXdEDW0(lq7tJYJVE7_#j77={Iqx@O4kbJEeyQo-p3A^_{SVHkgW|CA z#M%5;gaCVe505BgCexrSo*>jxZQ7byn$yH8v5<^J=x+EU*D>x2;7L=}6LGD6u}JySU< z4N8PH&ns#2>%u{k)Aw%2a#Kq~v0B~vGq5M;4@3oenbIp25MX>IdFRsUQ)bv)hIlqq?BU{vh1FAp6Owr|&=xvDKxRNwic{GP~H!(S(k-c=KHB@X+rMVIO$}XZ7S3j>;`8eQV11 z4?7fR5UNiosn@3Eo$tkfV#5x(MFuiuOU^4Kw@T`OI7}~;VF*H2O-oYXw3no4$R*5? zXc=#L&GvL*qVj{HZd9if{3`;v#Pgk2HYtV?Me%wDextr^b#yumu zeA(M4@_p*+rmLb6MxYGGS~VpSv@=#T74@ai$Fwdbo^gy=r6Z z-uUFVLs+V#n(1!EUq&X2l{I#i9^1U;Jc?IqCgW!!&XoX|v`Q&vb!xwLLC+}K+G!0%XH z$}jZNgbQvE&*y6@;sYe-=#87^`qpD6M9x550;q z;ln)_Pw@9oTX%sNEL>YTg2SSn^lu=kAHx7opP0PXg~M#C4?UedjDSliv=E4%OpiW$UTJg0W^jMyr>zO#K+%&(7Dw*qQLN$3GcEH=|0P zPkN$Gz+Tr9HG(}sOaTJ@`nn{i4jaRV4!UrKms-C~>Zfy0~Y^ecy_qW)6F^^tnwnyi+QIlWg`1FEnFO`wRs%FNC}*dFwg&VC6% zcf&(zx+8wK-Yi4}QG~_Jxs86!nlacggdKz1g~57|gT;u*%(YJ3YlK-9f-m?vYe>yV z)S5!*C`N1XM(ae%s^bR~P!R@}P&yqwA>EDrHktPa^16m<3=3!OO-&E@u_5`3XoVQA zqp-FaWlo@iYnuoMDP(IG2SZX%$YJ>h6?8W1FGkTq@*`G~loNa=U1`H$*dd*qFo5!S zs*v`!oUf@kyh zlKdJ-Ezk=M<>Q*@PTS5?=vq$`nw!`6zIz)+OBD;N1a!?h!{yWpL-!X3M!1AeV(6gr zoNry3Xj6H6ASFg%`F|<&Ysb zze0wk!R08_>J>{26 zWzg}^xQsJf)X%iJNz8!w{mqCTLSzK#faI6eZa?-Eg@6#V*cXzx_xwh8<8T)J4?*e{u=`my=HLxlQX4Cjl`lN zxofQL-L+BZhJV(t`vPtG>a4G_O`7v7%$xZi9q$rc?Kll^?S*;#gsu`qx~^kiA%8rC z@0_$21Dln93qJf2$BafY@Dn)R8w#noS%bu86ETL&Mnd&BiH#6iPm2FQmaQ0e%nY{&~uiu)P;HlNEnheg@N3Q?K zji_?tl~F`q&d_%5Ec6}#y1Cj*L{x}M2 zWUjdUCPraLLoY0p;TxtNF?}B0Jgy{glU*U7MYS^Wa!M#7k}A^_!B@5Dy4u1#gi@t1J#QeCDotFrI40ad0Rp!c zoBg>0Ni;HeV0oH9=tQB8!GCUt1V|N*1($MidV9UA2yc+RN!~5O*)v*wOscxk|6}J8 zj&`W{XA*uImik@!FDO|UxfB%3deIo~Udp^pUz;^e>r+J35FZug%@PzpierEGlc}FG zo#_ikOn&t7RkUJyn_X;uE_uaH=WtG3EIFk{61H$i(|h5Gr>|f;9eQ5kuHGtKkJDIU zeiq9Fo7c7bV^i9WS9T%IU77bh!4GIZ2H`jt|EYi0&W zHD`$rCOz%JjPONAVS2O-6QgG-7JRj7)30~pD%F|~E89-#zpAX!9Nv;sE0)Nv9m=e< ztn60ahp>`21U#`xAyoXqp4)89LRgQc{P${m^w?u6RaqrSx*Ids$9D+~hO&nXJ@_sW zv~t^|k|ChY8i@L;TGlzi1RhxAsWeS;KOT}u`i*sepkscN`el|4vQzN$ay$m^W&c=t z8;9QB0)tCDUO>4ZT6nr|Q!q9I6q{H0sKzqG2C_I8{ynrv*FrUBj})P&e7yLJ>YT71RXphhz7S1r=a zR=hMw>p@O2P>?dxKBPBf#sVcN=5>#a!jwrdBWg8^hs4^UA3IUh55Vnu9l+m8jnF5x zOVtLc(4ao?yB1s4CVs!$dS9I-Gup_eIbzgm43ir>t<31FOJ%Y?c6nWSlj;0At2N0{ zZ5m75wHNYgi{Dq&l+Ka}_9;smKgnP&7wVB|uT zQmej!@9soZnfj^BHRl1scL}w@u6=WyrkH3Ry;w9<`0muj*aYr$udw5-MBik9>aNe3 zAZO%${)Ggri7IbvB()xh4wSa%EC7|zA0Qu2a8dLvD){VEo+th&BjA8xjty{Z1dGT@oJY4 zpZ^)Wb#`gzafi6Zy-Ee_?*Ix8O1D2*(qI|$!JdgZmrxgC1%~WFg&tR~(YVDzq#<>H zg9Vbugj|}Pr@(Vzj=Z1k*~Su#X9?CGmS{0j<+Ka-)p1bx@T7b4AG^GOXh9)6BlE*w z;cU=>?`A4Jf5;bUpnb{V5v9tTBhYTyBpHyypI*}9qyM4s)pr7VaSjS}1w)wRN04}C z#3E`4mk-R{$Mtdi_&=&hmI3#u4BDCjH=xERclC;p1%BCx7}u^gik|IU6cbdW9msJo zY+Q9kb{)hT?pzc6`J6sMJyRC60U($ZrnS`G1xIP4sNsT80b}rV*BkOJ5To^aqy22- z>-{|aUVE)&UHY_ej=+0buoVjNNMHm=JZRVaBFB`VD2T#f^A&N&4uuc?Rx(mn%LJx& z%LU*l82fZ2K7+0nG zEl4_0CB|ibf5K>i#?C19TO94z+d~Sw9WR`BTPjR6d5NtGtHxWF$O2VZc4d5bHq}DH z?>xkr#;zO(*I_6vpKan4j8~etaZcq~VJa7=Pi-(&g0Sc|6GM>QAyZO?u7XvAahqfQ z9sqDZ2C;eJRW*W1WB-W<4Ar9Jfa0P;iLhgf&3cg=zg6R2Musg5OXWuKrw8Ju!dUCj zTDtLumswJ#RUIht*$nEPB~b2UhBBAv-)2O8EYV@Tw?HnuwF@4vI!z~W&y|ra3xoNn zSSO48(xx;#8f#JcA*ok>Oq}#$rByoyeF1w7G_gycS3_#Zk`X?QwS`L1vK`o*1@Ir=*~5rU5U_ zqt*TDz|77L;-6NX4pY)G2@{c&4i+~911(#nTH*pmqO9; zkc0I!mf^+49^q&4C>F=F{=(!=td#%Dqx3|r&7`c)h@M(JpG*K7iMtMorgT@sQd`8o zfap0na}kMVtI!ov%TCj=Qg0Y{{*0g7iJ4(^yag@oqD-j$L@kqIDT1H&O4>!SjFwsp z_ggU3px0F^T=8atFqjstH2!$F2PGJouHxwPhdWZNnTJ&0q~ZFhv~Ht1iXdMYfjMMI z>a(q2ou@7V8Pd@f!CWORB}T$8!b!8f`d1+tcaJ4&LSGABX_2jq&CA= zgFK4y-*rFI#bkIddU4v_vM*KUby~YJ_^JD0TAI^wpkjul^jeCNJj*E>K4QUj8ufZA zP3Fmt$JSIqjl7#>TC*dzm4g!N3@47RyL|usP(@SU(>BA^taq?AsnM}Q zsY_%ZFWXY(EC;pQ{#{-Q9aBT@LB-7~D_CfI{&{{>6t+K6gN*ibfYl4D=sWMym5w!S z?p1FLvOLN>#VMyj&)WVJY!dJ+5sV>MSF6SL7e)jGTLpdOt>_aXvu6Pq zkDC;YLz&eHVZqcpfyYoERiGXV#G(J>AL!alHOzBGz6m%$32rA!QK}^b5hl}UO0f)y zf@*YYDo}fN@l&Ty=SX5e+VDwxg2=DUWj0UaQu=0yS5X?cT0 zYyp$%U_5Joh><7Y1nt-?f~+po4a+-l#LDbt^7}zOsNpOLIV?j!Rq9YZsdeKR(G0m5 zFo^~Ij=YSsSOnRxD{mg+l<3kI1>MPfM66P#}Ix29} ze-(5OVv)-Uu>>a}gP(HX&>#T`TPz_)Qauz+wbMt+6g=`lZwE{^4`hh~)I;coJqC=uqxhtM*2HCukp>s>iTwbkInGA6|sLxu*CE4J%FzQveRV z4&OIGL3VeN*Pb+LBJM;V19a7AQytJUIJ3Jn2N=cp|Lu0f1(qpG4|a>az;VLR#@`dA ztCAp{Xc_g0s?vN(yzQp&l;b(^z-qk1hRkiWOAXRZ%6*`JZSG##zYE#EvP|%vjR zk{#8(zwZ@uTO&Zly5i!EyCPND!j(5#XH@x$z~Mq`d~9fQti^sYz*!aDtGIsr8Ee_y zTP27tY<)*`2LS$)lCrxdN00jRmlxxD)#HRpJs01}V|`fkrc71tmk7$zK*?-CENI@v zNxBVsjGYKm6}gQSQzE!e8VuRBhT;aXpQRjvME@PaM!tgSgfx4Vz2BrV1i#U&d+};{ zd|wsC7(-!Ddx@g-Ejk}QoA|72T1ZO#P+Tr5GTPlAlEbaPCj>K_0o1|wRT5sIJsrXI+^MP3l#LUb_Srhzm! zxMm1D*c0}ptIb+Nd62fdq+cSSk}6-xVCY$#;=g$&VP@(wm0fl99?jr2r#qb;F=Muw=|KHC_wW_V8@XDRuH6gujcYcb?=L3V66E!yGRsx$UZL>hQi7KD`> z2@YQe^%T{l$<4qe+;!82JRagEr>|VU$1I0$;U=rvK%?LLMV-EYaetMhBCSGu1$YdG zdy(f&hCAz&x`~OFKU5S7SIn2C=(n4_GxOg=(hc|Gugyf8wAN zQ`?=+yR;v7-poiESMc7l5yBXCVFtY_3`epe^^)b-> zf3pND^M4QTv$Fh8!u!>lmbTcff38nAzrrGqCb#o6sCSL5k-`jHWAIzp64@3U2&+-~3x4u2@ z+vNpf3WhZwW{wW}2NB#-_pmCiWhcABUv{o~HEFp`SPn4Rx0LVIEe#|?GGqMp(pisW zP`%QBZEE^(P3Mp?U_HqF%pP9RHcQDqb>7Lm(&SlxdOED>`L!n-X3ZGKg`mesngpa7 zlyUI%YN2UfBnU`#_cty?hD}>h{@oknaI0$hw7qENJuyct+~Ah=6=Nsq?F{d=RWW{d zl4q1YY)JBsICwGiYu=@*l|;?3UKHLguE08Nz7wIj8vAfhhqxZCT=;QEBr3x~YTE|< zL3ukB*$AX${n;J`*v>l9zFec7PJZ<~b$i@CSyz#)9XEl0I&0ZU6I(sJ7uUSY0Kfn#i`TuHvO3AlcP>yIh3 zS!w@x;8t{F!cci%Pf@L#*;{YLq8Tco($>%8`vz#;r3m8(s6Jjb#F=CX7Y$`An z4vg}(k8rT7PQW}5c`fY$z(V*oArhXN#~7thny(gVobkRGzRIxjif$Flrcjk5 zfO8TM8^K>iM60RUs4FJ`cMC%)oL#hdlI!NF#FoGAgv|1aH91y;*GQt=muP*36}xQg zOMBx{&dQRoDS*Tk?`l?9aexF7vD~GoGHd^qpnYo5$5sI1!+Q->KQ4X5WunpWYKq$H+pu3s(Y$Pt% zOTL2!7B$=lr7>Nxo`Kks<`XtuI-RH5G`6|JC77j2tZA!AUx2bH;<7A^(UyVkS}ak` zRh&=CTR~g+-qqtRBe@BAT%&=JM>q$vhatiip_fJak)9HK25|DrGen31 zo>LKyu?awwk_jhJS0C~;&l4<(E=y(dBN_-$Bp}>q%{HwPu_=mr6%J9)!UYQm080vu zenQy7aAq7b*^YTcJ@_%#7;_X1vQLdG z1uu8dpCS$&C??EEhbgueSEW ze@a){0mrQ_j(#2$_DK$+9SMiRX!%!TAi!qA|gb({P>Henx zpB^DRFz%}}4s8RpGXbRUwJEja@1&9Nr6|2e0a*xTYR=b|nn}pSN#OQUI8Wp|n4Jpj zGF3NkY&}h1_EG_{2$hd;wii-pTF}<$)%Y8E2?CaJq}1Rt69^GF21Ofp9bE@!s|H)7 z&tiuLhT`)_cA9Zz$@1X~Sy4hDj14hqMgJ_;kV_`?naAyl8k z913X%JTFz;8z#9K2Lk9Girp5`8HBxmiY2OmkdT6Xfz)x#(6hG%!bLliTQgAM>00c+ zwQFtRHvoK#rk&(Jdi*jDh>kdR1=)H+W-t(^NoENu``i z5Yim}rTC`Oh*L$)bs&g$Q2X@{MK`Anj$O>5QGFUH;}NVITE!YtdiZQDL&+qP}nwr$(Cty8w`nsYlQdM2X# zp|y#q zeauh(7vGZsMc<|z2x}}ke48X^IW?n{A%0FC)roxxZ^`;w5)ens3kja+HTl?9b2WC3kr(^{Zd4XuGE~R%!1pwB18q zWA4KcV`UzFe7jL`XFfObDrH$44Yj?vIKjFE35S}h+}C2Of-$RY_Yw~{0I^4Oo~w6% zT2`V)gPWu8o#)i6S$kX(B7(<%3KQ$z0g??j*Q)U*ii8xlLZ#guJ;JU|p} z+pe(6cd?SGc_z>a17wRgO1?4KW$^;B#N#K0=8ra$0kuK6{QY~0kDKa4lvLu!l0Iw3`UpM3~l3o zxL}E95PW9R8S{%V`mHkr6opB(xoApNng!;PJrh>r3Or9idRK+TmkLrSX`A>x47>L6 z5^YZ)EB6+qgUAEn6^lTYd#B-fjOcwvjA6aVZQA{+!ekoERs!5@-S97#U9+YF`&)Zvbb*WXQ(eK=qS}Ub={x=`_g@jpFElV8lh!YHiZdh3nEWDiO7u0wra+K6MXb~x zCXtc0BzkRlxo;JlWE0BH^GzLFm=A}%?#wk9s3J29M|zmTO(voP#a>x{_v;xjW%O_2|*(}bNoJ`H)K zoCHWK+2#D94^eJ}@5RJ?EPf1@z0`ilWtWs(OJDty8ZPoEnJAiUdm_pFudDLxZg=gu%2^TFvAdWAb~|kiuqG(P+>W4NH*;EH!tU39>dT&pWz> z_2l!!wC#qbkW{ft!hBUJgQd#?K10%?K&%bkIeZP|r>U3%7EMe|KR_5@$USJ5m#ir% zGmtNkZmbCZ1mCkZ@IKwGvtdYqTM5b)<<2;O?)3d^!ZB@0Uzi0u{edZIkflrTkitBb z>nOk9(R=UDVv=nFmj8(7{Z$LWA^cZKV!07uPS z1=!G&8h@%J!H3W=7eZZTD-7i%Ma{muZoA}IBh77jYBqb-ro^dBlJm}~pD44)#pkt? zQHZS=JQA+vcv&x4Llv&~*zqedfnJHH{gZk}AMh6(Sbu7vr?vc?Z)0h2H! z+UVx-_?I{1W=Q_cz%yQS#;AUQ>$|Jw*_&^|9=GV`+alCIVg2}rMJYezHh^c7s)Nw_ zQcn|;X28D^F*#H7Wjb#jvR}Q_KK8Cn%4Km$y2%$$ta9J&VZD_?!W-Wf=|1)%su=%p z6tjER;1}2>w8Q24SV`fo)B`uh-TnfhPdg{S zJ1ElA|8wyDuW|Oj3J%zr+5bD_%JCn3-G9FR|B!YZ|7o&Qq!+WWb~bS&pcngh5@RA_ zVq|A*!p8^YTj#_pMjy92ulGY zc8_&kj;4h&@EaE4er>108)qboh-!!D^IJj`>4j6kb9s(sT$)zVo=!c=u8&cY zk!0uJf!)q}5BVk7BL|Ot>tSEpl87jPeD8?)J;$S=%ofWO&Rby?wK!e!LeUm@lF>SH zrm9^ixperCD9=@Ac$5&5e2J{)6xu_T7w=O+$^CJfbO7Jyg@XU%E{(?iT)fYZ158-R zVor!8e170!((G-O3el6zzBgh0S^GL&SU4(@8F*EP zq2NdigLkT$%-}gQF6()NaO=q;{euyIhZWLA;vF;y>kB@_i_&Z5S`yXB0okVTl8Yi| z?+zcPw{(|B!DCVBe^yGgExsYHxcx|xXdQ;4cL?p(>jAgU41G#S{UMVBVBBwtn{mc+ zYhjDYY>_&yMz$|U1!t^F6C8=1PEopLw_=ldMAgAC+B|(lkED%4jXWco^M~)9C|1Zw zg0t+XDTu73I)i>nc0$$jtBHOajPD`V5~F5uU><#mnQmE18=;rV^p-&_jcpm7Bfp{A z{w^&@>nRX!6FJ++ns!;{O!cm7B8r!}l_$#BK20Yv9%+aVlD{w>Jd=D|BiQ;9U{WM4 zWgEU%;?khFLjT;DOWt^P=zs~GSgie>Mwe2-N?)uyCFB9U=nKiPV-DdE(?p!FF8(*w z_>rq@VQPSyRko-ZO!wWt5%|V&yhzSIvpU#9@kkz0Z`m(xJ4rWqXIU?(zO3;k-+pT? za#g?@H6a;F;(;UmG;`^_^L{pT=YRf#feOOz;QG8OM4xE8u|8N&@>NQ2v_rJ01M zF~qUU=RzGx1s#=nii`BPzH(!+Mtvowt~^R0ClJP_h+&Xha0nOWgoI>foxJ$9*}@$( zq;V@$U#t0i9&Uc+)6UVKDAHn~R&e3_syPjx^!DHG`IB2F4q>(2|VkW%Q6b3wrJu3AXXsF}S9|KuX7Q^t=VU-7I$JtfDo@9ok^~jW?GL8V$Ef5CH>2l?Ztd@|oAnwwC?5_M z_gH%mD|_-GB<}0Ztr1@QmomP?w9hG2O`mG*HUy8^dx#Ex0w1~-V9(r=YZi*tc`)5} zQ&1uDSVc^zGjLS+-Rmp5I(>rX6Ggc0V}MSv+&9|aeQv0+8}h`T0p6|5CgC?*JKqJ{ zzSh}he*@?_NZ+AoZZ|m2A}2Mwo0>!HxtS=97aB;e+l!YV-C+n$lFM=KA3T#`i(@ds z^ZTYjo~X_ob?1{p&y>nb;kcX7S7aUYJWdri z^wQ9i4dfyCK=l-M8A}+V3A!!$r6UW$sAD{PS+Ae;oR7jLUav1>5W7*s3Z zJ)jr3xzxx(k5|poNfV zMniL2;hoAjEM{>{(bU;S(OENG&Nj&AuU^&bxb@jtu3U?f#V!w;6QpByrH&IgP@Z=saW~mI_Ar*4%YUehj5T->OP_$- zQiV+L8kQJGlQ_1bo$0~i49f2u-$S?eS9;&B^3ne(UH>IW{}CxhHm3idbp0=$Eyw@K zv+dFRfA_zac^pSeHrZPDIos=c7wdvMWaTYuHeQMugT=Z;aGWe%hD5Z<7}A zHnqR5R^{W9q@d2kHEp-PJKQwGrb4$#&$GeTk%8Zxp+9QSAlFf z&F(r(hb)uwaMR54&ej%Zh&Pc!BZ^|!UmU5kG1GchgQS?dW{pPhRBs=&>>lPF5UTKg zyDg<#)eACRvDQ9U_50=rMyuAU9==@C?D(s}`cAsn+UcyaLk$c&`ZDxdin>AAEdn>@ z7yTG!tG)*4s|F03R_YqoUfAOfm?l?Lz77Wlwl5HWe3knjW{OR4M%n&;f~9Re15bY| z_-1#>4@;wuNP^@0j?V# z)~cMX#ihJ_I{V!l-WyZ|EA5)CRk}?DZ0&ZC(j;A_2#dLYSvS01ogUAuj2({b@~3(? zyqbMIzP-cW^_j_~`l<8yw0bj6!D+Xw8|>ZDnrPU`?1h@`VA;Y-f2zpao}~n6NMc0) zYy2(oDp}4Ca$`=9^DjZ{X+d)+|8wZ*vQ6n81-(xQau^?&l-0JA`78usRC9ZPleURr zHgnPF&EQwk{f5hvQi|^QoF@y@qpz9j!1-6rms$^iC`5R;piN&+sB&RELAU*^<)IdI zhcE+R_YcJgAa}dL060^wg_c4NMpdBhTWpnoxLyUZ!6s1z>=p% z(WDUz1*7KGnq%4r>S)Sp4IUj=K37dT$q+Oz7GPQr`(S>`YaK_!rqk~-q_;4~=(38Zenavnw{`xRIHULLF z%(UCyagC)Akhccr1Ko?q@*n6!w$-qpd1OpY3vHf&z_~e8f2bx_VzZ8Ly<{B27O)tD zU~H{ZC-BrZS+0K=EEbN+8s3#GKJ_b-A9Q~zu#KT1tco`qYbFO(NTRZ82B72Sy=#u@ z=+=W*(8@5}^-mhWmJNjHE5K~BXb3RBSVkb=F35XJa9~VRG8mE_9AJaXegUAgmIG4@ zYkCziA5UZhbDUo8Q;~|esKrEi_JLtEL`Vue`2)gBDeiQpBAMe14ma(#wYp2uPIOz; zAWq9oqnIpxt-qNFj*ryGqz@RR@bT1>T8#wHP~vcMR_iRg8X(;_GJrgis#UyBf0;w; zBO4a>X>LK+IT^x`2^wUvd1Q4Z(bPOwlfInpnq@k)sv~FMfdB-`Yjz9kD2|KArI5BM zf%v4`ORwe;p#t7?ngKlP@f;<7`R%FM)=|K+Xt?<3b!75MuLLL(f*}EQ!Hq^)llDM0 z-HV`(d7_I1rR}{sGh6CPq~tFniLGj1pg-db(Oql8awyPKS;x6!ox}KztgI~p2hHaw zMKUV5Q|W4%dsB$+ay>OP5g=fdYz2OzoeF|871}KXK3g}SJcT6HcVnSQH<$x!Vz0784NNLD1-%M{{{#I?vv5=6HIgf>V%z8nKsI*Idj!vT{? z#h1$`@7a)L!FlII2fd4KZE#J6dx1^>C;@O5g4K@@&Yv){MKYI@wLdnH_R%Ju>e;vw z_}R_Xcb#gj8cyu;2{gJW}gN74akkGsLr_ChyVhR<=Oqm$UB-`y>e{Sz=A z`mHPq*(^f>xw^sFW<vb$TP@TF&P%< z%Ej#s^$s&@V5X93&aD!AeO;sc_)eLY{?zin4<2!$GqiO?)NQ{<-dNNs<*-{?7+|fu@1Koewb1W1ix|1qRXU2}`+q+0(v3xT~cGUX>S86sv6) zh3q6RH&2SEAoQTr&X(#g=Z5pOQh0Qpz0am?GykhBcxm~!KF*NW)$Xy*=NAzGth~Tw z!|`r@u|i=PKwiFXjQcZ6NBL9%%%RROTaJLS<%5n2?)D+5|W^~Jd1aHpin#DjMEoEeesW_`X8|F#HMhUmg{sn`XQ5e+;_SStDeeM zouy+z51S?>B!Bgwa1KcwE680eE*5-y;hJcj4+M;-af=>1*K9W?c4mF>@dm6bNRjdy znf}{2Tx0gt3M3=-b-T?0V|D(@W?;A}6`*#N4FOM6DC8T=8yjki9TrsJ8p5Uu*+v_@ zPB5Hxm^33xz$imC;41H3w}1PFjCCXwB?$ZLElCW&k&S!uWeT{(7&!nV}Chh1n& zeE?13kQc9^6urdz6tj3UNi4f(o@Zw;>b0sm zh%+mLf6@hR#{8*N)3aqdkE#OqrM1?E*()GDZ!Y1z-~4tU5jepMxjiUBO{@T$vfe=zGrNMqd=E19*jYhi9IO@{#IE7^675r$EAbTw)3(p+*fe>$o0D6nhL>!D+tN*onTI|VopdA)c@#huLOckD)uFQ}Yy{g43AU8?xw zd|G0j5m`U#kIV#6OGRZcw_kiQZJNd4YxEU{q>mTutrpm$Pz>w=#pdlZBK{9^-m0-dpp8_5VesPDq+p%siIVygva&+9woc+k z0d*WHDegeg$}e^}Jjt7G9J{#mJ;B4F3mr8ZiZrWYS8S8EIr=lbzCWGj5Ry|9j zeB?Sef$Fi;;g#=!P_+D{l|50&K;?Pb^m%EhZWJ07M?L?}x8Xg1hkbnL|1!P(XD0hEwYxVT{}^uJ^BZ&&~v8Fvj(X zVHfkJ^r($&o9m-#71?di4ZL5#t**4>=genKsI2bgOx5+Q>?p?BuQzl~jI!k;b8~jH z>tMeW#nh~S$M{B z+xiaY?evMx?dI7HZk@d(rv^29-Q`-;?qM~nwGSla>HES|zpF2#5j8WU#dvU^wTmU? z1a~7S{)EsvtxneXIwhFe>r8}%c+a$!VRLqNTfMM5P?pygzU+^0aY#1G-QWagwvVn! zbBZA$d!Ox=5URY6*z+Q)V!gvZSR|YIPP|KXmi}a8#2ws3`H&0wgXcMb;fj-cTZzk`N5|KTl+W z$Z5%Fd1qrzV}pl0;%Ktr9eas+(2SvQbxPuCmK647ShVaW&pAM8wN96&bJ|ZwB_o~O zb>}RY9ovy7OY)NMvg{08Pm5)($PeVZ$U^I=<#29;C$aBpoxc1#Q6uLzmA24@gzeT` z&kot#^tD_n54}SB* zoCmkIM>Y$h(uK@kbu#trau4{;+6#mvK(=%?rDDVbwxECad`|$yt@<~mg)tx1wkgs; zex2N#1Mgr4bhI~kBN?H2d+_rn@VIy=F z@&ok&0C7a30Y0=qIVeS!U$F}*kR`;$~I443!dFT$#0 z0VxMzvcju%;iMJdp{Fr;ujt2%;2_Kb1eE-UghKaLDC1zvAll@=X*upBupW%yY{&lNN?qnhw`%B`Bk6J(FEXgt? z2exgba^lN+0Wx3G2*Vb#bCd#Vuw{{B8{)tk{WP|KIXj#WdQ!=_My&i8M@=y#f$YEG z&fG_{>={F7%%#By&)NVIzTukA^zY-QV=xJZS-^B#+Miu9-VC@2U=O?9Ju-Dyfn4dA zOVl&sxgsAidyDMcED^hBoNeSbp$TRYZv`u;?-q0wWM@Xkx1}sqkp`Tou=^ zsslkb$`~;0y=St*adR>RfoLowf9)pcpyibKpB89~xQwV1LBZhGzns#-lbD8tU-UFo5XDclhuvkBOEGqFg4pF@b$n&=F5Dw8IQcd*73J z5;Ovta~i9dqWd>dby?Dg`K#VVtyBv$W~(VRK>*OmO;@vCP>@ycf06P`Foz1#iQD)x zGqiW1&!@b&1o^+p(9Ycj4g?gREUBRZ4wv^bjy{V=_5ljxdhYU3G~iWlVHfwyn@4{L zM8j^k6A8H(p=C}$u}8v{9~N6y`s>S4UhgQgwgBsg`CpQB4v9Q~Z@k9EAX-{(~{A-Vp3|20+tu-du-S;E)ZZS{VkEw!kFd(0s!n88Dis z3t}s!tn~>%vcamOtcB(oBzJFzgL}yQ{Ru9#NDj{0EprhY>XayVsyYE=#$J5erj~&9 zC5uR0pF9{IFN#><6#~}*uGHEQGm1wq1t4Rfsu2DiWNUOG}LS2*9mN=s){jD z4e{KNgPkNnp+Dr&yAvc9HY!N(PLlXiD?(RYT*~1qh~rAw5tvP$he^p{OGR?O!&6oN z)XZFUY7+aJ1TI%qm1bpIsb+zz43z8YauwC7Y;!XsG#*>N@})uqX9y;ibNk@04Bd@J&70`YgN_rzkE+ zB>QMuU_D~7_TYs}KZ7{#w@jfp$nB?y=i?4q4{FMlpnwS=7EnWV`CZzUVSQTN?9tOO zN1QYxUP#Zto9Fz=zH|5DUgRa3GI=d0nJbRi)z^-;-r-WjjJ8c0g7ITD{0P>Fjv*Rn zdq{IJk8-qY#c88@=^sRBeAnZ2UO`NfTxynjNb6Y*UT!&fXEphGXN}a2#+st}pOe8r zIaYRRplkP?6-EVj^yvv$1NT*c7@|wf1w${+w506oqp%vUg!5MXk36o>P9C5b(Zc0gZrsJq=!X5Bf^Yob9;~b_reJR+;u9K~q&I3G3 z05~l|0Be@YKjwz)Wq)z$xv~K#j)ucIL!p|B!vT;>ui*et)@N1b0rmoFW-3ep8geVR zX(Oj8jFUN>(B{0bs_d|^VSCjD5SVB`d!Q%9r9a<|UFH;3%145wHDNk5Oo?-m8HvI4!DTdXlV3pmNBO7G5@$i0!s7&Ax{KeO5%xu^LHD z?u!gL&R21adV>u8TJhV>CW14`mvE+xE+iGwg7r&eOn|Wf@EaU66z@5Yo@u1YRB9K_ zR(KFxXDV|Z4Q09%TqpaZIR(FRg)_2&u(&3HrTLj{!-#NY0jcEi3eNlR6wU#cbK^`> z@^Mfo%=jCuxDhNS{kOG?6Q%2yJ1n}>a47n%FAWE+k?^Xc1K?^StX7ri#nng44vx%& zD{m$|{Jb;qnblg_(!TEt`Fqde>b%<0yk?@4rP9d>({$UCgVu1nw~D%>98{nQB?N&1 zRA2n0;tNcZGcbVL3saYyFSKEtk0^S8ymK~mihu|hJ`i~+GcY>6D^ikfxo-4kQN5tOSP9)-B^ndAh|pQf z7;w=JH%zOrn^_M!OQKb8^m%tDRNFcn!{>yPGFOF<;&qv^EZ?o5{8uXI$Jm&`FpFee zTJ_FHd+18tNS^W0iA^{vRvxKXku=0?HH!xo6UaZRWJ?4h7U)20(x{5LP?!%YD4QSg z;MJ7M3Yr{ESG$9gQQ4#$unF;rRiZU-L!r^Tb1|hL?)z89Z;W7&XAyN47oZBgHCcuE z@-G&O#8x?{`{V`kW)nmJ9R#e0)`#eYho8m@P8b8`jCx2uiRWm~{hu2h|KSmTKRN@TEgEFn& zbu^GnDLg%9gSozarKaFJ{~g^TO*U?PMWMNSX!U0LBhoj$jp;rwaYa-8)(^^hkm3w9z{3$_bLt)PzBp-A7t2^0obTY*@m-XE9{&J* z>b?Fhs1&mLt1lvqK63d)PRqqok26+gSBDdy2qKW^+bt7q$DOgVP=>nsjNJmXogiSuXS|fgPvw-C3_$ z8!mZx6Tlg-9xX9${Gy{mv>pHxJlN=U<>7g*;TorY+M=0ZX)(5 z%kjiOZcQ7bn+CH_I9JTaiGvu@ILz= zhK*?SNL(a)cGO#0s1@ii4LxX%Q3O{~U>rzHBmPGI89NiylBVRv(g%RGO3J4kJkfib z{YYj&1t_AJU7sX&rs@_eLkds_B~%g&&L~E;cduJCD|={3Bp?F}{B3`+D9W}8ASj6< z>EZwlDul@V_g|@)uZx*vgz1hUYDuc*%&_B*H6wDsl|LLQXQ%-LU{)__iD{T6Q%+8W122lk4x{J7OEgDFCCQ`a%r%H7I^Ecn8r(Hnf*F zg;zP4aMG~k`090!oH~6h%G4XYvk)U{)QB*}3_&F>`rT|EdE6eS{aLL=`N#^U&q&z8$J-zvedQ8LZS(^Jhi(c{aq_< zsc~EgCo=ufqBX3kh5I(d%(`1SBMxeZ{o|5r(FL&Ih&6-qv9V`h@g27(PP!EbM3vei zNAj#{sSP;5D(-297QV=!vOJ-gH)z6NJ$9f>8wW@;i?>Sp8-@OGtY=eBOQbH7k%X`l z@mO1G%1jp{mW3mx0l$quE14ao{8ExL##0e<%&d>oC&O+sR4WoOIJJe9*vsa1W>JsY zUSBOG)hqh3FJGj{h8E8t2LmgaM+J)y8t0A7EVh;ET`m{PiU&5TL_yeoG@-qpTcYDZeN4{_aWUouoqj*kqj=D>;f5 zjKv#uK`KTm|9NrN8wr{9xL5I|(~!Iq$5GKM44iNRJ7S3T#_msorLBpD;v=F$BK(4({*9T_F|wR2>ltj&+^Kj zi>u7;yr$SW%pdx1uOC;}%Z8l3Hx6jKQ|}+o7vEXdD8E|e(-R@4zntvsyN$CP*-od% zu9rvqUrS+^W=&dtd5;@4{D*!wJe|3=yv>6$~?bIfw*d$p#8475IKyk0i<-qO_!7(S)w-?UyQWcsXiVf4rK5l3Z<*DdYbhE~DwKrMY;1 zzk7VY!+vx2@szFVn-Snh(`5w+h%~_?lqzvTfsA}J<`^*TD5C7K%e+25JXl7a^I_a) z$wkTc%~{BlIZm5EmyvZ|A^MhNZNVJ~?jELj#nrPAK$Q^nl}UkXNtFmXIM@-+9GoNh zWVGO*%DL@Y;65oD855y*!hG#Gmh2VNyq-;{mtl6V*bjU3Yw=j0rldSI+&F8vcJ`Cc zRqJ>M=R|{KvhYR9YRp_6bbkHRPJ4j!YYC*F8A~ycwk~NiLb?Ke6F5PYgZnfRz^$8+ z4yZ^GV6G?UAV|~x1Wj+unnN~d>VB*2e|tlo*2KIbvwvxq zEu+#;tqNn6sAYhj&|buxH!sa1R^+6OT(artX6>o;!{?MU9I_2cdpRwQBcwvDuj%5m zGZ|C7cet+P-eloH*t{G3vBgF;V8AOz5w-^BrUrm41QdbaUBc#&$0an1W`$aS39Cq6 z%XiIJX6rX61(gt}7;kOaePn2WnSeixrfzxFh!Gx-$O@$b6^hLo!sucAxA9!mFKg#i zcU0(iwmu+Ehq%Xw&Z*OEn7>qAc2>~)sn5>@!a$3@slvzXkKBlQP{G^@*hkE9L|K^L6la3SgFn-}Yv^H_bWPSFe>BTc|Li z{MG)#Gn&to|0}POSSa(4EN6*K_;ZRD6g%-;&v@4RWAbqyQ)V)VH(no$65k9@(xiDR z3raGi6cEUn03{LHr7e)Sy9|{Wc*hY(gGv&n!F0LD!xQ}t1C4RY@eeO|FxdtBOi3@{ zQ9N43^DOdaVq6 z$hOvB{Ex?evVDYwF?+t!A3E8Yh_hF4LQP5RVO|&L1H}Ykps1|7uE~r(2*gvTuXu2_ zW+I&)_8@CotOkjMGxP%9wDi{(--kxkg{HQOixL)RQibMQB4Pv|90)*~gPIganiA-E z6P{p?urf$NENoE@S0_^7?ZX0vi6lm#I#9G7!J|mqNHT6V^a8o@K*&1W>mLME+9|P?#En$c7%WQq_3GErSd_;-02yKq++Ajo1;CK(PR*=y^Q~GLw2jBn^ zGG=#M8c<0947TY5@q_M>!dyYOkOML!E3`{~!Yt63z!rOd7NGEM(zVKM_|)R5=n+N% zBywb+%$`VeKSn)%emlb`K-xBquO`%ANFD&^pf@ycV%snRQ~;%G@q%=>YUAdDkT^3H zC`e@wLKe?_-1v1vg!)k*%jnV?HCynseSA^#phfE-$m*BCH2ysJ{2@|4k zeGq&+a$v*A`g!aur&8pC*65Bz z7AgIPOrg}NiY@DtxlUFH!QZ?X!D+)gR`Ao@^Tm)CRB>3~jD>6b$65!Cocs+yK>ig! zdr3XfX<`O~6vDD*5}4NCN!p6Ak7@oX5r43jh0;L$iVJbyCdq@Ogex$?7OHe_jG1o>o zRI7lGo4PE2gn~MiM}BPcOnq|W<9X$yMZj@XQ2&EIj&&&MJ^>jy2K<`S^@un~%~8Yi zV-&^{L#;(^qQP!tjAL)UF~y-Ys77O1%~iIwZ!aDiQc73;y(gZ8q*TpYoH5!di+5i& zr!YVBP9e~eoR2bSu$#Dzh6EJ>flbVthpNA?0|G1u25=T@K9c~}?&iib#&QRc*fl-S zMbO(TnR=dYZ;|?`7+#Cuz*&be*nZ>2svlLzYugf*Gt&wD=(y=LvaT%lxm(@1q9&(O z09qgMP$AUBmL8ij$;k)6L*^iNW?_;58R1k{doKenda2GiAuB8h5u|-)z=A|eI9d)A zd&hWoD+DUgOwcMX?x=$L0Vj1WB6Xh#q$KXCp=2ie_mOx@zzAtv1?-^IlTz08PfW|c zezf&6*yI%YN~mtMoP18|i1OWU4TvO4+B0dg{zpI@Wq^P6M|ng=N)F(a`d^KP9vhpm z%8`8vS5xFo$dNP%bSs`I*sjE-3^+UW3(=Lj1VZ%@mRqB{gyz0G2&e8C+mfWLgRFE@ zxWeLHpCQe3(Wi$fb7``U+78@puk2fj_8LCRPv6Mv{bH$K-isGI#{0 zb@q5_5uS+ThIw*kz zfM8UBi?;W54^DM*)QB2?eW;jwscw5I44?s?!B@RVz zyA+txcP}zzRZyr#g$%&=9P;blHYt>)^?Bp+>leQ$T&WC=D9A1?*n>DuYP~e8%}GbQ*x6v6gp;Q)GCOuvL|LZD*fvzVvVZ=&DG_ z(*td>m+2z>RvO=L+i`m77MfpbAHjYdwB=x^vevbJA@8^ln-{mwE?Y3&nJ8`eoxA=( zYvU#qvKw82p2Y~PZm>D*F-ISt63R-M9lXLX_X!5}`X(JZnnGUmo>Wi9!psEDlQj|q zkYk_VNKXTMhW96fuS{dl7s8~$D%eH8=(NO&1bMAfYib9ZtdtMHe8jrui!Z8006}09 zJZCTRNZf85dA>@XF$|W_4y)+ilB^m+A*SSfO-gf&8pyh}OPOX*kCRu5mQ(@6h?ca) zMHpj6+V0OS1mp-io0`ZsWruy;L3qD%=ZZK(JLx4TQN?XC{S#BV3*=-(!_2H(lNGyB z#r<%6Z_FJeDMr@ssNavy{roC0izG}=4lY`%Ay$$TRP;zYJOF8)w4YAl{M~p%6b+q7 zCXA+@KJrKe!C2;IHVYVBM=V1XdZ0e9`QMUKP9;#&Ysz6d_B$ws-Ne%LDvFX;up{zD zM>+c-F9#WAguG8j#li>YtX+()f`%VQj^#IfcUP^ zc+cS$gQA+H5n}vWSST!I=nkl*3pM&`o<*m(REkSisgP^tfv%{!Dl{T-Y2tn4mG(P# zzQFV-)&2F7DfDY3cIn{R5k1$o|J+>c9o!8c3YH$k*ZrZ4Rug{gC+ynlK?L-9LT~F_ zxFir5V01Odw0})+z#D)-k^jpG{@+;<4)*`1@G>#{&#VX&!~ZEOGNZL+`!6dp^GNiY zKO^j)Bf@?0ITDIbqUDgz;a|-#E{p?$LaER!Q9G=4bO!#gQE@Tl{470}h$2dfAn-E# z@>KG%T%okG+(ml%p19xlvftsin+ra zR>!lU!L#{3^>A?YaD1@vH_iM0Ebi@aqRDQ5ZPsl{k2d#)#!q_~FwZX!%PcI)4LbM4 zz~bXLNk<(p&GFpRF4}o&M-4i6^?*~_F8aJi{U(>@r=jy~wGe$$tA`6(W+qwtn~CMO zrujiYHGp)zpgla_#IqiMR)+YVp*|Lo0p_wI4 z^0DyUxsD|+3->4Ks{iW3q-}NeMO7`Rhfd}SAoOUk`bSfjn`-8J(Hj}Pwp;I8KG&C> zCCX>%CA z#kB7mg2LQ=Ls`pnetQuI5l&fh3AV{9#aSnqk3W6@_8t>>)8ZY>PJJ~@Np-QCk7 z(E*2K!%!jNr~cPWaW9ED>f6)T8NhLeUQ0Y5Y(?}}nYdgPg7#QEetuB%EoRmNe=`{< zbMWsd?4|)((xJvR+sdM;#A_2|oTD?{G{o6D{*!_Zi-A+*(K2II6NKkHem;vODJ7X- zr&d0~6jyhy+SqEo^9Fw1`5<$7nZmC7cb)mNAuAmh1Obd(FZ*mjnGR#;aaCksTxB_@$I6Jz(!!1~V`a?0RU+4)hdyyV z*%&8RN)hmP<8@m!Zm&X-imhs~wsa_po3*|Ce7$nAT@we3Po5XKW;3R!&_8;Pz9kO8 z&iEu@KHBfvPqSM#P5`T==Wzd+$R8R_f3~mkfi;(-BUbDthrAY@u;4ly=X{v`M7rkH zwFvs5%=<$7rpUHL<@>|M$U8j{pLP_f;H4;q9VSHWwiSU+?5DS)LvF(Yx>;A`7Yo>T zYT2;i|6Oeh(J81h%#A6aPE+OJ6kZ(4O6tqZB=8&CqgZ{MC8Sj51;Qc;JD<4Cqmx^Dmq+V4AGA&nfrPw zN1k6H8vCO!VgT#d=-i3EXtIP2=zflM?7_=vshf1e})*BX^q{$on47W{m7is~>LhS+)c&8V=ux+CkL*!mad9gvIa5ZRnJB(qRr zQFs!gODJG}0XGLNxou;gfnH8z=JfW}R}pZU$KS1h2fGI(V4^3^U87PK*Z3PeQp}6Y z)o9IUpIQt|JGHJnVwnIdtlHiY08mc&Y79UH0lDIhwuX8nFFl8BIda^4Ay{k#;Y4ec z;CiX;+4HMpL(%Z$5ly^zd@_nyrb;pJ*dRQ$xtg1S>>QwEwZi0s{#2_8_OJP4Y>Z~? zshBi|t^yJeH*4auY56y=?rT89tD>xj9io6KsBpY*- zpI1Wxt|EfKjw-e)ZvElX=LhWN4;OWF%1&6UjwX?}kmNJ#H+~WKnvvfC7E@W-v~D57 z0C<`8xU!;L31tDeeJBaWACIqtA0WXB=7~M?*|yMUqjQeZWoV>cUCtVk{Xp$zsN_7d zl+o#JSGj6KOPyy3&+8>O`zTmUmJ6emIq`~1RSxLDas?ZsGKkOrnd|T8XUFOm1Tc`` zz@mJVUjr%lY%{qCU;=j?qC$z2qPKw5t?GjYTbD!%@1@Q1#*7A}FQ#RL@jy)-=s__a z1AIg+-GAi=2NAcrWh7p}npaAJ$ko*6CT!9}XB~voo=*DK-Bn9AtAH};e$jI%3-OQ zZREPI&sx&94g`k6bNEi{kV*dz66pYo!dxW2%Kg-gar+dVBZ|#biqCv#aAYGNrjj0m z=4`rSj+;Q*SQq0etQrd04mvz;GQy~#5l+JHiLVvPP&J4`(xQ}L@O(&AOWz&}kL)v2Y=qwtQ5wP$ zNsOmUp`e>qP}oL|@yDZJlbGN~w=khWUtRQAhw3gkA!DO?{+ZK>c>=&C( zi{C4OTS$`Uf9ox?AebPG30RxnGcV?AsdX;c?|I_I!<>Pko$#P024Vvv%;vSWkgg9p zF{w^<$Py@yJqD)`By&-7Y+QL@QANl2`}`o3!@zTVWPzSHVO{MR6#1NJjo@kK|1Tpr z>|n9Dvj{s0Vslf??IcQeAnWb}&1k!l7sb*JNE%mCs8t9tHUdy>q4wyGLD`EKn`X5f zRaI_2GM=|@z4sPBT@VP99XfLb*e9n?h=SvY+D^*jj6L?MCxWAFWVt#wq*&CPx~(49 zIaD4FTI&7`uFKo;UaKe&WH@7cYS+%SI;Wb|`r0<2u5(yXLlHsW@5Z6&3#IuoMKW8d0-50c8V@0yT z3^xLdW+f^^qAJ2GFUzx{6gI||lqG4)ghGFU17D<|f>z4Xs_3(bMo}w`k+x)D%_#F` zh+>{(&?=^xj2y;bXd{$`q8@@AgCBC7u_aJZz*|n7d)68ZH{ekvdtgl=Xdt6&za(mf zi#-`Em1=K?4g*$&t{%Rv$Q8hx28Ib_+lY>I)Ozxlh$DPnYoo!CM+OL>Rc_26`S;t> zG3mtypit?EXUQ%+`lU0fGFVx>@~(i39V;Y0!FeUsX5hsgp+<*c9=9xKW_buBn5qQe zuRw*lpz9Gxdd@W<*9lyEAVl*e-GVLrA-UD?5jp%WI<2g{t|94$pZA~vQ3Y2L zebRFe`D5y$6x*aK1NZ7eKdZz9E%}2||TVR7x`+vJ#FpUlN_YNPT_MA4Nh6 zLAa`i8Q=;C5nC6%=R)hv1ruF4J#?zc@oXF(53-Di%7MXF5@3Ig@0)|-JcN=;U&ey< z^9fGie`T@7uQ)7#xIWHSywHPEv_wPCQyLN)lkvT&_>c4#^ir%sZ)Z~299kxwGN_i2 zooy?no)e46tb%9!l8wva!|1-2SylXcbC7TvB&G|48xbA_=gD}OrI`k}7^4iGHH4`J zYE_M^j%xl<--?HICW2}-_$8ZTH3H35W<)aHkt;r7ii%*@5zi+MgVE40(Y?T=I{Q(0 z8W7LdIuZC!-jrMkfduz<&wWubOL9-TwyU({(|g-x+2T`U)ihd2JVa3LaltU}(U9@VkFuKf zOlZ3!Lxz-`gB0@!XY5;ryIAycgr*dIrEb=GhLNz!rMRdczz#Lsu>T>-{%@)Ep8nh#^a?ZwIk8pZ-Re#vdN3@b(+p@#&=u1 zX4p{KGHsztFi5wVWom=;$C1E=qYtI=yVuEPF5c-t>; zwsvV4(W{$!uBHkC7HvLVi%}4=q1Tt&J9Mg)T|FDuG4WAzrhgXs5tm+gr(-=62(0}! zZnh4}m#y)x&9mKf=ZQC#kfmDrZeMI0`pvt(YG6Mt#G)$Og=yM;IyS3Buq3k3GMN+p zfz>nzvP74Y+5B8?>x%uwxNd8!X@H;NqPXx`-f+L&!Dt#%Cp$a~k$pd|JN*H>kN+Kn z)VqmFbM=t^)Lm9{I~()5EIXuGNZpc*`1s@=@plXtU#|b@#4a%`CTK4X*CK>`eb`^` z3EQ>x_4<0bxZ3fvIa=@eyEmG)>m%~x^{W3UXQs!u<^2OrB4B~U%r-V4(n*M=z6M2_ zti>isMk?|9V}v+4M|)CL?j*NtX05zIgNV>fcxon)euzl5`20dNv!ilag=M2R(LMC> zIVJ{-&V6yOUK}G9wA#MBh-lovk;d@mYEtAw(aLC8BKlQZ0}S6=*oFXYjCcZ3eJ28Z zv!75y{)xdyAtRO9x^2X>YV~~ilsz91Nqnhjy}P73?;9RKVG#3_8TNXXoOV77!j}*w zK5d)jCj`)H;^@}k7yLDJ!q1qPvtcg4Q63OibUbh6V`Us7|5#WP*hvhX>|FV~V!9Dp;PXaxC8mLBnR5oRxXj>rbVKLNQTHy&tJ#eyQqAYKR7i-oHU?Q+c{f zha0fxQp-eaX+NAX(_Kd*?P(V_#O*OAE8oeN3RU+4TRgN1VmAW4>z5;_2uqu_7dCln z(Dm!df4Za_c|ykHO9?h(rh@M`YT}+XGKXdT6`j;pb=@m`Hxd>Y$G$0 z+NRHBDspPwlQ<}_i(X(qn{*4IrgFJ+ASBGzr{GRxKs>@Gtrz)??w45aTJ#Q2n13no zBF&Z`Z8#dbiefOuwtu5j+wcgAKr9Bg^j}7#+hY?43*qTUC4jcJPugAoktDe&8s~~_ zI(Hl-6x7XT+SYJD&=9~`)=3l}>R^3G@_rFYU$>4hWihDS9lRBrDW!Y3$Mq}&nNaQ| z=4)gMkwsd={kDhafH@`C?SNCcKzN1`pf$&8aupJVx*taaIjgZ%Z4v4xAZiEw1u8^mbBmzjo zrzBa*yvo`!gNy_4kJXtJWeQAGY7~iz4=}V1&9FRiPKzHtXbdGs;=4=IYA}A|`7EbL zTbHr)xRYm&e<~})ydriH5(`62Ku-XEQpWY*I_DlRXu^tQ>qnQjbj<4|Bu(N}h0_k^ zOu^-ZKX1Z(|Jsb~T>1#ys}!k#ID4rpYTU;s>p2j*L9$!l;l`MV#lYscoN#uHmBkQ(|f`Q<&} zg%F!x_n8K?X0I;7nbVuIWKzx2J2rnMzL9-LvaAduNY)PdHv&)AncD(-7FbP!bw-{x3GW)euEPEDI)0_5r5CtT1xoyP+6qKllc)FZ?>xpOe79slv_u+VS<7`bh@v1HLXIkvIiijrphz zl?{#rF}}LPWHis#VmITOIke-#5^nlczKPDNU)9jWDEas;a-Lyj`C#dULkH6H2^#{gCuL=fW_;tiaymdu^he;#5n zrA$SDDsHzTi^*p^eTH0NOhb)BGY=Jtz^pBL4j$D~t8c`jw3}1xMj5Ei4Mi^*f!&E+ zHy}+3Room>cPXd7C)iSI3?YJki_$rctulou_awKttQCy=@9-t5I=i|P)m(}>BCGd= z>`8?m6fxf<5ESi5!;l9veG+JoGaP~;c3&)3Yus7@j>17iDQfwJ-4hQSvwaR!T56&T z_JHSBZYBBw^=-2{%|6vX)vMV`B!Hqn#Eudu{8McuR$?dp{&;SKF-IC)3-{LX9YLya z@0W|96{q|fW6AJ9)bwQaZM>o$Lo0~WDB;H9Iu)L?+@QqX(c`%C{Mud^ z3esa$ydsfy)a{AcEP|`4h#7hJS|D+&{&U}9sRo`s{1C09h~ zxJWeQ)bdwi_D6n}T=DkBew77#3uk9~>TGa-0oZ>kSc|t%XlM=f%|nFXy>|jPYMW-k zYi>4NRKT^-M9BQ_+pL8knB4kyPycny_E|YvvPQ?K%&+Tk-_&fi-Rlea>(GuO(R7dH zPHKXH1|3q8;wdaogE$UwkguvcJK66C7nybHOV17o+7vWoI=j?$Wy-1~0qLL>vvI1o zr=FMVqIn=x?Lo+j6LZO?w4H7P!;VhuBo@*h6wZ)lc5K1t-R@;i@%?s7$Sh?yf}ao- znL?-|+m;uVRcypE#InW$F|lPSHWr0bEKNlB3vL~a$A1}yp=K1DZ3mdJ6bZeGT)1@i zzeY589r&*Z22_-)m_66ohLja9c2()M!6v6G z3&{MT6#UDHsYxhOoy1F3NgB8=6aqYUiA+=wEby=9vuvyiAONZ>U;gv2j^b%wVy#L- zu6PRal!7>0Unde4Qq(&blTlH%UbX>w4f{q_EK;r3Vb$VXA8o>V9{g|}L|6e-4*aua zLXlakq(|1(fC3jD@uCVroDK;8LDh4MY0sq98enamDWi`me>~{`Q#H15Xj`dp2uHL7 zC8`C&Y>>KZiJe!dLkZJBvGnkgI4X|XSisG$TL1LPY(Hx3u8cJT65>Vjgg)66Gm=T>Vw@f;+7H zETyW5K(1R&hj|R0=b>HAeJk5e>&WHKtMgf1-tGG-uOH$3i019{Y}(i3g+8csmzyO3 zZyq*vsKqvfy=R>(g$J$>?KZZ&(>8iLw}r?{N=Ff;j%#&GDiQH*9cisGr5HlzKQ2eP zVh3R1Z^N|3H$ukZr-%jU<#wvPz7^)gvxgsJQyQ~hkflByNoU3ljI4s9Z8yemT&g!W z{NzeeIsi~-4;~3SOxN}~=eaa2li z97<<8GB!~NW$-H?N@@LTIodTz?q*0b&V&TY)LUGR=JH#-jH|deUW8QSBv}E+`2(x~ zmsDG(69R$arJK13BQk`9m9;C~S68{<7o4kjv{M~2u=x+)P@sd-W-J{t31nV^BP_(?{f+?fu*LK2PgMRVA$f(mk*xvV} zDgDDVyG)>OQt)T%8%C$Lakrc!ifCB?ZBK8eHg^1962pi6G%SNfOLCbbIbQs7)ht9` zQr>-)Zlx6)mNOn@8Ny9z*SSvi0U{rZ_n73 zsJUWbSDcRPzNr-fCPVJ&wFL|25`Ks-)!gviy{lzOK7vf=$UlQT?|N)%Roq19iYw zXmnGTm`(og=_wkL_j;VMoQPtFB&j^9Aua<`Xt!Lm+_#ibA08Ck-&Fnrw)#>OvK0OVjmJD4yf{T{?pp9{f6M`e!qOt!RdiRZ=zs{%nNd7$|8!## z?T`nyy*B#$)cmu#l!<^&vEF}d?sPM;%@kvcM8>`M~*iJF>9DiUVI7>RYia}x`5EqTdzXs0F1Gb}^a@o_x4 z9VZA~gi9hXdhaGp2X^Nux$zbO=0A_U2qVRCdEc8HoRYa7o=M~UGFMF!Cp3EhHUF=F zu=&7%R5q+1&stE>L?^qOVo8xkv*b#O!_>+8vL&Cwr|cf}P-fir{2Ac|gE0-_W{aZDGy2}Trc*b?XzeXKgYQ%?ukmk9t^Bbizgj78EpVj+$&&JZ-*U{Cg6(`=gr z%kuuJg3!z%u2RF`?JHE>LI{l?Qlg$z3qSFXuk{~5?g*6W{|^i1zxLwHOzi(J0gsV^ z`Trp+{2zELBg22#GXKBu)*dY_Csa119W!*k1Mb|4BbZLT2T}i}#tv(w?iP40EefMQ zS;K1x_`w@|^?Y7kT5T(s(*eY!A}I-Gzp(7(ujf^ow`I|(|L|bGf1ZZtxADGC4xZ<$ zViaX(X?fBp+chd;q9>+#t*fC8R|tISiZ{92Io|ihi|yF-R#zU2)WjHn2p?dw=;8{H zonM@u1Sh8N7mK(jNhdJD*i2bXojwoF^fv2A8UEOLJ8zmT&de}i)U}}}WvIw+*zC%B zqVP*ofHpB#g|@e|@~#;YToMMj0+$@uwa#rGG(* zsws#x@nmgT15ZWx;NlJ%3JBP;691d=Us@37`IE>SC|;gPhljK6^K^YOJ!>}`ck}H; z^!q^d^M3pCdA*$vn%0ZO<=yzKuPo&0kBlWQ7ps(&Doc89LLsoW6PGQze(_9fN>tdm z#<8YACqA<&+vmDf*7W=fIWeU>qK@`cePQu|#e#K$@%#dk1tki{PIVQ-f@?}M(Np{3 zP}ch5HtD6|DkTh0l)7ri?|#|?Z(?ipIQRO3Wy)&Mde<2vq@!;-*r~m&>h)r}U<)UB zasAQkufOziES{Yuk)!j+Hy?7wta%XL3oGt^i>9#04rRv}OwPm7_ z#?Gc55i5Ns#dn^wM8E zP#wIvljRB(nsoOfmW|aZ-u8ti_JpNlBKMD2PHA^M*tC!zPZzbyT@kb^%BMg1>4lee zQ`mgu+H6sF2F?a5OEdsDU=UZ1U`D_T{9>B|+7P0*#b$!+Zev!^Gl^~B*U@RQ9^$^v z2L0+^Sg_22#^)dh=BEGthD~9uhZV5`*F%_MR)FWCIlkI9Mem;mb!R_61g*q4VdaeT z|F&nm1IJLYg3UYg>+u zV1eTjt&6n?)6-!E;=p;);xXWb`X5+a`NaIxudTs8Le;9ZYCX&a`}&7R)56kHty6ui zbA@7(D97k!o*E9F9P}z`x=M7O{UVw6<3iS76t@uKzA5aJ*L)F-TLgm@8ogl*6b=AO zAl>xl8!QE#K=}{r{xSeumY74n;5M)?$K?ut1Wf)0OlU@FN@)1cc94fNWh=pUuN4me zAt|pcuK(EO ztCv5lMZuH@9Q45#ry!7t#AbV1Sf&>1GWl>J++RI|;qaSWeOD%6_Rp#zmvq_M@MM9- z0eP{Af#bSb>~^4GOV^dxt`aJI#(-9`v8#0`2fOm%MC&e6q?`r4Iq(w*%b@h#5k@pZ_6MM!KD*krh)n+tFQ&U7=S5EqTVswuJBvj zMA1+7rUixt^8}u(!9L-_03T%U+h3nZplekw7B4J>xb&xOefqS59)n$00MtW3(FX~@ z8FLwDLwoyp3cnDBnn|Lk9rc%(!XS=r`c6*C2^lVRSR--X;T5eLV-_JXyOp7yVp;*( zZwP=^Mm&7{LWBN@Q$L)oJj@3$R;D&wF~7aMkbOEt2I~R*CG#%X-r^m`o4o^nUlrGe z{!?KDYu?U`uPzC42fus-EDMXWWEIoRItl)$zP9#$3Hs@oAw8v@-TFcj6ko|Rz9_>aq%;Aua$G``Qjohw#9Eh%OAkmE zwG!Qm_sVjnzz8j$UxI*5+so`HDO1E?Qzd7o`Pj*l*Lu>la$U%alNmi+P1?N004K@PPTk zok}6V7u%G*!tqeCKjKjPL85-3$Cz95YWyhiU`u;uO2WJ#{%QZP$$d_^M(I3=hjn9- z<@V}UnLlMfGNFACX9lO40U8SAN2F?2_%-I`KhFF5WX4|>t~d|FSJ!gz}Jm&;B#*+k8 zp(dzTnouM&?Lg*Qm_#Wp@GVOILfsOd3}+*2{ka~v1FwaJEiPqqSOh#8D&#_V%2kWg z=u~w8e_Vc%U?ahv5$A19@k6g5z z3N?}3D8SdjhT!RGK@-4UDi8gktT(ZkqP^Ga7&I)Ba0q8PbbkwfZ*0@lC`FP@&ST;+ z5rnVT=bv%E|9O$*3@-vJR7HBI$zox8>EZ?M`(xq@&#{(-MfdmA!tXYRkv$U>g{vL! zo2N0*!3Z{T^NY!t+izh^ka(1yzhXpD<`wZ0lC#uOT{OSSt1jNXsgxwEd5G_0%npT6 za)RuG6!e(gXz08+pU>E&{+mWqL;!SO{OC@ZS3rxlMY7b_mNC(5%aTXJ3TejzQxL#poO4SOw9)9{`$1)Lh$&MWIi|^{L8Sl?zry~fK6gAu zF>-m%lj8BH5$8Om6UiOl;u8cMP?I@^2zcDo+0>!eRL=QHAYB*^s7i~|<`o}o_)3&a zDomk>9XJ*Xj;R9`)zuKW9Ko>JX93cCK1EA2$jYTNF3!N@&4E?K=;TLUdxSpT{unvl zX=5P1-Pv4x=0jD#wP+x3?-^C-ZzD$B*OSNNZwsK-x~auY`{+P-8%S}a-~Xit?W7ITq_ zi2&2|6nA3sPhZPZ zvw1cDROjvtJQ}7Ep!*=Wz!hvNPDf>mqiB-4e2nmO8KUA@@(%%s1<9#o9#W(uB~}Kr zgA0ZHG;5BhYwq>eMWsVldvaCwugmR0%xC)EhYB$OqY`6BQ4?zX1)WUz`o;I6>VuFK(-}a($9{~00A8(0UU2xHbJrri0dM_GT{Ne z4P91+i4#R4FupQPRK|+<({DGDuxD z@2}smGMEok^I~d!8vgCct9zzJ4k>#!m?YwrKhw#EMX^nG49qX4xKurU#VBYFwPl_( zt(wlkVsuiSZ4|j?4jAoXoiAsr9KsJ;I9j|;(yR1Y$?U;PdaU*$bk}e9y2}lA+xcg5 znLL>l3_az#YQU6YW4sTUuPQj70LkQz*D(y48sjulDBtLl8M;0M8u4njWaj8{sq_Hf zy&pzW7Z?CUk#Q8yNa+DT(lsMO*iEE-+e@M%pe(s6rJq;->ciuBs`%#UkhjE?!+XwH z8P3M$o^odMh>j)_T7CQllzvZ<^-Q>L3-dxmD5&9zhnU_#!?a=u#*G00>o_#HN}m+V zx8%E@Y~TY;?$mh_2Jy8VECObhfrrhBFRqBu{cO=zn4>}Mbm=UwQOSGNUP8<{a#t3l zM0k9bY`&bYrci!cJFDck;26NMuG$ca7vlZX9ln? zuH`mV=q%@_Vzqb0KHC7B>5st0|XJWUxnOE>zHm^tkLkc$_ zx*-Wc5{m<UH{xxK~!#4hGOvXHV7d5;UE6VB$|r%rdKRs4wSEt%3_D$Juwf!LcTU z0(Qa@L0THv&1x(^;rRVzVXxdFwB%DJZ8%49nzB>lil7@8`HMc zhf;65fw(=dKpZUCjM0jN=Yt~gyq+H+4=->E3?3Xag+qy?pNLQ0FhpXbieUa>tgkRP zmUp#mIny<({=;zzx8lq#d_Vj^ubEm?)Pv!pPu`IG|5T%mx7PG)EbaFp z1Vn$y>$h~@`BI@%JS;2~qI^{=SZi52Qa#5wx(sv(o1! zm5ZIMbI%~~duZ?d>Md!3zZ?v^-VgdNzhu+<+g`%LL%Uldce7u&yWG}XPx^gG>Z>%! zcD>KXxm~y*}lK8&7iDiXu@}0cAOGT+}z0(sQIl@NsrW0qG`?e*jzCL5Kh0oB( z{5D6BA%7(5)s`PzYK1vv^1;3hy5l(KdWV$RTy#lreq>kD*PO^md~V%M6FfQ3c)sJZ z?k|XYuz|?RPj}?1ys7BUD2W2vN`TQ>66YrjCUIhpPSBND{lcTzrYZGY^}q=;62oQB zLzg#EQ&Pu%ctE&@Uv`qs(~8+$SCk2ujXf$ESj$ka6sS&QpB& zM5sW8gPv|HrZc-K! z%A<%gj}XUf(aC8U#9n6~!-}~6!-h84oAs)=5Rqu625P#l26RJ1e!MEnZ5JFo(6J2< zh6JX+dDc!^J)dQ>9hza{G@zg3zjV9QH@x?gt7_1eIupmM&*!7VT_IC?!ni%%eh|pT z0jU&`q zlr5ebd9|yaQ2kato$8y6Yr-w>^>Drqvg^yqX`a5X%Ln`W2Oq;-B?|rV2=v_k*tjd| zoOK7rK)Cnc{RcPwY?GIhS%<^he$>YYH$z0R2dZ^?^(v7hxwJ7Rt;Ss=X;^hVxjaHk_IwEMHufQNUX_ZT(PF8CEm-Vm|54F!(zbOFky& zkSjt*>7n5@H%G__oztd}b%Hw$LPmt#jk*3FnJNlS`rF$i9p01xnl+VX=Zmb8a?&t^gOHLkX6ZNt{oSB7uBqeW%0Gti8-vx1-SdvZkon=Ub?t|(ec8S zjwx0#fUB@IRNCHAk?>UjsD+uq=S|iJmu-&ds)E9kv}cj>0PEX*?QqcEp%0G|j7U_I zwm$6*Ya>uA-swF9AsRs4zZS^D6z4sZJOxPdTC75w>)N1 z%>Tpfa1F(RM(s5H8zXGPuH$n0TAd?&V-M0n@n=)v zx0|AeBDv4r-**Y@(+p&ir11~;TM`x5!aH;6*DJ6Zk&1KBsE%J&UzTmmHN(lF0 zHOvF`aQnheBBwDHAxC^7uCdR~JiF8kEEq?ClHH3#(Km~?C1DCi%*OmMtj>+VbL6}A z?0M{EieN5(__d6wVBb9}VUDIl&v&S;l9)sWIn3j8lIPR{Gc6PW{M+l=N3rL~0_VX- z2Xy?;VKKN&_eo@ZYC~wZ6ttvQpjN4L{U>)gsN~t~fxX!BYVC){?RvG`9m^8{y_OZW z=2>}@d_Z)LFu;+Oz0(4Xy7<7H+|KHV0gJ#4)-aCfvHN~4_p_;Ah6L%ww4;*gIo3sVZE(VTyhe#KxTx>N5#e$u|h5Qc! zP>%ZDzD)5(m(PD*lK@TjQ?$FB2di2iSzl#6oq-C1$@R|-{yB)vEz(|Iyn9d>nTIr@ z%f)p2^r?ZTc|9b4FA)uW!7xw;py>2XYQJ*p~V;!?U*XBRsjoK$X&*n+|GC z;v&!)DoTEwi58}u#}+5l$GSz<`OPPvo0vnb=WBa1X4Y~KfPg!wNXd44-&`~G06Tm?7abi98I93 zzd`0j-Q(Hs?Bim|;1iY$5q3Xd&YLBj3wPWhyY86R3S#d;+lgBIgaS z7Zp;T_zRVr1`Fb8GhjI!f%@+*^%{`qULzPeeKM}O zRW$f#OP5-0SmlhAw_p})QyE2j2l&2^Wc4Q`x#Qvrnfy9iLY1# zW~;WV4LR^akTzdjW&)vMyGBai$9@5K&v(1Wd z2-x`a6%Ah`6O8yOuiFgS+@9Pw$oQQxeh zSk$)#u^S-r_UcPbAskbran=gM8!2_sZSWg`IlJz75!}Gr)+qxH26!E)mG)c&(@ zXQ{9^MrA7>JfyFbKd^*IgVwYw=zI2@Is{PyjXNwk#qRtNBe?P8kOZaob`6xekj$xh$^EJug`UijFRP zVYgp4LDfU0fj=NmU3l1Jdw!Q3A-w=apqh5~cnh-w-CaMdaP);D?egqr(eOaBM@aFt z&xv9h3(i3h5!!WYMvar-G091+2oi0`$}NP2^ELHxs8{AKuMfJ^&qX^T(b5?e%h(0y z6S_s*yH{u5AKL;zRZ&O_1R)cvx+^B#x!dKnBIe^WN96!TCUlJrHx$uP*b z3MTL?16-)S47LM=0h3-3Jj(QuG{e;g6SD;L^GnT{B8~#Ybq})-3GB3_Rvpc_32p6Oom0B?%Oq%b@0C%Xj+o873!z8w&852|MoL zyIdav;ExHMJpsX=G3ylV{hp|1vCNeRwfmbC&`{dF_IYL##0B<@XCyxOs#hWThl>?$ zh7g!XOFX_jJ;jC<0z&8HDEk)cohE4KCGG)s_B5q&$>} z8TP6g=!-6ej-7-_PxzXP7od`AJ_XiX*k*#2;8l-9PZ@gP!AG0mmH>Pv{0=7EHNo&) z&wl$`d`*J=hmoz9wDfMdWBN~4B`}_l`Lckfs$eo9W`i&|QVZ}l6`!LgOf{jdUlDB( zQ8cJktKQ3*OOH=}THP+)H+1YaS@HiAME@ys{xdSq$o$^~(SL1m|GOY!`(FtntzYJS z2coaq_YgOA{EfQMJ@3o3n18hqk-FDIa~3$x3Zj-#o$)x@%WPSsb>gtajCgDeF+U9O zH7@S3VMAOH{2W|fp*rX(aGpWTf9z_5Xy9Jnf!c1j`oDwo{>7#J$0kmkiNYBa?BWJvPmhw{G8b$cFlp@? zRybo%u+|Dz1STk12l&8}I-Kc!s0Hby;;15}`&-WO_>B1B*1=4e{G%yl%0?)@n>HL-^DNL^pxa({a3HQN^|LB9If0!o#y7JZtamZ9c zVKiI96nx!z4=SY0GC-v?bNsKjiUVX{Q&&q8Qy~$_ODIPO{WpY5cyKgrnfqQnbi$tU zmR5*E^d~UK%iF|rqt2b%@lhhkv+D=9+d)L)^+jA?85SiaZDCX%Og4TL2Rt-slQ4V% za{Fla?=kSG-05ffW4g(0Trp21xq;*7kzr*U+M zf}2Q1Um-_1>0Uz(jDMp}x>#PDs)ROae)FMTFqXsBr-VuunB%HOsbI|223SKRJk+qZ z$Z{wqRoKW|^3zmSQ?5~!Zd(ci9j@dw=|{XT*$0&PX2|(sA{&IRTT3i;_K^W&h+i!& z6U4KstK_Qw)9x=D2U~S6$=03%>vS<@l8!CvP$Ek%ES|7g^9tUacM>4w@a@nCRD8;2 zT?WnU?F^cO0YYW1xVfPKCj5rNqL(v>HEr(6+gY|GTH*V)V}u`fP_@9HUwl<^-Rp$M zC86$AoM?fWg2GR}AR*9z-rF|wA=I(g4iplD$j6&^)7vIwU_or|j1xf>P8}VSNk^qY zru{S3(c$QYWvyeKpChp->H3Q4*zVnl$t%SMSO^&SS-pS+L@ts`#-Q>uAH`!}Uw>?= zGE!Slco!MrgpZpzi;_1WPgQ0a_WC0VYuH>9jTrB#)+k-9uX7(o$mVW|N>Jn^tS~v+ zc#=UIdX7K@w1ovuNI{c4b-O`oP_X602)D!;&b!_3kqRxHJ^8CSww4CTnQDeusm6Sb zb;MNVn8kcY%`GsIM z0PY_8b78@NAp;oRp&qfoVE|@uK=mu4BrdrInQQVuvqQMW(S#O>%_4dZjNn!t*+XZRS&|0N*ODbnf&(_oUJ1u0>?~WJ#z> z;EKcm1+>O3+Qjn>T0^Xu6p(w7bkcrhC8M!zU1uk~MBH&&Xnui5SBEC*K1xBnSfapMT@nZ8A=>vYiFX=lkBeH zXR*%nJ;N30ZpsE@jYj|!YlrI$p3U|TBn*j8F;+oMCzatd&b(sNFL{Mdt=rt8`4bz9 zx^j~)WH)^503-0DQFFBNr>x>SK_o-I5bhH;Tmp4yR-$U5LZaL5ijJr=$z~V}2)!-mU`1un6 z5U^xe9P4ptEcg^iC8{x%neN2RR(YThL!v5(Pha<=dRMHCDBN@>sgvRl1T{pM2ABhD z)}qKsHM;Uk7eBF-h9X^@=(Ts{mC>bm_M*bHp@qKQXfbILB3j;xfFiA@%YAP}y`g^8 z7(=oa^kxfysSlJ)nj~+{tT9J7jT^*X*5kZEv@u*3Go^c_6*I?K0T^0zXV>JC$D9GU zWWT>+)8s#w_~0Rr;_{nz@d1h6Mnr6DJ|>-j)@LD;L4Yz-@*aIreb)G}tpdH#S?fUP z%0FiPttyL-L(MnAI9s~n*=d^Q-rnToKcfu0JHw+k5+t${@#&=byZlL6wimTd z-|?aK+R`#XRy`?8J2R4p9yZ2C!bXU8$2UnEK0=gU3N9_}f9uo0eXo|GcH{Kb@I{x= zP*0CXXGLw5I}9|)9^F9{9nYqXH-*bw+6aG zC(;QDNUsT^5D2{(!~h9335X&hQWI39N)rttDv@3U141MTRZtWVR1^zMjX*$jqap%Q zL_m~c_bx!)?z8u~#O{=WP$q^#FD=bGi2&wR6%k#;mzUWxCO)|07$?e@M#^>ff_ zDXzm>(K%P;a9u%bTMVw(s9(jsgheMjN~LzNOOBbBYwo+F6jyI!)Z-2WOST-dXr!<_ zZ)v+fbF4S3iM)3B8p89dY=0joZW_15trb`Gde-!tL;F{D$jicfMMB>+cym3A_@5up)t=E}`h|}L8 zn_uI%oQC<|S$cR%v&Hdy(4|wD?rwFaiD~z&K~ai{tK{5f`x9K(DK+bq9YQ3e>WZx~ zzrd^B`5nH{ShH zLwOr&sx}S*wtZ$0=w`7|RMUoF~TYp6U z{X&Tr24%_2P zfBE3~UAbS2rRIi=qHehvWo?ywepk&PS@^p7A>}KZQy~gPOUFW=j~v|f)j4-ffzy@= z`1dp4n+B$H8sah8n{I{QxteBLajok1=2^k-mkhVz9%rInzj~WDsNl6|9QW9)`(XOk zid)4TwQr&Q#)tg+&DuL(=lLD$tU|hPHVjg&9ch?v+qtd(Ej~qSZmv>3&I+UV2j-R5 zVUPIUutFR z$c-IJb}10@Jk1#F&h70NcF&8odZkakYgw6m>PT?d_P$f)w@yqhIfZV!tr(ZJ_jO$7 zdRfAW>#t3YKUG-Bwju6iB)@nSA;(ts*Dm&o^5bxBKqGhA`!5jFA63=|W*<-9Zcx=r z+_+V5hs&+2K^<7@@S3%C3-MV4EsDG2sKVF^|3GO?VWh>bvGQM9Q_$>47 z>l*b3eh&Z8D=l|GtG$wu;jiJ5{yz+l^#5zac?+vFkuUvtE^%KV;;|^E*6Ny_J>c@7??I?*93iu_b&_ z1wQS_mz(2N)wZW%=f@7-Z%FH#D2rZt+CRJV-uI5L6FpA+T>gR^cNAO+>f05J*nGon zhkhkZ>pr`D=l*8tn}rUi=7hbxoJ(0jmm4;=ZTNmo`o+sviXolvJS%ozI}%JjTVJ`~ zmbfbrdf@7s{4sv9{*Te(ygF~+Z4yX3Fyd!)&i4ycM{y+M+LO@KysA#vwxEL2Eqi+V zbSrCj1%F`eLf+4<&A!&QSE3~OK>3`x;c)Q#wKIGBJMQXaWj2bXc(%5sCm*a!)O~mS z)QQZf+BtQDtkfDib=i-nZS?q?Q@&m(FD8FSWWKvHVZqYVr&X$KxZe<3W0tP*osy^X zEO=1)z}t8I*ScSq<6Ix#=j}?~CX)Je=x)PtMVrB0M{~W~mTKpo^Cg~Y5wnPsTCc-= zG|Oz;JEJCYzu{KESb7!DmRq|EzQiD6=bEn>U?hX%xGgoWUJ~Z3HIkf)2#Ly_!be?y z^!4r0Exj0Z8Nuplfm@3bYs6^!jdu`bJZfg|k7RRmPR`XFR##5)WOJn%zE9$sA#8!B zdRj>HAIcyl549>`w_%4n`S8TU!kA*@F5_bE)ZSbL&-7_X>&~P*1IP@l9yHy8D%@ z-P>pOJxf=xJPiHKTTANamXg=E62q0q5uM``&&?D&HU-`2&z$l((81a_x?$#>aIHba z;k7e{YRv4$$Bj1|6>rxrq(@=i2-Zfu;vVwa{%!ArNkoIw?Pq%hNW^EScrfJA`+Vzf zVjI@)m*aHoBp)p4JGGUyXY4AAy$h@VTpiM`>pZ_18!6*(^y8sw;^@PV6C8ugV2JGU#7bp1|p)UF4jCIA~^XbZN2%)Ub{@r z-PdCc>mJ8n9PFN7e=jdL|LDxIkNee?b>%m>a6C@31ZnHe?#?%?k~Mzrar1>u%zfw$ z{a3syHz)R%eJjh6l2`UD-FkJPC54>oGetMh?6Vgn7OOu{%k}e~vSOZkopHcYLp3oE zds$TC*+W+9E?nw(&NfWONk4@N2<)Tw?U(YmUIxq4V+|ZP^Jg*Kp9S6MXiDu-Xrf1P z5Dwe!@++9?$Q?J8i$9sCdR<#k%KnQ*`+ZBVtHvYxUp`9fES^NECaM$Be;ktKXEWxB z0~7dt&lqho2eziXxqEyZc9Y58qaq8ky^CEH-*dWPvg>N+PRfdYnEzJ8@C%2t4sO26 zJyfT*XX!Na%xd)nD& zB-n?y-cdOxYA$!S6pL7(rmkHtFLGp$=i3M5HyZbgHN+GN4;@tIa>|ZUL z*VGtQ-*Se~+##b(me@YlXLslm3h%Ww79M8z@s67L6U!&naej1@4iVqZy$Ga=DV6zTieX>`W}6xQQlL8ZWs8?oYhPpS>gR4c<5AF7>c;-UFR zo1V}AkWv__y>aW?rhj4J`J%cq{y7bZwcSDuQT4^cEs?}YMb+Q>LF+Y*y0wJh$mnoD-_A3CT# zEEml(wWn3bEK(N(CSFz71>n#DZrJcgP7Vn9)*h^%PX7l$s%LWRki^lJno;Xo=2}UI zEit7PDmw_s5r_>rLFS+>SH8gMv{RyFKbyB2o)1{Uv!NI7GS%C*LO&^tC~;-Ie?3I0 z-$3m>NB%OBkuE1Mlbv(7pLHJ_%OhGgo00i&n7#u|Ibv164xyQ~ZFED?3%<`UfV1%x zLX%l%KeZ|D(h^_yM`lQEj#7vUB&1XPZn43$J61jh%^6%TT?Za#^5_yo6pugMT8;C9 z)Yf)wKS*qb@_#NKJaG*bSD{e<#%8yzx!A_fWg0S;+ojT%}srS}x?{F3W2?Sks+?YBoBv0S90xFhB( z886TCD4si78sTeETqqW!_u5>IdU(ezd%t@&FZ-m*Pc?6qxUH z332}9J}c2<#Y@qpyMYBs+6VY}%G0gJPN!h1mSRrl*LxXdp4%ZdYajgVEqJAx%Z};C zjTFnQFDj}(eVd+m61GG5y(?5*TqmwG+@-<9=;mZXU0%YM&h;;h3q^t?9!i*HsuOOU z?2}8gi$9{H3P0F9&b|9fr@qxY5sSk;lQ$#_h6$6coonPp_0_IXD~? z>k_Ss&uhn!SA(D4BQu1)XLuy~yxDng9o=@<<&8*fud9)LoB1`G=&OIjY}+>bLk99TC9mDqSVGn$ z+!UJE>W??TlU%FYj$DqqTK#cgvDMIl+|B3m!TsKi9^v~L^Xom^bcHLXxUPwLv+T2# zJg$t0W^3`|&NnJE&kiPpdKX<1oLZZ@m>svvkr*&@xlQ+7b#6`g505z9;C&yO!!Qa@4&`5ZAqoXAINsJRa>a{T7FiFMivq znzg&}_N*N)rSrBke@6A!h>K-?qa;xQ!7InZO}F3s8eyY56#c~%f=X&UYQcN?NWwLV z^qZ*q%NfYz9@QLXhO3G6CdxV-^x}=w4Hq99FCD4E$^sYT4;5^t1+gpZq}iXIGMdgi zluqmKS;zK&zD4GVxhINS|ImKaI=5|GPZhp&aC`LR0*{P>KsP;(o2%Z8bEn%AnZJ9D z?#+gTa|YkWlUw*uGhh9n8oasd$6oU!EROgpXpgTAcFZLmSM2VSrtICpo$8s-FZc(< zZDNigZ5QuBXxsyRd+fANM0tap7=ajFJCI{6UCN_=Kk~YZp~f8}bjtdRuB~;#kax3m zs%?Z>H0`x;;*&F(2N3rZTc6BS4~;dP4zuvz`Erlc=GrRgQl@=U&w1{-IvYRe?7@>? z<&?IC22J5pcI`tWZ9>0eb6S%5cAePjD-&+f<;|1PDs!NEkF>B?0GZ>e! z1HMH6h@CnvTWyqdT>YaXz~eB{5w^sYLy;?2GlJ^a8~_hTuFPqmmX=T*Yw$I=Vz|=E zPwkf90-Ks;S&_y+IvH^7|Ac^gs{*VFsJANZUj#&&tSJ4bgnB=Ft$#;C?0)c!Z21RM z>Mx%g(E2N;TxsnHe>J7vvguad`(evp4)8BZYW)wAqJBua-PtF|-#0=DwQ`-|ACjY1 z8qmK=uD|M7f7%$e{Km37{5z8W%}r6Ordzcw>em_n(@jy!ar3)v4VHEM_ayx31uM`0 zWMhNXSkn1vV}su{F!%=z3|3FVpEfr9cQyE%jSYW~G{b+0G{e71_#cS0f3mI7k39F& zwnnQbf7LsTer2pby~FT-MxN1cQ|f;qi~aPDzuDMm^~A4AYP=eTf5~P>zf$mz9AW$$ zNA#bR)MPac{PJIuA2wgfZYIB??N1vU|H>ObB>(-UV*gRef7tk^cOX|Tt^PAHBUdk~ z{@47rdatwJtDNq#HvfM5_?v?uS1vjDr?CGJhDhE2nT?UU|A9dKr;>+6{-`9Y@B#TN zLHy|!NZtP#dq@zz{C8}-dfkAZVCM()`AhgAk$U~w|DXI;?^o6Pi6!;_Gk*KO7HK4EHQoNoa>%~`4dg!|4W$0x z9QwbFHIN2B3gEAlXYiM^Ven69<8OEaxdK`K8@{uGbbjT$KVimiS>y+N`V$=?4gXtN z060i%m`b z$)+oK_%FrUivj*msU^rKjW|eYq8e*2{wOLIlUiv zb2aSrR$%4-KuD`s@cxS$D+ur3cai@WHU0 zLrVRBvgMyd;twg8&A%!m$n1d(vC;}f9Im8ePxcE}+6i4<P}d4FAwX9c5dw6DZXiH^QC+w$|O53jZx;OiA24?h1`dKF57 zuUA0Y^7D`H|6pp6KX?%2N(}@*H(otK$RET4awRhopsP6teE!jv>8*G@`1%Jcyn4n6 z&|OMktVAvo;CjC|@xLtf!%)_HBKGV%5ctz#zsmFv%P!0K``Q1+l0$WzT^yB=mf*!6 zS2^(C*du}wbVaw{km+yh5RfS7YV7I|kb2P76b1gN3tdfSIs{|rO0D?w@Dnf3EqvWB+~4-?t$V{?BW!kjOtJ`I`||DCM7@ z>Kj2<9YlwqZwOuO4Z%MRpsP*eZ*u--I%1?x#PR@SB@-e+pOw zBG5I$YXn7vg@naKMa0*tty>F&t<_dimQ_P-GBVWPq^DD4=m0YW}Zk^T+Gd;5%|DPY!f95)ipHX2rZO>p^>qPsr6Qj zjjbIPM|5@D=DvN0hp(T1Kp=@66dn5 zP*tDsR>~)=2f9`b^-_IqS+y0-{%?vM{r{!eFU9`UYXA`9hJYuJTO8O7Oe5`El^9a_ zEmRX$8=QwDosf?63dJb&wK({s)ipAi$|Oxr3ZCi>tIKiG?W&jSX@ybD-Z{UtKkBFs z6EI;hOqdfSV2tXO6FKSN6E6%SEYNwzs6=cL84wfo@X)8h#m=DU0V(*$1Npbp;4KRb zrLSZlf1U-yFO)*&OVZ%C_%eWTnh8CU)qbd38EFHb2tO?(*-(LwiM+134gLwAMgkZbX*rRz=ryx8;aE<}dvsC@1D4ZV4vb~Xu)3<{Nf4yH zjTs>VoJI3n_W2RUD3WEcBU&ETG#+UNcP(q$CcYekv_W$60M7pQSim~lRwYkiKHSdd zFpMxNtA{ulEDZ08^@{EJKma}w#Hq$5`GV|?FiEy@lDbS+Fljh}ALWxW)a}dyWLo7E z=C4OFTbQ~G8C2sE_)QyfC{-5@fw#&4Jv1N5wtGyZ~fJ21Zz#&K)(w>SFgA8X^o6*OzFW>+NJk`?$!!1iH!)H2J zhuR`xGG zSJIno&nh`I4X1seFxOZ1uo{35{i+g^Khk+?HKh+ zBJ<%G89G-=k3E%79Ttv3^2(E=nM_@_A`XcIm24jeW%Yp~!ZAuv_(M`FARmjjK@KLM zZ)c>;v*^B$VSotuemhIkVgf>HZ~}d__}C!XFSyB) z;@9VHWZ2-nK3Qh;J5Xd7c0}QJ1#xD>+0Bc&7r$w2#u#{w?7DQNg)HK1MID-{Z}Nnt zi`8I1IvdZk{jmqxh4_x6<1yjGAM!$uZ)}M$nc6{&u6dgV)v-tl(+KDsqxq@5=cKvv z+iNBt*!~@8zoiIntN?D?#uS6Mc4(R&Y@ftl>+8KF-dmPDOZ?`w{VQhIiPpzZ{xkJ+ zAKYcGEigjaYtgatH&5N#eEpdCo4vTFcTek!$UMfkMsa->b#qMGIzCesc)tr{s%Z0EI*98d(e&@QmQyn*e$-73svhg#ymPhd3iJZx=3ad;*SFx|BPv zC(#LXbO2ntkpY9ijhXb6o^~7`!ekO_V}Y>s;NgayxBz2@w*sN)yX;Mln~+#G7Zg60 z&fMwgyd)t>n%;Ab3Ru?Ffj8z8Au(v6^D;Xb)m-bUrMU_cr|gfyfrq5FVB%FMH-Y`IRQI7H1_b$JLfPy%{LEUh{; zPEJlTdt!su@HZ@0X5hwAnqxxs#!;li8m@SL1KckB<&%Bz1%uNZ3A9}8q~mG7D+KoO z(5WTc543*N=j2Pzdf8eBqO_VXw;h3Y8LfZ#VpPtj^6o6OqYzD&Z`+#@HmNa~#`3_~aKwWg}?K%hh5fnoA-sV*z3 z_NE9z=QvBlSyiffZDCf;H&@qivXh>#w{2sqyQ=Eb+lx&FSqLN7cRTH6KIWv~rfc0% zN(+*$tt7vZVexPN8cUuDwPmTCm^bfvQEj9aPkIQ4+&Vc)Y&Anj8}K=qFgsxalM$)0 zdu@3|_#-WZqi9~W2g=KVV|iC4zf^U&Ef&XeF5ZY9-JO3_BzzLvs%vpLO?c15Rn9J6 zs*S=P#SJ10SF$H}80^1ieGy^S&ASQSC`d(+P(UHo6OVP+VcP#2a-vEe`lJQ%=tU zQ&~5jG-(6pqDU&__`+`Dkh5q(jE-fU3pY8AlZoxE29$?W0`g$KoP6O~`vm)9mNJve zCq;C3|JgJIauO{vmILKg=U$u9jR-|k;(F3!9eO&bJ`EB%&c>6pP8jbtlr`kT|>@+(aG@0bTPUyuBKbca&}g2wzDM zeOl;n_9QmTGDpBe58f(2Asr}Rp-Tf~`tQw{8ccT3v@j5y=Ti zbA$o1$X0nr8M+k}&S(HD15LkG1_lJAHJ4A>s$>AI{4fI5TNB59kk!KAN)R5-3CNqo zesIy9w8w%W2WKy5gasx87K#QeDon$)5M^mn+HZLMp1;2P%4fapg;=boFt%oxa`^3g zFf7IiF(Q)io7I7+l)INDoSSX@s(nR<_njFXeUG2fej*>F@@)b3Ud=^UE%8}@g#c~r zm2wg#`0VZ`%cE60Z$A!J&pz4y+~dLlNiWAS?A@Sfsmkp(`Er06u`zkgd2&0HchBpq znVlF_g|@R5FZL(rgs{6~MLk*q0!>Co`#kxtna^w={gmx= zaX}ULlnh+0TmJSn6l)$B;)11d*HdkUi%`Sm<@9Hd+p`P{>o*{wz@ln~5@Tp!MZ zAt7XYf8MmjQrHpMWPc3zD>mZH=B7{mg{A1E zXbh^kf;pDs!hHhu%16|LG-dA)kel@0N@;vU;fTS6DPLnADWfCgLyP9k`WTY2#a?^o zo2Q@Oz(P5D^KCCeJ=(er+-^2NM`JonmX@m1>eE_z6(6SdHIpEqXWNh(9fpi^P7`1~gwwgG9uC74ZnVbfqv7Z~0Dc;4k4}^Zp>6mw0OHCk!#Q+A z66`tIG&m#*PqTglr}HvzEvN9Y93f6PmIj0}20<9-0pL6~%j#4427qP5CbSh6`5F$1<@okft+UZRvHvwb|Ks7*&3)^H~Vpk5*U1{rt;C zqxfMxizs%5)PMV4(+q+ycnDn2fs4ZP`r`RC{zr+dsvB#9v`VYT^#WWCQh;*qLdolyr~!S_Xfb zSx+a=v|`d8cVW}GY_`vZ2W4DEa@ohn2buoPGnw`Zidr!iRkQ~tnUc5FJu5mZyVhu( zR!teP%%$()o{^LFZF19kZFq(6RFp)qud&=hSyb75K`-~*@`RRh(j&7p7QaST1_AQ1 z)nX@)tM@p|IChCH{CpiTZfBDJKCvUF^H0|^uh(N4-;}#*FUTe@7B1Cv-HyGIZIrG0 zZHAcUY)v$XN6#8FV8yA5xQ=t-Sd2_7u!&ciIn~$Wz*|Da0UkIHV>f_@hS2=J^*Qhb{MB?hX_hXU0@ zY=#<7qam%*!x>;-1vSMN2f=|U8?cc820Tm;vf3O0b$Ce@Wt|+Jsy}JlPm!Q{zyW!9 zNjeMAu$#j1k@${+K|P8ueweKRf_lIMiS3FtbK&Yqurmz@zt0s4f_Mf@7JyHq87dTs zJk;^DIuL82@F@g&6Ur)iHyWjt>tMB91+AHrOJA66qIPkGY*TxqbJdKK6dNd z!h90=tUhtl$hxLI=sPSKMwt`oQ!m&d7WLJEYnM;~)1HT>_-q>z01E{B1FAHi6+$I4%?lkrb=c5)18vyO^v*3}c#+{`JjD~Nr+H7hJ;xbn1Gx5kc`&QltdfvArn zx(Es}co=sJ4ZG=77xk%U&j}b1j^jtg679IB2ufoGv(8>3drOZlJ-WMSSZ8*`^pn(r z_YsfT3nR8!#`lgxn_EK_WE<1gFJuw86594&puXC)>C7#jBT2FO%#YbS)g1hNj$ba@ zanbD^-pNEucW<({YGb7JJFdMoj}I8OtBwZJYY@pA*;miaB0DSA?iMMOldTvNyQ@&g zr)u6S(AgFH&hMH8!{^QZ+$r`3dWhRq*{bzY2K$|6Y-3Gju-oY`ON`Catp}@gc}63u z%}(CA&>V1az>e?I>Eqo|(jb_MTsqH2`$d$2nHn96Hl_>m%Lh#twyN>dD}itIYWt5O zPA=RO-F@n-MUFecMpBxVQe^+ScYCS1EG!V(-!S)6s%E_CwA+Z5iL`jAV7Y*n69$V}I2BRL*HV7~kF`?tB zn}xc$B+v{R{xQwE9S4|9+0&fJhe2+@Z=B}2$eLyYhNn|PZQs+mFlKV~vkE;z8OcE35~y=>V&q3pHh zm4)9>dCs@T&yDu=w`fPpNp_(GYEcDZMaEL8+6BqlF$O`4Tcli~G|l@X%DCSSGyMpb zSjAi;85!7#g|bq_Ie~G_Nym0`V!DUbwhX}(Ap&QJFcdg=ma?CFbFLZ8R}sfNCOytF zS9m^oJ(9&;NG-n>q(XXjp`PRsls(XZzd`@BZTqNC%KKgObHN*OvxdpLUlg=3=<>GB zff8m1nVOoPdc!-xtPFY)4j)2VwI{-RosF0*i~5#h(f_OYJqsE%T7c7WPbq_zraL3>uq;3?eh-r zEK93vY4$}@G2mS@n(eKc*If;gdo}WL{U`U#b3l5~^dXreuLeH~y->TK-d^vJ+b!Qc zY2RC|F3t9HX_Bu%M9U+P=ry*nNQ{z1UYQ3%-+`Ceg`$7r$hmMWGCNsaLB=2*1aD!s z>fitbf~;@H%VfjCLHHt1Mo8AqlVX85mht)2_WE9_~2>At2 z^leCV-WCwU*8yih!jR4bl4SAZ_z8#+VJs^pmLS~>?*dCaItgSR9SGyF7NiZrlrzKu zCNYW+^I$DF&(8!&u(#rcx5qkkgBXZj$iWX%gyJ|oRJb$&JR%^0Kh^{UbcHSe0%?O~ z@wh-5@}!w;=?*5OKlR2u-oa;x5XDfKuM+@c7AFj{3WNow9NvMO3SU+WXWEl(Ll!cP zWWeG{AQ#~a13A9nTcwbvG|_q(6urrqSwfpmKqqN5ef8ZTK6CW>jo>$07J(iQCpJDU z6T01WM(tS)3f{nz^}s&z;gPfG-E$U`Ngqp357(_7Ir9~f)WqbY1)b-bK?Q40I`Gq6 zV%P$LQAGQYn9`ZCf@`QJCjv{gFfCp|Kp4iNpkiJMjX}IXc!h}YZhyE=j#?pk=x$Nn zQW&goge$k@c;K_~qC#%hSH2md{pTe@7b?%&8vq8eL#~ykvBR`PP1u(`b1$T@5*^N- z&=8nNvlfX#UJt=)UaYA^sk{9lc<(-8V-rK}QEwppJ8;@bw6xdlEVMydO0~}&;~+Ft zv!(ouqP5d>t29e`zQ)ok>6wEZHKYah$~kD)2~NYJUi}+eJ(;I9aC1U2OM2`QsVdb1 z{srNzkuBG2=Pp;6xyw1pr(tht)=)~>Gvc$y+7@lR9t~&C`TP3_jLOc3ymt~29vCx_ zY&cQw>7=^l4SHVc&fdqvGy6|<5DWXFVxPD6sTdB8@OMD%Ty@bSo;Ag*i0bw z(Q7j8z)zuIO+fQE!=gZP3{Q0mx9&blusUIYZ?iO`8g`s34eXyn(fmRB7)2I{ zDUG~m`{2&uu+cSU6gav18_+3p?bkJVH5|SJQ$>C-Wyc!HJr%?miwnq zL}|aC!P6k>;`mVY?YL6Xah?RCSWX=wkeh~9HnVXIj~%<5(Z4v|ZnJ0bY|ZP>)>hm{ zu4BTo?6wz?)ej>5GKzA=O_t83TaeFm)$gy>Cd7^v6p{5}yPf4CnX-IX`B-8&*z6%h zcY6S$xL~qVsDmbr)tK~rAY~Et>`UL7@lU-nD8D`F^kLe})_r%@r^C3Dcs})o8wvoB z?85Y*D6xWu?392rs&e9wqpDR3(}WE!H(Q|q6QwX@T2Q&h`Fn?ngHy*b;t2IXiEx4)oL2he44D8Q3#L@n4(Tm7s*YQC*LK*$YBW#J()aE-Ldoo7qe!6%T|<1#FO(@pV7&MO_iJhh zJ;BkT<{*PxX^v21wR$pT zd$McY<>GpC6#B%Emu(8C-qWisf0@!7+FUz8+kSzIMWMXjnOS68eQ?h-B53Q`T(+>8 zUE_@qWrwskvC#A#oTrXW;+GEyH3{);sB7rg-qWk}@x=KlQ0>@f6$*;xekR z(91?N6z-Q4aE;P+R?T$tTfbW>B(3CJqjQeYxR)d8Y^{H2=M+|tC!<{XL^(?yV>-62 zuws7`bX`JPF1x$8LTrjHPiCNA5|H;hTOAeETvgM8{N+Ly=ps*Vxnp!_e5w-d?S1aS z8}84qDZU(J_%3j!v8$IAn_eAgA>AE7g|qEi#!+|-01LNg1Kp4><;+$de28c@oY~HT z0d+Zb%h3b!#Pf8XR*;%N3xd@_9s}qE;gA?zC_gM9t&SpEtr1TKA*3SCvhFOLtqbGG z!r5SbG$-`10Zk7$TLz>JTIJziNDu(k*s3nGKno_4uq+Hw*MR)S)X zJ{8c#$f%?gf-^dKvcA17&?|Pf{1a!M$>dtw>OFP!VuGx|&T$K8*7p8LgUcsN6bCPU zsiGDURWD0mH8rvxQ94 zPomCuX{VhC5%$+Cn(sF5imj6rZ1<>Pj2YzCH{CSab1X2Mp!uLs$S1X_Dl4+S{xDlS^2D^%Jszv<@~X{&AG~~X#(<20@21+N}z(+P2^grk_t_GG<7iS zV}FQ!@eRu3jFuzOCKvE;M{fit?|)6dFdC$R3L*><0{c&2f;+cSJrE}m%Z*a}a;NQu z#HeptE+JO-G<}*k|3G&0Mi@WOe&3Gff(vE)hMoQ0Flf*qGxU=4$Wnu~HY zOrb842{IrS6a4Zd1{Y!i>+|xk>wYzHQCd z;*!ri$tzN%Kc*|hZSWyW#Cqslphcb^LWFi$Fc?GMtA&H53($j8ZN)KXY z9R%Hz+ArXOL435Y4pqrOa0V-+=|9`@2@VGY>Hl8-@JZAq1_Z z(&18kTbP!7is#8i!|z;D_Pg?Lj`-5Mt_<=OSq`ZrqCD zz8K$Z7EL^tftzP-N5Kjq0>q!RG~E3r@S`s%YN@w2r+~ z=FK+$mh*9I&8;7js69`Qc1`(jVUUnx4&(I!9*R$?nWiayK^Be{ z#-+TC(d|+bH-z#I7ocK3UkX$>BQ>s@vA!mLL*rZX;_FQ*#n%%m{V&QVZ6X5c4K0VaS>~V-;R6(*9@`*&v;c`M!zxAc z!X#<>=tOWoMf(VvAE%GupJzgDm1Ixa)4bJTbx=SbBag7m0U8-Bb?Gh?fVW3?Fu6oy z^=-HXGY+Jf@KQ?rFJ}Q4RYTxFlIo$ z!i3I^Y8uX#nX*Apn&=z?6|JuG5(@^g2DsgV)Kw3_@U6>(7dRuOn=2sAtUG$rzMmol zb%KNa+tJe*;HU>u9OP9OkVb;=%7Gmi7+K)8U|_&&UtJf{SZzHUz4P`S;`^c-eFfb5 zyZcfe`lft2_35#3yV`fa^w7I?KG<28EJW*es}BJMgL%!$mXFZc?F zx=x{XTZvgnJR{?eiWa~js+b^xtK*^T%>9iK_}Jy68RRoFJyQ3=B7L4WMy6#?@sByUgU_|uQzz-$w5@x?wn#=+`%%Qdl&h$5bxeY z7quKrq@~MaWiRWcR-$L!p3chN#yuF&4*Nt*QUV8;S*OGgesbS4)bO-Ys!Ld0s>AxB z?uLrDF;A=ReCytW+Xna97F&ND*QQ37Y=;tp~3m`*HE3n$_DN;5|{^xLa?xbZPP|T zLs%!snZ*sV5ro7k+rtQBx=#^_*@hsA1%gB9+r*QBX0Wjfpa{1RzyWK2P5?#HvM-p$2Kko&@IUhObAi}e+3_JnNL*{~ zGaIgu*Iyipdn{PK3)O3e?9|k#kDRt<=adv@MoZ7mdOodH(lWY-EJD2eJW?HnPc^aOs5s7VsPiu5 z#6-(GdOo=X*g(n$%ngMRFAF1g3Oep{`{P})LoYPe?GYLRHtwp@lOMKOveVBC4~IPiaoAw zp@qk#Z&i$4JZ-i|Rri)0V#>8d6IE1dRbdTLKxV}UjT#o*N#-*FT%*>0c7;ut;qToW zcYIQ#W`Qs&{KQFWw{jN1R^t5)6N87414Wr~f&Il2m0w33&vtyi&h6oW^f>eUiXTsn ziSZ}bDlOj7E>&u|h#fy|%TvFOid36=ovc^c;)cQ+A>}RNGkYz*ecgw?Hov#G_-e=P zOKOTnF!$8+w+kN8@dU{GBRC%sw1HN7ez<4b-M2^WYSM3?2)<07vHQB=?1{?9)-Myj z1CmwN-~RaKYC)NIA%|nzNQ*ULNmE#wSB?)wa?0Koc6I_#Nh6J;K-ATrl}H0T2>~Dh z$c>7G9R#Pjc#s>+=YvmLF{+iI$iWo+769dk@BD=SKm?(e$&?NJAsk?S!VjL#;DeWd zBO;K_<4}DiSsRsx(^*_1eRM(u0}P|#>~x${4t%$b0K0+vt1eByL&k$&y9B@A!glY_KNVrAk%F{@+(KYSn zlI`l>uWWk*z$r zz^K;bDYCLE<_ZDRpbD$c{{3;v?`{WdMt zrv}<*dAA%cd<4!(W4w9g8_zjE41aRi4UGxy9(qKaBsylbTWBdfhl|xJgalb9esq<& zRRN(3`s}06f(%q)BEH4xi-sX$E(^x+Rof(Lt^~>48hD^#eU|#aT>%RCHE|~X^nMbY&hQH zvN$E^mGnY6iKRiUz1?9r%@a_K@P=lD@bOyMq8QS~rAY`+eybs@Sjit!*z~6fJPg-H9^TV9007-{)v9t(M#v+Cg z#&6(xsfO(LUfOS=a<=e-FA?#=m(+euPQ*`co|S*pL~fClYVy2@%qew`V!8SZDC8+^ zOi_p>#@>i0-wmaCh8Frtoh>l9ar|t?cOZEaJ-)w|^?9s8`?2Z9Nwp#GgxT%yxNl1J zP`9NxAU4NZGvu|r^c_>}q?7yj0#0Xe7U?`C;5?VTi7bi=1nGz~%bQ>)Ao^5O&Kwra2WNGG zb76pAg$n-!_D%NS4m2x!+aO*p=<@bY6FNA{kw`;0%K7B;;}B+?IXfT}!(9X~g`{x2 zso)~rkjK^QG5mmEx4;4uLe)i(O~DOkKrDybY08eL4Z#a%Pys#C5O^dBV1po#TPUzu z2Zu9tQPKcGZ77;ohB*fA0i=28w=HjtV8eVU>#CI(!I2kQ&=!ouQi_m^4MG&Gu#z_6 zHhdrlL4hS;sW^Nhn(sxd$)t@1oPQZz+Hx}1P`ALx(&Bm{p{<&zLe6M6m-s-Vju>|A zb$DSR;_0s0*!O3#SG*pCf3f}8w_uG3O>mqBTPZTqdwajU8u9k*@8!o(#r?+J&ko$navBYVshp|0R75gbF*%U4F_q}r! z{%^EEnvqhe-;N7#dTf5!4gS*6rsbr2-`qBp^DpAKIcHJ`HwQJc5>ocG0&}>SDQx%q z{sd8*J6u|w>vIhGr5ya+%C}#<)g^`JGnNylo+-Qtj3l^3Z0=|BzmlHbg%2QD=Wu3B zp1f15sBDa?_qAT5pcgvp zsF(T3Ny{qXu@r2m2=;!`16~zmR&`=v9rxq^hodu(hjRVj_%pUCSz1QfDPl&EWn^b0 zgR#z#YEnlOGm0=JOBiXLCfg{QER&hB71fENa?)a}uWd+@BxK2!Y$et2Jnj=lHNdawvmE5UOgOrHY=8NgGF;ia zKh(pQ?+AVhhAZpbt+a#ftsXWFik~R6h~@54*~?mcgf(F4>LruUE6;yHJFrLn$_CYU zrpJx%#DCj%_uIL|vC{??9~7ySAH-9+mT+ka$Nj#nCgSK=R3y%_Jqi5SLpUtI48fc# zSOHdZr2i4>BU=>g6fGo{Zg6)doIA(8fnTn*M)|iJ(%_yQIthW@A!2{!Y zIWNOj0zZtG4ESFp76!2_WRWKUSbM;A=K2&z1Dq`|5Uds20*r&X11)vYcY40t3$3;HF|nf^i>ELNiKQY?9o4m zlYa)l&GJge#Xto!an5DD`HE#{qjQnoF!RC)G5N* z`GZ!?M&!@Qj(0X=o}N^TG11k1ekmSrH<@m)sfqB)aOx^S{#DiO9Jq-?^in*GS51<7 z{~f8Z50B7QR8$Di)Kwd8R-?6|;f2Ul&n)`D3e`jy6yhthgb;%ZIkJZO&lZ`rcvf7j z=tH^=X0hmXp11$Z?_=eeVdY27g3P{#*o;_vXU}Q=QBbnx__X6vKPC5-zf731zlS)F zHn-?qAPnSGjZwWzuxGSAqz`ahOkTfFzl<-95b@UV|c0GL!N$4l3+OAaM799ZShp?IKWA2DxPezK(lVD zS4Lc|(^rx*n;-hswm~-U?Pj(5NZiYG(Zh40#Wxl9p}vpc+2eWcrj3V2W=p4WK?@4} zvNrPhde5s3ZCq!coB@txD=BwV04nd;^>?Q&cO3Q4{;anuOMAYkg^}c$6v28OHc_m< zI(6M(SGv=fXT&TZL4)RMO#*V*d*hOZL&qL{%ZxidwblIR(1)MWgZ&4q%zyDs`=Voa zY;%0n+86Hk$28aJ2tFhNNPf&yUr9-|5>V!p3a-PAcR?q@0&l;|*A`gyiE_t+idW4%q zGbS9%Ls*yq_5hsvT*iq`LQFOu31E{UG+=eIAj_ITz}FIJ%?6Sx3}>+v8~V<4*M~qU zQQ{~aD3fH@oVFN21BPirz!z{ZNYHgom?MmY&07`u=>&AFi7P0A9yDFd5oPd-1v=my zOGN|6H%>s~E3)Aa(4`{Jg^heoh^N3E;Dt)TP7-NNAU`%^!g%6k7)o#s*?-Gp^GBIW zoB!+?7JZL-ZaVt-;+vxucD<$}#_FD!tXIZH4IvKW_9MWKi-s=6wmYd64`P@O)2=_f zES4y-9cxfvI18t_4n0@cgv2JH9m!49rU_Sm*$yu&vgm59Lp`<*U8ajiVQNAQs?b7L z-9sT8x=O@1{h`K7?#aH8o*j`dy7MKfS~u@4xz)UMZ7<~%U-!FUyo;#@UYI~hI7yH_ zG0P33k8m%2p(b%&{rZP{-vrOJu&AvgH&f5L6;oEXDnxL0S7hH;{o=k^;&g$dk;~at zb=J$TS1FYjS8509D=E$u;rfTOqlGP!I^9hUa=%Oesl8o(&DTPm8+T|nkgBC;JCeKzH!q(cRq>A}PWtXNRpvbaalP=Y&FptWOc2*F zS%1v8OzZIKz%GYRWky+{gCCX1Z(cv&G-EpI^-A;dmVX|zHdcL<>wQzwb4zjcjeUuF zlQA~q(y0e9$?BPKp|cuq(Ph<&rIOY-N^y7~I$$UWAW0-}aa~-AK)i4czuhGdtCPLPrH_LLxjL{b z%UmE-0v$uiLNJ`$lZNi%tV9-Yk#@>JxiW~;R4F4^f00IkZD%M5B$Pk+oAF~X<`5ml z@ydv|6BWhR_JSkjxTAp-7Gd|M7_OXhlXQr7+OUV}dF6&r3ziRu@vY?{k< zB-9*lo@bzg9nPxM!P*~=sFzi%E=c)JQ|uUTM#!nLXgA6_iD$8VYoC9^KZfX7?|CJm zy(WCs&j($l7QG?I^2AC?|02{|tAFD>%W1I7=Fu8Lu+QshiW`zYVH#AuZx)s5oR*J8 zuILDyUW#)AWmH98k`p&Lbc?Y1OaIW096zg9VH|4xw%}HqW&BLeFILxv2U|$}Z_<}b zZ3N=nYbvJ?WsYr99Au51$Zn!nqqhjWxhJ}q5&N$e5F$G_xF5<*r26G$mT!|se_1Ta z81V7a`Zu{#e2=|#$MaE3u4qHV5fX0dpMA4yZ2O(Z$#WE!Wj(}MLcJjCwA;JjhwjvR z>#IgT8-PJ;Fjcfr{c|!{S0nfE6N8tttV8_Xg~B2EShJBLsmB;Ch1!fHLXRP= zdEtkK>PP8mc2w_<-Po^Fp3?q$b2c7&4HBtgeHE`zJ{h)wo-I=GrLvOUN74fh31+GG z;-pJP=QR@)4tTm3&)yqi>mOojU~>|_`w^4>^Nhud3%)%)aK8Dy#<)sA;^S>`>hp){ z-yfg2l@z;${VQ)ip!&$v6a^DW6FkQRbJMSIjd4~p5Q=kDlhwh3j|q2;7s^oyNC|n8 z1s^X%pwrDLTnUVSJJ$@Baf^bpv^qnXc1ImxlqASpBM``?vG`mp5UyCkFmvMyHj9ZM znoPQ|895!OL}?>OrD3KFIfq;y+ZI8PqT>jIT!5jP6$LG_sv@LLu};Yr^f(zxTl`hc zX2gId3!@h4Pz`nMX@y85 zogl?rEA2PHQ3RD_3QTM?<}~lHYhMa>8M{`7>`aeMb{?mIWumo_3afcHy=hAGHk z8Hg>y87{)5L229_`L9AgGJdpKy@2Dd{wMQd20bEGsGCSa`%k(!%?rZNioD&%`CPu% zHPs>R$^2NZd~3dav)^vtYP%ZSUY{dvL)Qa8;PWbK4XxT+Jt`8ZCTNvIEc!nLz zPN?9`u!>Gt>@p7d{3N&T05wTw-6CzWpBWUp(`u{d0lD@a^fI&S{fMO4QbZgyoY(#ol>@Vu`Z? z_d6EmW&Lj(X?`FdkubDDJC-o8(~oz#75QSdPNjoYJ7Cq#M6 z-=4}-hhv}I+jQ5m6+cosf}piKwbz}8{1vP7?B>uD6{&sqhD1u*$y4>oYWKDs zBUEfsW~L3j3^8wwx|7|;6v({MeWSQo{=xO%jT?<#SR6l^T5{(r>2+;7L*u-fC1t*# z`i&gG34x$z!_I&x!D*!qmTm@+pFrC2S%;od0>D(tn*(4QQkvKS7`Wkl1{e|&kL8KH z#0JvXl;M=0kf?ApV7L$@rB*zg9{65{GGKHDB*9sVYQlmIB7$oNei0WTdHt6ekF7J5 zwynq!^+ObJfIW~xgGi=jyCb5wC53)E0L&o3dZV?9ikK(rU=p+A-GsC3tm7(jtfc z5M}z_ky>mLm^Ul7#_GM&JuW(>8cDC`EDvX|ULLjmO_NB#@Wt=q{Q?^2E){~1q* zJXzhlH74fPUYlEL>I~T*BGT;8W1>my{gc;e49M{0Ke&l3sm;bb^dn^@EJsNurO zhkDjcwu|3V$2}__Xile{>C3xzB#(D`+ArhU`*y|d^W8&9&bH)Moh+JCgKlL=_t*>k zrcDkX*ZxIJyvSUEjIm3`-(cJ6y;w| zONxuw0Zefav8Zr^xWds2uGbJZiWd-ibxM5mF&D1CzAn|I=WINGGoW0I6a%38{;;$(Roq0pp;;0B;M1v)s zilF9sELj~IidMi5O1i?@Wx+3sMUx~j>*^E*tz`(~KmFtOVKzh zCJNQMcj8lDBs=Qpy;8*Y)i_%51~@f{D&(#t#Gmu$3OB7i#kW4mhdoMiIBkB8Kg;JL z9?9vX2%^oHZH1WJ24KsHfRy8fw_cAA7U$>#{+s#^RpEci4j#1=l zeedT!GKrY5jwR>GuGw&Z0$t;ApC~wzWy_3kD19uJB&PK`JbA|S)(N_*dGODh%X7tD zyEY-Aml9$BWX#0IzZhemQp>rC+vjQxge+QzcYPJKh8GShg)I)RP2;| z@}$4NVcizni}ypu@Rt^zudQD#Zbu#5-qw0*{bJBvLWkBz?Z94NljDMuG_m^Iqqt6g z$_VQf4=^=4!&#zE6*y{O4T9LS0QVTV+OGrD-lI9f02+aTJs#FnVBmVyfUm#~HEwAbt&p zGuw&+2uzRxL)`$exh%LHcD9KP;v-xhslfyzC5g#yM!du?;6M<=LDht?0Uro4ZUmA- z3`ayN1q3&7X(Pf4T!*q(&s4@DW6m*{DqcQGA~H{3+g&VwDsNks#q)AbU6I-SlLM9` z@_h{?@>dynYL&8=70W8PlDbQ!EmpKX{+Y5j`xoW(6vF|r7I&)I5rX3>(-wItalqZG zk~@Ei*n?b;I1x(T11CrLlc`K0CQAF8X;Us9x`D)YZZHX}{Tz|uZoF0gdH`WUFJtYU z2(273Ot5VwAtxi=BV=x3qplW{*gowOPiIC=5{sFAC5$SQKGS*dShs zFt}L705)gZNewGrBPQM<+^qJ%!+MxgRA#6Q*`V4nkHNeOjYFL%jWfz9t(4C1=7Ks+ z+0vJN*^Q3o-(to*dhLgk(t^1ZC!|xj=R&OVvE8vLw6*P&?RSj0=Y~#Usuv(0xwqwZ zMeggw^A{ZVr^LC~b=g1YGx@!3(Q@)D1@)y~DlhdFU59JG4ZlwJo z_#SP!z5Pbd3qzt|O`_%hf^@437X;lRotXE(I_&2QWd?;7PS(EJ1R$Qv1M%n2l z>zHf}k7HNAP5h(P^fi3jW05y1_1+zUiL(r4#?e5M@QRPASvd+&R+J&Jpv;vsmGsI` zuF20CSW%LUTyx0a#?U|mL-?2r?7U9o85KJ;4?~H^Q;`TVc8a`I2S>4NDHgv($aTTl2vbA1DTcjA zahLsS$$3&i>WC_nbaA$Z$;Y_ z!}Z^+s|ymd*a$u-BL$SYytyY2pk{>u3YixH9|XeLlM6JwsDcMJ4%~dZ9K|tlB2fg( z0>8@AE1D1A79l(89*3c8hXh4E6V(u1awP-_ERZ{v7npagdLZayX`{&^LE%CJS5wCG zi*q7rHRf7?e266_SPi;H#I4zFaSWGf*Pe4o>|aEW09@1n*IBK$fvUJB&t?p#^p-f# zFFx%?AC!ky)I&c6 z%{sAOVsm!Xf9g3F%XCJADg{NDZ%Jklj08 z&u|ilFf2ISvLYCMniDATp!P=`lUb2F3IXE`win_g)Q6C`n;6R&ut_vXQvy5_`Yk{~r2t&x zQII5Jt%9$3N{K39%63)@>S?Wz0hI?YuLBWiso`i4zm`g|7cRjvt29l-HVIm2sBoy* zV0p|TU){)ENnD6a4?3#CvZhMr;*5YB;5gyE7zB77f*`()05cuSuvhhxMReeAQxewV zksvsBeQ;qRQI3k3UN4$r5n8BAlA<#R$=2j%CAfpK8wJ8~k_Qxwth3+ppnN{=m~YPk z=&d+KN4<_d|KPS?VhyX&CVIHSblW-Z*vR`gM%v1)*H2rBBkOu{yepZz1o2Zi_IRxh zFIanslU}#GImINuzT#f_ezSF`tFQ8fh97kl&+96<>hUv7$PdoOnEHx+_($Wj<3gd$ zcupS5<|66#HPs^n-2HK4^lpbfy8O&qTwdV1v-M}++u)uq!SHW8$JajDf_vKECLRU< z{OkFdWa%Bn>GfJW(~MZ>#m);`Nx|3S=`UCH~v!Vf-wY zcsSg-4sn`Qwrao698%s@RE1|6v8?9#`6RbkZ&ac()h%iT;8L^fc;G$>t`Zc?T-Z5K zaq`@!lT{k0^M%3khvut!4R4;E84xDD-KVpkP+pAi-=(!{n9~Qn z7kQa7hiG{4);5?6n{^T`0YaqAxY&cYV9$+$+c}$$Khh5DqGvV0#RtgIS#aJFR7=uYx5V&rkL$D`Mb(ks6HG&A6SPFO< z08W(Bg-fTdFYLQbq_I$`wmnjN{L~T$Rz#!6B zzK#laTuz(Vti1r#CIlAx(J_LQEc9>WRlrrx7h;=rbwB}l%=YqSnwVa>u-j)BajL4^ z_D{6P>wkX{Ly2J1wjXS_?{~b^1ci+8R?@JB+rE~u%jv(Cq+R3g-}v5ld%c3%GwJeH zlfQ^myRSiE%IaN`h+Gvft#)m6y(8^1&Y1LS>bSR?#a9>8qYv_8inF=5lTeo(jWXq~ znWz`?&TwfC(ZXr+hE{5%D$5_oi=`~KtPlno*LEa^c)rN0LBz6zx(=?+l1&XZxV)gQ z5`n`PF-e~j4unlxboOY=KWP$5-3)BVb`lT9f9}dg%>%j9K=LMx!5jFwWVOv`i@Vjc zcQuG1*CR*S+ny&e-Bm#M2)DD$Hke?>)OjD(OoIZI|9Pho!hG+vs@G4RMWK6&omv$h zoXOi$R-p0U7L|+RPQ}L8t)#=z>Yd5=i?D-Ayw#kCIPDSE$zbuWo4Svv{<}SJPSy*8 z1yycjn?zGXjqj8EW5@q#DZ|wcmId{eZ?zEA`efyW^eDH8506oug_NCkud3~G@!~mZ z)y4AE+}Vc(cxD)iuW`))XLk)z*?U$}uV5t2gk;rm)JjVyTYP)WucyD1=`8Drs`!}F z_Ub;94%6dFPsD|qTHl?56eqb3;tNVk$`NDZ9xxSdS>@EH@a*%q-9{6 zc#=z^KpU)38{{5>aN4CA(bqAlQ^W_VjUvz0X!yv^75{7qYF)rXfNLJI$jYQc*m1{N zNvY(#&P-@}abBqbu&tngfFv>Inm*=|AL193y-Er~Wmo~~hZlSm49h<#8=A#?fVAqn z&cVnm0`YZLQWtt~+$4E$r?aH!5P8Qr;WLo{CYBH9n=NU<-xw6&})pOiAydpY|r63y{` zmFKsrh%I-FKapWns)Ozl9!@5kVKlW8ss$+Ogr?S1B!ZteNd#d7AVvwI^A&l}c$Hr@06>&+=`e zVG?nn4mq~pWeqMR0W)W+){?83W#n4Fil3@xz0~n`#Ny zHb$4meds#d3~$6^XF;o|WIDvmP#A77^-sted1}FGo3YbyiZnPHA3+F54KaMKsCp@O zhz&GVCbgQLcvDfmRlsRV7?P7c5}b#F&ph{{zISzC@UPn87&Mfp?4eI7$E<0LbPt+3 zK{eCx=AK@&DLJn5<^?pV&jGpl$Sf0p=Xrl6lTlQZOf zu_oy9fkJn&(<>i2zJug?Y2&aW+kg9;wD;DAllv3toWenpf#54O_eFhKUh1}cF(?4J;}4lnV22g1qJI_gbWQ#Gj3#il9bbVUOKPnY zyL}~T%wt25=t`2=!`Kd8rAxoOw(c^fzu2u?%#)@GQ;?yqtFMA^m$Z1|bGNA>Jz5*D z{W;uW&2smMK6=f!SB)3h@FTU{%6oK6vN}zv#gf8xln^Q5WBQ6JJx^Hta$VZSw7n+r zPjt{7>aIh>d#n>?=wWCc?M#);LRbIT^giy6^?wu|b=?oNciM8+X0&pnC9buV4XKCO-+^EAr zN&o?cioL*t1P|0mu_VDL;TpQDVUa-*c#7D8G$|ZP*bIF&=pGh94yHpbXeG244rfxr zp{h~6q8bVWNL1_y1~D4o;A_mmNY|nD{|1*n8a6te2uFm4csc4oNEK!pzZG|qhKxqy z7|s?vFEL0!Sdyn5Aznvr0%Z=8aR}u|n=x%IsC5ydEIcBYNrAx4$^wxeV&c-n-1f=8 z$Hni|a`CydF*eB1yTfOMWq!KU=Le2>>|%O)_Z1aSM7D-%vkx?x+k8kBWiLF?xGQ>m zS^vsh{4*xL{kYGW$!A}UJa636N{@3vmlV5K-1y=iwL?tK8Hsyq!4=s((+>P2>DePQ zRK7Xf(tpoRiq&5C_z3?QP?*)C|7@n`SP1v@w*!IS3L52{CPe^2N~%U?+|ofVl)qeB@%Tbo?Z8KiIgB~4`nlqP4z8zu&9;9t;&DqvbO-Cs zphuWkaq~9Gmc55n1JX8+vBsWW*(q`LS?-SRNqHqj;peW*{}TkK=H3G*Pd- z$C@d+=hrmUaUuHlbm8lwTgxQ{Z#zoo3jSwczj5HD!pYsQWRiX78hNv3ZsF*%FelmD zzhC4Nj#-diTHFtF9;FYox1JC^&V1nU+K5tCD*stQy)780AYi?Y8c`@Ys_25!LR*+t z=(jt4)VOB;;*OzD;F!D5)HY>HyQS6_5C4tW_jr4#>aUn>$?S!)r$HQ)G4NSEDQK$s zoWRITb;gP6olmj>VvNV;0_lb57=eq~1ANV-y`WhiQ7hJh>JjeRRrFXgR~+=O5VvFk zbhtT6D5Gl-2%lP#nJd&Mf?key>*KXi?H{gR=QZN&+E&$@KqLqp}C^qE_R!EIIXEDDAT`9+==AZ<{`ToX8bv!`6PhUk|27ptl9}u zz%S&i1ZPDoLs}hzK^zr96_*wVnFD$}2WyltnZS`M@@p{2I>=_ps!9VfR4v5;TU2$= zwkNcmn}Wa3^zNxvBd;;D_p28sh>RLYZb##8H(br$bu05^(4grJo5}XZ*%$H)l8&d0 ztgml*FjVCc{@yN^k{TiLKhgRl*PU!9LY{;kO2%I`h}~>EuVfI@W4FO~^Xc>tT$#yc z;^{O-k{kB@ueSvA|J7$7ygW3(@t?qglF28URZ5Z!-mk7l598`_ z$k467NRo7N_`KkgW9_~54j<78REQ|$w*NL`-TCJ~+NZqCDTxmUY`kZAw^7Tgsnb3x zRl-lCe&;<8IFDw9-L>=He-W|bcO&iUq;$GKSe)l)mJxLG0%EfYP?Q1PW|VV&)G0J#mOa+(szp!g|w=5KVRC=-<%r#u}uFH zuC4Y`gXFM74U-yFy?9f`!i@)i<_#N*a??jTLbdQmI71DspB-y+PZS-> zP|mRN{Y(@WvstC!922dSnjeJk*ROrPA2lyy_aaI8pAYK?WmVm$*_6KsefOtv{deC? zv+i5G%8)O{DAo><F5~;nCr+cm8JF zq>0{EicSJ5~F;BClS!@!npV@Wd0w2gC`9T!GjWXDmIYT%Hg^gdKJEcwwKAh7&&$FN7j}s&!oGf5eEMSw_&?BVY zsce!`aRZM~@~I>X0B`Cr!8TY7a!NSZl>#*+OrR8;pu&N^T3{iR0`GIKfDp^8#x$0XMh-$4ZQxtd3`hAB=W} zjGipG26>WoIuO0~mQu2=Q>SEc^|a@hT$vpt=OW4W{>lI!&m= zf^jseeMPKf`2|2p9hBZV+0YH4qYeV!o#0NjD)P0-N$^cgh}f~`U^V5^bU3D%3120Z zc6S|#O=cx)H^-bPV=Sc=Ewbr{Y6IZedtmC!kbgn)PC|oWv zv{Oc|(1qBDp2B)7pv*7Q$B2D@t{Fg=;^yx72x7;(GEZosOu>q&3EC@IH$x3z!;yN) z-F4wkDF1{|Q}cbZPDg&oy-lfQC`m)j9=c&jd_|~wCX-o$@$dZQBvgrQGe%?;r$XYZ z@RDkEu#zCRQ7HUPbXU?kIX%cPe{c%97SZdCYJ57V79zr0cVeBo?hu_q*2?>o?Cg*8 zvMJp+u%qpiz}VDpP$5VqD!@>dPG7>m(_UNUNijO;cp>Wq4b`pm7kTRFnnCdX_WRt! zpV!@rwNUP%gEa>2#5mv3-ouUnyfE!n>dRqeW3A*YSF@pm-5I?42$!4)C=*3;L;<<> zJgN0``$0$q01=kf?kK*&wt^=*0vQp)dC=ud2+|A|fsQIV$pgVk6V$j(P?W}6-B{3% z3CN@XGoBA}7Q4+IfdUTbBnLVSmgA=)VEJ8|F;CmX;FHJzNzZ|GCQ79u1OOG$cxePe zIdYDw9gtGM*3&zgC!i#rBne$X_|Q67xbe^=x&*u@a!xb_TL1>xke68i)mRJ`6vZXG zG{bQC9cK)HfS1@%J1{#1OfeTe9%e4Fl!}P1Ot3{$Nl?zulN@(knZ(pAJI(%?8Mpg& zb-DC-(CxnbIhSX>C%(8O4W{%C_IA3(>$zCQb=r*6&R`w>jT429^l{AbPZ++N8NJ?V z8?B`S?wZ~TUfXhDp0_&m(1*w^JQzi8xfy(TI?=^utCE^jpA<-_N;qE?&XTE zm)d#YO8le?4dv&HU!&^w#a=Eg-y)@;5i@AMGiU;vJZ;{<=Rgs-k4qIe~aYU&_xSNfCEOBaSnEJc0aG=F(P0{;`UsNO_fU@?9_LdCbvhGbJ^P!C#*(HF zreyJJ(*)&aQ%d5Mhx?wrKY96})anuNPmjq*q5wg`RBElI zKmi&C$g37?izlc}&>ILrTfZUim`PVyWW|L_d@%sDCcNBr!LkTqxh40&rbYVdS|6*nFa)#%yqQAU1< z1>d%_7AmBk^sor}Th%};Loyj%Sz6Y!5HqBDzDRKyNTD-xtthG^J((QWJREXk%hmcU zEj&~~OSG&IE6`Ms$$-O~%uP z$T0aU0dr*lXOmSt!!aVl>u(cV9LQh?3ZaD%6^+jf#MFQkq2WNpHbCzb7(IRg87tLo zDVh1_(KhE1soQ;n6W;ktL7!gV31*cg)?IzBG28s?nhrXpX|juF6B0a5HY4>|t-kuF zV(2TnY^z@UjL()g#C4^w6qietVzkusoINe@D5nA%lKH_xwG6U=+2iiFt z)#!ig zd(rhI5fdd!$)|cZ@-@yQ;@s1n6ol4Lrm1SVARO!Ad>hWHF}irjMWC5qh)Xz|k+g~q zU8@#&`B(z%Z}38Cyd>6cRc&v=tXOYG<0Nw)BHj&dq@L9b$z0V-qHTV$?8%14JI<&b zbz%FXit}m@c3oU{zNs&$|rMKKX_80N%s+tV`L%8_ov3`{DVU73KpUpQNvyyoz zUxSgMq&o+Y=lP)V!Z{YJs8yyCKZ?}pRw^zEAs=3+8*<2!;@^gv$HVy*E>hrA8-$8* zIbv7Vq>6xyEH1LMon@&EYVSjMEX4p*B?Uy}X%dkRIeD!vwm3XS0&$BaH)Dn41lbY1 z_kEXC5`-~^uP5b`5ELH#jJTBt3RDC2p@>m!LtF481Y)7hRv0GN#7*2>_%W~Z0>`|d zUxNxAn0Cqpqnq?mdVhNc9j@jur7@zT3Lw7gQ>@4HHXbDE^>+7! zl;zv#buQl})gQR3Bx3K`k5<_&K)chDB2;!51oK-&)D|$UHr5TCi@7Pf*de^htN4 z&yI$gTHgdE>>~{KZWF?~fs{&|M{N6-Hi0|=utrX8{_iu1B$J;Y(j<-lyfuhck@(b@}4e~eo<)gDf)|) zW*tVGzTa`K`}+Ux=N6%JD0k1@5b6c9_2zZ&@iPq~;^HU+PgYy&R%CE)%k&=!oGCr= z`QyJ6zjp7Q8;70_>=a|)B46RYLHd_0*)3OV3>n%8u3JSFp?KM{b zO7$Bl+jr3=_hrJk`SX@o^5Nb$tGVHq@{&z!)X&>SYz3Pq-rQMpQehOwAy?$ub zarLQ8{uZOf2GaITMl9$iEPGib`)XBA0w&otNY!cclC;G>zgHiK9o%>ErvD}oHOS<@ zNYH<%=M7YgeN#b!n82>PxjPy8A0MfACI~wOD-rU=yvd zhU$Ey_v#PUcFC|#z9=uye9RdIEra*w6&?h{D5Oh&w4bjFyQB%ez=K|S~aU=u4S+nksehz<5|Fk;Yhj(|mTgRjZ*H@7kP znu>pN9v}&4`e_PG%Fy(Td3IIhy!ZypI#+=FH(TbcBjR4M+#nYjkSXoQG6tQ?wU)n9 zIa+GjpzQb=UPJfg(gi}P@`uD%+(nJqx|O{o&7$Aul-8Vj6`0q3R;wI5uKW&|X~MTp zdtSM`33?wrac>ey*L#;=+6j#*tEXA}{-gSehcrKyezeU%YCtNwE>ORneWrkWLOYC+ z?DaWNx0syUe>8;Ni@hsGD-d4Vtw9N zcbi9|CS-l3^3Jh?b+R`F#(YRMt)9%QJay!8_!>WFr@~|Ueks?2EMBMRaTKmP9(d&N zhl2yriSnB}Bo2R<*6_OU>)dtVfxtn2+>uVQbtRuPH)_4GMI z`uik{p~cdejF>wik!F>l(JKEL@0aLS@HfOdk&{Q zQLoO-I>L>9MSR>%cJDhWSG=}aK+(?*sb|>u=jcZYnTWa61%f;k=?sm@KHJFuR;)qZ z@1&LA)^%)c)o}Ly#NR&5hb^h2l42kIwo9y3pGN{L-^6k}AOJprl#Xn0&D$jq>ZnO4$T~&9Y8+!ojwKfXt zy`Oy_%48aBXdj#pb0G^NcAdF4-8IjgkBC6hk>PZubO!dZW#EY+ly(**f??Y5La|}9 zB}2W14YnUnfCNchY818*oY)QFC1nv+|UtDm~4JhU)mZ+9Y^>+bW1Nf z3Xe>_;MjHsv444qeWMMEIQSwi0+seTzeID>1Y}NFr#ncD=wfbSd6?9xq=vw}B?T{u zI|?5BwTy+|0=VU^ibAO4Sd-NEpz`@u<+;B|hfbMXWqvsm@A_$Js54uAcSDlfH09r! zAKv{BGoqwfE@PrcDX;$h&!Xh>QB-FnVT^JR8FoTOs@V<&zvp~%bW*bV-+n|@z3AA^3BbZudN zWaCc0u7xyXdF-Y42T}e1lD}SDKIRi0rM}po_`&j@A5Ni9zG}y770pNOI3d3F)B2=@ zH^+Hu@1+@YX7rq(( z_qNG)w^sg?=;lL<->;+%(W}P}6uo@-(XK-Ax0X;{t-|KSr~IX0r?=g4(b*T~uIo;8 zC0oNGXYgm|n-WCo`0>m0MjA6^=f6#+jTeJYols}>XWbL6)F0W-c9YrsZrg!{wxBKl zl&Xj7tLR$S!RuN=ELxXJ@3@ot`+>!uQx(=G{!W&eH~u2!0XP35t7`6lKD9pKzGy*w zp|SCx$0u~ujo`n?8Lt1cO8u&_h2;&kEtbAb-|if<A}c9{%>w^G%%mz{O?Sg4RM~ zo!Q0<#?OwRo;_6^@^-s^WN6oG8*%vToR4?)TRYde!yDr}{wE>ynTc!nf1f7+w(DEFC_FIw+~zFS$7Iex>%jDz1OFj%gO(By?sahj_Lp2`7&BCWy9#-fR32W2iCdkpG3;`0zu5 z>&FHg8SO->igV}QxXw) zbw*`DUS^JZzr8wxY>LvHIs=NjTkriG?5%oy@~3&Us+@p?{iP41%^Sl6wk)Nm<`Rad z`t4J?aAN4O{0-$*90M~aD6FZ>)I{2g3j^{XNS7NZmPACF3fA!Cdii^KwGC=8;R=qA8)x~%cDD{ z1yDC9JTlNWb@B&qPuwwKmET>o=uVK}Fmz$bu0Ug$3gBN_yHX0kvIn&io~^i&^l$-b zXwAyQHfG0xgT;1i0iR+sMS*Y*lYy{S zYphoh2I+8Kjrm=1(;YF3ie(+bb@T3mlJO)jGfW7nNpGZC3Cw|J%}r$nk~`V3D*Kb` zbU@nM1o6a*_S6>m52%a9qTXXDUXTrESmzLwUm!Ql3(x5Rz*1cgMY+lNLb{tXsgK%;{{PcRqV zE26w&%8JVd9;O~QI>L_DN1m>U78Vl3ss*1YLP@SElc9Mz0soZ2J*(Axs%=10A0q)k(G>wmAM{G75} zYkT&V7S}IB?~dz{3o%v?5>DnF(-=6>asxoL(pMR)6;lM{>KYGRj_4OBrE^u3aXj6= zK4wV-o)8nN9KGngSPlut?Dxb^bR=ZPwTTUh&eBbql@<%nS>fed(gNY=mluh<6ppVR zbFahl&?l!|^XNC8F9^|nNhz)PiNT(1*&SWkavz(q7S`St!r`R#VZx8S>LJ@jBch~? zjkXoR9YPapX#POLb#fHvo8i%6OCmAy=6U>o$K(f0H%Z9Nk&hUkuxOakXvy?*Nm2ZB zYV|M&f9LGPJp+N7M?yhz_^UIo&m}(AtJYz+zfQi9@nF}dgueB5y$Wl3x-EX*;Vo~% z6tFD37{*V=EDyjfTK;L#k9EF6-{wJO`G(P-w?EFfI_YUxvmbt&FtR6NFQ$MtES_FG{D~_BEIU4Y$ z^4puy7x!}&Z@#EVCgix=_SvuDj$RZV9c#B2=U_-Xw=`~6cR&1vt~`}KN09*_H@fa*l>cwP*svL|Ofa!2XCBE&Di zFxm|DF*6?l)nb@N-48DP4PfL!31C5hsIU!Q7K#%>wpok?6yO7acbwY^a2NhSiO{Pa zmrQ`6Fa?~JTEhGsX98Gw4-3ozS{llZf+~9aA3mrcD=$KP*bGHt=;jH4_n!8wDT>>BsmE`tYB2gQd|Nv`|^ElLs)HDT8(E--bH!R*(&wVR%B&m<28Rz!1f# zzv}AsJer+vkOe+{fVCORQz$Z-2ju~O3WDClHM8#f!X6HktbNaduqi&edYO_x2rJW* z?8HBnVCc0Tu4h4oBv6r(k@Bj%O9B1`)HGjgwJJa}0XU(PWL2N5FaqNKm<<(VP%YGy zu&J1@SR-Ndx9sDg;HL}trsq(=*SAp>*}{|h2YUV@1Pm}#*(#NIfIv-aLuwm1|0I)9 z>V)Cy0{%|RoihZpD1*OhCim6ygIBDq-^}upQeuOxQhIoIHw5_S2hiW>-z}TxI1#1w-o3N&SA&B7-*C_1bi&@V`Ak*6soM58MGX zxAYbQz1Bzo@`PY0J3*I>0o5(8H-H7sx8uF}zlh_63gGf*vrqtN$pcq)DSJ)YL*7Q! znO#4=BHQoQywXJ;abqS7-kC8vefjBgMrgA)S%!HW6g%kt2-&ha1*SNm?`J&sB|Q^R z)pitoqk$R7%@+3d*E5$^di@e&AN!I%?@z9Pa$CCbkF>Quagvq@uXIskgLKW&+h1d{ z26tF2{P_rmvYt+6d`?=ywk%Zg-DcdeM(f^Prvx(2|3dJNUZ1yBU2aVO-#)xcql|Oy z?5jPbce_r3hu}S@ZmI1d??_<@KW{T4O29K+AKdY}8%6qgoe`;Pc?58+Cz*l@KhCwh z&^ivep(3=p1jqkte{yx7?~BMMHv`6h_a0RCs;>WN^UZPfJ3qu?xb6$(NTbD282(@N z?T*}b9nM9)-YRBmL?883jsw!Qb!(OBpH_@fxND2SMf6JzCVr74mNxx zYkl1WO@NjQ-`-0a8hSnd~H)AH9+tt}N2AOshTb z5?VE<#6O4sgACO4M?SUc6dk2v($*I}1V>5{<;F$-f~0J)0A2V_ z&X^7PvtjrnHyP|;saUuP9^VTPNRCvEYV;rdLo+cd@ZvN&8}&nHJk;OQ>_S9( z^K8{6$&72=FITB8I8l$95UOOi&-hJj_;sgi!ZBU934$J%fQ9RupdZ;E?6)iM&gBIQXC~ zN&A~C>SQ&d|J1MmdUKL*Q`U5ArL8C>V#v3Eg>o6Z+5DI|i-`fSJuETfdEGHihP>+Q z+F=rJ&L?!3;y+=VZNGLg;}c$J3&j=f%fw{RgoZl1~lD zYySPq<{12#4z6ocfy>gtYi;|6kVBRQW&IT?gnz*^79X$o3JaL%n^2he0r>J(}2hp+i!r1Vm_>>OsnLxA6EDG2DX3<8m1wdEQCs}9!W2jOA zX~=SoZNvk)#`xpXAW+K-916Bj7NH#g0GwD#+mI7QMoe~}7d&&GXCVPZv{4YB$jwH=Ht9?Dm#@f(;PT_C3EYo7&sOo1Q!gc}c}Q&>!bnT)AeBYqZf3A4u{U-)3>eHHqlKInFzv6c3%oU2QZm zS>ScZIoF`NR|FYm1KbYICPuhYtcRS_Vbo~tqYqDJZ~7To+-cNk4&K-eHNJ}c>EmDM zi{l&CsxBA$f7XgF-bANu&Arqay$_WXNZT&Bm0Qs1?f)6t)87m~5cZFPjn#1Rt5~_Y z2UoqBb4~rINQ8M_BlN$<>!>-f$yALYdrIs-!#6RJ{G)(YlPp?=fL_0?r^jRcX8gys zqHh#{su`y0sXYIA%5>Nd9QcB)R!XS7^ZWnrt>#dj%Xe;af1Ao1VhHWvi?WW`Q8Q5V zwVF=}_`f&*P617-_GSnl2Nj^+AVJzU#iu2PAZH(BqyRA+Ac&>@oz;pD0jD2yJHbFj z-w;S*L7K(zbGbnfXUxGHVqm8saVHq0rnM|P|8B4{L84KBFO+NSfB25nD8vFX}$OT7=`iJcc#+ReS5zpM4mVJmr>hqX?C5?9W68hT$Nxh$cmt({B z)cSuSuh^BYH7q+(+pSX3KFl!(FJS)*A&sUJ%%7-duLL{Mu63#~40lP*yG&NU6NZ@j z>L@~xTI#ihzu1aJ9^EzYl(H}#5jb4Q+A)9->)|TeX6|VyS=|>Mugi)hLt9rr&6boQ$3DsWu6M- z1F|h7un%IyB&(Q~qOK&D(U9m%MzWFx_8NN4Kmmq!{s#vGbtogv0d9Md z6bBxckX>F(6H;)P+!A~Xaj}i3ri2naHmvEU?sIDZW$p^`#Rbt`*qgg(9?m~Fv_R-!@g|^kxBMxIg~ZT6 z&L7;7K=Tj;14K!&-aH5RNJ)VD3o|5i^S1%@J7u`|2Uvwb^DxNSCIct~IH2dM8%IMx zZ1=B%Hh|BDpnYL{(7*)H+vwpNG)IxGE}J_-92+Q7xw2NI2M4JUhz_tIu6X6$X*r)7ru6zH`= z`VXQ8W&fV@I6G5DlyP~6uT@d~r3%F$I@^dGYc%cPE%g8qScJ&zaYaJ2YM1L!_ZdRHbdkV3}sB!S;VZjutJ0^q>%e#2Ur}ShDOXvt?gf9)Jujg`&Y4 zfOlg;;(EcKB?}@2&1DG#rDY^LU;xn!apWxa7J9NhzoDqTotVn5yh|V_OaTrn(2mB* z1750lZZth5BsNK(Vzc{)W!9lYoy+9aMz^X5+uhZE-rG}g8IcbsG*Kl-6`D0f9Qcje zA+VQiNz<^v+_>)v2G4)&h%7sAXolFv^^EAbo1`ApD>M*$B*){=%2 zE)flvddvQtw!VRO1g^paofZgwh1*?GYkYUm~YzF%Xni z;ApOfs&}nY@2_~U)67}NihWxx<1K+eM)5--#!!oTyxK$>Am@gOVSHUEH4Ehfrt`j8 zwa`BXjZ!#M`D}NiQ)%U^%WsXCFr+%Xu7SjSJG*~O#sfA(CZ~oEy}LXoLa0!QiXQr6TisuIpdmBl zRq?ckN*0m>JhEewytTu{=2xgaptK^E43f-TC@TzPgcaA*Qvw!&=^YnMmDkQKhSQSt ztL~-stjgW08ZX?sBS}aaF)ha+FSl4iQ8Sf6~fefItZn>9Ju4h=~}`y7?y@ zUBUw=_YzQ24pMUp>u?yri1k<_Hl!h|M)Wa9=c_;n_4qebx>}%Gj2iUZ2;eBkpBA*l z0#8$r2x0(nsC<5T;;!bs*?^UM72}Z=;tRvWWCw%it8a`1Ifv%x69orVzD@9kUZ1hg znXff?CbT)I>yT~`Dvrt-92>~Hr8P_V`Zi{$lVg7OKga{zLY?njSJM1p>m%a~*?|Fz z`6gF`f|Ynetf>C(RVa>;94e1*7c2UpX8=WPszB6jT-H$tR zkUror-~Fg}T3GfFw@Ph)Qg9{=GY^c0BG-+-r?}m%u*#WVrDlr#~X|@khZ< z-QN4*>~H3;xGXy<;rhhox3?SgVluGPe+nzR-sx;Gax!SD+T4boC>iGa z{*1rK3KSsbSPBB-f-_UOog&0PNd5Yqwmg*rDc(2f?0&Z@W-^uyywHv!^x94YnW`zs zB>d_z1#s7a(jHC0S6ZA6Rt6XJcJO99NAuR^gT?j@D{w^4e#EH0#CTpX$Fl3T-}|l5 zZrQh?@%_4Xg==k9?@rxSEK3;X94cw~{qfpC0e!hBXf~jvG4RPky^~f~)uDG<-gyz} ziEyLlI^iqAPBFzSXI*tExc=AG&Q~ev)Fp?Pc z@rqB%?`LYs&3dh(U1)2VH!HSm{#MlNW_n&(0rjya`*Q9Jvg;QneMmnYo-W?>=x)cR z^1=FXfuSPk^&BjI2qsjZLD#Jrc!AYGj*09HaO2YfZ6vm*q{7lRbH1jwwvZd}pmI9Q zsOkZwbK>3+_c!KFHmMz0+zmCk~q+1uyEUMKR8AbXuCj9=jdetn0?JGaL9mK z1_#EqKeP5Gwha*c0Ko;^ZK#-$PXyNSn)m;xZ2kImsvGpzsY?cri%v`V@i?={BCQGtNbACEej^9W_L8&ooHyzE#tSK;WI69G=MUGkP zMsDTJ{SrlrH~xdVyEUWzCa0^Vez8-wz8-QEMTK+0gl<%ycCNP=WdeGuzv{LhFiwqd12JS3F$?T_zf1s^AEFpP*BmL)O- zxBuF@So22Coy+?2bQI_jQF9EBF64TH+rh{#GDB2}9iQ_kS$ci=cW=?awXe!|TzV|r znsoMH=egZuK5s91#b=HU@T2{9m#E8bwPa;RJT_mvVfZ83J2LPACOw_we$7|YnMG{p z9ZM*o97R>%xQhHxagB7&bY5&*Cb_yszgjNm6PWpKWxailv(x^+dJ8`mhWnkE2^hRl zmd2^8*B-I!<}FJz!zg$x7zR>%oHG0T z5hUyS?ZL_l#)F02h~F=v5eFW%c@?xZ*cBhXXI_j>(%t5t@eVhdbpKUXa*!{{tz5bz zi4$i5J{wS>)roVo!m}#C*53gNoM&*=NW&gLyk2)ZKAz`mGv;WC(Qk%0|n9OLKft@W4UHT{j%;z zng8OzzE5~fx5lKMP1ULRFJqP|Av00hLr-v@U8s?Kp(LPn^3Ej z?Fmec9&;JZlw`Cc$eT~MC)syAd!%9fo|2QgOBXmeT*fK{GwTpF^F!Xhd~D|X_kA!f zr(AMKPVt{KlrPsGS@(7(=Ry4H6#I~N01I@*2FQw9)0ciYLAE=j5F0rU{Kf!6;*d<-SG{Kvp^p z**dClb^l42HE`5M+!?&tKFs|czHj)p-OQbpv4HtW$fj4_(_-CE6Q}!>qJ}xI;4Bz(KhhDYZ_t0UXF4@HCbrW4P$YzkU`u+CKk9YODrvv84y2T;yZXy!) z)_i9reL%X~seM-d(H*_-L0Lskw4-*{{TaeoEmxO39aFULX^6dk|7Jutrdb(h79*Nfd+5}sr}9O zYDFqQ27u#Hu5$%R#ljUS!e&a;)dCYTLEDrQJ>Z7FQ++uM;bE8pChM~WQhRF^HY7kO0dB;_!unqq~y1m0@8uvAHR1uI^!{C)EhwGkd%msoa30dqSHpI~^k)lTTYkQcCMFnqC4&=2*!;;;R#yq1?x7QZ2Ro0(+YM#xHrEv5MA6NgP~B^@!Rr#}6P1M^0H)Y%%ybPA8pUph*1@7fLD8+5o+97k z+HBa7&D5~hYr2#nyVlJS+t*$nsc?RMCciSealLY@LOt@LUtaVlY>PV~WPSIry}S3W z2cq# zsrnaVs*4)3U80?A@?MUr$w-iZ*;h;WW9F^xyTe<}wVZ>k*5-05Uf-$pHG41&ftf@) zj=xdP3SL_4nG)1RY8P5#r(>==?L_48%|qlhalZ+_fSY%{hZtI?VcN-tePbKOmr9Bq zxrz(gAz0DI#|KML8H)cw?gT1t_1ReGZV)Jees1EV|EyN@%N9V*zb3LAmcmaZ@=ROc z-?ktBQ2T*!KyuYbb!Tg^_?=;x-5>{)%E`D&+%h?L+brQ~if>M5^+v6a4CdqCX|;3y zz&5#gYZkRHy)qV6`jylLLSKuZOXM-nHdD>%;2G23cgYU(Vms-QBz4B;WxzAnMV@9x zZ8QAfCHjpFk%D)j*lSH&#vk@|^74u5VzJNTY0qP^sG-Qs+Xiktc9oVojsky98F&%( z%mvWrMJT!0=-j2VXO?I&YGDH`r{7^vw5OrGCXMs3t}gD(w0~ES6EjS&WRy-|jKKw} zA$Z`%&g(O$ACTw?fVuxCR?gw0mGz_^E6COG!x%Nvv=5T)iF2F>1@4Pt)2|2;43iF6 z-_E@ZQX8`Ub3`g6n|WfE=E#xyc``^V;GJzj+gf0lXM7WgfmSS;o<`OrL$G5)n^?g^ z$kH6qr>IG@sdmNkq*GaB|AJlJ_p5BEPrzeH+=<%rvE+~Z6PRRk7o!aLr#G~VIngJ( zoL-xvhkApQWFnM>t3@|WpmL%|qTkfS3z)@BWb&(c~gelOx`*;|?Z?b2x z0HYefiifP30`xttN&iY}x*qVceh%4pI15#l9WHMpU&YdnT82qVz!~w}&Pdj)BqHh= z-%4|QOAg*kSbyYc|In$|TeN4mR*Z7XBTr;ptB)A1k_+2R_XRgvyP{ObhOeC-kJ7Kc z+tOxvP-i182!4V4Nz-ZcVH^QYsbav@BkfEI(cSpLK6C%Eh@)F#6kHE6>eHQ3u4@DT zgKYXy{*ia^Oa8w*51)ELUmAFMH`lRc;Z}h3I!^VBPV89ot&z&@_C=9@n>N^a8UnoPR9K5e-j6_tQeoy69mD+EWT3&jv0Ia@w&Z#}4%>lAi> zZPkX>(IVJ1aRx4N(njq*+ZO6eY4dT1Gh4`p#C0@^G0${@8y^brZFU}rAlr=r(qSfp zSpu{Juk}IZ9$$m7Kg8B{19`yJ;|MC3Rb%KB-~c&Iqe4=pJ}R_8<*z_#o&fEwA6P&F7-52+e1GVo!zs`5m=PZ-O$z) zBsAI}NQfW<$Pum{?EPSI1#-*`3>CDZ2^~DcG>*b0x+k5O1+CF6uWbuLuVJ8^jL0vw zo&zGEhM5T^fYDawW6{UAI(ue%W{{o$|0auP>6Ir%J^c^ziICTo&h6v5e{zXXPb=q|Kp{m#2xu2NX` zD3bz8C$>jbopyH$eg|hqZ1OQ;CR8w+xW+tNLo{xn=ow%iD#NCOgP(+vr<^h))^~=$ zhcf$CP}pUX-g8H;$XOqB8>*Ar`3{EtOlIyu)Q-N6Wn>#FO7)(nVc3uEB-M%B<~3n& z`}Bj8+6EKU0=XR-gu(z})a12egy8ULR+O&zO8a`>|8oLR+W+7(y#Q_^6bmCh3 z&3GRKOowlD&2G2K?oH%?xaz(uZjHg;Bzyc%)fF8Yb7Rv?k=F>pgV)+k!cH#{tNP}D z>{b2TY&0Z;-waU-KhJ|CG)A1I+$6V>JuqxSTvN$JnX(O)5M&w?b3o1m1=zCc+`zEh zacYkimCz{-Hw8ri-d{98{plN)l6BS;+W@Io%60pI#2CG;dJf5wdU9t2`h)@2TaI|I zx`y;eI?5*+<%+8Xzi6F@6KQkzHdb8LICpN-<%z3TSfBf+jEq&vy0pAQ7eq(|vI)9b z5_a!TpYL6bX-V-zNtrIDsp^Fuv>U^n3vQ8fJEr}-Q$!#EbEg_;@PD%@LTPS|}_9q?+>OY;PfoYD@^SDEN$b?B+of zp91^(zRv*_fK8SF(m=7!#01Pa8-k4UaDX9Welz`$qXxs|j;92?AH00dMiF!V#}ZKu z2EdPbo^H&c?9^{|BGa`W`Fc_YSxENvL0@`b1emFf=G&cnE3g=9uAsD)*QRSGw4f^4 zBxzY-j7m9os0yug#cqr-Udt0Os-Ri-{bxN}CV)qJ76j-igSn(8O)lpdCX>(vHOyzl z_UA5ODulIqKi)_~E^T}qo}f_q*V^OGk^K+1|G9!fFam190B!n9awP*OvMcD@ay%+$wm{sX%F5~-<0hLKm zX@J-kIune*iZN-t)o|4`RA=XG5DX)m4pQ7Q;~y~NA8x|sEt9nx{n|$9VV51?ikkiB zuG17o6P}_VHHm}38q!p~?pOb1+U5GFUc>WAum1;+GVySm)A%>*%i}hL-7dlF-D7K) z$*nrA;j=dnT>9Upts7ex@3-^A`+2_ulcG+&LbHS}swO@jRQav<`Hg9bWk0R3r+g(z zU7xjKLOcvEZW`qxtoj)3#TK=>T5U|VG&`T&NH6#3P*k=c)WrBzvA)y;eDN)wi($fh ztYBojBv%pdG@93b?`DPwy&iNFSy)Su3d%bHSb)b9XA4g2T*mHRW&uO6K-jp#TGMU8WV~n2kX$zY<#+NO4h+053QYlCx^zjrS z{fU^8B?-U=l#LC8@|WOYW{*r)s5jOKAq-y0HLwHo>~$V5=#t3_YS>8-Ohx!tWPttI zQPSE=m9I`yR^fxuX^=@evB*bHziL#yqCcH;2U8>U&DD3#9BTy7rp&%atU#5b>445? zG>)2}{S!n=S`Ns#CS$-DCq%BMhN5mp+4)g5$;Y9*_EEArX?mEM@P%Y0#p4W9L~Aa1 zE)l?je_I)XTq-1r==~8}U4suLxv$f4TQ@S2**jbWHsT|cz327hycrQj?YNt8YUjNd zm=u;L-XGhr<fkBhjE8z?pHN=A8b^x#^3Lc&(m3q3uN!<|MO_vm=|30`}kK?pUb zGD%6HoONs;J|-?q`$=WesZ)2W6Y>Ttjfd+!f&ihS3tO#_z;ezE&2d6O$`biooI&pm zNGL(1pqtu)3hXK9sLSUK=K_;hXd5^(l`_+B( z+?Q`%g=FG2=c$-U=OizcAQw$Chwt<_KK`u$>M0F~v^ooif^2R!Q;2lO10V*V^FZ0F zOb8JGJX}$`9*}dFP#K)zTrDTe4o(bl;j7?yOpgB0=pJT&IZ?`Ek9Pu zQsg?!sK{y#VB5EUvD!R;$9-M%)c$#pvY>|{yFbUA4_)nlPU>vuS;VgPtH#JD>2j_G z%Q=~ZfjpI+>HRo(CGjTL*1Y&*Bj$t%zQZ&Vi1y%>4p;$J^zCTBEL3I|$)zvb14B26 zk;&PWhb0NmcqY1-4I+n|T()*1D4<%zB<71O!f5HxY$o#{O$muhOu&ddxK^AN(RX^+-0GpTBaEVcTKDMqN0;x8#iXp%e>@9_{C zig%)8sp)JbR}^}%_!&5{R|p_+@mId1-p$YW7l5C(Ez*#fi^d%eg@8c`wU+_oE9QwI z5Y0?5qhLHCULp0UR6Lcj^Za~}Rr7ir$!Q!0*}(=d7M9&0UERQy{MA`ii*MuU|FM}p z-VaPEZ}`^9WZ+)xsBSxBHc-S@`hg?(yhJ+cb4QX%Qd~5|x&Pkr95ov6{Koq;dwPG- zznn5VyA5LyD<7aR#8{&&AG;ql+c2hIvYOcjp1&C6kFV;qMXX!fDin7|8-x zjOuPAnEoQJ01UxkNr@sWR>u5PLB3#zw;P}l`tD&=*sjtaV<+rtF|u)5=9;2>U!N^{ zOA%`c8r$IKX(})tyot+IAmkSY3|{FmCA+JIDg!vc!5a_C07TWKzhiCT&7W@jo{S@J z-w){<6Fdx$06h!+Z*11C&iLuSZ9SWo*0;6Cs!ngyljwzc){Xt}zb*bn?iDt`UPhK} zlW5KFSu&WqsB>v_bVR3v)=wXvMPw@?-FV>x`^&(hd(=O zIzr4BlT<_6ilw+ly;AYs$9;t{DuRrgS66YEwJ$Hp3nq z{5INk3I=|>Kqao~36`B_g-QJxV4}N1a+{=S4S3t4E<7HdrnQ?beVyf=BcFdR=o z*BBorxsoZF94_zCaLuX%%~x4~dc5}iV380M?7+{NEcIl}^WdrA6G4_jokHCNLS@sp z!Dk4=O!+qrMg57(XUszY*q^p9+Kt(IJ{lnG7v_234(k1IJ<|9*a2n)lY*e=s!-aLg z6=erXA&Cd`T19>_uozk_rF}AJR)jrR(E|VacQ&)!7l=|!b##Su*u9^tNkgeja(4|F-|>;sF66k39iJd!$|u0Z z+T}~WsWL1B7WGLQk*wU7SN6jf9Z-qau-%|1*6ZXvC5_!_G`+~kW*!-<27NNV6iMEi zUj#-oPbudt0Fj%!TVAz(D){$6c%fqD^M~A(F{esZt-!E$B>( zG9Hl@TMj(~V&MZtz{g?lg}^s; zR8J~Si;%8&N!nildi1R^J_H|{qejx>@Z8XIih=N7tH2t$>1c@vo>o;G=-fkU{{(Oy zEG^7>Fww~O2V+W1I$JM|+l8X|BDMSa?AN)>5i2asNBYs%H&y;`S|ZqX0%h_aBzz3f zFS~VS<1Y)vfonUCq4da6X@=Q}jg)~ie>aW!JUn?ra_GKnfsi8i+hgCbueU4=W9-3`?Rx=aImU4-tjcsf#lR2MIy4K*^M4s z^x%TZa>c)jiX_Z5ARsG&rd&|%yn%MyMRG!9`8`Xjn$u_vgICDHpux_>gCGmC6lx0^ zs?4wSn24PXiG-f;e+t70?o%(d2)kj=_=l1#R^UI{KJB*PXS}`Kjnn#mx!Z`T2DZs5 zF}2bS1E-IZCIN(v7pFb0i3B{Vo9eMhqyDnKT=44Crp~d@c=t|rWw1ci3ou;AgcgA; z4~wLj)zmbxIh4Jhff9U258hzNAXz9a{Jz5yHKo=^#4M_0PC_S4poN;qKf0Vk$r%~% z3$k5-NmH@NM&Ym=p-BtK9g;*yUKi?P)44IY5!rv%-%oLfn3V}Iub`68c~WQ*jLIZx zQ&-JQZpIlLAnD>KD+(0_)=|O)&CZLQUF1?a6c> zTwuEa&dK-9;5fpglt+l_*_gNm_HooUNPRWD;msbV1uKf-0{D zB}L2_7HN>quWSODubtTfj_kB z1w!gyM#%G&20zyX^>+XoGI;vrI8jefAxNR2RHI?8WEg_t;d*{kiRMh$d+W*eSdB=S zPEyBz5H4y#bOis#uHk!O;i5!d)46doUDZsb#BTVpCdNpn=ubDy3_FKQA_an106iP{ z#O_6U!->C%U@Y2*hJ}F(+>!GTuaX6B8{?Uh1vX)zblW*xH1K9Flc}{y;92$X-0V6ZKZ*XS883~3yX7?LA57g8mkX3F*7!dvx@;_NFk?{;lm%@G#K zFEu}WAy=24ARbSL(wF)~xM8lMy>wfF=_Nl;v5gdG@3p~Ygg9EH1Ui$H@_`ReCg;M{ zH7t&z`kAUB1J^=aNxWErdKQAjYg2}pu8@J-=Q}ts8G^cZzA0}E1X^c3X8i;H95QgL zt_A&(p3~8Th5tc({vh@`ELeX|;^&M%Z2$+xXw}<$qP}Rg(SrNG&iN@}0EgvIRttr2 zC1>_gSK*oh$Tu*ETS0c;rS8nhg{?Vk*jk z@dPza87MNw+kF(8E&-2$NMEe4*9r*6PX)QuP-@S~c^>603Kv4vine1QwaXIWDfkQo zsTx}OlLY@r)jHhMa>9{9qs!r+u^`I-&aH{}#gRM0K*Cf?U@{KH_^i_DWMzwBWr%gi ze*BtNl`Dk6_@#q+tWcHhTA1|F%V&^SxBf)eX0~w>*0oNv1qPZ*V0;8pyOih1Q-qgQ zI1|1=-_syGQ1$|PkB5u(M+}_Q9P~=tiD>_dlQTHJ-n7`r>#w3TYKpIi$QZBiX^09M zk6h<)DM3@tzzjO$hh}+q!p}f{r`A9jDFZiT>}1C=Nr|Xsn#D37JXxEWKs%KvjRw1@ z`cqqa(|)~B-aqBz8a*8Hgnqt1B^(^NjpPH#*VR?q7m^iMe~4_}agAS8*4V31f_JOx zsV7@r>o{E0NqOzJj6|1>72@xAV7CTgW87<(>wDD;_RB_#jfVQ4k&k}Lu}mIR|>BeT;(H=UtF`P3-MJ_9v*KnXps_y@? zp_1o9R(JngyWFtvkaGXz_`yimI_H6h^8tw~Nvq*Ce#aKSxLbnnv!JjP_zpyeHB1Uu zn{zBfzMcc$Z^I&C=H`&&<^yp{1cBTzvPrUWm0Iws`1h83tAgzCOcMBJ6H?xSWphI( z|ISwq<8Q_9Tm$d4!W>Iif%B!pl5qg@w!fQt9X!{?#W44ON;9@w!y46YIp^ow-2?57 zdr!v2x_rwzN3PiWEaS%NV*O-bq@^T+{{Z}!b6(|c6UOvXqUspJT7_Gc_tSQDH*-=I zxruW%IVM&R^6{khay_Z)@|1(#@A`&cK*FNWcv)n6d0mB%kEH6*4pj-uhX;JNwZ@)q z?yI==;sP!kF=YWS9V-k7nu$5)T^j?kI-vKrEEJM0I4|dYA=^T^w%vvY%iNgx6+-eZ z1yC$GN~cJ1N8bYZ6y3veTHv+cya`%Joa6JQ{*qi>SF%}aT$i4U_!`t0il|d3Z`a%Q@7C6P+qMt=}HRobbZtduB)|`d}|cjaJ=t+CEp;o zp*;}TiSr-Azs?0J|IsRc;8lWo#RC+fV^b0zyDYUMS~N81f)kiQWt zwK9>-n8!AyF`nt~C$uy``>R$&59dp`?V+e02h==pGyeHy;g2c)bYm(c&PY&VZ{CB2 zKL!Bmbu#WU>T@uKhVF((sicWu`tVWPEYLP>?O;@%lu4o&2u{@Iwl<_0PXpgANQ~E( zCf(9HWI6e{Tf!OqU;n!3?oBn;9^HJCbscuCe4W^d;Nk=%L#C-gUb$)^H^$eUfE8Ky zB%{j)zSmZq+fY5gHIWn?O$pMgNfjNYD;rf8Hv%Umi{v#aRA5lVI$nPjTOhF9DHQJR zL|#;Su#AKGmlnf{>zVzGqk7H+^z`_B>c+?lnd1hGGRrfEqQ3;^Zasfo&i6aYDbMy@ zwz{sAR%gb%`RPLKHEc)Y4#s^<?yB5m>;&y! zHca7kPBglw=OkzV##E4B9%SJ@1wq>M>m4Y+BUWl$QJV{nxAM)bBLjA!pVQ8~|MU>L z$NaTF=j#iE)jsn2!~Z@`UHS53_+bJz`kZrIjs4%g$_d0IpLWk(17LsyMgcfV)V)hZ za*lbC*=Dd?QC27dUG+dR_|AD2E64?d)XY$5ndIB(&5ZTv>xbj(LTXQ}Q_p zhf9(noZ8iwSyq-`7C$fU`W)gJ!7VHsFJl$hzgDw!y00JnTP;MN+eOxjMRxO#9z`x%!Dw78l3Xuhe5iAT=Mr&&p&=N_NvV%6^ur@bDmVplD%;9i0>M3{;CV589V^f) z8-AY6!<=FCAGV$6y87|ly*;MO!l15G2&9=pL5!wA6)l2S1|DSQ6#3-FqWv^e{6Ats zb#>{4!5ggDlf2`g3VphpXR7zbku7ikS*`GcVTU8EV$LK85je~_7~dGLv9Y;L84WIG z86a^DiyVN3Rf}rp$$3bHIDXN9tD&Xd5Pd}+sw>6+J*MgkM1+kaYVojXpg|q=UgcyB zMd}ZZkWGlX_tfzdT#asg8W0WD)xZw33%O$Hk#qoiNwN+XD=W1R2!-d-C$7ju`tE!O zvzy$Om{b`Dp7^r{@pw(QSn8p%>4pFrP#MciYq_a>Mo}lJ{UW#sZ#gCKToFZEYgBG; zEj7?RlH2?>%d$+#rPbqY)R>jXaf^eVKVv9a)AHmtua4WdRAIc3Pz%3F0+VT&la&%0 zd)<8d+s;@@G-_tx{+*1}_8K|A&i&-8n&%OEB6z4(vteLNnXE=LTQFSFRAUqTq;Ip` zG~Vv5Bz=PUeY?}^HMERbvA)Q}5e%W=QGv&oR^ftj6s1eGUi%Z?P4Mw(zc4d&+u0T# z7cOjuE1xx_5#BU9Jbc!O#JqGdG@v#cHR{gs3=PP1p|Y%ZWnfuj-}#8J0yIT-D{vLg z?r-wlQ^jOCr8b``3J&6tiSDD-sbmT{%5)ug|#@0c2!t0mvgA4+q|?DcQkuFBcOg@JgX z)W7110TfuL87TaC6ca%<8xN7pO2 z9~Ug_B0FEB0VY zJNRRuDnxwM-^zW<#p;8A@KSzgkG6=5Ndq=Y#1x>2Q$t&j-O)~<2(5{^E})P1rw&ld z8=(aZ07@zv$Q$#!@zqrXhPJf-vU#CnQf zu!af8b?R<=;v9E2NMrCc3Hs@N(81~=&o<;^?a}s{B=5dP2bb^Ed2SbSC?T(Pp5rPu zap#%mSO$-v9NqfU&2N09IT;BcBRNj7i`DsJHTy8|h^MNo z*NqPvS{c+rP$kA;!OxpEOtaj9{M#%A-Q<|fx?b^&Uv&e+yQVHLhBws27>_J}VQw_- zr+r|y0~uIv%}I9eeC zM0F(@=L%@wv2e{%a{vKk^0ef}a@}F2yk9Mt4Znb%sLwY3NzPp@>j?s3y^ZISc0fmZ zRF}d)XVFL^NCJ$UM&b0U6D1&*lMcF-a22Q*Z!j$}OQFdiq|y84PINl7Wn5wqIEMqJ zsJTzer>4lT+Zo)Y-Y<$5!P3#TI7utm#D7~$Ry8xzA((q_>lgPVvmnht*0ybXD|SUn3hJVHX=df)vt|NYXy)qxY=PKn%xR!{J3F1)()JOV++ z!7%IaS!dJDE}oBuh(YyO*k&gK0xjfl59;FilwdGk`UQW9G)${GQJoU3FG8z<6qtz= z?aW+YwOTFEA0@zx8AI-yk!Vx^szCp;glb}CM5z@ckuG4RhcJ^9nvx^3A{YWvP(NFI~t!DHWT}4%}#3A_9g0z;G@JOfE_e7S(ZEj)M|b zN#a004c3z`v^YlfqU8I_NAuJi4O#fWIgvT&Ab&r=XlD^5H$YJTg#PFi^#$IPD=7{+ z{S~!xk05gsfQm9Ckl(t%%Cy)kt5!UZVTYx(>+_=1*5*|)PgBFrSbtbo@X71ahO0Yq zSWx~+Yr3wh)r*!lph@?i?YrLa?!mz?ttYl$(3|HWTn|w&Th|E}>&7G_p7{*R*XI8Y zn_DH^u%wPw+dYGE_+y4pf^gaFTVBkiq`*wp#XDt1 z14Rw%SI)c}cu?QavgxMNGk0pUck;xINypi+nZiTrOZUASm55^nlOpSn(c?koFZ_73 z0W-dRWgxFKLZyb~jh1%mVKkXvmCiPcF?XvAl88u%#T%g3Q&?WO1lA6y$HGJfr!2nY zmYvw;DmTnyx2i3ApcEv(zSuL*+HdH5T*rN>oTtL_Ig7Yk2um)7r&@;(J)VP z8%f0cP5Sw`!$gMZ;P(IkOVYid?g!`|1t0hAUK?)1iR)?`%TMNbrRw2(HjK^4z*z&0=8ie4RHO1lE>S6@L<E5Ve%qfY0|ybFJEC{&z^PnGG z53t}~W9BBSJpVal-2+F%-tp$Cnx8k#&3lbbI>Pxq@zsB&IPA2yloqRFy??z$5AlBT&7}DSN!}PWr-*t#@#x<@twGxpzd)8=*9syJ zA2k;ktmuBrV_lR7Dt4hGzK$l&Of1n2w#I3EQ1*NDcfE0m7L{jSpR#ay*Af34Pu&e} zM^$Ci15D71L_I^rf}}9lf3o_GFQ*WbEGlp4>}}MfUPU>2!t468H2ID2m`{-nPx%jT zDm0UAN*Hj~nW2sk${~#x4{13(b|Txy{ETk!ug`q*|0p`|Xtv%zj>p~^+OxL{VE&YLD2P)Fw7X&9)S6>@8GLd(>{tqWb;a-@myz_vGArPVRl4&-?v)DfVe> zP$Tr(SoTogj;+54H7;hGIITCChpVT{)|X}(*pczZhF%yRNxHZEQcDdTE>|qp@V2cR z#5zDe=UG7}81+>niY!!c1X70#z_G2T9y2lW`0&An_o*FEU97;J*&1K0`JHzzB{&Yw zSvRZ11lT5d?K)bJPMuO)C|lr;&bQEgly!WY;-lOgCmw@I!K{BLS&vbV-V56P3GtuS z=U1|%9<3oEm)a`j)RmqW3nf;Fk*Ikn))wEAAr_D=e6<~=x2!qWiI>m?uK0pOH_2}! z73Y;2_i5v-544A%Ti&c=)`xG6YFHv69vE^7oRzR~nv2QtTD$ioSBHGS8qaPe;fCwGgfcMAQ8u`Vofh~{Q2I}{Ha3Wd_(ZJGI{AnGXsT_2|KJsr5Fd5W&Su&#?GFJXm{g5I`}RDyau=ov5`^& zv5DTahmo$z#vD@DR|DXLX@=Ulv&2UcEap&z^6nLol(+-X0}6n})u|_}sBPG{!K(c# zebvZ!DJ>uTA4qs6MmZ(OLH$dP3x4VD#bS;|xcXxfXvw83>ipHzCK8uNUa7L+bz{1` zJF6}x9xxx}X!gpMTcsRnM(`;=?yekDz%Dh}rQ8EC)B3$IsPEFOg?FBxwmlrRo4?UGLmuG35KX3aYvzRJUc5~fTetwy$=ejYuJ zN&9u2x|UyS2)wke-3?t@ZSG&VwG3|?jyHZJ^{#nU?x%Gc5U=wJkVlJ!Q(b~A1a3|r zh-y>Ev)51yN!qdB7npUOKv6~twFbW}M7aHrCK*>tu7v6Z9ZJo;N9$S7OoeM(cU;># zdye5-^aZ3E>$y6OW0o$M&gGZ@p7Yw&`z~$Tu^{@T^;81=Lc%BdvY0R{F*6myq~<41 zYsg9d;QprC_CROc*1CCEV&G`qp3Av|}X8`d9_SfjK^V~iUY(lhpT?Hj(_fWq`&7Uq-$9wzNU75#qO zu$;RH)8CaNGFu-MAPmKk{d%lC*(S}1s=y|@oZ6)-e7~Qq+sIt;T1}(UBa2T{5V`44 z0X*LtHR)x@))@4!#8V{i#bbGOS`A+! z?5XG0pb)_C%Un_+WJ*%r;py>k-_@un>i zB51NF`7&@wCVNt|!fGu)yIe1WR|weVrdSrHlb1u+ol@p@lle>PpT6#gub>@CHe`@K zeK>z=cM^L$RNcb4j~8K|3Cio7`s^-yi!@ITIrW@}wUspZWltJ_It}`YzVf@;yT*wb zGOdp^FgprEb!qS6P&+i4W2xhw`{?1tg zmEu3fk2H3tt?kCt!(FlW^0L#dDdc}%>%Os!tbAu}G92m!lv|FgSS=$r!r}f1d$cSk z3#J%Cu*e4P0r(&Y`J9B4%~hL)XK6rfHF6<+s_qAj%1*;wJl zFf)@s?cje@z0A^;DgKL5SIzBy3EU}0tFze$rm*(lJp?2X2vS|l0sY2acp}AO&OW$^ zWeHp}R}hDv^A8*ue2LocfD%*4s|$*U{lDssQ>WQ0nHLGRpWDh{Fj4|!=CFty9Khmo zbX7f{U^Gzm#qTPvuqPwhr(sm0?L&Br4c*0+#B+5%_Ke^k$dWz&glwo*hwr>pv({*j zIlqu#N11;qcOlnl3l=*mM<2EItop;K5l`%FzVC`Uwy-&e3kR{h+XpUac zs6=EUY(eXayHJwvgrEryU$q)mTg3!|O`px6^Mo&J)a-CJh?nBW=*n3f`6WfQs^X`; zRTRTt^qKK^;=WYe64N81W|u2CV}^mm+yqfaJ`RsV|5dZv_f;W+ob_B^vuxetIEg29 zoF0DJn1A3e;rygz3tXWt^ZvULfv)njzvEvw^Or7*nQ8Es7tKwqwWBWzwoxzDEAM1LE&jkuN6>>{}iav=LQ@poRki|`w!$GoPR#C^56jr zV5<~u^#=ke#yb2G2gbLw^4QCi9d~ zy;>Vwg4LTkvRLH^qhS;+4%?bi&nUP_REx5I`@ouekZFJ1=5DJ|os?ZN7I0|LPcN_D zzG#gakuzH;<-uw42v5VAnl)l{QPF<4t*icgEioPft{?8vkMQg5%dKe9NPC6yijmcW77BF%k4Z+7;vP<#ww@s$NHvtxe$L*dKP&e( zanj>H`;9#??|Kphlxgz38|8reo<6iut*C_4n4B7LUJDoCNqKPPebD1vpvn70l&y zOf;)=>4LcyqigA}s;Jm}^UzpM!uN6wMeixE${Q<5i82#9U)Y?Bis-5C(n`Azl(|P* z4s&3Ygu@fG&E&OMt-G0xqK`Qb%qeHn36KJKbSD_0AMK?s>T<+gaias(ZJmB_5q8PU zR#qVhsrDz&Nh>SRMw&Yx-M(Uzh;-%~#uCoyO{0!u+zcny#3tC~AN%}?#0dPNMe}^M z_x(658;1OJL#I??J1OCO@-t&TE!g3pW`v;R99O^I+GXoXe|itcvL@hk^DAm^spuqq zqNlmTZo6WMWgGT|Da%>dz(`et4v&(Z`QQTT*E~#T1|1L&u^Pd8zl1nWP36La@qX;_3NyvFiIHr z+GkNvMQKMy-#hB;=N**)n$qO)guElCbN<{h92q%svP<2W%)=dV-LR4Mqj#V5<;Hzv zhHn1@1tGoNa0=G{-AXKT^82vkELP?|#?$6CInnHJeC1vg`7!^#>6QWS$f+pC)?B0< zm-x#!aColH{)p}au-eL72%3nhN@U0`}GNldfT{#WhZ z5HN>OZ0|XI5#cU=#WWa69A!Vxys>zF=_eQ>yhVX&ZWz$_n7&o$Y3`))67>M##mW; zJ(nnC|B@rO*VhYV#H@~Ty%711F5=G!sATKywT7{k{_gdW0aIX21C2DP@^zi>u?K3^ z^RX}^-BQ3+wXHuyLTs#&d=Z8DBV}DqAf8aCAsu(#%=sitmiwR*f#} zd6f22X8+c1cR)d$@(2A_)z>$uYV14Xt1>2p%siJ(*xU|MKXgW_Oh}4cb`B7ag&HFq zX`>cX0Q3*I-{!Xl99Vz%V$wO zbVdlF>xgO0JDTj#lxU(+j<$}q__u<3yq~v!DE?p_tA~4&8uR#k{YT>{4SrU)s&MwM z!|~Z_0ne)Re&&fj)O*WM8{K67{dtn*`JH_1GATB`3?xqqF=BEhSzo1yaO%-N7~-TY31OG z;{ZY<{NZ72#t0vO^Sp;txC?X)JBF7K}JwpNo;{S`6 z3M)TbV{iUnSqdPN4)m?K4XA=xjo3E?q#kUH5ND2~mzx83Ps`Q0~r z2tHxDO$a*EYGo|jip0q?#uJs`t!kZ=ujD*M!i|%FU=Xy~Op0$k7uzKVLY%LWtQ_=L!(X z48P2E!-(6=78MvJEJoQc%(pYP_rYYDm68fBwFp(NvbKxm#s*GFA~dI3&ln{Vm;WpD z+}CJJjp>md!G!L`hr<09DHm~y85Tz=7x15A!YQa$FKqPrREB5J?K4(uC8^<2PmD_e zDGoAZtr8SplR8%E7js!gm}N*XC0(Zqp|5%=n4QZ}Ah{jC74@Br;3deUb2q{$+I`?T z3R)_6IshJJ?6getBa}~-*9T{HQ2Gt;OVKdBqXW?s0!{PIEKpVMkt*+q!(15!Lq*0; z)6)~mnABk}Y?_pMNb(&cA7RPYpRmP@WZu6U^HDds zcbEnt>Mk*M?N##b&!vK}XI^AOsm-kY%G{q}$R}By9aVtRD7u1n$GYGyt2ClO-3X z&hsQ5ZoE2%-RJvFx{PRT-~ag52Tl_CQHMAYUTfJRm}wx{8pi~EX#^vTTj9$+mNB8d zR%a<&*o}tLtxDH^=ODm)b!S3v2wmlb{%-BD#c~ayZo9DCkb>Yw8 zJJNz{32rO`5Jf0xQpQui6zVOTtwWQ-hr%v0>*35u@n%`7T@W&iv~lXh!z$Zpjd2@` z6gflqq;!p}DDoi%kMbNv;ng%R-}>U-&)~Y3SZDU%l)K>4kV;+F)@X)(Y8M!f8iJn%-^4LHV0AN-F1@!hu?Yolpq z$Z7@}r~wcI{Bl4b1@Zkq`BxuZreFyeK@t?ol+i4F(niw+EURl}$LryaSvaxHDJ? zMQhpF`3`mjS-|c|O&T)-Q-Yn_!OjC#~IXC_53f@R-z9GsAsJ9CK1<9jKE? zJWEaGZxO4tLl>VZWW%(1j_+@`qV>Kc``T#aGcL^GcnY-k^?Cs|zJYb-Ha+QJq;m`b z-4GuUJ~aD$!_ZjtZ@0D#<8gFBOo>YWP76!}uOW zZe2CL(Klqy5a{+54el)+)(W8SQV+rRD^2Aav2>_6W2e#Z1EvjFi6=@nsivVDp~eO0 z-S|~`5+lRb^%K8GD0SR!jahcS2hg!?7&j)f?U;r*hGe8SStjF=`yxScdDQ3eAf%sK zedz~#c$-qw1&FA6_`dZ9R*i!h5q*AM<)$QU2S4Hq;6eHj|DEBWfr{Kd12)GpzP$Jc z-jB2NjnXrJlC(0PGV7ao#I_$ihYThq(7ng3-1wRP)(yt%yM}PbHP_FKu_9B>3%IM!F?Bot0;x$eyP9}Y zzu~>*D2R$Ox@m#DoqFp0NZ!Lx2Z~D$`O89_VoZ|x^`Db{Eq0cB_gMNE^85>r~3vXl`qk9vtpGIg#7+ zO(oHafgazT&G3W4B^p@~rK<*1B%SndhXrND=QZyzLpE3%2!`e>v`WlWiCQZn)>sl) zy*C*=RsBY=7%$3Y+)Ts?|LI{2F3pX14*-#3dq_azzr+9>%tEDrVXV4p(L|rYB1cbe zJAz&*-T*o+2+DWwJJs2b6JMp?i6&~ zGK_*XlqmBkU}}6fD0PK=l?@fpl)71J4O7`|(*jvi+f(7FOI7Sf2GzQIyf zJH$WlXW^Ai4nc^>VvNR!|3)G1wzACmS^nIxdN{VcT^;e!-a|P*k$O2+8Ch7lV}C_M zb-ErWJg~o(VVRAu`ZWQk7Q0QNMlIK}(}Ip`@jSz#nqsaeod&z})PE(#w6$=KPtlOD zK3m@t>b)u?c*(&KWl47)EXcDoo9Y;*( zJ)!q>S~bsXaDo`?E|XJ8qi`uL8LMpYauc?-yMhTLu3uD0%&(5lhLinL7v8pn*Ns)~ z+3Z!>T9lYB)B|3bpCe1SK`45OJPFHg;1PFdSn?mJ*c!?CeY`aySI^|x(%V1v>K_vS z1JN~nc!Itbh*>p>x~xC)DVW+s_!Lw4s-wq7>%u}Y*y;p0O^OrGt%GR_1%<5>rFh$sr&}@CBxCtMl*YkwVy8kzz1|KDcHzK*G$SK2nkf6WRd~jAdJl zjnijh>FT|F`Jdh7;yG{MYnAYJcd=$7Acd$^*-ZVP1im`DtGy$r3veJu?yNcU3es+Y zG7q|di4Y&^PJF|VK9oCSl|4IG-*HUxA4rh4Jlyzu=$JxunzICvLfl_~(0ODf+@z%N z)Af!xuH)0gNCDcs z1PzSKJSB#r$WNAdaHeU*zkMSLx$cfwyx-I-ccwS+eK|R7YGu0?UA;D-%IM(2j z>^oPz!fMAanyA+;z!8sLDjZ^m!A0K5JzD|Ov z?#i36$k!M12#`{Y_lD9WG-k)k8=(9cjH5MvNh*`Yzz8xSc4ZHc`c;?g3zTLcZWbMd zHf$HJN~;Tk$0gJc!MHB;+!spOry#X7qn?>*5L+eo+@xU-l~!K88fmWiVCE&X@MLM zf?86dn<~(L9(@_%_FH<=BETq&-4>H#O66kXbZeSngO%YE{*!L;3ll$UXwo?T3PYa4 zg2)Pg@e=q~W*M6g91AQasof$MX4u3C6{6TRqJ{R1Zrq5|S89v~4%}3;qvw60+dOHI z+APkOt8}5JqHD{QK1Y8{h3or!u{d%Q{MB0deE8~8zdszwUj?lO3GbUdGwcbv)ne6V z@_yVpLpt>N(^h$&yG1td-y^K5?ws8n&OupT~2gcVYQ^l0T~LE{D)3GvEjbkiM7*Eocy`c_X8h zPS=x<>3^t4_(^XyJvrRplWtsZ(`>&rj{0Mw-Z*}v-F>(CY1U0xVD>|ohvvAxRYpnZ zqKMY4e`}jOWbK8}9J#!|dd2WG*9))I0o=V9;<($;w4%k=!S=r0uBfa_j=-I{YnL$Z z-FD$IAefs=Vvh~JTQux-{5~nS{{9i0%C~NP24j_|6_P^P+X533+A_+l06HV0jHp8@*(W)wSOMLS`Jl_ zm)!j8OF~H&b-u~or;;;ptK5kKY_s?`))xJ^fg>nUY<$y*0D3Sf9%G%QkVWE0DzhA{ zThpWX&B0QXI3KPQmevjeo{Bgno1gJjwh#n0&<{b+%od1ufL)?0<@**b6C>(TZ+9vJ z_Wo56M-A*(e;r-@1eSsW7iOlB*5)s~nmcja?O zQN`o_>R>v3TnoIMbYiBYFY71Y5Sd%x$SdSvvB9zbzSX|jD{A}t)AZr4zUvn*alg~; z+>@(zZ!2YhYff_b$Ap#h8{)-oHuRC6i`|PbW)&|pg$}F0L9yr@tN8d~nT<&2}sagr9M zP)U9YSJRZLd2=4%!rU2ikPOIH`ekQk4rA9c`+)3jc9%uNC~5PcV73|38owGQ-X$`zFqCq{dDDu($nVau#>=x=l&J z--E5YBi7)n#vj8SSU@lN;Zy9vaBF>6m#4y>hGHE>KMKjS zTf;zU{|lA>K)Ei-qkkSQOV*(^;cXk4_Xkq{fjk#6)8I4lyVdahW@0AoO;MO4{Yr5ZBOS_(S#YM8=sn{dIEpCBgcIcZ=Q^>Cc<6 z-s`N4L`=!2;vJ#0}&T@IQK}Wt{kCC$s&c8-#n2nzbqRg9dF-I462oKYc<@odD<5nZuO}w5# zs(84CyDiUAdhbIx#dG%(DYxf8$gv3MP!oe+gYKRjr$D{GJe=~oPAla+at<^wl$Q9o z=dD{cpj^kX`b@zi;27dB+9*1=ENc@xWndhJXk>)ad0vD9AR$mYwzAq7xpMrWqVK}L4d)vRB>h6L-15xAE}4?9%;QED zmL^AmQZRq4@paAUw$NbPs8Qr$JN8t}a_{b1*Phbo^YVIr4n-XxV40mI!Y8BxRRWq% zJ{Q{>L*)bH7e39q(Sv?#ezFVdl5S?+U7AU_ggCClKsB?ShzND?TpRLqNb=UO_1FNM zVBV=58zpw8o-hHIY(`5~DMc`0R8CJ;c5uygKWyyqaXjFehkKjMCbD2o9Bkiu=li{B z%%Es66{cg2*o=s7d4k#X9WM#@_-HH5l~?goQ)SM&Za3Lf^!c+oc1@4{WxpSz)%0{5 z7wUsUD~Fly2qR4e8>Cr<2sW)O1rOh#g!7j6qtpk{J;GJq%^vSpWdj{OV2$2S6uG?D zm8~V$nEOgg1$eJq(cD8$XWqV(^e?AABz}T$D}-45tY{bfEB%7%-?gORQnpr$RG_9G zh+e{bU9YErtQ88(Z@>Azbb0ALfK9IWy}`~9l8`mM zn6hW3b!~(=z^z4qAw1uhOjgCXcNjl22n`MiSd-;=5XF8BLw;l_bWcu)Xl|N6n&dXi zAvK95eG|)IPC{>NHA+WMS02neFzG>Obur2_gG~AyBze5w=iU)n&CPFm#o?^fzmeA6 zWI;J%!3$=oLO6G3J_SL+XAV-Ud#Wv-#?t}g45t!3+*xU&H3TyYB*omCx<2y!>ZU`c zCSvBlwwqx2Mf3V`ul$Tmx7TT`ZDmebKa)_@NYvM-Fykn{3^_7x+K@k@@T@EDPp_?< zw3lw!7Ym@DAt^sX=GZjLT-a=MI~Y6`JOb9N$5m-b-j91~l5>xjntfkV+_e6gM{lBK ztC_Miwe$Hx`}oWXPDgUWU*tdT`#X=m>E&npG>ai(?iuk2o#v%m8Aka-YAOGk$%Qru zv-hCJlFhhM&*Y=-t4#8CNKb7Rc^AI7W+Qzt%FOD*uBFQNAwtzPMOZvM%<%wI)vggs zBKvyt5E8L0ZWSo1b+-@^6{%?ssXwp*P;-gz+s$zpuhdf=))Eq?^Bf4sCc$d+owiLj!~p#H<*j@FsSz@!8wqo>?y-j==lqg4MbHU?YZHh0Jmc;CvYng zYgqeDHz4ObfKePN5fc$0;7rRQA9`=SHy?2@Vnb>3#p z3A3FH@h!xPp1Bt2^^V$jG3xt}nI;%_UMN#FD|D1@HDm`1i+Z1@4V;+<)Hdcm{c+}c zTv=AmpBu(mFO%Eu1d(!;Pw+^-w-zfthF#MXy%fK?HOKjrsV%`Met`Wi(1T-7SgU~( z^oWVV!+wF9=^0hHujyOMNYX}197Bb!Z|*4(VBQ31OCUV)R&e^rZ0GYw*Xi85%f`HK zT*G4<;dtiR7MUML^k`K+K3%;255y!|dsE&1%`dQ&{s!%zTGw@xR4rMt_PL2xxo(y= zgL=<~Vz5FWcC$uen(_LonsI(R@H8ZaAFmuWChYv)eS!=Y7}{r>PLs1g(q)W+q_e)>N-CLxiZ2Yy#tucr^K#gi*Mm zOKAb;FpDMCD$1q^>65h5?0*T=r`x`@QQy={e#pKbPHS&nT2;UvfLzLwS=v%v7TuDH z9ci^d3X@L#VJ;D2WXQDyjb^JbsLxOX8 z99iJF$z83c@`#Qu$bKHS4s8>xKKQ- zDtvXn9)_iyL7_z!rb_oKp+VJS%6dzN@(>`_z?muYWc^pc^k4GwaLGeaW&PrT<~pM^ z?b!XrQa+ioRce;Y+odpZKzHl#;gG|RLYirwVQo{|y(rxDn+r~HX@A2CcAkyQ37zM> znUxSys(kOAnPL+gu;XBxW26}^xsmRX=ALnt5R4&?_?~^7IVLzxe)&6K?bA06fhML$ z*CS>3j`ez|6$l?2S4o_8X{YlCqC);x{z!w)i~q}%tXNv=Y#8;edSw^_^_rwh|^D)c?d06GT68Ja)m z*>2B(VjM&{ttcEKcxH#UT)=j>PxF6U? ztwa-)7VE3$5D9Bgd=ZzXOZ-_oert<|PJJ0*0Lq9n?tTdz@;$K?cL&>(^C!n&8wF(X zkb~@G5k~^eum9jkJ`Dz8WZPz)F^LL3zLOd-c?udfDgHCGHoZs6d~j$H>4ljNERY`8 zbLbnr%9m`@$Q~VC{Nf^FRhn-4=BI{K&utXYPgGetIvOW~nv*=FT%@IU%v~lsCTQz+ z8pITN+@~OfwSvWhCx&UpUh8p&i<_KgrOf0MK$r+l%Wu4q04HSoM^oCQt6wKMAJxx^ znLpI&NSRBKWzc2S_J@6^=g#)!;jYbc{TYK2h^eWDu>P}pfY|KgN2Tol2U^g8o@wgN zr8pMEbl@PA5q5w61pxd8EQC5r90W)Sg2met0KGYCN{@-y4&T57r2l^ii9$ONsKGkY zSq%Uhl&8EPITpC4HT>YJ#up6&$EV2{BS88^3^ssDFXOioi3U0EndW&Jb`BOy#w39U z(28iw!y(H1NRW)bPRXUcZ>A1r1`A2?865BzFv)^|0C8_k?Mrc{@U{OybG10eoH;v8 zhW#fF7JLc3`1ttz3a7LCm|H&WvIDd-dG!hb+lFH~L&K9J82*;2Fb$E%v!$bel~*Te z$F-h59#F2)BG~6#d!aV;f~Av$)5&Pj8F$^sXmkEQNou~D93?vT_uu5N6aM}FdsOy0 zI$Zlv=kNBn`ab+3KOb+OJ?oxshM?P=jqY_=x5UHC(?jQnLQ&`j>l~2d zy?>yf@n$7m9}zX;Jh_k$hTaa0I_QOPjgrQ|FDo{kGSdhBz4-;d@`mHb`249>2Z{@e1IKG(meYNx#ZezGO2!uX@{-P*TH*a78=h z8_N%Cn`4X6?@Y9v7@S5S+M<;2H_~@?-I5;f+m%#j5qbS+%@EV?NBi|T@b+Hy;KZoG@!iZs60yX&rtWgb=V$P?dXi?1qMS&{veMIPwn(XeB zl0Vf9X>cs5DKaXKi74Ifn<=O^u{IXy9AY;G0rhh|z@z!O!bDrOnbJ7n?UK~I-s#k@J|Xc!Hcvizy-Lrq=J_K2zJ4?RZJ2$?M@ zhN9K51wTP>9_nA_GP(Kq5uNDdddB1{T1Q*nq?v9oZHtppee%i}x%Kc*Vr0yX=&<^` zz~`e>x2*eBB;=-y?zn}qP?;qcw=qTkXCli2`$s&2$$lyEvLq%i&v(A6xa!1%nxmyQ z(Qp^2)NsMZozZnL!K=aTvT1FEiou$_!918k#huM}!j0{2PR^ivPl;j?*(H#9Laa^R zLEjt6+H;G*m0#GmDgG3UgLIcNN@+QZn&i{XWFNpqdVJ{gSs}Wt!e$$AGxYtbZf)FW zsE9r=+lAh~U}|#?MX0u>ar$@l$isi)&WWYPZUln=xUQz5MarBc^xkKzIouiV9QXgo zUhjDP=r?EShuG}3D*G)tFRXNZk59pPFx!>%H=%Dzo^h3LWq8QFSKzd-VJWUFI~GXM z2s5el84lyMTV>E<5SQwA46lpdQ8%Sh8V{X&C=dEOB}$=eV8NflOBfD$&!zfO%Jmq6 z#WWw)o*;F(vWU_Z#h044_uxs|PAY_v%J{0eLA?v7&c>qBEtjBElJ~?~RkxBYbsXIK z)N-a22?S4KC_Lw|*ocq1(#yc)Rq>oGtERAY>N7K^%or0GT^T#$S|kVjeMTX{f#IN4 zVGJ!#i-f)8wM{e#wfkfh=s2Z;$_Pu@eI|UbYW+6jF{=Qgej>PtP4>et$j?e|XO*V2 zwTxMuh*PmP(TJwGimnh#DpOvjzy|&9q(YEls!E^3ZiSg5piRoB&w|kE$J#sg?9Dvk zf$&kD`q~oX2eDN=C{OA>N*G#T3li_7mg)%zYnP(Tzg#hMeP2SI#1Z&1uz5?9{nuL@ zrxc90ZY5sMNa$(BF@uy!YLQV#)Xx_UUbJf#jyCyh>4FDjoZq0RF(_?EP~Sl%jCY_}q`XgmfNn)jgfJKIuM4KR%w!sO$-fbejTN9#`tV9d3Tt!eNzd3r-2MsZ8)YWfpJ8k zpqW>T17?;+#yQS?O77l9QrY2UzH$#h1BxA&-cbH+ND|csFd9y>JG*t?@un6!l0}v6 z_2reSN8ee8gqc0NwV>ki3>1%TB`96Y&FD!D`-txO)M>`V>Am${LUQuB>PEUsC8_lb z^A{vybD}NJVYKX7#y)pZO*OoRZ9eL%8t-E+aRy6lvxlf39&}ICi{Ot2o^%Kp)Lw$= z-irAq{uMiI)lkN0Ius;b*((f?6+v`2DD)Eu7*u=^E;DBjs7FEJa5$N;ygP_MK6F-7 zstoAB_Of6Ss@=h$aQ7o^{}Y6M3>XxI7NkSt^nwVa?u;f`(>HZaba786dGA*lRNy{P z7&cIqmhAxX?)YlWXAYG8Mqo{E>*DPI{J)%Fo+dWhw>+fnTNFlf#XIehUdN$GP^PU< z2xq!=fV#54dP1-Ild4SK*ZT@Nh%8tP==Vd)S;c*oI7(ulfwM%BcN$rvw)uT2PeJrlCK-4k1c*x#*0Q*{lb&QOP*k7 zh3adX7}|v3V%tOzplEMY9L_a!5B(P_kgt?HzXDjGKnw9k@nim%sfqzQC0`j{Kc=ST zv+rm9YG7Tq+`zuX=I(n8k64jgBE*ufTk?7fZDA|HlGorPP|q&jv<#XwQhim`me8*U2|Vuekj$K0f9?5{B?tj?Dp7J4j9Ce!#U7t* zAy~FGxN*OTsh#jH!x*9czQ*}b%%Q@hk@&zBU}!myt^*bPJsJ4xLM`fKk<-TuayyI`*p)y$+tH zacG?7S}g+)|CrWxd}IKkTcV>Fdn=GBnw3;)6NE~WDiFhpnXl0fAf(aG$7MBI1PlR` zdW__@U6>{z>RoThByqF_Nl7J`%Ny$pzQbRsG8gyiT9~GVR zopDtBC_#<33a=J6?|3WIbzOP#xC>9Drp-df`BG6N^vFoc!js?OBZIy40zRRm!D1zn zlx(uJ-!z)WV0(29v#0xT!xlB92U6QW6ZTJviz~gJt&`x*Q;EeLWle=8@Xr(Uf}BWH zmL^h59rWG5lh36N`x~DKAzGoNVRdz+f>fJ(K?;RcqFB_eq?+S;lx=zJ*AE_33*UQG zfk7q*?k|!4SqE_6xKFIkUOet4bG;S)tdheQa_A7>h>L{_h#3jKbx7M*vAwTVeptp;A~)*O*e<7`8khCU1VAl(zmxnd zq5R88CSePEg&a~;-zHr~oIxeSi^AeBBDV>uB`A^3D!4$?>tH+}w^oM-vxou3^Ao=L4 znsLulEFxBg>c(e{i61T5Jbk-RAd`C~IE8?Z^j3z9Fjrq#mWL|^)9Ltb=V=f4imO$q zQtD*=KncO`-)Gdy=q|+-19Mpyqo)~6|A@AAinfFql1F$T{29@Ea$iLbL1pfmMUr1e zID5GUY_P53!>+_tICC?z^tRW_8idRYrk=80mXZE>-Dg_vP!c+4qyHGoGy@MFpJG2u z{V3c69|6YKRQh@~O^31%hJ+kovu4vX%X?I1+pr>~mL7#>qdgzTt1bW94Tse_b%{ws zy1n*mK!%KTP5yq*1RizO+A!n_p)|?(uzd$OI`pdP9!pDaY~`KKtqze4PH6ffvEDy< zmncmM1VAo+OtX`vHXJ;Ar0P9PMoZBBujA==2g?0XspHUD2d3lvKF7^Sn;;s}Z=$k7 zbNKjD%^6DroI|rpv-BV4TMMZDV``z(yI2R*@=Jhe2))-eG`jyp`EtqnFD;)bmS z$oClzzxV4^7nqxQTOf~k<};OvMYKkztzCMvKNc)pFw}ltdpJ|-8YaOiTFryD za(Y4|8)hUosS@pfnyjjzb#{@CQA|l1IH;%a<_cR`HZMce$1t;($7twB(kyZi8svYk zFSdyE8%B9?Bl|^syVCHbtA|ma-WI~>t|}%-9jkn`qNRoA> z6AM(?AtbgAM(NA*Dm|Uc2ea^Am*G{(OIM1!HM@fVD%)~~4+0>bNa{{V=mW$TLk@=yF9OuEIsdsF*9@Zd z)wu__2wWvg9#Z!B)-fZnCd89KRhu&1yWJ8$9hl4nX`D-9AzJ8JuI%{zzT)AfJJ{+M z0`~fi47J#ubdMk$ihCi~L|4^eClhri!ESEpr@ntVJ_OIVX_)fLgT%GmIFvi32IN=d z`8>sNmsV~aRX@ca6797Mc(Q}2dlC$rUp2u5X4#pt_G>wttX}QD8sre(BNLA`hJjua zrZ^GIU>pf@2iqX5bDdQhl%lh}<2v z=O;EN_OH>Glk(Y;{kg_#IhMpN&%|Gz=W+$e*TXBO=A5w-j4O)FW;L8Ztg2a%;}k?n z!zb4Q@II2O-+ro>$RnS&d1MUauoT=Nl=<nJ7-4U z)z!LL&!_##MXp=}sGpv?eDC^Qi>`#h@;0I{88UP93~INsYDTR$d(CQe!(Gw0JK1LF z9KL_y8C9hH`pb|!pXC!W+C{JKQ%&ybEYM_kbnG<&_&3uFIz#;Muo?c0zTxMELj)eQ zbXHFx{0MU8Ra58zA|vvVv~8oT8v>MsAe>-d%92vZWq=?A3ZEhiuYc_hprPDJMYvMa zFRk%O6i$Oq?V)HGx4BJ*>HYi#RqY10KBSG!^(g+B_tB84=%ddfHQ~9I0oa-20*bE% z3bxZah^Kjn4v2Vav7=Bvk8*EsHezl(tU%f1lSP5tZ*kaNNiC)Srs~n9D%)1=_mt6_ zYnkpk0o##S)ok6v_v?B7dH#6r z+aE1vjL&tQbDiaV&UM~#EMqf;i}lgF;4F#rC*iVelw@hG)^SOs`D+D!{7#dY`RKj{Q`PpDOS+6yl35-SXu?MyCcMURmOS{@}uKt1J2apU}~UcD^;+&MGKZ&N3Bb zCyw4IDZdt<<1vawN3wTPulI_uv1?7p`KF$uhCY&@Srdi3Mxe|s%32IJsze11=GqPI$#=eh00Ek|d5r3E2Lx_r%Uz&zbox5faQFL85Au8GPQ6OMWA*^dY491p zvsN=p4SIo_cp+01*QSumO02n^K&o~>cbIY7nV4%5qpxt7;+Q{N`$##6*KxPPQKVjR znQ@d6RHlee#}635F(Eu}qP@LB!b~Ig?ftOpk8)3+YTWh2n{lZ8-L{P9J_VYgevWZ3 zAGhL8#C07+b~$Gh?)@V4!}rqSzSo~}mc*X!yCP{nZGH)VWH#evSUr^HMHWMSXyVB| zUQ1xhnFYLEo_V*&+`6ak0Cne7zx? z%^tmnUD0K2Z}S$MRnMh{NvCM5QOqvc?Vr^bGOU`8bxletLAIICzN-_*p02)|dO}3; zBES2^2KMOof}KD1D=b!J=&uvD)e6Rc8L`K6Fm=jdLy{I=!m)BZ~uyRfLfIdAsxM`wG2nqMjY>c_U(!aJE4usL=4y z>*Ro!znlBA(}M2GD1WokKlI`IL&1gIH(xL2a-&j4c~Ot5eEJ9eU_6FcuN>+0dP-bAdo?64=Be3;@O+E!k%Nn$bquy7-d5x$k-LX=)q4|~32#FV zbc-F)yl{L-bbGduW(hJNE73njuI`ZV1Gr+8v|XxE#MMG-&bIS+GI@oh5YK&UU7*yp z?OyEF@Ai>BUEK_qB&|q~Xt7r(hecB6#GV}c)Sef8D3)ZFcy_KhH#Uo_QR(yD?H8<^ zr8+&+swRBwy=?dN(6#69C)^cuUca-hWtM6-C8HGoLDY@+RRV=nvY&kfmkeUJSnK2zm<%OWiP znsXCT?d84QlgWuq4(=ux9s1Wr!l{cc@0DouNZapo*Jhaxqpc)%Gu$Na;ADd#6XodO z$8g;9K?ro6C)ODX*aSrja*>$qA%0H}HVr>pv`p!JtZI|TTA~$<`0m!2Z6m+}1yhcH z)c*(BO^j=m67!?Pw<3mk9d>6l#n@>xl`G2SB#yC#G*?cvr1fE;+eZJ!Dy5Ns_^oiA zb41CjLjSM=hWnLv)xZZ^wdgcS+YFTU9=SUUZQ=4ndH<7l;VEXEa%ZHvYW(8!Cf~k$ z=KV*vOsu&GYcj$l`p@-m?D8m03DO8YXxZs5Q))T%=v4(fMJrKX0d8>|1uJ+d=yA=& zJmBvWJi1Nxy+L#B^g)`tkaES-mhOXu4>7;L@y5PP#N5XeKTs6 ztQGNX+9SNpQYmfZbmlW6`H5hrTZI1`1G>#$b>nb%^sc_sJGa}qVx$JFddiN7m{?43 zmE(=42a4Alo?8aCZb6BE=tRa0w$eX9U?P@uU%PK%{)a(xZLeGH-FX%9i;Q}!=HB|? zhK6(rSD#K|kk=t&V-*xCIN!8K}?2ziT#}v|%Znl2Esofdb z*7C4JqIaY5n~hdpxp<#BD^f&bdSzZ&%4~rV{uXAL?Yb|~!DTkKX|LSn-oE{2OK72z z9Z_Pf!^`fpgTmQkw~`M}+6CUvKC?uKGYj*dtrMV4;|vw|b*)Of^VmB0+3JAj%~2)z z{^^CPjzX-AsL|MK8W-NK)t#tOBsf*5Spa7jO4_=G@956ddj7aDEs&Yhc1v?sr9sq$ zC=h~gLni9BJQ|it&`xezSn%IE_d(oo>}dJceZQE{CCxog(S@l6&npA$pF4@=xz$wQ zD2|yy8i$ri3Sp3mwMeD1lASkBYsCHI&kXrgm*c017{+{8hV zYsnaBbkn?}p5ajyUXiS~bqBbA_QK!Z`Y_`NNqKcCRcsWYrO~4=jA&qo(wxfsUsTZs z9cL+9%&ku8*8KP+G!0vl42P=rCir{p%_JFIox6Pdan$-kjvPO6_L5b&vQfsn_Mb{n z?lYpE^on5PfYCR>=u%F4c-*7Q^q$ZWq52>Aq2sZRM)=Za2OjJ{mR(YaKV>Ae!i=@| zGT5S=HlcoPrS<*>4jMXf!ia|&GOv5#s!;?_&>Ce_9hsc54iJ3NN#O5Q$2Q(S^wtWc z)Q&n+e(UjZ%dc!1g~3q&zjP0FaivgkHOKhkEBX5(8P8c#5DCr{ev#Aj6vwc_qQau$3Ft>7!$B&8g_i2PpYlz6{IY=2jb zJ=W#KEjvAhk63br%+9T6!>oWM>h8Gqy60~5LQbLnbAn9uE65>gQsWuw)oRZv8%9gi z{%L;o{B#ulesDnm#d}xd3e)rRTuk#~l_WBsh<<3%u&yxA)JT8#$~Gr0l0|4NM2qN= z(mXSk-aReYvZ08~)5zf$?{W8F$PkhOuNWgP*J;4IWmZB+yZd<6QlWc?VGg#EJ|}Hx zLIs!W>%#BYGP=d^8vs0u+$uBZ;PG?|xtrcjC~waF6YtT2Y3ZGJ*|^UYc%}K~M8E2U z#Ghd~nPIV9KMAe}QEVFt^82L>BRnKH6f-C|jTPnJR^AX@Do z3umQi6j9&oRBUja1Ggc2Pqd|NG>azWb;w!@;vX`UWKUc@Qu(Jp?}-X+Rb3{aOD(|l z+{B}Iq{LZKk1eGS#dh=PT0g$zZ&hg$y|6H^Wqr5LPsB+z-0W>g+<_~7JuIOWJay>f zSCK0x_r41ln!0MF$ehd4;#0wJ&2`Wx9VC~8SdsGD3_Za>6j$V?ZI1N%fNk5p3vZ09 zEIl5z4=2fQwMwPPmj5WzdgR~YfG0R8x5`|}`eMwrDmdDD`q!z$8x5MrT`uRhrG=LJ z1;-Cp8y$&CY0R1{wSRS&clzR8NvxWal4)+J=xr-J+X^lxvvYOpyvn(4{q1VU2#;-^ zU;MmZNAe5*V{`Mypz8y}3YKYb^vM$uI)~0bN?6U};)aBa1G~jJ@21G4M+-6Ao^IfTs#h??JHJmo zQQ(@|5B9616_L3SBj4U#7xQ%HTk0_^dVv!-*(lX)B%hqY*>R*|7NJ33$Rs<4Nv+ZU zR@4s}Xr40Y$~!*}u4>o6tB^fwkP}NcZ`NPsOH26&g`Dq1-OP1(3`?6h|E7=-Vp$Am z>Q*O0`W_l3Un6KP@yRG*GAX^`pPMiGi?*&Pf5N&l zR?`ZXj_eA}TvDf%+;m8Cw?*GsDX~4Q^9RPUOY7bq z3iR|%7HRSG)&4yncEVGYCs#fOZEL^e)X*HY)l$|Wqg7sI$T{`2mlGIJl>0`iUd#gK z`U24|UU=%eP5t1tufK)*^;oP_Nl{hqCAsm{soKJA(#J)9<(AM^?jBAs3p8JK2^MS7 zKG0O#XhqdA5&C_}^pHV!jPb-V$~Y(YXsl6QkZIK97v< zki)8jD+4VrhR62|MUB493unDPT(s~&R{0#4B91?~5H7iZ_iYdO+I}}!dO+gsj%JL0 zdQ->Ve5Vg1|DfG?abI^M&$;6-FH>b(#M)2Z$%lQ=m)m=8iUeQFN%J^&b7<@9*cHan z7w^s>5d}}I8eolEZ$#!MlG2p&?~EB6^w5=aC;4vF_}@rIj7oHT{=$yv+|j-=RsK!8 zCosrcOz>zROZvY0$>W#_rOqYJn}>v!+w9{3%HHuPmwe4w#c;H zN^7(9`Ukxnp5I-pq0)pLx4m%3-ntmcz5~A;yxOmJ*SloaUz@LVH^=_#!^|(SAN57g z(rOQkndw^wA-D8|Qb+a%tpsK`CFDDu?Y@c`@XUEB=bcE(TC4Ya`B47l2rs2h*f0Jf zQxmEDZMdQLTbFCLX8MEq^6OcRI#RPerh&pI#-jC#p7IPL@5#4#24Zr5Gz@^!t~OoJ zKiunVDx4li)M&gy%OA1ei+>`BHfe$$2-;CsJ+$8u>RMR=nj$+1W)=S@}md+g!Zj{M!%Q^#j}zLcM|jD3~Ap%NGD zXU3Pc_`JrU=%GnYHNli>9?-A%r-f2!za#65G+=J_?z)jY0_J`$x?=^rz5B&SMe_CE zu%N1*rqy7@xL?J;KnStqs*JgEj-?jw7LoW8#Ni+Gb9U4{>oUOTwYge_R-pwJhJyy( z_+e3Zf7gA_55kAqh3BtkPKZ4hvy`y|L*d6Dm1 z7(3pHkghrRIzPn+*_4& znVtP|;=HLO#CwgLXVK?}@4CRolBM&n1<`CRo=TAA*+mIg)`$ zbv){vqH0Y|<*K=aa}~?8<(=k>iJw&+XSeBBh$L6lBX9d z-0aJbe;;L*dQ#HLTpz{NmnoGNO;3F4KFR1!%QhdL2cvWz?z>rHkiNE2XRdwLP`kMZ z>4F^(d{a%ow4C{dWJe_=&8k zI_C`a1{XEI$%S8oOi?F^uuVbm;Hd^xrQYfQ*39G$F zMD||cJDaU(%&wi&hgxl4qUlhG{Z{96eZh0^`LM%PKbn)O*FJ3IH72rTCK4VL+8;b6tX&`%cOmM$#0^l zesnEI(vJLSzo77wi^w1UpecuqdiTHVKPYJzKdj8ngXwF`V;e8pC!}+;&kK6&xdoU{ zU^dR=TY<;D#k2B0=IVQP9@m2%**#EI$9$dCoVPJw;m4`_bFVyyek!M+l9JzlH0NN| z>$MNo9g;V`^VD0nU5PCbx&NxX%(d{`ZR<&k#G+-=_TR_y07)MiWj`02i*J~_psgS! zBk19*_H&-IJLP8f`O%Pu2MXCkuvjn~HB$Y+cdN_#Cok>Kcv(LHgk`trxXrf|Qgl|W zVJ*qWM3NXpb5O;*J$R4LkDo8NJD3q1EEWA72o~hIc-GUAE|H z$rMeLfjtpit3QLM%;h8w*hBzUr-$SN6uEcrpM`lRrgtl!Y?66q*%KW5J!hsm;P;`A zljXUxIvn zwpH!(n%b|4u8g!bHg1TZO_VRS7XX(7HzrEQeLsAD5fN19ZhGjuIQh`V-DS6dXV^pc zPgc;q{Uktsvd{j#y#K-gpJNfB%N#f7E(~en4m2-FDe1#re;-XRUq=*xpLNSv^aU+=%?U$UgA#%${Y` z^gcl~j#VudQ|#!O8rV4SO>(NO`ukVhaA4`VGCo_Ez1G6Jyh0b%es!Gv+fIdv zSz_OnD$W)WmGA9%64*V{>OMMYer%S~<4jpgQimBibXwRRG^M<-H#4oK{cZ5h`+dco zL#iam=-<<0T{zJCUA1g;cggY*J+-PBJWqoVuN!>nGAKkrML}A}`9hVitHg~^xx2Jwb zPen*PQOA(s;Lv|iL>Bo(@M3=dXK1GNA$W`E#>KzC(rNr3 zOb-UaYmN){d3RTV@rA|^V(OAt#N&;OlL!}T@xYg+%C4i6-E8-5?=p3pcK=Q#kn3$+ zA`^|?DO~uS*J>L%`|@4|B41oPV`)kE*WG1&%RX~d%o4aNcSbvxyfqhln>^J~_ECiX zXZ0S*;P?#zvD?Qd>JqggRPOzpaQ(|l&uG>72l>kX>c}qtVI-%cwjFt|I~T85rb_pS z-aS#xu>nIuRkO?G^m4VN68vP%qkh!9GMjU`o;P^<@3N=WBIaqADf7y?-gN!*xYF19 z&Bn5T9oT4LanJ4}88>W$r|a~pC_Q<6ae}Eu2?N=4_f<=@tCs<3(W%vOrLCr;d|DU9 zjws6N5BI#R%&@4B|J#@Gs%CfZEe`^{d&wt646iUZ{%V_)e0@VhM&769v)=?qM|DXN zWUa!jh*zw{QYkrOg@4dhAIZO$KD8`b@Ook=;uY!hws)V7MJK%wdb(AxQC2Nr@5O(R zH)>1L?tjljLZX7>6XHSwA~*jP9T+Zx-Jx!*zWI+`yS95I1}3D$gls29284x(Y`2R( z93AHo6A%=#eNRXdEhvQIU@NkHFD*EMs*W)>F&5eG7(xr9Ca7aD7_7*4TUtUqDJ0G= zIx;3YDkLgF-ArV=J?(HpNZj^4cAk4ef}(>%w!4Hxg@GU6X^b&5v$p=R1?uzxQgJ4ixAR9sY8LR?H-N>V~vPFr3MiIm%>uA!ujGupWWYh+?#VdG(M zVdZ9RV&WJ`bo1VK;NSr>LTF@&&tVVW1N%2W1STmZB?o%0F|I_=LoyWgTk675l-vtz&z36*me2`U6*#EN|yMZyA% z`UN!G&W;3x+;I%i`FSP`j1bO6aUo;{XW1SFEju7L9}W=4vJmFDz`~qS49%QVlPMUE zWjGz|fI^Scj8T9E#GJ#`O9ey~Y*r$N1usJO5s*+ZdA)`%&ve2v{77&>=;=px;j3kO zIMN_W6~C?-cnx=A%oz^>Vz5=fD@hYa2GT{)n?D#@%7C1F_>p3kJjx86Dn$uppurrM zo_;nP23WUnBp7}XypM!hCO}9Ej|8g%?74V;LtQgAi{FY0)@dwa!9ba_VFVq>14c8i zMUr3}wKx(D3eB$$$2w2ZrDirarxY+@B9IBVK2$%8uO>$c4Rr)EKnGo_2o?`+074y< zz}(_~EZ!Wj53_hs%_hGn7+#iXZ-u5)Vi`VmQ~4sOnlc8CY0`6La!GsjdrI0tt-(s#4`qtPLv;r9esMEaK-g zh4WHR&I>LbB5ctXtp< z(~rW$;)R(Q=K-Xc6UNz594=SXr#PPlo(K)-J~PiUTtNGe5OsvA2}Z$pP)HDU02z-L zB@&F%sSsBKOvdIw3Mz{(wpA~SZEAR#4GO*y|V+7+llF9|IUDCvVK(qMCSj8H2; z6K4v`kPw-xOS56Yb0>OJf$#}P7+$ay@cMK>3ALR-()QG4(5wX7lqktKsA7{KoyA|< zst%@wlAWLD@W7LVF--U&WCG9#7#A6u13H|LJzRkzB$No)yE!br0VHMAxE5K?B5A}D z6xaihAv}jdg3shm0L8cqXNW7Z;5p!eX<(+nk=kXzO&s8$P>V~fQ&%3FVxYyKTF&-x zm(Wa6qJ!P0hK_;8C?+~~)xk+XM`1vqNH^$wxqu1(=_> zMkuM`j^YlexDO3TWes(}R`5!JTKUD=Z+-(%IM#wwCjxW_35Dil5!9R@6d*l8)#QQ^ z)C?zoBQ(YtkTWA|z|UCncx0fs9mW0N=~VZp>J*7l)lk^N47 zWS~0&&uy{JMFjP&S#Dfl!605TX9&jzryel0;{~uphK~u@hfszO6uCVd;wrEZxWrn8 zS{4gXDWL{Y5Qkm6YZL~IOd<=xQRECL0O?B<_ff$vlK~?Fux*={eMzY#m@~u49DM$K zKIsTJNn}9Yn+OyERhzpGiJ%6QN8t=CIP-=`iDIA_%419cWXJI={7Drmd&S-rn9xOM zdjcT4qH=zc@j^80vfIzG0Z9EDhs8@9g)`lNxYr*kc7YhYKmx6yZXFH46n=4#b*@g6?w-^)??F38bN92TYZS z4@#3R#oIJzB4`V+vw*=Ea0xpBWfwpVAQ52Kl~9X#VTJ`|%oYd(oK>a|8ciqvClK=U zO%dezphnR2z$|+}-JCCQWYZV{ih3Fr&%Y@}i&4~o1`?XV5_2es0YeC!7o-wo=OnIJ zLl2xj>G9Anxo;{{^Ly~BNuvTi^B`15d=@pyxnudLcwmr;#3%)1F z(QPrFXZWC@G$8Wd=uKuyLtPXf3ASFl3s4RNjR3L%vMvVa6>`~oqdKz1l%ahnV`W6U}6bKA=ILSlLZgrsw~E!`Hi=<8iKVu@T~z| zK_kPo7+_mqwJPsNr~{BLiUW)z*%=&|`Jz7HF^gf&j+-vQhUsHn45{+#@qivXVeQRo zfhA)4pe_p&40RwRi68v;RnD3{6*}4s^64M8=?jYGy7xDZErjrlk zLbCWpdBdBbZ|M`{AVcY5V-A8GKq1cozYL9a0>`DO57|rFbR#$@nZ+Z&$`=KvLKjW% z19pq@mBqL0-~*grF(oiB9HLOU3blQ}-{0m~7Z*c4Eq^GVdBnU(@ z8^FAAAQeGi&%yc9rT*lt%+safr%I2bje+0KAv;%1^z(xQyNnkmsL-e|a3%tCVu6s@ zi{QMV*j(kYEWAKUO_2a_2t0rAfjB6EMWM_oL1wswS_T==>5VxNHjNiKrwXM^f>noO zh&f|m*W>XxaJv&#lS6{#`B<(I;B*mwaQZgSr5T$878Glr!s3zO^F^(OV3n+RX9p+9 z)(l53q%Pz6fjfk-_+20t0``8kQw4mScx|g5&_ae!^i-MZI@H4==TPR7fQ*-2xhNcz zU4{$8ZThb6nIe@2hy%uSf{~}O40I1LN5EID5%Hn~4ZsHnjoG7t9U9PJDM272K|(>u z(Br_Y2{8O9ft#$t3@5w_iVGqy$#689Mptr~zmQ97vu)JlK!M-0KiLQtONb`6>F>9W zo4nZes^TNteAZ0%)V34X1bL^Mm-vT?r7j}N36|<^pRLJ$H}eF~qY#az?@MEZ)IEpH z?l-3j737=9YB6R_e`!Tqd&Z>5KA(!}3^h7jp7~|FCM!&&wZD0a^5bx4)oTN0XY?1? z0nDV-*h|{yGa3lcEu?}%lBf_4xO0f?3@i#Tya~Yeb&&C} znVd234Gw#eh!=4M(K)|@RRgYKKnUWAkkYBTbg@tdAR~j^Is%LO0EKM~I+n;Z0n@oP zKtu@KnL{c>0&_Efzhaox6m>#IC|rdma4!^ICZXB=keyFfuIE&C#dfZ?!}k=~M6b#FXD4_dz(5~q3&Ia5ZYBay z3bL3rlk;;kEns57ezM2~ATSV|D*qrQLtBt7YB=D3C5uPbE?uoe>`C7BIYRjXafG(U zJ#OCQcBh^9f_p=@b}QVVva>qhAVB+``KqrW>8y-;Ostnkeo8ax+PlXM4f6-%$!0lO z92HtDA=sEDfwmZL#|t|+q1}MUH*JNJ3BN7|58VE%-1T~93?!m zqUJc7PBKFRLMeW(GKEA?m*^lLN6mv6jui?5hgu+knk;BFNBVmZIYZ#K9f(G1K)`Q=7DV>cnuCu7fe%REj4<|87#ckR zK8VLS2z*H&xE}yAf|@KxNs!NUocIEMb0UbX96^}P264ojF`&w^c!)E^*@^4`4`I#* zUP(ky1rT7;fo0>U>z2}`&&8?X{zUNR^B$ck{s&22!dC6p{JLjXWSsuu4M+E&YvZ5Rq@R^mh`sXWC}_dD ze@-6IkDPiRKRnZRpy~Qu%^X}<(E*da_S6?E_+{6e)g0sZ1nchSrcyJRtN3N-Oa|l< zTK1eFGyo}pAidkAqxp6N>=D zZfK|x6hHy^0R!oA8a?nh3J2znTatmALelmi6E&78WndVPIZFiO5PIrk&Kn>LcP8i< z%XjK10v1CMN{j+y=>cgnKqM*5Ft5o1Hi@%LTmgTXa~3zo?{ItQxM5po@Y=Hp3)~P45H<5s$Fog&_S$qwcfk>2hVbSL^lQ#W6QQP2iPbHthRc zp#NedlpgW|6-H$XfGxG|09FtgxEX300bUgF=?HQc(=U*|1*hbfN`V2R1wapVnVhjr z)n{UvkPBrdwhfE03F+T|Mxi)@5kDKy@QKaHB?Jp z9l4%fN>oh=I+%{0o}09b399kyOqD$0|M`QDt$EPxHj!s>Z;r_>Decl!*`cFa68Dtw zS6l^cUF;nsmqo0kR8e8#DGR4HKX+Ep-@AR-dyzSFG(h6T_qo5HXHKkW!`R%@?aY_< zGW&_c+&E@13oa>pBP8Z*H|9;w-oQ|oSL5v0A&ToWts5Tw?vMOpl2& z+=>HB*#S(nIFb$=xwP9GHJ{duoh64?Rv1@v4df429}YB5qadn!&!?%TG||JD@ygd+ z_0J8-(qPFh*Ra#5A;q>4)IIXaA*aDlf4V(QO1`#^Qj1`PVuO39n)Y9NqBS}>yPx$V z+0AP4_OmnR3wAoSKQZ-rGA|owz0q=lQXarH&JT|$_%fj|5Tw)Sh_$C-oGAbiV$bKs z;{{O2;9QjUPZE4=Kv!H>Tpc;au(VSB3OC=~`0rA!B8zfdip+M3Vj2XgfXz!+sy z73rh!+|)55h?}tlJ&-Q)v$b%Ezk!-Va0ZEH^&aX630nsQa&G{Y5p?-ClO-CKiGpUb z2#8mizMCBe%3_S@5bm$Y;VK8_^B@lL!u#7S{{Q@WU>Qeom|X_}WbJV(z(!ty zJnlV^90^`TWMTmzNYK$RQ^e6{j)ufuUknobDE36FlKE^+`EOJ$X5BJk>n)GH;+af~ zV0+(&V#(e+efG%DGlX^7{v$q;SW3<;CsoIs4$hl}C!_=d0Vl|;&3CXMR7iV0(4f&Y zYi90c?Nzn6{?w-uM$b-LMMS$FGQOD8Pm z-QuBN_BPeMC0&&XE&4|ZhFN?R1|W?pL5PtF@O)7lRvLMu4&mX=|iorkuK=n+XcDrcKh5i=TdYpB5BUG>z`W2uwmr z$d3^_;9!^-_ol*)v&x|z#^JdaKX+_P+w!|{D8{tK-JRo;^Z8ik`2eGL0+%%Ap4jcl zxuM`6el2|R_OR?;czgM1&j#C!^@T{nJgX^UV(_B*Xsjc@;()qb&J2KSKrH2$N770446Lb$^E{!^Z^4AsDbMoVjA_#^GDh+k8seIly4jU2cYy-R^0V(MO zf*+Ol0FzkTG*tkX0LrF|0s=GC3x|AM#sE%pu%p@uFrzSGD-27Jv7k0%E{z(XweYd$ zMXezG2Em=eriIG_i6(#mfc2|2V=>KGh-G_fEdvV7^GO7p$FoQXeq0bBVGPXe zkW2*_sw(OYuYidG=2bV=8N{pt`5-G2b_Ph%D4ay)%+RGMa}6!HU-p=l!r@jk?W4mAU8;^P@ATZ+>d6y`1~_HtFx@{X*}}+U_N`rQMPG zF#hsZZ$wQ)(L?|N=}D)EBq}TU@3?Z*@q7pE&*cbmxt@oo>0!Tpu2M_0NS`+;_l~NT zv~zCiD5vW?9<@pYeW)Sy^;VVLcfZ-Y=Lej+q|i1zWV=7w&Hs8!#tK^Cy2!n2<86kf z`G~A?k?5sAQ{=4NIi#b4pU7TKJ67 zRufFy)dNK#*G5xJhkEYUtLz(G=!|}Eyn4a+a*M)X@B$~XN-aa5Di1MAYAc+O1z zdIMzM@-j>lxqC%yD&N%3>v`mpWEaMktMEv(l`{^VG_Cl3rClOT0tBi<40h^z6fr!g zz-v*-|DG6c&f9CJ5|Toh9pxppWGmv>^F_PJl^)QdJ=VE$EQbV7sBJYAgy#$Ma%;*M zcr?8SfLR#(CAEs}n)BM2aTmjM~76W}1#q@w|%10Q3!bp(&Xs{l-~37Fho zOQ$jHg0t;Cuc)cT;&j|ALlxnN2F9^y>7nJ?N-lc zCCFafQL^ncUXc0NUD9vcjjKMk8u7K`(UAey?hZ>Wm|HD=ea>kq%RPN0>RfJJ`&MH2 zb4cKVM9HqmN~JNO#n%sM2#lIuMyp9kcKY48GDLeza%a!e7`F_iM#BqFBZo&M8#w-Y zT{pOQ_qfIGU6vahd}s8{Ok3&I=ch?6@8n|?8R%b1d4_%ZhX+maCvNUvuPe4Lj=OB0 zA?^I@WmU<@Ejz~h#Iv-J>w(CE=T}@$fPN0|$=I`^`7hd1Ru9yb$(K;GCid>61^=3e zv`RO)#4u?`EoSa1vQ;BZ`)Ny;#nbuSJ7#*SWu4U%vW;VND!r2q2O0IcDivyOrLQs{ z_N*bxM6W_(Q`(n_RXKvZi_+JtY+6e!WfGGv#Tr(Y2_5rX_D-!A!)D z{MxLE(DvfP6y1Jye{H8MLLM2HHiqXKivhIe7q3zp06RzuOdN&igM*u{u&+S1fQ$E$ zL{>7v5d)<$ykIIwn&{^Llk?$3TtZ9Bh4CC*1#s=0$Kk+CgL+R78z>)ub=)TUeXx%4 z1WKeB0M)lMII*A-hM+lU7Ma%;I3kq4*wo_w8!ZX2A)x7FjLk%}pKGYW0^pqx zX9UF(m?`5J0)GK;NPz8jRA?51CE&{ILkq##RcQc7)+lct;A3KA6J(n=YmN{JG>I?K zKsqa8y$N9`^ENhd(=10DWIv^I===2Su+ImRh^jS#GTqvk^T(F5hz6MpA>s$e1H-PL z4r-QMIN){bWbMI_fV@`P3tCdr3FASB&gg^_5%?SaHt#!iJR;taGf7szRF7Z1tQ4I2 zsy1cz;70y8nVsII(s4v>CN!Bgr}%;^btpTiVE_J&`a#F=hRo4Foo<+_;#-G(hP}-= z_cxk)bZ@Po`0S&0ksiKS(zI=fbIhv$c&s6lTradJkErPVGIdz0)F@dw;LMDP2JW z*{s>PO2#7YVXgROqPzOqdW+|EV{tlMAAm+`*HKsUuUSyryxm}2H|4-93HOgaET#xZ z%8sQM#6B-NK{`o-*?MT;d(u*L&JAv*FHOik=?FXU#?ViKlXXq)qqDk z^2d9xsWjg3<>iImt>EXQ1l(w>yDH1~hBp^IHWFetqa+#3nBlR0I6oLrxHsBs>1)Sh$lHe=t5(I>%OV{d}{C!JDKynu zcK%c6kh;w}INU##+@5Z*{THR|muH&CyTEz-veH{G*%*zbnyVR|6N&JW#NeP@)K!(S ztQJ>gi=uw5=XkYj&G1_aQmlxlO)P(5uN!U)0JD(6#FJQb+@O|TzRhc{3 zeaTX`r^a!=xNiRk!aYEg{^;~K*)zRsSE6+4c0kR?8^7<@?mpZLX3l}}lTSGhj?V(`$qa~g zI&$47b$T$BX-@K^556isDPiH&zAdbqGkvO?Gi+IWyx@6Gn%7E0ItpWij^lsyS%TUe zE%c(mD^=OE`>DVT<6wuhV_;Hk=XOvWtH2>P#S04V$bJ-y!o=$c;y@3>E0ErFY@&N0 zRs^K-yeuM*u4Kjm+V+L3F0tM{lUrBB^atsP3iTykkjFsNpbG>AjzDf*xv-NtXJE6g z0$dIopn0I=>g>n|>fK{ER6+HZr94&u{3>5)G4QN<;X#iYCnjmzp+&B-VWFT0nHbYp z6@H@3=+7ssCOC14dRbn(FX+xE{TnXa`??p|xc)Tr09Re+DJ|>ur9i3b2gUP+xgg3c zEL+A4&N|YlEBHIP6O;`7O`o}nKgq6PNC~DM%{W%!esJe!qRoDv95Wj#FR2Zp+vy*xbs zL3#2&8TbHuQ4faaRBW_*;3d<77fjwAYyl?A0~;`moH(1sH$-c)<+wL9y%E4u+ zT`(jEJZAuam8%yH%6b1)`bUYiKPVnjEarh%>#uzzeeBeFzv6@?Ta76mco*G(>G6|y zK`b_b3_N@Kic$3w+`Gs(%tmkZ-MZ;ZI+w@vaKYa=T#c3oB3OIWHxM~=B!QBe4ycvF z$y`G|P;oS?W%^(N!bVUWKoo!~cEbwDOemqHbVUarKVC8$hy`nd12ftNbWpf{)Bu8c zuox-_{WY~9Rsm5FNL{#!p#IOVThzx#0o^jWC{0k>rTByX5;18g-{V^@TCe||fFwY< zO#nP>Ht4%xqN)CRZwYEXC{T>u+?`AS3!&H2e})0&N^OKirg}6s^Qt{H{%djY0qqry z0Ds1S!VBnZ0Ubm9pfw0o@IcoQB^{g<02qvesyqsM460;Qn02SS*Y36L`RV%aye0(> zANs@+u?YC{o||w-milwA7R~5BtnJFwJ0)pu^k|mqPnFyl1Bs(Qy4#8VV7`2l9rPg}#Y{;g;0bh#apj zhU*2hHhHCjYDkiCZ>x84OQDy&Db^hqJw5N`D9?!+=`2p{K2?DhTA&m%-U>e zgO%5m0o^2_Y5eN)tpJ*dcY)@MDtYr|4WQgs!M@EIQe?x|7eT8{M?WT)7SD{-vvU;W zh0>|GeylUEh$F~^C^Qq)5Hbiy$1XY!y~Ew0we_lTjEy;w?CR7l^OW?(1IYp#0wwa_ z>~<-2sQb77zBhkCblxRM*+W|$65riMl%>>0&MzvqqTWrYjqm*~dP z@kXeFOaz^2Iv{!nRTMljk%I$9bs5-j5=i1tr5-($T0tRvYrH5|#<5`b@msgu5gQ|Z z2kRv|6VydEwM`ONlgS00Ej-GY3!GsFk^=(Rp@ZvSPeE@7C}gAKK^udthu7n$+CyZn z@2>fp9@3{Ps@W$5^{+(kQkv#1(5%Va_$O*Qck3?>M0`&rZ7=b?XnI9`{N}k*lerj! zt&d%*vaheisc&=i3w|Q2!)6>2D4h-Y9<60-E}L%ZFCX=mv2gRT`UhGa+Dcqb`l=Pr z$(`%<%|7F_cjz-g60JUFmg$YyXOhaOGAG9lw;jC!21Xg=o|s)G!ls6jGGhz8!b%S0 z3bpX3xZBeDA4qDCUshs^cp;gUe_WmS3M9&X(SH-8|D!wSUg}=CE?(~X zT7z@0Ysd%k4%6*Wim+-YX)xLAP?tF_z4PjDE9FYNeNK3|zmREZ*CR=%cGWLnF6a%IlsPZwRy^ESraauUKj|D7J{3MOKkNV11t-U5>5W zxIYlM|6EsmUW~r#UBXXL@$?Q6-RzHXI269Q9lX2hF?0Ax+SlXI$DcVu6=j`zB=VasXQ;9|5k=R25(ob!ueMv52J-Q?!VUI?WjEHymEoRBz~cTYpHg~TISUQKL8R7zkC+x zrJ$B$0vNzQrg`+hcFrrkh|q$v7l$)>4yFx0sObOgtjxHol?|1On*k8Rk^3Z7t3;w- zsHE|gm_=j^jr6}#mcv5KN4%hu{=c#o?N%q@Xg&ln`%3&WZn+J)`CBV)7YO4|=@bmG z@8)i!IbAXYS4!KbGvR`QD{CgHzi{4bWR-!_T^>I%0{w%3>E7)w$)ki zz2ae3X5nA^k{_j<$h>>aG5&4|A!BO4|C93}Q;ya4$ZJdU;_CtYntMMxuO^<}FLKP= zKBxU`#xC&ADpt>~QFp0e5w~0Ey0^{IXW)n_ZM0dY=Wn?x(C+S=N2`Ja8NI*Gu{vXL zUo_X%mo{z*&bYf1^Y)S-HRZzwtsnTL)!6wg=$;!`XcJ!kAn%Mdy(PkE%qa3e7IM7UC27Ktgom*`|C_i zk#4g&EpN~_{&f^pLwxku&z9RcPHH#G+_GyKWtS@sdwrRIe*1-=VcFfjx&Gme2CnA< zqI9xUb9YByQ_Z<+LyI^hU+3kHi!`T=2^7!W2c4{jr=127z6_yI zuv{r1n|zs#VZg&kgnD#WhJWQx&xnP->1jmA-1NuoU+*X#20z!)2 zOD(W2e?D8uHUSvWMN1*h{|tb}WvF-X87{hO>A+_}&lDsZm^mCa1;`}abfp;27|cLK z!e;^C5et2~(#t?skb&bYFkcgMz_>VZ&U%Kby98_t_o@eML`Y#_GAEPI9 zEjm>(1M7c;s(N*6?B%;sZw&=~FYT*2@<^^q`E}-0yj|&APwd0xYw5dndP#nU@8&NC z*LG!y2KFCl`7rAEfM4=A-|?BFOa^eeDi6=-h+6MOHkjusv&-EL6t*dyWL;#*d7793 zG>Qa*wEa;#^yl-!$}f%u{k#9#A`XZ}i|p+k zl50%HEEm8VMA1_b&%h25lrS2e1b}SBaexP`r8|3hBP?Hj0G(h046HY`qsdGY*p{B$ z_w5qJ%~J_GLO_O`xP$m>^)TOscpx8tWq`KEPB_C^$6xiGg2b?3&oxu6#sIY|Yt8O> z0Gtbrg%z0K;OD&31ZVQAl(+YUMO|01FOEW9X8Lz=vmDGnc9`lTRQq2kp83%m?MHuk z{Y>KZ^mmx%tQkyLqlam?Md%cMbhKUM=S+OR;^Nq8{M?b01Xi?!O$_irKxhC(0v;pi zTyl9_hbaUoE5C0bJpz#IkMcXKD1M!z13TqWDp6?UnGjI}J0m=25hPz9-LW}|Ht@AM6u5Oz|FKQAyF8;iwU(25lE#g(5XP< z!?Ren5)?L$+YE&X_y%xp4TvFCIEdE*-b`|bgP#2$USXdlejUZ05+i|UCHkfCC%6zY z{1L1ju&!d{u!Hz8VB26U2*YwERPTfb-CG1r63j^=P@tqOIBb(HrVm~gnKG}mHOY!L zr3I%)A2S=9Ukzi8N~*PMJbH>6ZQHRkJoa`C*CDUAYP}(XV&<4a0`*Xm`I*FW5i;bW zQ>}I_!x65D@Cb6?nqcFv%f<8IuH#B(!+QW=on)n_ReLD+2=Fp>L%wCVJmZbeg5w|% zI06rM8GGyqY!Sc_#)EtmPIq7`?2|z7v%tJCrU1ve$yKo3 zpY*7N-Y{{v%$ZcxNhFSkPIK~RR9c7wEVYBswi?JQ7~6~qfcR>kMy>Em&pV3>Zl?3f z(tZnt?+i62E*oT1FM7Ca)&=O$Uup@@jQ<~J2E1nyv>vto z-?sp3RT>AkV}Kzz)!IWDz&dPz&8{@-S^4>~18fyL#}j3Q^8;}0r@y>r?(PKkM8qEr zHH>>{!7{o8AqV-c1aNP-1@Z8OP`zx%h?BrHTgpE*x@5rG=~WHuP#w72mJ$b!}8ak)GB;)+oVkASNl@zlOqKw z>Q%ov4O-bh9Kv_2)=n!$yuDkgZ>Ie6MwNebfU$p0t#e?`;l0PBa&LaKu!y1l{fho& z=kJid2flCn`>^xYl$wver@l9e$NpwaybYn52g@u#_+4dO+ER&8*qPdS*3|dyCaj}c zd56STYRkgBHg_46FbD2!WC@oowbLJvdYfHbsoHqWXfY{L@;h-8YeRc^R0Uq$jpS#_0W*{;NDd&dCsdxIR8=p9e5hsn9v zEUu5;+j?c=pXl0k&+)Eb#9InQ$Nc8(O2$}|LCGUqt7csTI$ci>l`H=37i^L4>Ch1Q zA%t|yR?CE+Yl|(ki}+L!UQ`^h-0}C+MY-QDew~jf*F89QO@@1YWe&fp+RoT%tt+bY zD$##WJ00G;bBiFi)hGT-)a%km84+*4b!h9%+;FHn&@*9l^m=I3LW_!UD845M)z%a7 z$VDNx{{%(MymA`2@Gy!PFpmItX#s}suM33|$kL!h0hmu{6i*~~rTuyP&*?#xE$>&3 z@$d7vf^h%UNo)hsou?ySvO#uMC=B~IH zSAb69x#OOS7$kv1mn1i#B&%j(h#0gJJ!_I&iONW>EMp3Tgh>03&xe%%hZoW zMn?T`N&3y2Hn24)&9kciR50i^g+K3VHL`mb=Fqxn!8EHukj%7IJMVU!H|>Uag6-^+RrN*O<%hA zJBz9hoiI2x z)Q;P?=s}-2_jxvUUA4s;p)Xt8iP+EYGY_r}aivynYlG44CTr$A&d z52P-0BY{or0DvxlxI(cPxH6!Hhq=N&h%L>HLrkTGq8Kki`p^^yf3>0&yp41MZ1F!j zSjRwLjKU*pJaOQ(Lz0c8t^y<$5B?-SPfO^zhLLCClA$Ru#oy<)QjoZc!M2>|UECq} zC|6)2pTo>Q(mk_%>fw^VbLdbq{G7(WKBX?ON{zM&d=R*k zXLG~JMJn?fly#B|F^G={r$M4c;1ysZ22VokD?oRw0A4qck&_ zmb+Aq6U%`|7|L(9ma_b0(LSjEh&8nbr_CS6aaf%xUv(E-W&G_r&)rE8eSRlZd;Ohc zX$7C&wpWN+YQH#~l6NFx{La&s_`aGchH2ki=jBH!9a$;&7B}XuyhSn;m(;%j=)1#Y z5J@OoS7&kMKg1)`u}24@vngxxB3i3DRnAE}y^jeb2JE%n)_v99{rW~ZDhWGIG|y?i zqvxhBn}fZ)0Yy-&#FmadQ(&Y_uReHFL<}_i4}n&|7%RG4y~T2Ggj2>M`FKN<5p~Y} z6n1jMec`Upe_hVLZfR^5sXy00swz|aYf8miBY@tlme?HH^!j=vlOz^yKJ_Z$_Mf1E z+JFQzbWY^;TH5Z9RSDy}`i6gP|F<$||C=#CMi28qnoHv0MB)G-0Fn~_fB%7{W1lwk zVW5nu!xU8@-;G}wd{qg%;W8`ZeOF^W90jj97FV`+Nc^OjD+3aJM?&wg5cvT*4hKRs zY{@bvIH*R{@O(+vQo}5{La-Te27jT4XRj%yXeinP?(s#q7Xk085xo{Q-nyv*03ibD z0KEc`><_cT=-vlts^FGN^AaH1l~EGPUuKy6RG#fh!)A-XpiXY zdb{j;LC%n3v3!MZ9@e70W6ws_VD$%PhpiX$O~_0C=G!aACi42OkK`?zF|)S*@iqO# zbNWrch~e>$uukuO-KfYsyPen0-5B2NZ7d3SkI5EQ$Hi~?(;0p5)PeivdrY#F->-2f zt8Kn@qW}4m#8;h;{flk4Z%mRj+7?otv zhpsE--Pp74r_8UA#f^un6IF(+Jc=(_PyU4?bLtL|W$D#Pv3Gx7HY$GW`7U^;-l5*& zJU-SpdcgfW5%+;5hMTQp3RB3ro{^UAVLDenr_tI;%{$3q?4Q&b^jV;cnYFZQL@aKE zgA9g|iL(!!*n-KTa1YXlj_A7H`6o|(<1UT7TiMpSr>X@p&KRD9YozhEOmp9DUA=QL zdwlX5>r;2z&EDL>$6vo?7{y(vZn6tDr7WLTQU6uTfv(VCwvhhw2NeY(3Ja=+Ju6WPSaH)ydqa!q=~%) zK-wLU+-Ly!rh$j%ED=TRfE#uub)SihVTVVWtBzio@6eVcQE{fGO2?WJLWIO3rJND&M#2wbgixq>b*}Bcb4VF%v|)}np3FpQk<&T zWO{zX@w!JT&z@UQ6pKtFB2SbR`J9MntQ;1&*7LLRWk?&Kz^0vWk6@Ej?f-s5{H@16EC%;!fD9ZU%%B?S@-VTc~B>pqLI*?V)ION z)LSIw_PU%kl-MHms5|bjQB0hFW+1Cm>G>>}c^a zdEK9p<;(sdhTe*?5wlLcycBwEMY(L}hk)3vt#X4Lu&G#iZih&R8O`QiA_30&;w-#;&YkNB{z?n}@y3r)9c ziU%0hB8ow~$Vo3fVtD4^`bkXG+r0L7b*`nA%L{|`{x#r z`9BMFGJf)ZWd6FVp~E8iPN4*c`~zG-ZJ8%(0KF_ZX7G(9S2?W!Uu{b0Us`E&rWQS` zS?#3wqyk+3wZMm_767iO7%2U>3NVe^a$SwbKeSZqfSW!9b34W>ZKt$U{*OM!4w=nm zmmUST>1WnUyw}f;CcRjbrjNz^J@XfpDx-lZ| zZ=aq`SDd_J3T$FIHQagWC!cO|jvC7G;*zQ1Vb6?AXVhI!@RQFSA7c%hVY}>QbixWA z-&&KumN+=Zx_6xS&}?&K^(d#ENGCQ6t}FUqz^q)4t8?*kQ5z5SxjQDPK3LMJ7yjq~ z>g$RfiK+h~4#k!^Q8|f`>pjk2bZ-I6U<`ki;f>WATRYm&pRZ*H<)0t zVSm`Yx&(Z=lFNPwcsx|(zHjRe?2R>%L3?h-+#|&_djvH3C+_jneYY=YUET7o7yWq) z*B@No79ez8!!B-FAJo3GIE^*bdUcs~lXdLxokevW)4yl7&ONmLe)Lc_O(F6`i*JbQ zAX2x-J=3_3L^b#uT53z)w&;A z(cp4?_Zo%lx{NQb0STLg9n+I#G4-VdXFz*}yE5E;D*YGgR3mES z*M+o^pal+8c;MYiE^ZeF=8OxE{x4G?hXEy^7IB5d$KZ+sWR+lRc;-XdB*A`&1_=>d zwj8nV%0rASTP}`+xjNxGLD0B@xxcQC;7j>Twm9|7q=UtqNgMH*_bBb%%d66%;GabF zT}-9YIWtub?a?lc4NWR;qq5A>2cUV5GdvOZn(uGdC75E%paS=STbGF7Ea(#A0%EvKFx` zFV4CNFSE+O>3GJODFi@ljQ4&Cx#0vl?3@tvRu?p!bWHiMsgoVW*fKL-T4h-=^Sh%l z*}J|0_t`UIiYFkhOeXUrl7*zP1&5`i=LiM~caU>0Gk_cdkq>DAL3uL*re5q^APA|T zN6!TiB%34juW;lREq^Iu2S^`Ko+b~`0{*AAX7c{0p<4fsB0(f7xP? z4>a(`FfpJG2;1MLW5ipgG`Ht+stnlkL5AO;jaxx77eM1w@@3jpZ#EV*?WkVvUMp2X zy|Nj#D%*=*_tk&jjT^6x`*M$0@BT%xV{K}@em5idmLb#0r9efV+q8Sz5;MsP_Q3bt zCep8lieFn@Xcd%ti$nr$1?I$UTwhN0AIy`(m|dyfn>Ay0EEH2t(KpF#Wbi*f%fc4_I?h}{iIP|bEt*8G0ki?t>YLzoN|jNA;00OCBcT*n&(jPugaL%-AhKeS zfqcW9j6RyyvT2S{=T!*$Q0`79cT>0%;Pm|9z&~!#V2Rft{5_10Yc!g#3)xJ1Y<)G; z^E!(xw<1vMC%Fy(!P?o|nfVhJBQW=qVrn4q6v}2E_E!{6xXoOU zjO#t9pE2L*ICFtB|JPhVRLyOi>qe~zBVj)L)xRL*9anG&rY02kWsa`-4gY*A+cnZ? z-mNQh)FcVMm_&cQBxFZ83yYfI&;KrUU{WXwJJl;$wmU+^=dbZJa^^G=R4#dLG>h=? zTIBLW!!IXtELavBcuT@ihN9{!p3C7B$_CRJI<+GTkG=69GKy&h*7neEn)JiB zsB>HV;@RuxvfX5jIAG@N($DfJ!_v}8(Y*LEH6_u%V0A#ipI5^;;5BDQTpE)%yA7CD z@FrC|FQ#t5d>Uc!ufFTNNLvy!KaGrds!`j~6=h>;JZYH!#bEM3J@3pnz{CCXa8Jg( zr1=2suGGN)+MNLGq%QBQ`{CIC_H@}DnXtO6NAxI``#G+cD;G=Q%3j*Pxg*%2!wq(q zdvs%Vai-N=N36^PGvo3uoMMwIVRs|1Dus+s8n~Dm)j=U$>vKK?KSg*I< zA8sx<6yBTbu9%+Z-b#jduO@YNk@CzhhM+OvG~&5lZDf~bTeWF{({PFn(h2{bsy|16 z1+=2w^AUHG$UhfHJO)hdI(M>?DbnY)eUQkcv>LWMa5w@7{<**r=%6cR;;D4Irs<~r z4bM|f(hqmJTYYk&_4IJ+c}nKu9SYs%O9p?$|JrKBJRKrvuG`l}vdkpCp4>ez9=Gb( z%*4~gO4b70{*hf_(e^{nwkNic_EE;P1%?wNyPkej|J0d(GWL_ZqT(~=?dcnz&1*X| zEgF0f$}z1N*Dt%4_P6!mf4*_+=_^omR)Ck7S3lR$Q1k8mm;~n3?=3@63O5B+kN15Mehn z$l%LA9Jp7>n=F}cuJ|)3%pH{zUd(8RzqU-W{R|x@VEytJ$*Run9Tgh-eSYK6pntVE z+&1stZ0^?ON=Cblo&e&KwYToI^`~7=BE2;n-WT&j6`f9+&Q_=j=LYUH^}&GVO7qT( z>6ZdhOslct_2awtMtJwf*@fyY>A5tDH8Pk_x=eSS37+P>k)AG(s;ROt)UN#88p{m18dNkZ$0kPbnr+7&eK%XStDZ| zT<~)%A*5UNWuh#fZCkoy`bLqh-}>{pV>=o3zKs-$3YdhlccBjs7;hOKzDu4h7f?bX!*w=J`+rFRInZ>2zTt{?ilQDK zbtPHwbS{`$JbyLqGyRs2JT7zA$DsfgW&0Ke`>QJ^&Z59~qvu3I{fx@h*t57%Z+V|a zV#GG_Dl5SbX78F^XU7hBl+ixeRLv1nB38Xr$x5^%9s=-8P+8NjvgWhrr{7h^9u|fU zVN=h(HYX_)eJqpgJt|sVqgmm;iLzN2QRl4j%P>klJ2pH>_4!jHf)n+*jmYO2y*ziw z$GU0l^2=SLwm~TovX#Y(y7uYFp835E*ar*47kHSEl>8?l} zcl*e02?*_p9`Sl8yoeGeKj_YUWbX9nZ2tiAZrd_}-TgLUUY538*R`de3zQY#lU69k z+_xSHRCkP*OCiOhDL2>5KjT;~OA{Oz$Ezz*LKI8vm7Trkw---mt#>G6?Yc1HLhDvt zHjJHo$F@jscsd;MS4^>wnZ=`C+X?S28M&<1B*%oTq>585ZKO@Ir5=}?JViH>eGXnI z^3$fYeq#)bxGOSc-kmss`>r;aQJm-H`|wxjIrSZj8>>VIQ)hDSzq()FzT?B3VqCAYOaL%Pl9s{>8)Pf*c&*caqnbn;BzPGMqJd<}HH zZ|@W0qePVTiT#bP1F!F!#-~0jW+RI5e`}NKCR|ka9X8BYm}3=fy5?MT|9S{?H*QLu zK{#=S(14d4$Ph&(lO@~`7qY6%Ff54cgJ$@M2VDjMd5dKQMXm=6Vh9H^ga;U6THJ5vKj)}yJ@L{bRCZxW6dX>oL$*x;PD#!#P!4 z%Ge?Ofn%Xu@R(nGV6G!v`U6kkJaEfSas+Ym(qF}}w&NuKFrXaZa%SM@?7}IFodU1K zKliPytN!$*G6WV6G?oX3OnCq0egDYY$O`Aby5p}WSLS49KW2s~?TFf*m8gH`{-4@+ z77r6?vii5Z_P?AhJLg_J^>BFtSBvg?;JnKA&D&G`-dJ7NF|pkdmDe!zdhF8>>L@)U zL+t(UJItqys2Cq|YZ4w=D_an9P$wPdN2U1s;gR%4%ro&rs}Y}#P003zLLu=9rdy;| zp6#iOKPzNV{dM)T2AH`Xh5o3nR3SsW1~|FUL&P;+gw>Ur(Zrj}wU$(nO6DYCwez|` zr$SkL`-uew%Y!`Keim{kJY{2e;#7sf7rzF*3j;%D%Fmeh6nsTDLByHW zY9$JLfS0i`irS8B(2eE1F{-m_w$-3``=dix$2>4&%?w+ADJ3fl{cJj;Sgw<%T_1F& zH?^^XHdq}JB1fd81}`PNx)xZhXcJI#TXCz=Z9FZ@Ik&U;=ykRi}VR}7n9C9zuB<)1ziP(NR;`Fa_ zbqLc0qcm`>SuN&}K*hM%w@o{IN(k1`Xk+t&2dp3KNk;jKt)a(hT8CUW&o^FKJgWkr1rziQOIFBzA5 zG5%rxd-_0+ed}k^aJXh(dW`VsMiYlWN0fOM^`U1EDMxI1(&UMj+UogTlV^s(pJskp ze~{<=)k10wVU4<230HPR9KKdy`|ndOa;R*rA@A8NraNOkjxB#rgK{LOT&-+1E_L~d zq_PQC%&)|LzkhjG?S6@2Y&z)b&R&jY z#s9cz9{h9x*H|n@8Ab=><}$=)4tx1m<>|WZs0StYGpP}bh`)_7UlowE2OZ4>-np(e zWhojA|2@ARGnZ53+m7?h4A(g4{yNPcs6Rh{jy(^NUb3AoKgeR~1L^gc)~!t|GHgTy zJS|0y`zJ;qm+kYEEw{ig2o=dkSZi0HdQB~C_|ED}!69g({FO{J57{OA(OP<9)SKD- zV$?nYpE{dC-=+Vz5t=S-`Au477`Nx%K9;-NxY;M12&?>yfy)Si{@$u`_nKAD4~d;( z+KKohn)mxs6;zTb&Fi1qrf)}SSDL+;vf`R=n8GOt}V$ZZ8ga{p{Nf z4f9}Ej@)dz?fiE1!gj_ERikF|(+Y>r$`zc^pE`XYh!{Pc;;1Np+`sgbGnzHC|4+y3 zWO#@Rhhi(kBE>Qf$JYgb`0L5>j_g=oLYo$zfN<1nAilO-3byn>d)_(02B)iPow z{`AVZNJ}df^?LQbywFuSfO0?CHQ*74ID?PFXDGEG}u)JJ^egp6r+3)(fQg>)Qpj}X*@zWnGWz20y}_cX^} z6#{dQU_RtsN<@J6z|y zvX{~*vK8JWO9c=4FqeRuoS3EL{D)izt3bHN8O8l~r1LJc80puI{k`huvag++ZtA>w z_1$VtMA#Omm%wPr4o;|PRc_cl`5)5pviXF0P#*ly4Np05QmE7i>p0c6=0Yh0ob@Yw zXLi-WZ_`s{tJAXSNM?*i=o-K7`XP@;hgtjZ=gRU7i$h_-wo7|QdlXZAmklts66F2x zQYVFl0X;NyMzp&k4pW2$3<^iq2SD_2t`|Y8-Hc7_%SlyGwkp4^U(i5#kqcODywyMf z?$3IE^fJtqz6^gkxa4aZmeK8}6;fHXYpSNK*s^!FXaybCoxX19Vow#D?6iwz%m0H{ zVwS5x+BVN>wU5zh%5y0iij^IFm1mhzOd0-NhCZ}ey_q6C22l3-gLgy3=Qf^7ULs2= z^F2x$yk^cDZjS=UZ^0mmsA(NuiC>isw_Jvu;zrd;M-|LwI79t=|1my2J~Z3 zi+zxFf14}_G3)qOWf1HEn*%(r^I>_bZ`p}Q6t+3+CoG?NrO8k4&JP>zDYw$} zwoJAMrZ;N)YfvuAslO_(zIKd>TJutCN-9GuV7R-vw$ScV>aOGWB z(b?rM`^q!Q+|>22S7jwtvj3^mW3`9suZ-`^>1qDS{HjBG&ggP(v$~$W`vJ}{k9L1B z%SPn#oXWaY;z_n}-n__r@`ya|ylS@UW)jeAsHi=T=xE-2VDC3ZMDeiY;RYm3b(3EY zKDlyowkj*aQUiH7b8l$^t}7odRP7R=D$_6ihaAaLZgBg!7w*?%_^Y=QN8Md%4Y?0B z{O);(qN~*Hzi)PFIp}J?o$%*X-;JBqx=Y4Qp9Go>-&HPkT=#$jt9Gz*VPtudzyyS` z<0%pM$GsM-dg{(D`^fSc#Dpq-sbnS0TvwV-1ta9+{iXdik1ckLupH}rZQeN!ta2-e zhRZQ~>FxekMn5_8L9-TZN#}2pCzY`EAw#k^VqS5Nh76(}yt5p*SG|t%2`=f3i}Sl` zJJYV~kOohQTJTBDMNJ28T7%i)M_;PHf5CJqlWt~@MOn4r53=?`1j|YpLz`&dUg5rM z`aVmwfqb>{SS}Y$p}e2spnGWQ3~}jY3Gj^ZPsX-@%ccO+Kt^}v1BMMnx<)8?=0F_L z<9vs>t1jBg3D1V)?-Q%5wx~sVyw;~#rU%BTwuDPqe8$aVa=^iWnN3w zwZ3~FPL~PZ9Q{Z~2Bw48U&r-^*SxZ}zDb`m-2xMzTHmPq;YFzXe;gHV3A|fY^>-Dh z(kQfxx%2`U(Be&$@!Vk0fS5He3}iKTi+Qa!xjq|ensoK$$-e}4W87C|=jT#|-@E7i4xs3yBKFzM@I6yg;Pt%3H9$-*&z*$P(?mK8svhsFaE*>jFTc|VW=*taFn zCw?uEu#GxBYmWmj4G|^4VGt!BQ#52ZbK}{v*6Zg3T`A&vINUI+slhKxWnA4Xc7-tV zwsf0m%OI;=(i$svxm#@X?K#6S328^054r7cGD*T0)w2w}p7B(Fb0Emu>eL&{bCe?}&F~AN@f?Tqm?}4(cPmYBEfwjGmzqWtwzX z?Kb2wd{0jJEX!^3TaC4PI@c~;)4kHwqwl7(?PJ%0kKZHKht#|-d0nkXbE7GpW+H_U z>2uE$@@q0k(94|bXob0ON)!$~*$|78fhK0O8y>mewAu1nDGkH2CH5`_i9DaH;;-}z z={A8Y<3?PQMm-?L&lb;~fD~HrNa{T5m%5q@COxVU72}#%HZ2L@HHq%b7|89CB#TB* zaSdtM1sn}R_er+xZahStV^jl~SFhO825Q=5Z3;Dx`<;UDi7VDoAa1!=$be+HK!DwJ ze92(QJ+y>BEX>C!@f*QLHv=7P29_t#U2~07XJRW1M0vmzoDQebEEJ|l5j$87%!67V zliKl-!Pi}#kD&(Apxbqe?3C)8R5`D4ragsotJ>FCEsb5S;1>}*B3UPLb=&sVQ(m

}(V>Zu~RI$d=KC{A6}rLJVOI|&f0Ri5U>b?Y>%F(@mvIMDZVs5sHC-3f{X z5UEkZtPBMRS{k-gIDVYu%SRc0Vfn`dbWE|Ap$4+*w%+Ed3lNWo+So}jiMQLdqyO!A zPyqKAcO_SHt98Xgdi2ONTW+k4r!H{wRcFg(M#!nCw^9i3?EC>b&AT~?-7a0gbu4nF zyzir}b0nF0lub%L@d&j z!+jKl8?NX)iykLk!h6Qh{OWdI{&v+i2t`=^O9=yKALt(7X2vZEJVP1czH3%C_cw9e;ps<&xtg@1}u7_T*;cf zU0PtL+k!vFahPg}=DAp^=nY(%Dt)F&Hy`q~r<_!fHLEsMGAADHqObhtt}y6)C8j`t zR%cKY9kt?kXpvObsy>MBfs8G(_E5CfG<@>|sX}Hu4pELU7idYI^%3{2IXEX?zmT?O zila48WKcEWrL~{)x5h(wK3csG;-3|46$skDIoin;fcMDDV7Wt*l#(zMcLbs#AdWup zq%b3HimiC^;C$X(P(QlC`REeQ#fP3MODIRvk4FS_(l(iX!o0fwkLcYP{Yc4hTZ0)^ zYv;y_!cQJ8)Dg|HjoIRq{xRPq0kRC5uz78-DQnogtc9`yl^TITvG_lPntlnfsI-~p zGyrh>`hI1HjH{K(CL=5v_0a`iff;C1!-zyZ1vRQcyOyfI{1^l!B(vat4&5-HFpmzZ}3~hAKjnCy=0gD$FO4u$Bi_r+vl^5+xvGZmq>7EjUHq-`~+YW4y%nT$!Fzd!EWMl)95+1{~F zcN~II%Ydn$fmB>8NYgzH*RUt8slHMWp3t+zJV-xn+mX=@b{+fsye6z%gIRqyN?=rN zRmnAmsm~kmB6{J;j(b9yrW+53Sq14f#r!WV)Z?T?olCkHjX(y!J0M86mE4L`u9M4l zk5_d}*P1QsD-uYlUV|h>tl9}|o2SxAu!#MK*buBR#ihA+9Z{4(SqhVm^;ZL z_mVhr^e>V6p3Hv(wk1cnO;z|Arpj2m;a_LV@z5%lyp%sxXjWEU)4{Qq#dvtabP+xC zPF7O+ihvQq3SG#HZg<09A}oK0N6c_?p*o&X`ZUe=#6k745{RsU83A;;KmjO9A^>mg z+MgF=j}bWa5EJ^507JrGVYq!XSvCB+_xLp|=NyP@Z>IPeV1$&Imu&QHjQLBhK`|D# z`v$C5c>WWJHIbH+DpXo~HDj}476M~!u=t`TIj{ugrn&q5+sT-MH2C$B1Cw(fPjfum z?&m4D(W|k^Y~?hb2q{!*eOahxGFlxE)vQr9;+P<)t(H@@ZiK?MONBcj4qfv(QNC2X^?-2_8?W!$&V@U`$vebpcQF?{H9Id!#W z+!aK8@_u7kZj4io!S?cE0I;!#eBqY;fX||^>Y}HdWnZwQcv4O zsZ$jbZI~Z@G@S>z4$N-h;X1^c;bQpXG+yLRMmh0XfvdEcV#^H_u`WU!8G9M-Y`YQ_ zMn`am+`wob3g~ex?-kb^#_W*4Q{1*=S9V!rh9$K*%!9DC6UMXAw@6`AFrEhBR@Pn~ zg3cw3yG?^3XY1!w2wZhkK=$q<>OY}w+vP4>fUh})BzkPukrKKK=I90fq?#5oqFT&wR2h`v-% ztkZ6u6y`QUKKY23z{p!TxRD^Ah!4+o5H~a-XiZBl?k&PT;1Hjz8d z=jqqSmi~^5AIK?sD3y9n)<*bK2Cvm2o^;Y@+%Gpp8|Ko18uK@IGh}$oVD_QL-DN=u z*K+vD(;l)3XU4IeFBjT?=fa+>sp2LGoS@koZ)p7zc#yu&NBQ5QTVrJlPkU);4X~a} zeB(#gi*B~+22VH1%kEarXVmSpB+>QGN)=Lx^*^lcRZ9=@@F$`ugnov&F|?zE>P!BP zLk>5XB!MU1qm!n33qy@@G4kaj2`v#;3lt{|%r0RD{Ei`%_UesfyO>hJc8l&wYb?Ed z4h9l&8jP$Z=RIYsmq%JE#3hk%*wNpC^~+ex*qNS+y2?~rVZ6k1d%rK&ZXRd`+2o25 zk79D08e8rFgL&{BBt)r!H3^U&m>Sf>5EqLPZnV#M260egXX8|GdNKkL0XSwVxIlQ6 z=3Z-p9a!ge?z%F_S&;_B2PS2}Of7Ot7zKIq`tns@be-9nu8d@y3swh?OKc1EG|mjd zfD|z>&w}o6k45iLp2kg8KBS8MQ>y%U?#9w;v*oF*qhQlss|tn3lPFO>4R>epxwisQ zX=B#^p5Q4#oG{kW^Q&n}|IiYDbK{9$^_W*w25#8Q-q<=5-@JX{ri@!B_gHbB4pmy4 zGQG|?5C+W~v0~knaLg|)cvMVTj8BCB3AlhW5oW>+dzw=`g@}B{{UXA#C^svvT|BQz zZ1G1chm?3Qw07Ob`0l64G?wFWUU;;u?u9o_9PNwKZH4KJ>nXZ>ibfPrumtt z_NS5{kV|FB>RDUy>=c|vSaL>&sS0xXS<^hD0Z4R4TJQry?l$ev3R=gE2U{~Z`)cr} zQu$i2M;w^KtZC%hrFt=#FH8svxvrdp(z7f*ZN4oM7U*XS}ZS^Q7un$b*Ik$voTxGF?YSV1z z274K8H%xr5zfE=SUM6x;zjh$W!{{8nbJpyM-yN-x$^Z%0t~PMULolq>G)GH; zU`q1#hmTXIIO^k`)MyU|`F6dlQKe**y;=j<@uXdx}k98~$9DyqHM$3!P>oV9R33k>v1=2oIeh8H#a3s$*!x z1&wc%!>?$EIu6<#2Bni)Id^$Jpy zkE`*9oaTs2vXB6OQkXgD76yj@h9nNA9^GK3is7#ratH2DumR^-jhK3CbrdRiLsKi9 zrZWz$yQiM^WONv+Ks+Cmr-fdnJ5y;BBu@%%g7ll`*91sN81vQXFXd^?5!QtFWGQBm zV)Sgu#IOI5ag87A=P$KH^p89Ce_P_WuU6`wsrY;TedW$NXQR({A`~pXkMx|ZcIgoO zQt6o_9$VgzggwTGXLh-N(QEt4PfErcV_LTop`|93z~vbf+XTAnN}dg_KbY-$0=IKq!|5H&KvCn`v1|`E zn3!Rad45sFaFQ0WP(iAfy3b!$u0h+c+90M0CRmL)HEMq!g{e?k)Q;Azo>YG+1v#qR zCw8)EgwO~b(sr9wkV+%TPZ-2Q-x0JM+aht=xJH1uT^TQLt3gJ~7H)lMkBdIbc2;(B zJpq%YfD12ZcH*J!zss?<$RM`m4SLqHS>G!3Qx!NytiaS<_e3=eDx2{1Bpea7LmtJS zD*ez9+Nx!0j4*3$ zd-&Ick7`xV2kK*fhgY*-i0(z1{|UD8_0kEWq?*8ZCWX*;b8}bw@8bd!R~f`8C1N}7 z6SnI7w%~_hvWveJPqH1< zZGgZkE!IApe9V<5texcD#H?x3nqkXkdws;5XON#x2@n`Z_kR?fc_7pOAIEpN4XKg) z4nuN`=APs>Z0@5HiXpjjb(ka7a*txf9CH&zs1%hm=Nt)1?jB>tgb_16^7;3wX`h(%-^rkVFRuDj`yfK6{@I`N7Ff^C%O*uprn2snWwnNgW%E# zt6+NG{5bf&$l+YlOH{q?(*Gc3MhD$VEH#Xp-niI+4yF@OOM05x^NEo?9Zvg@O{8hi z;X&)aRY|MswhrBjFzs~<)TRy-KcfCq`-4DWor9Q2%P|mHXL4`DCJ1f?x{!UKBDo{J zCT=8hfv#ZXg9x*$V{a^-OlDe~fsfEfyvC~t+68usiqO~Z6lGUvKNGED zL1Ys+^?#R6lJrI(W+2S0fO;O3%jIdd;eaHQK!W#mq2|3a2x*oy76mdNrns_4hJ>V$ zP@D@nZRpg=c+xzGqm+%H{ZNF4-!2<)6_?+e7DO<%OydLOpzrb(@5A^(N zIHg#IL@u2@4F$QJ9cms&qYKNB#MlQn2#@t0y?n>-YQ);Jj7Erg*UqRi$0G-^CABjt zmIVjkS?UpT*|NM_&Zjb`;1t|b%!HgQJU5u9101T9e76k4#3lw z&N6mDi=F>hI1|N4ohTpR0WapLCeRK zHM5=d?A5Tc)Qfu#5Ay76b!Z7AO#J)bJQf%v@W)Xh#cF%Ju|8Y%y6gW8MGc!j+8UYw zBars0{FhhdMfNAeU*)*t^Kfo(x=S_`RnC&xE#y1)x0#(*{$|RSxcrC4m6f6+^GJx5 z_+-o9B#{g;+eBsWvX${Y!%7)oUyrJK%3$y1!P_8~K_RuWRb*mn-*)S3S zY@%pefb1!?K!O3B9P&i%cokT;g=(fF%sjHOniR)Qg}T5smCUb4^bSX6 z$Ie{3o~rWtQ6>O~<@sD)lI3&%IQhuIG1KR2X7?AjdEUSirI%W0?Wp&-ij!z#|A=zy zevu3xWZ$g~HATCBb?HGaqJSbG$-|_6+ccUu&1ij*zO%Z1W|p(d`QhQ^0LFIpF9fC> z0_XT0$B7v?T&;x@t@<{2FI4(b&Rue5-nI zB|}7{?uo~zq?Bb5EidzSKmNWdo0NCHt73>Tv2ZM+3-+)MPKUVOdy>0dA(Ei|HY}ir zWrW4AT|6B_V*p#)PB%(7(R#Z~VVMSP?2^_e>yp8$31MeT8yC}32w)Shvg~Ec5F>{i zWOLZoSaHZ?M0C>67yJYwp}tZKx*epL0lmV1^y#$hg!nXg7LiXL1T_u$A2|(&#dnk$ z#b&R>lV4J8vc{`hkqAFDhwV1)@AxD4hp#lT?}i7>f8yh*7Zzw|3Y+f8q-`g89oWNK z@Wx+JeCL~5SJA9V->r0ax+J@-|2jfQTgGMZECZq)pJjoB9-w9j6{ia!k5NNB5mZR9 zrtNpKW?J@r(C+ybjuk?Ze(umWSs|E+o^V^STgVZOaDvauUqvYBaaV0uen{LOXZ8-U zswv>NCT5%f@88ZA=Y+MoR?~2!@oC&OMY!NUJB^+8G$s4$hZvK$Qd$I?r%xqTwN5n3 zdmea`PJzUSX%r%oXopPtNyT1Y$>l9$r~bG3-)BHQ%84)cL#=Gh(e_YKg@eU`4TT+) zkNs(kDVf)6N6(9BTHw@RqEw|(Qg=Tphs5R zc+layOOQFsXhSOZJ(lj%Mlq&miMSIcUMF=h=;^SXk`52a$h=dZFcoPD`KLH3xcD=x zhYk{d>Q(0@4W5o&i+pJGb%yEb39j4W$*ft<542qY@I9_m9|fSy>+FwM*s8DNSH%O| zZfyqeW4ZVMy=AhH9eiyqSwuMzCblS0<5M~q#xZT?*f5Ar`gq^C>O@M9EQ&<{gYGvG z(Va*Ns;opgHDZrRpwzp>!Dx(~Rz^390^J3Fh`24$+{AJ&z5@+8Wn!U&Jmv1RBmy~J zTpa6td%HBlA0io>m}wEMQ*q4!%QF;>TqL2YI#;s6Vx35_9fbHib~gd}sk($EuhDfJ zybd(4sG1ZeNcf8{^oMw3=SR~YQUfK39u@8o`&cSA%pVUKlVaKSgbw#p)l;WoG;mUyeJ^{a6}PeoGiRXTr3)*>IiRFq!jwY zT>l3#REm&PT<E%cWd@2zzruFgGwsWD&Ng4@2kY(6&AJ;Q@L*Nx9cusrEw z@9&kzuI8_F8gxugT1H)2n$`FFgL7wKJ(5#fkD}a(TuU*%gUBQSIf)*m;{(0d$ik*a zZD8nGWZRU;w7~tBfLM1DEm7DMOykttWBBg>L(VP%;FaFbm4uk`l@xH*SeE3QgJ~)H zC4m;L$0>!lOhjfW!O6eyd(q+S|*4v<`0Yb2MK|&0~R?l92 z5=@;y!`4pB;W~hzNU?RJG;qjr63D^qd5w$*-u3@-B2*P+f!?&pod7^-BO~yi9TiYK zImF^}2L)$-$^z9U8aS4^-A+fAktED?MWjmO8xO zvhQ;I^!~4%`l0nhhnvc&`G=v~gC|-Akzk>j*{VX0herTf?!}7c?I^Bx@07lDPiM;= zf$=}a9g_@sBbCu7lKpKntv1KQ&qS;DzEAJYKXn3p3q0O6~#UN)kk0!gG6Rn%}h@NpN4Et>o$G-s&s3DFg!)$gNBw}V`EFc> zmpLs|rAw{nu}P(}pu`A1EQH171rWpo7Y;Cj=CTXlkd81`VHsSaWXPFt zEVIbn9wNq|Y>mLd7M@2(*N-kGHUhB(0H&m$+w{H}EJqtCfGyew;ot2cb^*>zvgr3v zV<2q&P1LQ!Y&DUi2O(1PgvYU_=+Z23tKg9u;!*6B2U<@^wT2EIgCxz{8(yZdiZKcW z)7aaAnAcvdb*BQ3U2d<0>+FK*?tAnOlkBz1MrQ}pq;X#urbZneU)X%!aG}nm8x!9<{U|PjQN^O5PRW(5AjU9<(VwqG2M%pLPtbtNN zs|jp8tURIEF6q09!@=1%{S6e4cxPM>#~uQ%IG7%7m>IdN+nm`gNq>{pL;{Tj+cL3C zyBQ#}VOquFd(l31%A`Cn2>6Mk*~8P%XZuV(WEwMV*fLP+b{&JP(O|guuvtHaD;T7? zf&j3o@3wFQ{{}=4ayq*XO;&-2T9e}*%w@-1jz`RxO;g?n6)N&;>t2penHiK8?$tV# z-9fnPx{HQNV3;6ak@f@ zl=`6Cf#zay>9>JcE)|)_v61Qy`H{mWRJ*4wbTw(_;OVNWe?zNuNxwKN6%8m5BZfNM z%=@8+;&~A(f;D}?y;Bn@Oypw}A84+&yFa;GTJRHlpG4T9cL_kGH`4sK#Zmr%DY0GF zBQd^Q4E2pD$Ng3^?xJLI3Jh|~;-$ne?{=b`n4Q-gzSIMo+nEao`(2KGEkbVEw zssu}mHpyPr7bC8ml4?EQ*r3H*r#t&K>Nw|{{)5Jy%8VbzLqgMaIx73;9Y-5kCf2WOhSW~Y^I55| zIb&!?b-5UV*RwNpff@X4aU&D!nH1L6#h&7L8!Hx$Z}m>63Q2e( zJ;26m#F#CA5TZ;-S)foR6L^8tuj#Zrg&Gy-4iViPX;+k@dWzXYbVaVlM%gyCDxe{A zbK7rpR_IFRw#2hRpOC+>;P-`2mLIVk?vGOvnKKouLVi0gv)1%ze~g?FVyZSTg5@)_ zMFAPfIu=F%ovKpE*qeeCl8`yNZsc;AYhErygSc@;N?6hSi*08Z%y!!NcdWx*8n3zq zoB3S)_CiJ4oEgE%64{+fNl?e~KX$Nc+CDSO+l*<-NJB1Au}&Md_UZ(*O1r61@oLKmBveub4Pj%tW99GJ;s#?nI!j6_Erg7F?8(UCb3&>5R z>=f&fSFU5lVmh^%;cZ z6*cVRo6^)hx;w7HDBs|WM|Z+GP}`+M@tW`h{aA<%Vy#Q`sMx=Z-X7u!@>;VccgOy4n{! z{>nPm#d4Qbyz=1aKHjTsn1h^|Nyv3ge;()^sHTQxI?FZ_Xba$v1M&nwPm)$sDL%!63R4&6o}WV5 z1w>^52a1c%sPFdYMx)}tHKkkF4f8C;hJo)5RU5VkT>DOswu2XP$#42hF>bVB0mHAH zhD{wLw~A2fUB~UJD8lAS20!=NZKSB9_-$)Yr-31~VAY!9fo`m0+tOI*AA7id5)GT! zY)JM}>qu;%ZyiH!j^`SrN{KEh(8`V|fJAqobRFPinr9Sd|FSgg2s@J>f~}nXq+y5L z*Ti<;d<2Fp(j11Kj(@?rTsB8?>4H5nQ#Qa7+5ZQrvrf~r1`Qw5=QjoI{$1ST4p`UW z_xOQZCU)XVI>YZx;D$@-C!dZ9^jVbkyT*QSxkeH7Za8Za%08C`LyBuMaXC>ZdAm=~ zr0F?CiCr7C=f9#9o~Ab{v%6De$>KFamK5H=A}!V}3!L&R5xBzc8heORzq@|MULsA) zlQ+61P(PzvK@AO!Eg< zJ5cbSdozYcXWFJPy#@hIEt|&Eq0~yoW^toy0|kRYV9Uh>b%1uVqI>pQ8T>9}v>}Yh z&D)f+ootcoc`$xyxDH(afW#04n1@nNhY(MLUU>X;c0tPJycbl@5%`mEtO9zLeA*X` zmWSPKn&kn!bebe)xnccar+jIF6cUa-Dy%O!iSjbKsc7}+}g=vRkImm-YN znzD6qSnjXIAa*Vc5Icg4FzS)J{chqau z567_^D7Mz7KH|a@ev5fo7c1u+$>~qe$as5D^0It-#X5>N3GROK@r5VxyU86J?xr;X z^7TXcp2_`l>@wO2b1{U=k$J)SP{Qnm;n0C6PY-dDND z{KGfzo}A-`32i%V*Wf&4=SNE&mwQXTcn=q$7DIailFd{H2EsRq`Hh9w39?=Vzo_}~ zN}1DTr#j#t^qqnh=&3J8SaS=~3Y>4h(Ec(UJ3v}GRQB%F2v1{`XWcmyO0haQhNkUS zBo111=bOqV+P7D+r-(e`(Q%DJat!(l+>tHZo|4{@N0c{n$zBscK4@F!L9_PuM(|io z)pk7y3{NJQx>`2{SFr5X9fJ+&RCpI3MJ(|XYVXgIy)Xy|a*E>>nbkT8uN@@9GoDc( zQmk6qek%7B&0eOXOV7Xh%_ZR5*N+`x=@F)FSF*e>Y%0Ih;|_V40;bs5;A7&Z(vR#+ zY&f@c?K!q9^(S^{1Fh>8oLh?PPJfqoDq_~jY*z1E9sLhPFMh`zoY|ka-m+(+8pp-r zzsktw|14mp{5U&yJYg{k>ks=9WG}?;bl!}6WQ?b$Kbpp!-$vJWLKZa6i{!rW3dIVB zp@higjMfdjJ_8Zr58J)TObK@yUAo99=sV@*53`@DVo4O6aB{m&7MAOQkxm|G%PeVeX-TH%b7ul$9He7+I6Tz5OH@=t_c>2mD_AhgTbrK^_I&}#k zPQ&&m!)88Z&J{iwQ|}Bw!}c!hp0LoQj_t z+pZqYT9vw*9p>NK_YNGX!Z3-2nlAd#N0n}Rx{cRcl{j4%%ur%GEMf=wl=;Ffl4>@F zwFAYnh@Z{jyyCBsxFeNm8GF4x5%cPV;>!2KFBC;WAp`8p*ajk zisq1_NjsHe<{1S`6Awm*M*C>K=VRkysSM?9o#O3hvmxM!du+|FP^Q?nOCAA4Hx{tJ zfK=57lwKfTGYUzf7PlVc7%HJkFWa&a8`Qtcap=^#c|K6BAjQ;BTO)34vy=OHZ#*MJ zqib33KT4i4>YJ<>t!9i<3A5TVa^nFdz^C`&gu6AIJ{1LM_Ozv09wGr2j4GChB86 z^egMBPeV$dKYF4Dt`yEXo`U^Y8h$rj~U?mIwpJL%gs))zx!_;n;&D|igU)MUbLWq<1m zOV^=a90KC&-Ag0-9rOEFs(-l;3R-t}@Zn8tRE^i?lDKrxUIqIiXOzrXMl3dP6+yC8 zh#nzApTI!;>Vhb16R{mb#Gf87>uwV)w`)e%KBQr8H*Qy4mS<>2iH+s-)*UPPR0)ug z0ol)>9evpct`((@K`Fpor ztJy_X=01XXy5{CLkz|kPqHy(#R#!B; zFnbhvMhB`!kpE`huvDGn)p0hC%^_CnU5|lKcT`yXbEvcFw0e&Koz&-HUD77^6E7N= zFsojlDVI79B^x8$6lCsmbdtNn!d%B@aIM3L!0=^<%;|D-g27tDx9}cZE@D$Y%Rt-v zmY)^_!ecf%Pa&(Yi9PpB;;9dCZK~k@)u>e`ytG1>yiUOiy|n{d0exa;nkM-}5N|W* z6`-wj67hzbxFVd2PYYGl+;~Za3>~m|Elm_Po?U|qs3eA^I6Pdop{lU@l)r0dRh!}1 z=V}_Ole(w?A~;iJogo7B>*z~TTsinezh(p1s!k-7Mf+|djUIuYE>}_CDHmWP9XXqX zh_}g_;Os?K46GuTE_Vxovpe6G)jBcWc3PNuSyHjHOud)|Yxi6cs^6p#IcJz%(|8XWO*h+9 zC*SZ=1obM%EmLoG{GLgumr@jNF=XAox;025nIwoB=P54(D!!T+mcGfyLDMv{*V!Zd z$;B5@l!CE_uy9)yFzJ##>NU?OS-v+Ymr@IX<+_$c&^UA8+Ljx*Xp&66u%593g|N97 z5>p1VIO`SbXm#XOxNWOkCDL330hWvW=s~kv_(GiZOCKQKi2P;4LdJ%ZBNxJ%PM?<* zu2_qPu3LC3es_AD=IB&nEMGl$#K$wT_?t{J%A)I}&D&2V+)I5QY*_i701Lm||R$*antUp-c-Fx%f%Sb?*!c z0Pmh#A`@>EnzD=mGbYPQjw_eVJ^(IKq9vNx+|$uw_V8C19B_-138trk_WW2!sbO+f zJQ)%#%OavVs7YoAqUSABF&}jQ`EAHG^h*LDOiREPsj*jBLh-!YuyCxX^V4^<%SYox zW?RPV^y^;x_^}G+8(mqR zQ;}uahYU|42n~c=v5TW(22UBKLb&cQo`Ku)?U2bgCWUQXKJ39c=qQbDL$e-6wdw#) z;$Fp9`ykO;(TdA8PXZ!aS%ZA#Vn5`U*Tk0Io4N(SMJ+|YJ`OLs|B?xc4Vdd#<9s4( z@D#M1@A|c5F&qVFIM>2G^CrH>=HF9iQWFAa?wJoOYv077EL|g&8#+45H5QQz-z>{! zEo#XST655}$29svd!|XONH^k5fp|lRzYR|0q4VxNiWvE=z{4irSOQy+Z=wJD%lT2_ zsW_$OD}KD*Ewh%w_+*w zKpm(6BAkhr*Klg91r*B$e8Y-Fc1?!4fs#@8Lt(8GqR!J4Q;CsY_UB7uW#d$=2`+O@ zurVnp*52o0mZ=`OJK=ni4qL(geZ#QTAGI%i$mj1+RrQX(P*&HG&v7&NvG)^4nGj$% z*AJ(o!&AJRLS_$%UwgzAVT|67ivmg(%Z;rQu2Y2*-au4}KKbObX>ii`?2W_cYB5ewZ^~X0UPWf*>+?%4_7;ryYPs`nNr+aLf zA9Z5;v9ne5JWh!?`hDyV=kJOEw(7aIwa<0>=MBxZQV$>9YPVv@;?unkw=>oauYu;D;3lrNIz~gP^QI5LxQCNpvVDR2$1MoQAt!xN!We-oQ zziKe0kX&(saqL&7>vV-j9vq$JC$O80w$|UcI&4;vep)P;rg|mM zF*MU+Om%e7XCv=9TLnjX@F1Br+|`mhtrY!px%!7$pqR&iE*pI-Sm#Tn_+X-L#ZNAi zD2bRZ-^0Q$FSPXCY~yZM^7=Sz@T+}QI-SRECSXDQ0NT?$8sSq6?gzJ~YDUH$Y-)>} zI*Zu!G}8a|=FjDNHU&%X2p~SFZ+xjdC*iFt5eaPh>a9Vmom)GimOp3c9*UJAwr~M z@o!JrW^>qo*4FGg>+66LX5#!h!E{2%{-ePf_c6$EDpk9`U`!N&MSheGy66x6HoslH z)#jN=cvlwki70MnA(M+BaKUuPd|hN2g{^B!gxlF%*t1FBgwczS+SrnzVT#=C(KKPv zqlas9B&AFD&J?-dUzv4G1M{^LVK{acFA1W(Um_OEsXR#%YV~Q_snWi(M&z1@r}-1! z&5y98kg8@}qv2?ZS=Pg-U7YW{AR7I$+w;Sa!<`OCA~1I5+YU zrtaMVNq&J<->IV}U~Pd^UFVN>tocYTssyCCEVh4W`mg`?0A6BwJKpHnKCdiMKhpG zTdA?@|LOkcP{4OHO*$q-BWr~Jt?c`bW#c9CC<4tEgrPXog)$s(`&$X65fxDb6PtI|cPoIW0$GexQ`xxx!aG~e z=yUZy(4mRB($`7j6!&3IuFOUJGiCAzb?U(<&~ZC?w|G%i6K|E7vT+d~0}gy`k{=lo z7!nPzTyXYDN(uuShEp{Uw~XIoY=8uXVNb$Q;#8NI1Jph(+?ilOTGevo`NV3~&G;`kDY2a@T`n)%)3=5;-BMNwUHC;%sbBig9PNf>0W!*BH8ge2PS0nym|Optx>y$mhG(_z1wLirtBq* zJ^NU$RkNyp6Oz-fHvlDXbkCmmy~SA*n!u1Y_|Vtx=?AWo3xmqH(~2Unk>z`hd{!%> zj=#&b%gz3y=vDnH8OGxRbMMf@>Z(I0i?7&FCetoXeKVasUy^uTvN`niv|rL!hEo@VIn!+TyJE#^I@#%Ax`Ty%_j*`HpR)MHc+sS;ZK7UqEFH65K7K{1<^7;~ zrn(FeY3B9nR6ZwT&Fs+01&$6D#1tg8jiGxTWfa$(I zI!$Q@GT_kRW>p}NLtY<&{eYAqUoKEG6rmR7D~VZ3{?fA_zbQg1Z{M+Mz z{H6TLoSo{5_Pn#?T`lW6?@i5XEjN6)klt1Fi?TvS%{rH)wgu!K{JVe%nafrY7LRjJ zNII~^Orvg1WTuuM(C^dcj$8S%ej0s$->m5>R6G9`dw!`Vde=CPj z5J@YPWsf_M^g)Uncrg5#I3b`wi&qJ&PJgjCp1dYGFL3ni`EtQB?<8r~US@-1m|a`6 zd#?Mjxza42_AdBHZA@u1%CIT23|bU$Zk7;Aj$)rCi2#h+S3WB*E~`Q%e8{|)!x7(< zZLLc__g?^GW7F1Yfn$2dhGU!FAJNxx38DQ62jcotsTBKYIsqQ02%TB#*h`h3HJ6)s z_u!LDhGn@WTJAE>_^Y zt17-1GVgN!415NimYHP?dz2K$^-y>%PU$H^v&EClH0+bKR}#J3Up$R+y{z(p5?_#o zO7#nq{WKI9cI-KSYeZGIoINenw4PnH(Q~!kwWX!d{H=ugIcSR`%Z`>v{XnK|hY!vN zbI?{{Qem_7eW69>;I)>OT4m_meQt*bZBMgM&k}o@b?1g$f{t|sTXSjp7EmMb95V)0 zu2Je`4f)aB1rD#DEX(TDy|FycYW5=gOB?c=toU|MXP-`WP5Ce-u`5FL-R?qaN8~)= ziHPP!hH&X#J~i!%1U9K^<=NSeFV1v)&Jx&crd>f-$Rc7YRI{d}5(10W<9o}Gbwa{T z_A*;XQbeoF$XEMfQ37njO<+Am&BErTz)s#IsTi49SpJatw12FD#T^M>~>kvz(NP zPXNWqNeat%eUS$3RmeDkjf0&kb1oIQ-@bKd>pC3A^j6)Mm875DQUdZ@5p4iNhMsTs z9Bz)O;7$e2O*c7y$H#eA)oCTQd+|QP)u&bXWZSLz&u67D;1=xH8GZ)-gCN>spAc1w z&RepFKOKZHKseazpaY8VlHmW;vg%mI@kWgGm0lH%_*8d3t)3DHWAo|9WIr@NR zQvRz0BL#scLyoNkIgLXQaFSA!)#>!u2B+lEeS6lsAw$rEw)!ChAKPaWwX5;mmG^zg z>{1^Di=Q23H^y0dihs4Zq(z)^*4k0n+Dv($ljd?+nK_7mr6i)4)Oks#%jDWMxwYb{ zjCM`@z`L1S$a+B;s!6D3@2sFsNA>?8+SkVxq+JDvl<;yse~5^rInp5Kz@hCtxwOh(R5| zA>$Gzt=pcG{-;S$$oXqlc9OkLUEpt@(Muw|pwP0$c>cRh=0c~GJu9Kf2SZnQJeeV4 z0s{^k4k5bGcUu($6y%L!PrK?DvIdF-A-)$a?7r>AYcXisVjP!IjrJBe!Qi$eXDKL_b-)sYA;eDh9B={{OYUW?;Ra-b4_4pak?Iw z*Ep7@6e^)0yf$kub8cAHPp;s@g_2pNGmUC{KV6*#JH!eTTAErP4u6`Ya_7TL*;^}U z?8WQ&UV1+IPX-LrrPjLZ3{SL~UDMI2y3lTto=cg`bCJ1n5dXXCKH|%5v&-Es?OJ&x z(JE+Ae=)X9`kb8>7i+Kwa^;Qcgg(`a7Y3X=X8B%10_RFH_f(=Q5G9407To?TroXGV zEZ`exQ)L#`WKCRFbW~+-f@!JLcNW`y>vLTBX!C>HFpUy(iIgJN)Fr@0^5}vPfVp!7Fh`0^L*`tI=*|A zFu`=<5DNb!B)~-_mg{bO0XW!amw(tH$**53=-bm_DZrV)W{(8dTc5Zhdtm%@z7j?j z`T69t<>w=;iOuQmWQ+LF4NKvUy(&T6x0{O4O%5@Uy5(nf?VgUaoJ0O7&^^@E)8wBn zx624q()aojU~fB`i9LE$+>A|0`{qmD>|wP#N=hiPl(g-7L3zZPEL&6AUIrU&}g66|Pbg!Ni11a@P3re% zNd)+3v+S^qA)<(Br&hs3(>qe*cMonKhsB&=@fESS0FR8R9_TR~R~G*pf%d%gq2M_Q zeCrsmV?#tz2FC`z4cr!jOj^8CCyoRI5!j%`(csc+=GHbQzpy&!0S4Ixx<^NjfS}B` zb#Bk{FLpAWP{!qK{S6np5Kytn8>d+@3NrO&MJyZm$VQAht0 z5Vh||)ERwS*}&Q)Hh2O%bn`DK&d3DwT%MclFM%_W)6mh6U}6QZ!{W>ZdCaz!(u`GV zo4J-$a-50Pyzy=nZRR!Il@kc(|51ATDrm@Qd2v&8J)bPKl@Mo@TDKHjGYD4#)@B|c z!Abv8en_?9%Vxk3T%O^KiUYm*zj^d6xqnO=*8wr|r?dV&qvxiu4>3K97SR$D;orjIBF1iK-^pqsRo1)^(CEO~s$77> zigtzVd~CSN5fSL_bb)B%*00F|bRWle(-GnPP}{S8OXP78hgG^kMDlt!%G2}&Sv>DD zeEN>7y1R+R?GVF>T~pSAcsQrxK2F(unFO=(67XEXNW(c zsR?w!%(Qz}U&3=d%;j#Bmt~FiFA9u{1{*pKVt2zE^z28Dt4WP5{W4h;+HlU|Q-9W= zBk)-8QG~~4<{zitrYdOP1x9X4@5KyADLq2u+Eba8@|MOaHit|XhDIqJEt z$?gpal+F^LW6$InD4k2%t%$i&n9bUse8dBtCGE|I5s2zH%>EMmE`k=Ns2}YKwU9-$ z>GQiAUG|wy^vfi}RyO>Gjrh@8S5zyn#XVn zn&d~vf{o|N)zR5s{Dt+`T6@0}R@F%r1q4mG%#%`NPW5eM>lj9J z?56nIYm_CX#E!`YdGR)DWGv1)T}o*mR*1JS5mkzk$Pu%Ce(vK!-B6L51EV-u+r=;& zVSV?$8uw&POW#)8O5O1joe*kJ!vn7+g2X#3*kd>~Q^0P3_`L}_M(3~WTusE1pLV?z ze-vPJDlK;6&%@w_PkN3Qp`X(HVOg?Q6GZH&r%5~v{QAEvpoS`T>MV) z25T8lewa$>@i*u)pttwQsl}q41_zFr+3Y9(jHj*jaHjy);q4ico;_)PHPO!axeeLb zMjKq$LRUVYw#uju`b`(ocMLOI16yM z|5q;dL3a(09vOHGb-1nJOq(qVdReb5$ZPzSmuy-fmmcvf4JGB+P4vQeg<5q4`H@4k z@>usL%Xm9e3q*T=S{a5+3Q*5C8MQW7oubSHr)-bJ4>ztMsOf z7p8vZn;(Pn&FrC~=X}{%1^#!yi>V>ZRN&~XH+*=UZh%C!;xc#P<=vxkA?X1ruKl8$ zMg8qY2dYM!Tz21bU$+`5MRFI0ir12jCW>Mko(&e-|8rWC{D_YW!5`*G{$`a=Smii5 z7013vjwb!KW4xfy%?~>*4=Klgv#Q#+z1=hVcI!;K>|r|NMLKx97nXVc^a5HiK}o9{rETvH^UQyM z-14W2|Dby=R}b&AN=`ldmmNl4J$lmRpmeMB+uMU8dgSM+1^}|~@z}@r>lK)PG`qDd zc}WO7UB7rBF&lY^GRwT0_TP(mcCn#bWQPE~dLypQxF=T*QE^Y|4pCE4m(o3o7j z^8daw&wZZq`ZrG(4B?wcwwZ_D7Cd$MCXOq*F>X_`|3!Qt$6CUp-RS?0>y6^@yB?fI zt;9vU>}`{CmABc!e^(%D{8#2a*Qy};W9;7LvU93Fe+8z#d2S;klyw+ZhsGp zP{VoRmYJD*0X-?;oxS8Bq6{BMUUtl=x%i-5vt&MYY`3IkKodVGBA`-A=eVA(UUQng zPI*QX1uTm)k}5}H$CF+^oXpL{d1tAH7mOb3TRE}_t9zI7_GDlAo?qmGE^92+KbAIjw^FnT;X5?Nk4Z~uO;bb5K|ekz3bAo@VFk1e z&zl+}jWBX6<&i>{hSaeFET)eVcbWL(de3+h>NT&N>u~b8CKPF4xj;gyq!ouRtelO2*mHKqK zAv|SqGFR5#LMC3O`iM{#FRDdD(4O6@eX0IUM?|GCo8d*^*sZ;q<86kbJ<9bY=Rj4l z@GAy1RF4okSwnkk^yyHXm3K;r9g?DQ_YS+%_^9fic!N-EE!NrKv+d5YcPE4|5`tu0 z5CKldd6Y_|mYk^mIi_k4{Yr=>jb?5yi=TAb_;UX0F3$lT9Yde zNI~oWH%1u+ionB)QwK&lf^d&3^3#2~*{@2s%KnY!{+0v}xu)P3l{T(LNu8Ggx9a?+sIP-RyZql8xty)UhtEQqr5LY-Kkk90cy*eXj z^e#~G6YZb0%|TeoFVl{R)2eZI88Mr&6gRWOn?&A{ymiwz-Bmd+C^*%dfu{~kZxTiA z#lgs6VlFg=aka<9ji)l@TDdm8$K8cn)T5^kM8(E-Ua=Er-f>VMea?aU6l?IgU!}IL zd(M3IMJ$aQO}{JTQJ?y1)2}yX^Hpb7xghPUo9%J*hqg>hb{%9wk6Ez8BsG{a+4kT$ zMYJK5V7Aqlm`H~8n2W#ZopIT&KyyFPUu||CllD!ehf+qI-WuwX%eZ^X;(z}gFypZp zJ9@xwuXHI(I~xYAP`f{HnL|-jx*uS^K3(_P2!+qxC%DoHCQj2LNwDJeZ}9A zWjt-M6cc8-R6VXCn5zDV3W?|yXzLK*Hd#?t$8g)VnaC_XgJ{W~xzX5M39Ekh)lN!L z7_?hvbRY*~myDh(aeT6rI7~#}32XBAQTel6#g)@HEKkq;_q9&FVE~GTia%{SySa*% zWy>JxtlJnLjP`Z8DmEH^^Fbqs8C6n0sqwN`F%RVuoh!H%`Gocy!|l;8lI?xTEGNc4 ztEI9d?*$ELzJTQ%u{dZXKUg4;olId;e9J>M)J9EVVLPmzv;8mkOBvUOttJs}#xl9x zSGme0lCwSu8_R|0I`|FEAJ25SbCax{;vIja?^mmr8ZjQ?joQ+N_8`xer4*KDyvua0 zgoNl4Ji6V4;J>(@hLErv`oAk>(%<(fe7A>}c$snbRbG-b>>M8}O?CP;qd%7a{#X?o z3Hl8ERwT`J;)@uNYi11GXzovUzoGG9&kkY_mu-QhHOu`x%~lcpyHYu2O!ZtwNjzAK z@1jCm{4sQXq0T+xdvwUa+sJU|bH5>wbu3l$L{fu_V9FIPK8MMsr8}aI*RrJ|FTFyau@`ST-CkE|WQl?#-LO;N3WSH^EP3EJt zzYV;$x_z>5DZTqXN0P})XhMim-Mb(->sRHVlI}#f0^Qkz;OmoMT+-n~e_>Okt|b>6 zCg9~#N5sL;M!QFTa6&+4c8aC^^rFgxvaj^QighEVR4QbiM>P{)t1wQy>g_Kqxex7Y zY;7@8(|1@L&-IB6EDtLp%okovO@H#aqee-X{L-%B)jN)0NC*$><4A z6@@d}EBBETsmqV}&M4W>e^CEN;r^06e!udiFB@CVJ>7_4)ARSbl^@)3faTRVfw}P{BrP6zClRvl1mBgNUeJej@ z_2$7`%Psqjk=&v4yitoPKV@t1>L?*Uv{?JOf0UB(QH|+krjB-ZfBk!Sk>MP4<>xh`tn_g3iN%5@$Tx2HZ14D3unAAhU; zcYAcpprfLCChLSz3iW-tKDo2^7EcptQ9_KK(jlRkw(>jT*Vl5!$14K{r5PyUHmz(K zt(3B2CgQ6HjAyg*dRog-wed_`-OdL25ut7I@&PDiw(|~YK^$`}3wLcnwTwM-P)q#a zQKZOpvfn}w@ooS2KMQxCi686#);n@D5gI?X6LsEB{UK%}0u6g7@pWt|d};nKwUXUHSeX^QAPeH`Mr8Vtak9zuPSfDhk2@-K3ePL&uGLplvSDKx>l6F*J}hM=_sh@ZH#wO&ua zEcs`&iK$qY2YD+Yj37;NMDt+O2YS+Ua3w`OO>kGPO}b4^C@EFA_RGl7-+42_i{1sf z3?p-u<7x9>%KPA?!s6w2*hgjg{ViO9o1huqe=ly{t9iOIdGFsBTXlRxn`!zG_RPsc z!@x#KiC5p5x;Ffl-T~6H7tyF#P^la@2K*@Rm<#cp@SXL>+hor_-Mhz-nc`YHG|6p) zCG#sI5HWM4Zv8y&aUfzr>^1ax%jeblzGDdYKn`7imRY7?r|fI6{Cb;U(k=`FBb-dd z(;>4~ndK3T9M%J#cP63lgr(qM|6S{A#2MHB7Sf!?YU)mI3|h<<#@UMsTqA?`Z{fYQ4M~9XjVgO*ZbhYQdf)W(xNLJKij!ypzPNOF`r5%(f}N`o8yf|a8jB&N4pxYqbb+OKzgEhC^RgH~@=RpN21XEKFHYYp zw!x>nRfLqMz??tl2y$yj+PcN(8}xU}GyKcSSe&8WLh_BwT`6Kj=2e8(5^39M-ATaV zBvrjw@j%$se6y`_(`QeR2kB)FCfi6!1ADI(FKhC2L3bC*tP6^|&MdSH2RsQ1%&jtY ze#LDCIWcU+8#Si@4<+pPfesUX1*o7ed^Oh$x|J{@;pIuybbuNhz(ZG=f|ZfxmV<*e z6<0MOXkmI<=@Bi>dSuiEN;eH`1^G!v!+tqO&0(qC_ZUu~-lV4trl?g^CG!^sL91l(*%y>0HMj%FpG2WP%0; zEIq(>A)8Q7QGGr{BVd>_u`Gp4pVTB?I9&F!9JRe$E$Y6~E-a%ZmWEiqvz>O;i*-gV z=!MJ#KMU-kyS+&X4)%Lar1>#xmL@2?@MUsv{3kvPa_V~8cM6eI;xf*XfYH4gKH_R6 z-b^%43-O(6*9|z0LAtD#`Q`$OHLbG@)~3z?TLJY$fmS!r@J1W=z#rOs2E1)!MMh$F z&E=_UD=~l9J;Weo+*=AG=A1UK+GVg4>Rue;tm;BGKtQh^jUI*;&6j5u0_;W(pE1LW;K$Y!fdB#xXL1>X8laNJT1V;YI!RF=xGTUC5 zo0k9YwgQC7E+(0BX7q*6)4^NV#nx@c&0K#u2&I6?Ch;29;pg4u{Wo%s95p1>nnD?S z%*oRv!6_4RYU$F~3=)enrm@QBy*#ac{w`gBK`m0Wb!yJ_dK8a)%=;enwO=*#)@Mr3Ub8s7$XTq`TG^8 zc2iM*gTFNeP6P6av+Lqve8Z?FkxDkNO;f(q$=w9zqshme2a z%Cb!2U{0!Tr9LF0D@QTL-7Fj29lzG^O7_CG*!oQBEy$jx@SWaZvd zvZ6>3voIvhB>ZGBp zYMF_vlttMCE>x@^@Y4O z>v;Uw9h56BuK|xU=NMapDs0V{z5pZ>3kfEqotm0Vh_4hse}< z?Zt_<^UQuQ(Yco+W8GTgIVT2vc~jLG72_~+<;xa+W5b5a}cRUb)7VyUTuvLoHn{B~WPg&oT?g%lC5l zGcpTrF#^@CXTjZwI{_sz!_{4HgE~7#U18K1C|JAz6;&ga=xVQiurfwq#1gv$|7MuT z4sTBY_rZp}`Mdg$*bMIma&eww0s3*@Ds-efO4tm8ZN_9FKq4{lx#a;j18I$yJ!KsT z{1pNgTz#%tTuMOzMBZXY!!4OM&jR*76PZfgr0|&P*ixkc*Dq6cS}YGWE~Sl+1e#V& z3`xYz$vI|ElALeJKUK`OnHkAtz5@A+rZNa2~M~ zQIcwg`1^qY0uu@JJ@b^Tt`hS@gc#6V9ku0EE!wfZ?9nxJe~%T{5E3jA$)1aik>9U- zR6t(PwEP}U%GEV&#wgtu7yMK3sDZ(>p416Lo(qyf)J*;lfF$aiK0bhPf~cqv85`2M z%wQ+c6KV8_Gtr3AFyL`&zbpP$NJ&`{Uij_gl5nW&M>Jr|xdB4m#<@OeRQw?z3}vCQ zMzjwn%Q1}xW0&$$cWrWk23}JltY*0DV}8&p zNR}lqEY;9Xm`yRll!*P@NpTnyCI19pQ}E$Awzf~Ys2wO!9Fkuye-9Kh*dTWIcbErS zcoyNyKx}hbf@dP4C<_T4uK3ZdWg&i{Xm|ft`OxtRFjT{WJxu4nR*dVt{{c{kFj4Y< z8}VC$dd`{aLK24$g`Xf>SmJL_1G1o8W#fJZ;S2TfGRrO?)k7en`mOcbx_v3Gh$#`HTrF;&BDg?0(nZ39;0>3T+WjPGKO}L7iCqc52K) z6~&cj9e9MTd}JKpZ;tr${IOVlmsj41nx%l*I@^Wz0CD;?0^rCx!|Ig~KNfemN_X>L z2R1S_NTnU>PE^`3=K|(9GB1o6uNXwy*H>?8FX+}(va zDMSj+MXKSNR2Fi8(os%6yj9`W1)xEg?z zfC+VX^-bq6RA5J3JP(A{KJ~@Y`Ges3rPlYpkHItHw~b}u-w2xl%pm}a$BXq{Y*=m=vAX5QNj0(Cw&52<@Ksbh)AthD5(#(2c$gtPGM*>q`bE7`bb_ z_YK<>vys`-C#d6gK#13ci>eztDQ=8Wp{j#?+nQRYWdF-DDhT6wIu=Zkk7m~{jH5L# zGW`-|T7Thj-0c4?Td z$i_9o+7#f{b4|-Ypm8&9`Btu!?G$IXU}E`?F?WtYOD{JN0Cv0fV~8k057)$Q085&- z2#0uaGM2@uhjMzS0Vh5s(Vq`pIZy=+IJ$J87ByyMWM)d;(dFHLf$MU=c9tKu^jQtV z#rt28HiNH|MB)T3`Vl}c)P^{3R8ybh3bIBF2vf4Kq}BWOvGm0Hj;+#RUItON?#BG6 zcGvW!eW=ldVN7MYqf+M&Gk~s778_rd4e1iEaN*wK?&g$j_-bhs#kKjy$qDAgu=bpV zinZf$(U4qT=S1fL1pYEtsegJ4!P&EbYRT zD&f+XDkQZ_oHy8gc-kUq%=@nmDzl;i#D?2Q3n4)x!&=D1HHAMShgz`tmKUS0OmlOn z^a_XXYD4X6!_U<)qh=D%5K9+OV9lg-d~WG?3C2qMNk5GCpB;#dy;8p5^3=E z3~xZ(mbnPso*JmJXw=8c>;Fn=+lRFZhu56bn5_c-NtbxXFCtB7b~I_zQ>W zjmX{#Hzp|d#@^Bu!13V*ah#1^w+xyH4 z5R;GB;Mn_G%HfD-C9@ydUsm=8zv^_Svcqp^G0WyXRJR-ue%QRiOaD>*;l%Tn?|AJo z+=MV``O6;Y-hQSGRT-!6H*9-r$} zg6jxL3D(-RQ`mv>s~UHx9=2V8Pskv#I{;oK-GYGq&}C(A4R*v%9?d*;nIlyTJl*k= zcjjsPl^r*Sla@s4F zxlv`n-u{Oc%iM{6=4V{rqhgzZuk_&ANb^fM&J%l_K6zC`KJ=J-_8Akw*quN$6uyw) z+9e|v1IF)&OrFeWPJ6Wbrq0T@U+OlN2yE)mq`fXE3{y;2-_iyg<8u!Yq<>)i+uF(U zF#S1{o=D8$2N&_+J*pz96(%}Meyem1=KMgusOu>}T!BkOs+(7vZ>HXY84|UtWvp}? z)Lf*Wwp@TeKGe$yWcM&klo8U9lvv8sHTri)RP zy!90kyov>vNarEd!;qOc8Vj;0V>WU`V`p7I^h&z~OdV~KAx^7x)3H*sGbXZhwNJrl9woSY?!<_d1vvdp?0R3yU3Q|k%)7T-I;e+ap^darX!}8@?y6*2RLfN7HU^v zdTQOU$c6celF6|43!gU5)X+U7Eu$M@x>5m+50-DsK6Pg*wFEOfd==xPcJ3WnWpZC) z#)8QT@mm~w*BDthWYAv5&k6T-o^k3Mw&I_4r*5WObxb4n+W(xBrN-%XS!}U} zpJ2q5$g8HN*sLV;XH3OCSve^jKv`&Qr1Z_%Z(XC)U1Z5yqm>qK*(!`gN<(ci$o!8^ zEujxWHIE&%XlaR~VS(LN8Z1jVw0M<2tG6L)75 z)t&t_24#)tcc`)Ny9dT=q#ymbsJ^#snp0+16!*Q_J~hQ2@o`W+|;_c}FvMuE8w`v#c` zbK1{Y^JZh9Wf2)3Ig+}yuT+p;H!iw^a;DL1aelWeF9~W$Ogl^Ws#~0Lihe!EH#3h> zc;oX$+Na#w=_Uu(iUj+piys1pv`4_DQxW@`!i7~ac z1j~%R`S4t-(f8Dw+rh2;Y`SBHN=To1Y#9r4+;SOw2y%nUh8E@=Z$+6%-*<30*(lBt zT>l6iVtO0Mc89rPEF8nr#cJ_k3~)*#n-5Dj&$inkMZ9#lCE8F{zJOieX69nEqf)LJ zKJ&IA@{b+A&p<{y-j!vX(Guv~7PITWcfgn+^t31yK0y(*4_L@WJl7O+H#HLqqbfSO zs3wIHckGo!+*#pdyLKsa0SakR)K}AA;<@l-rt>$3F^xir@@-)5 zWj}}%Q0|&`?&wm~zlOj~Km^)&G1b&{LC#NsTvVP0#axG_#mD1O_IZa5=JWqP?fq#N z{&aTzspj|rLENwdqP7R5k#}zq0Le~e-O`r6RK?2Qq?0X}y|j0`nX#>jeX$QPX`oKv z0K=sSSV{_AP(Q(ZFnY!cA=?R4v2_Y-bL8NdT~>1}y1L4BTGb60Xs2W<9lRo)* zp-g+nDdoiBj4iXsqCzI;fkV&qkNdWX>2pl&<~$ z4V^Sqi#(0KlfTAEIH3&$Kp8MAMJOOHQUHfmuA()Bg&q{rI=U~T6XH6 z&!vT_Q!wwTOL4V5HRI?SgSLPf-P(CnI7qhlv)wrXasxFG5#Mnv)9x^s%)a7G&^Fdgmgv*J57sb(Hr ze>$F|aIdt@`il4WTBm_Y8!6in!4oCs4V%k^SSGjMOaBE(Tsc`WtoGS9=+y6ji~OM) z`)-!xe85W4=o1}JbP|yLO znw$Aye4r9K4)xq=o9@x`Bc?Yjm)_gVX7&@X>3$ly(101YTwl)T);uHe-Am0W&0&fv zcegA+9#PMMg#hm-(ahCr*w=V@!hf7?Ev!-Z#%O+BD}n9o&@sfa(#qZq##WagsA^QP z$}Bzr#877HBwRw(olG0Y2Y~KWw>t3wZdyVPJx^hjM`o#qBP7RKi1sWsH!Aq zI3pg#eIPM@L0@X?!-z57iU0hF^g4WXAs1L><;Jl=jr+yG>}ZuNkZ5L&PV=Qb*}Hk; z`w1p(N1#kK&i7)5$%R)NZC;#3C3c!Y@|D498ATJMJx2v8wrSitX4Y!W-p5md)u-0L zvBo=z*7-d*K=vn)7!3-l%Vh+)KH9hZ8I#P=3bm)NKCf`2l)lx()Z6!6l#-5HR+9zz zO16qXpHa-+oy^>QV(>D_!F(^%xrQrRi;=?-$tt~xX6EB^ z+?q>{%snQDirIqb>RcCN6WEi6K;s1O*DKBu9*r}EB+LirOM9ok1>Duv$7Gr$ttwcF zH{~T&lnF+vE2Em&kjg8j7}vuF1DzMmHUS^AczQpLC<{IPV0758?phqUY5)fORrDoT zKJuQ{nR&r)YxS)rq!Fmj#!P56yOw4={KYP~L5V+dydhq>-YWBMtxmhS@yQs9IZD&< zz^FKm^KQlHw;*UUo`=RFuUoyjsm_!Up=mZ`^n9BubscT6oSLf$KpK6o?`XZ{C?g(Q z+tl}V3PLgRta%@@;h{{INLnr7XZ2#c@b$%==Pp5Kwd;{^HOSuFB|I`E?0*0>11x;t zaA9LCyTv6k)gU~?okyixOG;B9w@&Q1daRt(cVlbJ?xGsVBxm& z?f8XW3#q+pTE^eXooC@-d(X*clH$Y>4ODWkGV8T+zVC<;f*oMXj_Kvh+opk>>d~9$e_tQ z_(CwlsiQBi3}^)h6$AnT@)~EJ5HzY7ha14u$&a)Vw~6&43DhG{OdE90d5it*j)w zMf*Rh5{9Rp3)W#2aQHmF)9k%S<6M4J3Kgq4>HH5)tCfFuu4|_sxHtbx}zj{Iyi<{NF8!yEQCVJofb$ zp&A(9Ozl79Z-GsKkU!TAppab%O1Wh?s#EtP#(h5>9t&j346d9Q-TKpTIW@dfnKv+2 z5EHpc=rvO)EcXL5DnQR=ghi1KDfpKxA2#mThfv6DRxDPJ6h3nkKGn5z6euB!n~80;<^^}1 z0$fUT=`>r_qus=Cfl{1QEzEqQ(XUtrz0)vqi&_@yDPW9>OgZFPD8qR^Jy#{^&ir?T zxDAvDdhWW%1{PgQeOH;emct@dE-C`JTvb5u84(y;QpgyXmKgaR}Kml9o9$Ek9 z6$-jRyQ(k9w8&iU=2lQ8(Z)M0Z@0#=F;VTCF&~v953cuwU}v?QXFD^>h#Yb}uY_Mc zocd@SVs8;?OWI}+?Pg%LrpS4_O4d2{bTqUsLKQPBQ=6%y4rj!n1+4B}QPUG`74=gX zWCOeX%53|2=pWXN;B6Dhd2ybbwBoc_VJY;YZ%koe43w)2iind4Izo0CYFgWT6*Le0 zbqggmuHRK-%)u^^_)u8`tV^eoKH$Xfqk&-DUS{D%XaiJ*F`G-6K^D$yp1|S4L~Gyp zj(j#rHLxzy2l6&^vq{iwfN1H#3sK@&Y5VsDSF#v51|V|6()Wr1;4$Q3wpS zeY?M^-?|29)hAqBIg}W|s3|bD9xm#ZX&2lM$ZSMc_&bN9L5WrYK-t#NV`2^eZJ*j< z&J_X4^9}erUc46WpmMY8w`?8yk$Vx1&yg8R`d+G4Z0JA8C)6X6zkh$yqpV-2XLo3t zEyUI}@mb9#kBhTkIH)9VPY;ftS<+!QwC_X&IL!*Lb*-=(5*h^GO`)eXw!vx8oy5@j z>?f@Wg-hE-_LCkpb)Ze{lb_3X2E1_sq@@dbD49gw2Gp zcJ)Dp4j1CL(H8d-AMdEVK_{5gwe|EMnjWWlX?8>Mh5dyg3E}vWrXZirKy&d{S_IRK z0)nV-Q;|o+ds4`CjvNrb+vNxXmZ6Ej11~+99sE|!X<(Nb(e|P@U3>9Fb*fNrmjRK+ z`uE`mDYKr-rl-C)ccjR%^op7Qt#Gjk@=q;x%hj7% zgdm%t;quOViS=&Qm*c$1ffCj2oNY*S)%wK`gBLxWN+Zt9k5}t#*S=&6%GOunha_{0 zZY9IUrp%ni0|%&gL-R3*mB`HGbm)EK zI7bz?mOIWFSF^q>=MrSc{X!uD)f*3yZ{i9i?c9sSsLjkE_k>G#xu{k?{-+YJuc2PgX!Dy{AQM#I-*aZ2RL}Q8wE8*M-M&9)0Gzh|d{%YcaO(?rOI}`L!fEUIs8Qg!s#v;*Q17Ts@Bp<1f@)&Zc<(NNh~;3ho5e*A^}WFLPxhQDvkGrrvi3R;-PotL8N@RoxOYX~#^p&#ewM6`;)i%Ku+ z{!Hch??sos{w_atCjXL=9>;QP@WtUl^(Nf^^-A5Y{lPy0VF9{8YR4;hw7+(~PX7>; zp%2xt(JSF78u(Gs{xnBS@S9cyB%KpGW1)rrwGmwwq3>m{|5Yn~Wye!t@g>#AvlH0Pveryj$yLup*PcEHY}V^)g;yFEHq{oe6kdZRVcD@+p&k_H z!n1|=L&z3>c(U1SpjtLjHcLJgC0yat7WnyOHPU4(q}Fv8Rl|;h1<(u6uI(F$`mDEk z>OziR5>ozsN7v4Wk~L;D*mv@IhMqbw?Y>NKy*rinU+>FO0n}hRAkwLWmRq^xWxqU=HSx@%=0Q^$Cf$4Or&DkI-ajF=XY1VJY@~w73xng#j_Uyp?^LzXZ zQjjj$H}shvKMfw)d?_|+XT4nBXYR#RpXYF>yDR)7?TJaE;=>$GuSvsuIj~^u+cUxC zv0nz?1#diMK1k9|yD~jRs2*$3h>3r?PFv(PU^F$EzZv4qX6|-G-8f{xsqH?z3EOFW zP8=xwR@vWm+Z!9Sk|>tz24u$8YAs?r9KSSa(joNEke_^5O2gRSjo# zQjQ2Z(hTu7DoVRBiZ^~6X+!hRSZdmH{vRO7wdCxfOwBYZ!uxY(5Rcq&{!oo{&-Ze| zN!ka416m4f*MN8Fe*mdg?pwd+^w*5=+btM~Uab{VwVrsE69qTh`uJP16kpQOG~f@Nc#DY@v~h{Z}kM0Z?P1r6a+RI{|sF%eV09-~R{Tvr0BS&_etf zYS7;NjAQ6&u7Zgium!o1pb9?{9agM_l>btt%a-L)Upu5LR$JbY=G<}N#%Iijard`3 zZN^~BUDqT7SKdT7*PaCUtx*QbyUutSLN%z~Gk4pS5XUK%WlWe8${l#iy`>J zp;h(o4q=gQ4Z)iM*nyfxrp`{*{~lBT7F5Rt{$0_-MUfN`3Q{8`@Utb2v4dxmVP-5jg%gr9d{eBr&Qt4zg2LkK zwrUsrLT%C2epeB!4sRNO-RBEZ2DZpcug^1YdnB!v68&bbe#G4=7esTc|8wTdKAywsvWyP#nC>8w>?hEIA}9HTd|+bst8*or-{@vS7QtDs`T z4d!$I&R1A{))=o~$mTWW+nOu(te_N9{5Lk;+7F+VQ#`WpKe+WW#J&PgScg_1j9VYia(r)s64oE0g(u?&IYJP||NWjzwf;oSBaTcc* zhEU2T$;dX@y^e{C7lPj_|1-K=#i*@OxWrw5!8%7+K>F4I90)G2=NJET$5|r6QVKU9 z_aL>xr}f0ge0#OjTkg~Q*ij`Lzk$^_PSQaAI&4mV-F08N?1*T}en?rM?3|cV(Hv!hVW+{d=Py=?QtG^teGS3MFUC3w8D>G#;mO0~z*|zJ`QX{caXe zr$ULZ$r=Y>FZ5_kZR&)PzDL950@Y!~9r`VOTLn=#mW30m>ub9{J>j16GE67y3-Q9D zd_1Qzckv{`wRKj@phkei9lvpmgl-53GYrx#kCb|&KgZeYh+J8r49$7r{MREG(1SX& zA(JGMXaoNW16pqv$AM4|1ANfL6@8yhJt7Am0+L>Vxy)Oz(?9JwRvJ4IK!UpCPz;xZ zS`c-uwnpm;gxmiyn=ts+G_0=ZtR?}%5Omen!;C)KC7!ZzM=0=K8KstHeRQxBVOkpv zYT6i$7;I_5k;W)tox%A1pwxrkK%7(`cW1}*w%6^beZK} zyhCR47H$4Z_65!9b78s3DaROjUuDlr+}?$UTFNer_Tkgfa678_{0Tf0Sst~3Ec~Qt z6m7lOnG^N6V6{Sw&xAIcC?KjHIZ@M4VS2t7F(>!H4i=KYAc8Gs+A%*CfgKj}#WgFU z8KtH^)@Q!z(uxDMP1f(FODV>|>y3odu919@WNSa}x(G`}-IzJL|x#u(ffyf|?SOUAN4|ESd!zQ8W z;tkC*YD$T*s4;>SK}W9GjotA=8;rVgWW*v^I>w=(E0I$WW;;k(A}&kiXqgUw@g$gw zBy0}tOd7j#JMw@0(KTz;tl&BawC^K1SaD}6i2BWY=sY5Qep$~%s2wB3)c?Mo?rse8 zimD@Sj~`Z{fQT%qP#^=Mz_i(YG_AH-GR}tHsURg5JYu-hd18U;BwjOo{bxMR4$*F{@;}w3Y;^sQYCPNQYKR@v$>1AT$gAlYa z8&EtrF!9+;Wu3u)-Dk55kUuu$6UR=1M{~^B1lLP?SH@VsM2zz~Z?I8V1H^~XN>qRC zEY>^cgeYrawgEY7oeo06`D3aqMFy$#B+QjD)G4~)@J6J&_Kz+m4~o-<8~g>-;YWfz zu?`WS!+Gwh0_w1*xkUJxl86CsxWksZ28i*{pNQp1!Qz%|7tDYXcdKO))2=(u~?UvRvs=J3vNmD<+zVKc=P<&kU(`cmBk)!O+3rQ=#-%&6^uw<*=pX2{GO^kGH zK*ujCek-+EW1oo}s1+M}y7^7dGek!FfUy7G5(c?=fdRLFcwKmm@(b526EZ7~?8{Qv zzvJL@TgkAXY(Ez49pJj-6~O_iQ=j4r*(C=n(#bf3$l@i|*E|)YM)1zKNKg5^OFCDU z-pXK?64BKa39>#De^5-JmaUN0@Xfr-ejNtf6t`m`UHFttRc9v^A=M0T2R3yy1vpMW zU+PJr^#Uc%0UJOT$=Pdzhp1NtQwn9e;^7!qlAC~pr94cdn>AzYBKRcw5K&Tf(3q|&C{I3#mqzxYU%h4np?+xrNQ}?&3xYosyvkH2)9|> z*C1rf5&74wH{2Y`w*DgJ1bUf9@7A)kdCOFL31vAdn=>}LKzSpCj4reK*_{Og`w0om zAX~d079XnSJ~HmL>x5jzcB7RX1QKwt+13vi$=J=E!*Efm0Gb@TM|)l*bM>Ts84?jz=}Qwm!=j z3Zm}tyfglCSMjq=&iWlEn$7OY$xR0+*uy8v^3yeABHG#oF0`mJY^cyAgl2Ck}`&%f&9KZf3I*p9J^5c;a6D{eAsxapCgI zBDhm=JIlh3X7S%6u-J-pSEK~TxcKxX?sswDYP}G|b5U$@{UJAMdl^(e?VjASOnuf} zT3+e-mvzc9cPE1vNaQ=5+^@OJ#lvYnwI}}2@*v`+HeRGBp?eI)K9PNH+<_$Ovz9Oz z8oW~@sEbC%)-EW#$uXF7RBDPTP%6abeSk4?rC=Y0oUFqUS9Npvs<5y4Tg3^=+J*Fk{SWY}KQyO8ej|+VH2gf!$Y9 zR!;0xBpv>Onw(~G!*c=Sq{_8*bN0l z`g$m@o&*oBFJdok47kwPC)vdkIqmetk8J(xd+CT=8r+;CF;?!$SO`QcFLCT;7Jwu$ zjgR#^>)EP>Zorip=PUa zPGvgq=laHH+;Z~A_NDN-CAG_6H)FIEy6#WSm@x%d`M^|z+cJe!$QHpxWr9WH%P4hq z7H###mkCgnE{PxBH+GpjA=!_ z{g8|&8kTq+vmWd11f$8MrSq!W`lqMAdHI0+chn?iLON_%a^LQHYM6)atoxI_(H5Sn zq?dJ<&1B9A1mxq><8%kT+IFHZ!d}`>U5nPO2{~_65cDocaOZl6n{kOawpzY(>izvp zF=$O;e4j*6)4n;whXsX?foi8XY2MKSd{bRnT$Wu1+eB505^+cyq{NJ5C|JNQTq9oe!vEN8V#GpMY zoNVJrRg?7Ik94u$$}Q!jy?j`8HMTJuqgl zpy=5i!u3Bu{j5yACe`+Hainv@M>lVdgskby>BC7Bnh*S3&;c08++Zft3_U1y&6=8F zGgxdQ>d5QTP0wXM%j>;xVhuZU^**r`;_3UoQ;VIsN9mKLxQTij7}JLC5Gn2?`)OV}9!lCNyf^2CyU^7ms~EY2mk zkjA7bVNQW{@FM;CeI_{{SGX6ike@Z+Y0N2?%`pZ$iCLE~?O=``!F&ohbM-&j z2ob@*v$z`VUaZfF*u3?m*jG=xT)&+asVK$d(6F^?uEQKhycOM?@q)-wI(63I@6dnl z!Z+EP=ra$v_;sAS!M}DHgk4q}AH&I~L3JTp3dik~Cq^K+cT1{f*);_FXf!dex?IME zF@yRZ_=TbP8$LG^`=S=CxUF7vY{SwkBK4P*$c`Zq#Dv7K$nXI5CpF4V@W!9Gn{UNS0v`YhY?`>RSjM z0*AKoXr4c5Y-P#x0=gUHZf|{3y712+ck)x5fT>2wgPXea1|F8|-jEsrOBGW1LbVaH zFy)`bw@@f%KQD5G#Wkm+hnx4#5+l)GG+OQjj_6k~SJqGfN_;bdlfTI%XxtcUcaM3A z|J{FTcj>mR1_QMoRSs8|P;uOnGIJ$^F3lRb;g(yP-KBpA zm+ebBsBzCBY9p>`p)~#W$a?lRjkaJ*dFX|&W4!uK>z#QO>a*^0naD^Z*~?Xs(CpVL zR;t@BQbtnBW6Y1y60Tee3HhIOp19{HaP=DaBzFvK*h&*mP^^=Dh=*XBs5Qz?E*~~3k2W+6R2^RxOJzE`gfJp+ zA(M4Nlz293$5zuI@CHzbD@6tvJ}^<+GM0{pG1!S#(AMIh&4}DJBB1&cyykKeE&V-3 zI0tH2JAQX&h+Z9P2^H%a`9IFyJF1CpjT;TUgF-+;lTHHC6QybZLvIN^0wOg5L^=W% zilW9y4J{xdN$8+x5b(94AfQnQMFm6!L=h1Sh~2vf-*e9T?z(^6ds%B(L&(hRr~RI` zXKyuHXpN1U*RV=y+Oqgt9?h_s7S@$TAxzA>DZj^*u!Y@4LA;4PW^)+Qkcp%z{l5P* zA6hc{$|p-x9V-PM)-YG|z%~nzNiwueyptx*sU2nv6ApMXG(E9n_KrIf9_n5zGQI1c z6Fqu)=mbgQIk)cfkOWoGf`HQY%GtDU_r5$|&2z8tfdS~moNMjxty_q@wozY*`ke{L zeuy)ER(B~PzIL^#EXpfi_)Cj~DD9Tg*b&?25V}C}ZG+p1C%~E|FTy|K?Syqw&FdT@ zQej)81!{XH9j$d+i!OrQ_rRJRgE|q3t(lRfY>0SISoL^%$-un$SV8&;(%U_Qk!E9}h%YTajbKQ&y(1lqr& zW{e$I*e)^Aa>?|8lr#S})%V+^5Y3Oz9toC=zWX37q&7uXY3cX?qBgq!P-5ZEq}&xh z=|v+ueSDe8N+GIO$0VN_Mz_yLwTbl$GcB|G$!8i=u&pSF7%U|oc|GKeWr@cQraO?Fxwd1+(g*3S5W0*MAV%;HU&C_Y12&)0R z`&8*1u?ayJZBT4Ui}0MiM1(xzN2PUYOQy~v3y9Q zso8ic&t4qNo*zmG8t|`Hz#kgf9w^bX=#(N}baC_g&Qhh1ruMR9dDapFr28X*t?ib4 zi+*49>ZM)=Y~EwiZ#?Ex_wGDz%~_HRUK%{q-DRbN(I|%gm<6)=Q?3tl&uvq+=k-4`tsQ&ldMTTfyOwmv;jsN zPa^!PMv3pX*V57%n2ye=c}e)c`TuHFl-QhJGSxF=jW{L?~UFl znkgf7*LCvtkIb@8p4f+&x42xEr#{L^ApvrP#nD!BNz6Pvfy{YHIV*C{&_% zjT9zET79l_w;Wb6jkAayqidBUev*=BbzW07*? z|J(%|qVz7>wa-h-0Y%wL=g+BvBuQBHbJ0v?)$TVfngRQY@FySF;&JR|drQ&GqHd!% z$jyXTR+pF=V`(D5-V_sW{W*R5M{2aL0R8QW~%c0wbUWBX$0AII}rzM8pS zdPv0r^{giky1PQKO5^6s@+Na;ZA}gz4b|z{dlmcm-233LDOzlz@hbCj<-UDe1Jhc1 zr_*2L`*9h?0|w!X*l(wZbFcJk$RlU_5L0=GK0?`3N{xqmsnl6r-Q1~s8lTJgOaE;8 z{{^=)i(l-=kQy{ZzC*Js`8KNFDn|llW<8*>% zj|SK^nmn1^BBv1%(Qn>lb?PRV=5cAK^Nl8e&G7b6N}a7OQQe_KXDygn zr3mH}8#={dc{0Z$Qa^ZLl!~1PyK72)!b_*)7U_1cxUa?o6tg5z2Aik`<}I6C8@FFU zJ(Tv{CJ%}{?IXTsO2`GKcQJZ!{yV)>y8WTMo1W2ua`^Gg!v4GBV5i5JI8E_33!}b= z??B@^Ld{8xTftwfXSg+kUUET?o*nL^qh6<1+?PqgX`Vr!5uQ%x*nSx-?mMd61m_-~ z%FP}gzk4p);B6==dHWkaBYAX_+#VekradeUPA&0p(4>YJ5Cx*fl5idULbAcBV%pw5 zO=7ZrM!4$t%E-+%Z5rnL3U$q|-BvHdWZ0g>@?Ez}KpgIV)Fz;99I2MeGaTA3c6^ej z-_6taw{(4Njro?MYK3h+qZn$_fIKT79oTV;lk`5EuQ>YI^)DYbUlrxKP3IP=@3)(1 zv1Xo4+UU^7Gqi0C=V7;uNpfQIBlvZ9D zjT@Do=Dh~fZR{$Hf~_^xN!wS1xbgL*qMS}=reM@dt)+;~)vAN@`8f3)2O*{3G@iqn zn?u6Pf02spr~ucTw0-RDUoH{0HGAiUNbq(L_ozPfukm1+xHz0KMLaTVVU?%aJYqRA z!}3X+EB0RjjjJMj;MAdW$e%5?`+B;Sk$9RJqK~hqNZQKrUQs^IEe3rCsacZ07C9&R zL@(Q&f<9w%gQi~H-WsrjR4Zsjkxni;frTvvTtcO7!#N}wmS5BfUX>l94?jjCx>OFM zmK84j@C{FEz48`J$TFHn!1z;YPsnArW$zqoio?GRbzXZTNFKibPw_5=ZR#D=oau0d zCe5uV#UpWR?fKa!mmZQ!Vjtbd%6Ihp#%CR>_4z`plYOKaT5|u6^g+&!!O!w#V3K{> z^l<}cuuDU~dCP^QtKuIY$L|Iw96I-gHEeNE2<{S z=f_}&;?pFPTsaKPzJr5LXBdjdD&lH7n`NCZZ*^|pi_zg1P}O zd6GtDeZCUB!-swDhlc7uvRXLbbz__3ici4w1zTN5RgHudFb67+e*crqJu4Y4?Kqrs?1Frw593F} ziua{|RBu`N?(_Sc#`hczFTI~8{*ot9$;XjeP`%2GDypjf?)@>+?2`j;4!0vH{1ej* zp*qpoBC4P#G+8@vL+XqwDrn8(mT%+@D4n_ky~)4OP&y^r%G za9f_)-YWC@q%tM}522peCguG2O8l0Z`b(5cH5T3-rg3JE;PAO*GDr1^e`>93v3mAI zvsUlbQmfE&e7oBdsKdAu-!eaWD2>OA@8c7&$}deiI%9rYyF_v1sx*mD`ElMCBlmn!+N;uFAb#<%!RAO>ppASN<@a|XZ!wbF2;A0}D1HB%6_ z6AMX*rq9Jaa7Zb9ISd7q6tlE1wF6yUntz zP|)e9 zPH?$B#Utys_th`t#9TN8)|4j2tWGY(QOmZ6%tEy zGF46sXKf_uvE*(Kt6s0SQQRG1E{mTPPMvK}zkC0(k_vc@E#MQ0HyfcEMKL+8s{D4; z4wT;Z_yiiyf9L8h#J*cjsNh&G*xXl%eo(kvSnVyo^UzJ+(`RCOLT6$PL>B7Hyte9b zd?e(RJohFn-E%hB{?C@M!h!Rb2b;oA!sVB|)yqk@Fd61|RE6415WcgIGa?er8|8G4 zr^~j&^zx1Ij&<&qqPECWIg;_Fj`Jqf-X+8pt1$4gU4f!*KCR#W;$@}O^_CBu`7FtU z@RQEGcOy$U_CI=as(PaJSS40t#ZI(dU!UG%AtTk1ty9w>A(U+{c3i8AGwCe|ANgjk zqwDEQt?Ej0act4MF4E>3-qGMP$`XWy{TAwZP5)sTcO^Ma3&Ogh4~ZlE!^Z`j zv|iVZS4G^dP`)~>U1Ztl3QMAsG;d6MGYimQeTo>AbX+idll@0QGb@Etb;#%VnRZT> z+I8J)pM*m0Jf_&`$t&OZ_}wR_VxD?L$!D=XwAq;3#LoW&yCYvu=w1Q^ziY`Y{hqn1 zpE7-tMK`@)qMvd8RuMKflHlK?nYG(F(XnCbT-?~3w%>vI6?K@&udB6o?fBFv-pfyO z=J_T%wGf`&FD8<|^gY*G!WJImkxM9{oYzKVVJ^%cv(+4yp<5*ySj(_H=A?{2HymC1_L(6g8SOn()1rfcPqyD>52@cmN7 zZ?Mpu^nk{1sZVaEGIT#y^YuBre))Y4qds`3*gbZ>?Kgb(NOYEa~x{u20?+%d!u)a8Ka@y)$T$X%5VL_YHOu8 zPt!a2W5)X>#B3o|EB0Dg^7{2PEv?z~(8+kyMW4_cw6nDd*y5fBYW6j*{HCAJEXM=d z!G5BWJEPUQ(-a-mPnQmGdv?*NB77`Mn7zG;F~LsGA#kC3XbaWTrlO;CZ90F7~;1J%l}UbI@v!G>G=eMY_+>;LNL3mn&s+ zLRorIE4Wefm4Jjv)c#+Rx^D+QHYjDgmd70<^m0wE78~D&zj$b;k*KSda#(Cye=exrdRynlJhimf}^rR6XV7V~g5N z^Pe;kp7hW0QDXge?J(Q9cJLyq+f$$7ew-7Nj7nnT1^FUb-1V0(Wis1C7$UIdca=eC~X&YBZSgshe`2cQH{*J zNC@o3*t!I6 zKreiN<@?$wCRc+FxM+saTNbu{EAiBGPrJo<)IXlve~eyK;8itYrZg8%RlJteB^lg3 z7ImS`{Xr{C(^DNobu_K^LCm61dN~q7lRh_m>j&i#ny=9kCX`C6+c)dJw74a7&(D2i zeOkApXWjkAd~#2$_F+0B9@a7crFqlQ_Mg%7*BfPgwT}q}{YY=x?RG!3YX9%1Bc-v2 zZ-d4Swl;3sV%+0Wfn|bn^y2N&Fomt>8=rR?DWm5!gs8*X zk@7+%lg)$cZx0@wXyE41hkIUC&#%G1<~`igX12yWx@4o?ale?M&M4{)QCYosc;fqb z=FK(68!~KhXQJ?%Xt5UzCGWwJou$F+Uysh5&(T%?K3Yu;Q3(5To~)pico!R=K(AoD zer3k&`f=L##0>mF-$|#7QQUeDTGH4@50AC5MbE+Y@+DV0mMc|Kw}&cp+q^~S!b_j3 zl}7oz4 z%_1xGq8p1kS*UY!9wqNRVRzH9VHn|o#W8Qj`>~jHj<#9>>X4ccc;O*lgo8eMp&{^S zd%dZ}a&`}b54`g6WZ$`-d~*4@rMd5;=iVPtFKR!tr7Yspha0pdGEG{_%SY`;ebKJD zdC!xi2{q@}*Y&TSWmPONlqKA@e823PgM!{W!lly^ZncT*8pC)Oto%m%hmRt|<=+b6 zLpa@Y^x={&Zc{^suNY17k^Z!3MjioiwT&3pvIZ|sDS1mmFI+XWNfi&u#2+vUov#jU z-17%^@8Wm5_m2YCDuumdd)Fv>xPf@C(gZQ>`}owZwbSl*O@0o+IFW9Oh&27^>7&if zXaB$yY$8$2udOe?4-dU^eZt2Pb&w5<|MW$&zJ>Vfw#U{(o{{5uRm$HI z;~ks@7-ENBv-WO%yU6%uQ)}<>7$^Cke+GIA`GA}h+WZ%2ffy7&BOSn}HQ z>v?a{4pSVnH!$iIC%X5HQkaf<>36S!>8*I|_L+HuJd9?%E_+?xGxf#7g=v5qtxFer zuzBo9s+Q?4-RHPA9S2`+UdwA0C56lmH^1RsaNP@7YEFVVU z*Gs=$d0DDwZEN|%ivpfUK10cW^T4nY)*mn89o9KUJ;Gh2>HRwJx%foctGT{atVpn7 zdi(ikw1?KC64ghpUfd6k86iH3H(H#w*w{D)-snax!C=`0c+#QPuk1KSERlj}sW zb)1@0z_~w9MI++Elado7_U(tx4unRFnqpLqRG||qD?_i8(B$;^2t%j+`=TO54ebuZ z9!T_x-xn5PxH}@192P-vuoX4*BZnuGRE>>Hj6@9`Bgj#tWL0BhV^dK>TXJ%eXGEgi zf&K9Z;v(XbRn0^V?a8sp5s8Mo?YwtKgdGTvFm#QGivpMLFg8aU@7($CQ2spm^ByK? z1I7~p3x|Opo^7meAz!_3^mZa2=}!O_Xt%iG7-&p&_|79J59MIuKhC8wmO9Zb*2J$5|r#K}{X z;u2bES$Rbzy^g_T)i*RYHD9{S?!3~~-E+0~&fUKLdjo?*+|jY|iN{Z#PQIL-n}4-|f z4hpg^OOyyM>4PUZ5Mjtg7YZtihR3OjkJuw?d8s3GW2_*F0T0a*6@V^LM%Kb2%cxxF z>c}inBp6R0oSl~?Dq%pj80MiEUB5T2L;Ts3;7P5{4`_EyFLqM0-WkCby6(xe(ZrqvxeU}}XB~1zZ z=!6we!sB475Cd4tPT)5KjnBpk7?|2H{v8-JI69z$js%~CQY`RTK{6S+@ONOA+!3s> z83WDs}^jHl!=@mv3-DEQ_!#Bf>$s4N0u#1ZH!7y_I?7zRW!z>pZ=F)+M+0(d-OLl6I@7VwJ$ z(}&ZNYxy zHw(JV5|4wp0nU(hkRd^0Mv)HIXJ^CMsV6B9#UNv3D(EQg^U)G9-@u{q`?(MWw9Y5aS*i$5EJWw$!-DP0JeyO z-vTxR2zA@AIv`76vpghbU6v#b?}8QCuq+}92}A%0Qe)L+Z6b_7@_{T17%>cG>H?IA zH^lPm9rnS(JZx;RZx09PnPu$wuF zAy}NH>_m5`^#HusxEmcH3M36~&IWzPfXy2QfP-h5(k(}DMi3@#D54;hKtb}LaPYH$ zzkn-pC1?T{1|$&7h8RbH0roqa0FKpBLjI1_r4LvwI~1S>ptQUV42?}A0D3ua8jMYd zEcaB!g{3Lr0UF>S3b z3wDr!2H)AZoyC8J0OZbr;~jY^&H&WmNkGdO=wlgxK%j#gx^%sf2k12xo-_&M#A4P} z2q0K>g@Om`im9VK2~Gvhfp~7Ah-)$KOrkp~s8=nlUm#>AxH9m#m8U?}85bep=&I=a zh7uq75)Prd`dl;@CH!U?;|X59N=``;aL2`eDOURY-FNx;)b5u~-`oPvKk?f^>chxe zfPJ7XI*>>RAY9g%fM%dn;2g_Zwom^LV}UFaHW<#H1Tuq=5~vs?A*qZFMBk7d0mfu8 zSVl7NZU*`LmB7DQu)oy48iTM{x(Rg5o$a@giLC1^GbXgqkxhVZrm zt~1a;(8>V#{%aZ)4S2{@A^8*jeGtIgB!JZrE(2jn02&DddI&rWO(Ou;X& zvIFGNixIc`Qaqh*7-gcjB?aCwL+efo$EEv_C0;oz5{FcyjdH85o~0`U&;K%JOtyfLv!V&61b6t0-h5(pSCGq&N^I(Co}w>?tx~ax3(T; z;8jmcPoEv);n(5;xJ=_8Sf=cdpt(jj=FPh2>60p^4{_Rz>! z>P=idW3uu9rXnIc`1I#jm1^JduJ_X+FQ^KO#aGpot>FXD4>{lIZg{LXJZw3F!IctgA2HmZ+-|qoW81&Quo*c}xo^%HoAgBA*0MicAKP7UbOp zk!UINa1GqxjZT9q3%E9ohsizzz4n(NSM*P@~Pc7LdiN6Q#5P2mrZWR-q+#S zriLVDB>j9Db673%^g(M$y-N1slBVx|VWB(j`i+JAMQ0$`!K3pJ>~}8t83%0V%s)?g z*+K+`f0GhXV|!#H5;+SQpAbB`*{|Hz2x~RW`z%P9_F`i9W9q#&o0O#PPchc7tsRK$ zV}a!RN-}QJN^8v>E2Z7CEinz(a<@rX`U}f>`R?n!Ez6Lr$V%c!uX&Zag%3D1&%?}y z0N|4bL2mW;i8hQ2MA%MRWC_cF1Y5BOR=~qiMgp%u4+KLLK-A)01qY_^1+^E9C$tQ$ zj-`chGH^?=?9%J-$K}xyl@@CYCl6tVI`S(QgKp-|K74I`Ji++P1M8UKYg#Jz9dvry z7FM;C1rT-Rve~v?+BTYo2qlvu0zmgD%J)!YlN9U$&0#>v5^44ho zFoP#b^v!9TZ@1?V-4{K0us^LXkG0q!#knP%upgai<^z>}a4L6d2GZ$oc-C#|*_8LU`q-4P9Z= zpzOj0rz%Z>+)X5i@kAvybO}nhK*;F~;ED-3LtcG}7;9N;cO5R9Fx zgisK=6QbZfwR|i%O%w)VbAUK?IUCRdg&<%w8{>i{*+bb_7i+M$lrWwWAHXC<}wxm);0^SH2%_;e*CGveufT3^J#t2+ZfJ5>`?lOpGSi6mpKE| z;F6c@srsBu`sXVARjj2<@Oh@ajQdF`XKp610e6HV5NeEMF(|Nkt0<|JkSb;S$p>7m zZx^lg7$1}Oux}bkb@z7vKwRs&u9sn0Tlv)gfs5=Tabw@rdbRf&)>W9?nD~I(feW3< zO-^H4zQ46v8rf=b`$urHLnQfTB5lSS^h5k4lD>2L7q{oGllWBL2fe$436u(6r6#)V zH1e3}q-;Lw+_^(0yMUI`eg(a`5kKskdV2r-)QZMJ^jK4gJRTA$LiyKP-nL@e_tWIlEc8rgPDGRdbwKI7ufZ;kCjcDu{6 zD652#z&;V11rR)<0!Lq-2rhXy9XLfZHS}H32%||Cc2@Q1wBxxYTfP523Z;+h7(Gdv<84~nHM(zXw z(f?9zF5*o&?SjYy+4lf8sEC_4BYdUY-%29wh3j#}^x=_w48t4f^DI^nk zMJ*#qHc0z~qMgB?5JjS9D>mS_z`v?ZH?>DDZa7M%N7RU^80qiTkI$8qn=J-iICJio z^J{tj$D12bIc<;_p)xE<)$ou!@cjvcViL5o_5 zrV%ai{>I0Fg>Q%w$cKXDEvxUzO-sS(m;9_NTT3Gjt~L{6Sydm}7DcMg--suVCYJK5 z*fa$$nCRI%5rGGJm01QN080X_7H_jqC`NY{f~%0TKuig-9VF)zX8|M8e+y20=oH3A zj`%lMR~6*}rA$ydnJfgAA{2;N(Lk;M4}hG2=5F{PPe?+@{~Rj-TgrfEqOn1s3NR!@ z3&j2)NdRg5h6*a-og6Y?$c1uv1<1?I0iwVJlt#EfUkS+!P@4iFP7nAELK*}BHxNew zZ3B7%xgRemLBzrbVkbp8yP>jKlLA5F` z%j~G)_Be*h>A<7DU)sC+@BP9Yp6J<@M4u?@jqK0)XH7Wi*W1;P!-w@ahs<_F8x`1n z^Q$K`3Ij*&YbWX)tc!T{`n01-2eVt+&8$}E z)Q&47LG@Lzyb+;9lbCX@>SqI)8*Zt(Fqq_+Th==~#g)5oSsssN)(QYQ-WUVWZ~O|Z zv>~7>Vjr6DRw8`y&i#jOfn~p+*$DLQt7j-UJ~w(%Q`)v&J7x1t<>=5qF#V*D(H*Ot zJux2|#ROsBDNl<@cpr_M$IDklFJ97HReg-^LP^z8bnW%E0mRqyjzF0^LumvE*rmt` z6w!#zAV(3X12XFqq>ca}sVn)Lff}Gd5ep~|BuEMhb`9UB1-}JqP$0^LT#q@63B)RD z{1-bQ`~Zh4(5$~@J)kLAP}2bJYZ3~4{)Wmx9X7m{7Y=x-vu|nzKv@7QMiE5qQUFP| zqnkXso5`C1Kq$0A6p5Y$kD}onGJp?5hnBEF)zj3;Re-5X&KLovkPK`Lig6Yw0{k0M zOeo~+&_H{EpUr|7*(W(sT$5adyxf3$loadl`H}JQr|i&C*_0a0A6UWss$O8l)*YBO z{bLVv?`Zti#vjh`V?M6>8n|`Y?DJA^0hQ3$$q#2&!bjD?8)xu6Vob9Mx4H7Dt;d5i z8^;o3wv%T~R5IujXf17*CV1GhU<-G~#o5l-HAJY}+YC{Khk}Yv3?wkSb^oz94(jM# zJb(JG{e1D;&m48>+o_+7biY3KRFCV=oVy+&e?G2Olzh2Mr_*n|(oja___u5B9jl&> z%Yowy?C|cWVCF*SR=3V0-Hp$2>}~dkQNIFGwoGj1xEu-(bx(5C=`F}uy!le`a_X%^ zhn@_eAAPmguL_Ya`p5b^;mfA?epgJ!=kWEM#5M4vG-hRoGg&RPy4hZ*X>>v8Ae*We8X_n_`P&D66 z4Tj_&pWd4Hp>%N9wm0Ok51nrdcfT<@*mRJzTKKDpYiBZaO`%-2g!Lqt_@Fn^H~6l? zB%~>6b^yujs8B(9k?yI#rjO@)mG{I`?e)CZM!3Tms7X*a?zKJ z=47P`XR`dIz4uYyDx2SzA1VxNE#@7vpg1Kfe)#&s(#yW+@RmJkTaTwSi$9v&-F3Ke zTi1-Qv%^A`@*P_p+uG+|El=kT&o<~AmSMBA*NMs~A&d8cdB5e8 zf1IrPwNHb*3NL!g;nUD~<+K<;&}@~5?>iSADyWJgBm}sZyd@M{OL_dW=YB-dQH8F+ zM|tmeyN1MOJu{uW>UsaIUcU2#5iy)LIf-DTf$j!AG74mrNHhrEt&;zivTBEU@i+q{ z4|2n0Lk$yG?kqrPs44>^0XzCz8DlI#HUx44$QYr6K?fccl=wEX%8h7ihC1Q|jED_9 zGE`TU>4YqdP1tbIkc$N=z`uqlgC=aoqHhJ_>89YWP;5a*z8K*airJIRLA5RyWS8zV z1tLgu5^&mw8+ky=17b=~yvv{ttZ&>{yElPh2m_ZNu#!Y|I{>&~UwXeMkC=?~6*SccUfvFmCf; zx<;~gQ(5h6Wis>B^+C&pqfGt*wXPndK3Bs`Xb z8t3BXXJRtwR{a|07~!3(J+&g&Cf1lHT}?mVZsRUwX~_&o&FngB=ApA*^|_IUVP0$C zzlE@#Nd5!cU)50Yhvz%2anp|)f!I@eR>bBkA76+__Nuj)$Q#r-GSF;ETNh5%LV&B52j%9E~u^c znWuPF7x_>1Gzc=D-n;mVfyr;G7v*;r)R2=LE}zVFQq*tKux+{+ zE*^RQhj&DtgY$!jD3{dpwt6A249_fsE^qg1_=ne4KKpG>1eD@DliVIwWXgHhITQM%2RRdt^vm@7(NzTbI|d~GGIb|c)i3lB?RK$(GdweSe0 zVccr)%bRCgigwt`sy{du6+hckQt#Lxmh7f>`5M7CP&||3A!I;3GNa?JLj|iGHl$OY z3IALwk?UIG#vc_G9;3~hoa<-3)ZVpUrq!VPEvn8Zj7oVWezovLJYhh{?10^)I~0bwMHA~8V_=;X@J0m&eb3&j;QU648u zRz#uM1dsrN1{qkPam5kkW+Ybv2gP*&3l<|-F_7QoRfy3+D(OMc!fVDNXleDGL&*7wZC$Ld z?xj4HRX1h-IWKU&xN)X_^ttMy&vVc9*5ZZ2F8G-GvH7PNE(_KQwVCDCZoUlb=D{Ad zijs+nhlk1RDBcROYPvfKM7J_F3>I7%WlFIi@FuO*+IVs%>vyj4zh;p=61Caz1b6tz zzyeJr=Hk5an5dWAAPasMS(k4?cNR2s_L?bCVMk_*acT58a>lT5AjPy#CmIR%sPvo} zqa8sDGA{po!`Wd)Sc40^H;9J{gUeV+4t&y+EFo5dGC{65VFeHCip~8feH7XBk0i$lD6kcqxyo< zjTUGX8YwAJzt>#B8x&!IFAB$+e|mq0Cx`ihm955Fn&(s6!yfEpzeF)A96WwCy+_$M z)%5o41FI|)MS`_TUHvSwn+j~)gPf%Bfw!u^k6!yEMRa58U2ar3c7%46gnJWHzC(Y> z4ID0&vZ*OYCpWF5>wfe7^chgBS6YUH;*{>p8r@%1u$?R*po%uGmAr=Df64bI(lUYkR0~;;^6Xc6==QKB|57_mc0v zup6!_VkO_X9o8mf>ZJpU^#|K5$rZOJE*d!sDeDmj{=gXRF_*;?X2oj4Qus$+?^-|O zP@T`NXdf*g?6Z8mqOf!LcYPi6wOOqg@2g))?pxeyI{j5F2qPi?=$~e|Z#hj3Ih^2a zLVDC@;C-iZ6)nJh%`Zw&?v4D8i5Uj{4o0NS<@kv_iGxcXGM~f)yep|zV1Z)l02Km3{*5Amz9mTE zjp?vpBvcSKhl>({>kXykyx*%W7)=sU9=CUD<_6d0SWLK<8@w)C@+{N2o?>52ysTrg zG^1imZ~knWg4x2-kBQkNaK^VgHmyaLu<|~Voj32XZ@&^7VLjMXu;lYD=}QFo$8^Oz zE&dUwwI(DgGszLj;oU-sGj=}wMjcch=0Kj0Tz0jYpmIYgFbQpQ7FtEXX!yWOylVob z{JNc)xga|acvnz+#vWCOZ@-&xdXoAX>XQckPWB>adTs%u&~Zje9A|x3Ah8~SNg!C# z_u(Y07#0nhWw(A17OG~-Kxy*`{H!@++LLclLd^=G%^h_32+l}Jise0aO0HJ&pW{TK zndY|v+ix9Z>*{pGXB6$3DnI3JL8+KDdaLK)>SJ81@ioRiCPk!B?|#|q#{47br@BAz z8vCY}d|3t3@w(J|>#f$h3JRLj#w#AaD?U!QmOQ+wBbj10-K@y!y|^u$&zIop3_fBt19>Y}hU&bUl2FN<$LN4f9ZbbPM`S z^>C|RiJ;jZ*wS!@cl1*$@7xk^ii{HXg19dBEb{4q_Ss|mF8%&uGnLS1NK5eLjhL=E z5=M+C3Y{#}E!tD@(nuosl6hC4im?;g((b6m9u@t^7_dTqVyKG-`aRf{U4F&>a149y ziTgJe6MZE4uD-lran0G^w5$VYrBp_nGV0W+n%ria@kJY91@Qk0#u~IY!y?A zDKx{P&oCOR6Afd5Vy3eI)EQxi0`CNhQWb*H`OQa1qLUXizoW*`geve#~Z|qglI;O^pkBK-*v}+ddoTdLU>FxEHv*az9Pvc zB-h4A+rz<>4I2lvs7D)29!+DX)$@90fV>iBQD{v@?p*cSRLcJ>FGHcj(`{Jh$dwdbg zd`PzGC&^!nq`3aT7hy#uQHc`Tq(#TDtK1{-^A{}$QQBFOYZ4zgH+D_R?o8*{WF!dh zY}JkG@SN^xID1|wUhn*;_1i0ySIe)aa%;w~?@uOL`IT#ookl*h#eb&Ut8^;8aijE~ zgHJJzV3QNiA>=mx0-~3UWDF50)6=BcX?sn8XA;L% z2BUlX5hmJl|8#OgJgI@|WglbfV%zNIZTx~8H`}pU$86aHE5(mz7n47p*T2;oZU3h1 zl-x5#S@941&B5|?VUu;&PL+Dd4hmq@x4n-DBg;31Ar>lZo)J`4A1C%S?|w<1N<`Yw z3&oWbTEvH7ykEE8J$iOOIRw4uaErD#a`~RQHhZ=F+b!$2eTi+WnabC7&sOwx|HQ?{ zYz_rmkasNa8k1^jzh=xi^;Bj}g$6vfw1r$5 zeb-AtUNBqUXtluE1W-N#OX9_)e7fM+A+NL1xF@}1q!bokKMxF$Rm-ah>`G@`@?{c;rS*sP2tRB(SKKOJ?y9o+5 z+d6q=LjTt|MizbApyrZ2;l{M+^ATgqqcen;|Y3*U)!h z_P75cQ)j~^5WU4)t9ip#)QLu~1 zA5TT_4&_v95y;OYZZ9-+bx1oh8qogshkvIX&;Z+@Q>P;NRo1#@#nhDRu2T2Ec#JHD zgX!@EG3Ce$@|oz;Ov=K$Kd>>%)Sd$NqNa-Tgx0yAnfc?RdC#i5&lc?pM&7d;;pQJz zcyDHRlcfr;Rj}|9g!jN{X`mM)m^(p@YO1waWh~-UXR|`T7}@@w`t!hDu=r zeV{o68q>fS5DO*dAg(WjYWGPlAetWLRR|mbJx&uc*%VZlVIz)U!qP$^=th9V0+&z{LBzfFKC}1QVb`i(5G=O~T8=uu{E#_%T4_#p zf6gXe2km-qQB%)EVe=N)dn`^^_|=bbTVM+K7VhD&e@m)Q&SrG3ThFm3x!8$ z4Q<+oQCVS~e&@Pm!({n?b#U1YJu**tUU(hHIKcnFUI(3!r=>8iD>w3^m<(-dG8&Xr zb^EjLepTL7F@0*8+K#0mK$2Y;*-mspo$_l zG3uiqY(7Cq+kfu>v01{(SXn~5olsga7|W-W*La-4Nbv1Cx3{-iX}$F<@^VD5V{B^d zopSZ+{hIhY3oPlP=kSllYpu`taDk2cx`WR>%+XOk6DX5F^*Yv+@5>t2n_}!ro@*!X z=1MNG4-IfsKXnk^n3Nu*35@0Tu(lM#(lJNxAHSOI;jdrdDdAH01Kxc1!4AUaLZ=4( zca-aHBuv|lgS_(5MHa!l@zuL6 z8BE_H@Hn9HYqcr0q?#v3zU{2LIyAprurm7VWsv_H>zMoZlA$;Vn$DAc&mRQxj-g<( z*X%|wQvsy9j!=s=6e_)esd9p#RfdH+89eOi7qiu%9SYhUb)aSkvSd&`19f|-GX_l$ zk&jH^rd_VRFmeFi^s?t?=~#GLi%8aaoK3Nm?6xqC6yeZa#Pf|?rR;0t6NS^10-K?OOYZfO6%A?aqf{xP z#c(=9g$?WOQ&pjf2CstTd$JtuX=IJOhYrof3ZWyZncQ{Ija*%0D3cHN!E`!Suu9xa z!fUv|9Xgo#>;iCO*&*6}j19vVeI2RENN}3TJ`qP_OwhuV$sjYBV_BMGl+BceH60}k z-B)j~fb|8OstF|=hqeEUrgH&jg8l#h7=|1wQ^;AdQF54=vx+&hAtjX%8&5JLnS?~O zhan2fVcF)CDMe8!9T;T}b1F%N=9DBxIrYCi-{1ebTwSBgF73YW&;5D7-tP|sC8Ukt zO$i|_GP_tpQEn3hdGY5>RPkM?=Dd!8IFzFJk1$Q}SyHa!`!Bpdoi^9{&&Cb{rt%pgCX3_TQ-Ljn65SVr);&k^e&=B{3I0m1alXGf% z@r+O;gd%&oaduio5m?vh3r?;9aSXQNC^c7H#@NZhxUDofnNhFEC=5v!g$)5RT!-v6 z0BCp(SwHL|6ZF_eli&MU;4Z=IgrN>rlVkUp^x&m6=NEp{FKck0RRh<iiY-9B{s#k3ri?GE0Axb#PtZf=3*;GD-3bYB#3{gY)>!tBpOh41coDIfU$ z+imNc;xH@R3%+dS-Cr@)>$aE1*TbJ@9->vOp874wTpyy9J{ldeah1%`;nm$5Z!UJ z0f|>l?(3nxXOtl(1^_ZVK!G(0%Vf;D{O%Dj(&M`g7$`}E&;>>lykW-nO{=uZrQF~i ziimLDohgj7U5+g$0Ws@n1}^R@od`6uOW9KzqVF{0Qex-iR6>TFtP9B*xE$ZD@#Qj7 zffnITXdYMdI|SOj&c;r>{G`Gd23vzs&dV3WGrO!N;o^S&iL1;z3Y#SXU8LU^;0EGmtE1=+s+|s#6AXmKs|)Nz#Ab zUM%Z1TjdY<79o=tEBz~jM(7Xe*_ zpH9Q!+gcz%$!OWLi57B!a3(Tij|9NOd9bzQCL#Es%nly7boUK%Lx5N6>d*WU^nV-L z&Y8SfXA8ty{6xAjpNZScdRcD`fMWyh8Nic7eJ$ssEw(O2n+PQEX?%JeT}+U^cG7a%L&v$*%U@w$wA_MH^ITTnV!!m{*&&#$IGsKWBq8TOb zb>axl1g0J?b&3rS0c(`vX~C=5*Q)3K&iU4u)Ms5#=@vL)j`#sG#~fcneC!68hDm;87Gl}lOrnJjeB|u zN1GY)_p~$gKeZjA+%b7pt8AX_=fFJk(C8)-6YX1?r&8-gd1wfO*Zm#~JzHhu5%zGs zB+};FZCsQKvBI?0t6qKi?*33ClqWnIXr1AOHEsCdvrH|Zcg#7+2@Y}Mv zsdex(_*1X6@t6vXg}!+e>&B^vbf*F93G#->JTDIvYM?$PIlZL!{06ca(5i&&p&~sF z2!->E-8_LZFVWA|?c7HFrP3!ayM1*wA2rleN2@t67=DsHwB_MWco0BQ!aFPu!E>h% zxr(%i;1)Og9pHJS6+z!Zf~&~grvTalAt{cV($_Npf4Wel_dpI%{D2;&ZRi33cPU;- z-X`I>4)z|QUFrZY;{l@$S0CRDR!Pxje-G5|PBaL*^cJ{vZjwC5hF+{(5q$DPSAPo1 z_mrLUIW#Kwz8#g%(#&DSYC$+;r12l#1pJLy#kAUV)l`*V=1NsXgzM6t$D^MNd*%0s zQ9l10&9NRFl-UtO0^fuQ)HG2 z%TdxI?#_9Q$&37j#KoB~O^s>YLYy&o)x`qT*ArLO)p$8-MF4q~^|J`1eqj8hi*Udl zSwN4b9}M7)QrEC;D99zyIv>g<+6sNac71gQx6!5sCOG>SY$2nC=(651MU;W_iqg=& z>kWDFve}76F^J@yk_Ngpw+ZbUTAH=WJ9lbMvaK%${%L0Y ztAjuQhfE`%=JjD4$P@^p>e#*xDesG4f_-=U!o;3FyKFwVlPo;qe7752^9=Rrd(@~V zt+Dp&^M|3`N9Mpdft0UZO{U#P)`O0Zh16Yw%fIT%H1}A}i1m3joOmyBIdg$+@Iub` z&Dw5jfz>lvRPxqfS|FJ7YD}B1yDM~VYb-QArlzVMz3rWIiN*HUE>uyeFFV=lcQC@Y zC<`o8o%3Wv3gv+$#`Cqaz}eLYzXz!~W!Q1JH7 z?sUoibx*rOb9|8-Gvrh8=#iqDMO1j003CSRp#)X)&L$*tHRTs`6@~dN>ft%u@#rTi z{et|2c9%ojgy1g(xtnU%EE;E4?b^3Ys_QkbZ4aWQ6waS4Lj2-*b+Gjbc(^LifG@CJ z?Mssot@y3E+gkLIqQGo64JzN=V6n8QOPVj1<|z|x+s|gs`GOP4QkE5UYizr0(20Oa zy$(=iOKEoiu9~*s-VJ~<256OU`WgPu9wiLmZUEr-(17y%ABn`GAC3myV5n5jBCufy zXOa=zJ&=9c-*NMfwscWow*UoA@|=qkSXrC06rC56$%g170NScZhXD#Vlw#}%l`p!R z`AMfH{E%6d(qjXi)&9ueSC$OhTlOFs!cSdAR4Pzd*MmO$4vAR?)?|CvONl?w{n}{c zCwB;(WV1GpSw?DtZGRz8kc(iAffqNB`6^2su?WmvZ#3YZaiv+!Jn-^0jDa1>FhXa- zrMPKQhnHj4V$f~TC#O~r7Ev$NFkBCoSn;c67Kg2_SRO6^J_;;WCJNH9$S|{Bl>38= zS?S&hnyWdeXP*0B&tS-iWqJVMEUoLrW6es_ml!Ol6fQ8go9rocWZ$0xSYWd^)C460 z^P04)EbeHCpnjKvAp6>eEyG^lQ7j+K>N=)K{`Br+^KG+XB5fk$`=7s%qv6#}^)3zP zO(X1s4qSONZlmTr#X#(tQ}9Xu{3;~jQDowP(y7ND>tnv1sXC#|jn{c)Uym>F492Ul z8$E@ID*Kmm|3W_Bbt`p;i6~WCUHO?=AY)~ZTRL~zChW0t3>sLY2da$o&T^ViH3(?2 zp1n9by>NUn)b4ASASdyO-lfLB5Shg4+v`0iMC1COA0WdoZLLw7*s$LH7jh9CmOsL; zHTVzPtaAPg%onz2N#(G)e-(BKbC5?9xxnwyqMvtiz1mqg5~@L_~S=!^X?@mzM#FC zhra1Xh@6x5{2adL!TpVxjNNR#Gx;>{3g_iBK5Te(h6-%sAac>9-xqmD?RNnNJn9Ry zHoE^8A|d^GjqJAZb;IY4a?XjCuC;iVjj0Wvmg+Nw5VV!<&(1-u?KRnVN{8Z>h2Ed> z$~j@HAn)Z?zvEF=!=Fs;njf(}?8cfWLQm;i#H_xA`JNk->(%%0pegm1MU#8AGpWe2bwRSum7K11w2IHaI-}c4F7ZZ0ae)%PZwWsDFmP?V3J1`W9hJv z^j;5TUbpbXz^&U9cYBC=vKs)g88$W$CNu?P7$!*33SeF1N4z2=brNI7xXSRW3 zRg!x2$Qh7zn^UiY5^_E+qW3FZE$m&f92`_mS4#Za`x6Isc=f3cMFsk%#uY47f?oBT zL*6ma)jQP2yA!O?X`AVF^j)BT1zy1X@LKQjU}mo4=HGi&HobWy2UeG)1y6yD9mZn9 zMAY79@pwSoVCkH!tMl4A@OozXDFoI&e)6Np{3I3(-YKsfz)g2!)1GY8nORcTlFW z1){q6qBH9}J?Keq)|XzSJrr}i^u%@c5p5eIqJZu9m92kr$aC5~L9gOr-)Mnth|t|m zwo}U|)eL}Rb@Y_d6dl{tdE>t5ZeV?)K@43l^rwk)ttpU~{n2;szmxohR*$Voe6H7| zzAeT768qdz{Gg{nIbZ(6)w_u?g*T_}lC&_dgO+cAtxb ztszYsE)dwffmkD^=I$xnfclDo$=l-kkEy@iE!}>kjll~Tg*_)i73zXldS)F!yO9e; z6;(PQpuV90mvtpE^H)u^@18sJ6)nI2LUd=sxo_4&Syz9HoRMOA95nRt@<>)Tu**I& zSuGbH6t4}xT1E(KnvZ#y%UOOjf3Ppqf_?JOvM7A*dh^PF6Q7xN!=2n0I(3q5R?*7I zJK~O$t5;yK_Td9foAeVU0sh(~MqR9fTu!lTX0V|R1uPWN8NCrLZZ|jpqTOWb%98AO zS-d6sylp#}uRI{NGI+H7o0{|ZSFo4rRjWlOY#wJ8Kc5L4S1 zUXNC=b=^>s1K~aEqpdUpfRCG%C&e{@C-k2?38ugr8^{58?3Uj>PEz2*-Azn=VM@C^EdqT5lA3GbL~`OQ58PgAw)Eh}D?k1MjSiltwI2V-qt0h`)LvZ%Hh&>ta6#&%Oq#mH+m zH+2LoR4=%?=l=q+aGrIFXW$LnX*EY%D<5I3iq3&^&yY%ceB^vjRcs9 zmqXXlklei`(S=8TkNfTqXStp^F^2Cl=}k@&jT*pud@?7XP3E?MC%vvE?0BkCL}^kF z_U0ecgH6raWqGZX%Ad8*l}C?ZRyChUPOPCjc>gV}^5bKHjGw7QxkCT;jrp39hVYW# zf52k$JN;bSLF=n|(GJ@cvdpBT$sO>-S8EPDedYKk4KwgWvb8!cxQB&4iMYHZL<--H z`F&Ns#cdZxU#G5hoZIjQ!3==$l z)jVmewNdN=YgGqQ;!LMi?_DLO6#7ir^gr$%+}?5cDojMq%b8a6uF~3`)Bv+Wii>O| zD|PYoH+s(1XLc4QggZREK|GK8_eo=W_>Q!p@hoeH@gpJPHN9T-JC9Vqc!QSbIH%Xx zsYu6uohIoSU)|>3IUbE0Gh@j2l5V^Tq9Nd3FnT$A&;BrHh^U&g1$M>}+N6S%MhMC@ z!1_FiM8Xl4y>9z?6p?oI)i0}*8Q3SVmcN)~`5t}ozooocnQrRfy>-B#wJA#4{b#b3 zhA1vGAys zM7BO&p|Mh9wSQYV@+F-1MEOL)$Z^L#k25$2>3t3I$)(dmT3g#Lbc&u!6A4z;dt2y# zBGYd>&Mw&j#@Z(@dcBT}P2R+5)IlT!kcEA9*d7y~56He{;MwdW>u0~7Ik+XeB`QN> ze~I7p>)x{q%KiKswNF9)`QZPbaplG?8^erDH&-&-T#O)~B?uHNPA4 z))&@hTutAEUjKb?=zN+_%$JlC8AWf0U#U2D5&a#={p;rIv%xbrt?bYF<(WT0PxgO1 zA9~u}?i@+wmDoY_tk+<1@A2Zxu^P9AkeCj7pO*V$nDx=Ms&DW<+IwX$EvopKf{!qZ z$w8Oq#3~&e(0>tKDVrs}_tT}DmzL)D1@11neZR(G`fH80k>NOPB-K=hB-szgp0fw1 zWBRF6Qzv4glnh(%>>PNqVrZiPs!Q>~)r`d&)kCYVGv}0k9RE?mihP(@eXg?V)sL3z zzg@^NJ&zlY%=TQZkC}YgXSArfme9Mvk440e54ZjK~=((yJCMl3-Rq~zZ&+kO# z2IKlmMHqj8IX+p4i7E#dxLFWkLciG8j8I){LQ1R4T%B^T-_KTa7Bk;gAV%gtX;DM0 z_#$DS<@+oDue^M*r7uRu*%N=yVD>*_Eg<+o-3L&8mHP%|xi48@hW#cc4USe20r5YK zIRtp5vJUsfIj{pM&$0e@znSRdj@*o(pdppt9pOkHD zLcCAV<%=r7qh!8WWlTA=F5bCtx=l**-l~05fu9c~{0a+bkY~oqX_*vN%HAZ- z_?^(R@LsK)qRo~!a;^T=wYHya(T6FP3;jy@j+o=6iJxl%9G0a4O4(C*+Z0$}V-$0m zhz{0iq=e$?rSJ-AL3Aebl!7yWx|04W(^&?w8@|$;%tghN%Z7<0r3F$QWtRor8n_H|YfE3hLf%zAOSTShPXhC$SGerrbbts9M5 zKi^S4C_PiHZ;N2WHk~$?bpJl0a8*9&o_SM)O8Cu&$c3lmT9a)-Gj5&8-ctIHRNPbA z{Za8HIu2_0B~p)6`1ow>o~LIN#(0lrW9kD$p7|O`BLel1J?YB_QVEBDY+r#vuFC5S zX#z%4@yzL-Yb)L*gq+ohg__vZ@13cX6W9;+!@6kVu|e8f^*8=BetIWIlxt9Hf_=TG z(WvEAU<v>(bh^<@kcVt|j&Bk;mruzlT(R z7*^16f+?8zqJ&8UkHV%qTJ<|8Nb(&~4%G@#$c^a45&1X!-cSrwl2&@3_wQd@3>&*} z%D6VrHz@SfEG?5A%}crb5PjFp?GqU7q=aC*{sTPP zo-k$JyzO^W>LQNjzUHZJ#$t?sT$F(niu)%5ULlrgg}hXEWu;prE3`wtziN#!Bq`(%CUdHbFF6vldpR%$fcpDqq&h!vFw@gUdDn?L_Ztg z{#>q%U=G`FeoFwOL;g@)7krja4H5k`njvuMKs`UrC`cwKF#2wNJ6AY#)Ya& zrx_jK@wp3CdADXFW98c5acQ()D&`5)Oi<#2(i!``=Zix`3AWJ@>MXwUV?j^d zUV}4+3DXy%8PjCpCC;L!-S)FhEqUGIk&Ner=XH&xV>{~+I)5Q-H-=TE%&Q61b^;LT z#l0|Q%q~=&XbqxVCby%9c1WcVH{NSJlB*Pu%2fwfv~Jd1pfqHUH>EUWw8mr^}7wn|D_-?ZAJd?!j)J5#$Fi&2+fqgm2w zom{eogwk@}-c?{RvLr{a%wKNDSd3h$TFlsHkdPD2jMYp(ZLj0(XA1`eetVogBf9XdQ77J)pCD zl@@^yT9BJ_!ah+QBX~4@oFHd%Q`m1b0f!Rs!UX}-M zix@+yMc-Lns#EEpT<~fo>%O#4_)P(y5nnIhmmo+xO@qB2OT|>rJ;EhaFG>=A)%ri@ zVl5(JVPz4@E4@;km{Tm}(!K__T~{yFyTpgy^V=d72{ya?t4pY z@a2wYp`J1xCfIUmZ4Y5aC%Mm9*14hXdTzw2?d2imihW7O-2)B_$z1(~!jQ+VoDYj8 zBWEHOZx5=Fj_v6Ra(T8wLnrr|#HLT6>1|fw2*>7m=iL$f5`(6KyU$b?BNU+~xo1v~ zx}zex|CAu!mhsVJ*PW8Q2v)X-j6iQIDi+Y8h$>^1O2B(x#J}F_O7dJ z(ZRkW81RGBe66_3uf`9U$~fSMt-^J<7k`p|cZWp5w5b8n+=OOo-8o21btd}Bcz4J- z9AN?c4wh4f6Y#^b#AB+Y3AS+ThCun{_Ye0P$lXVk2Rw#$4dlANZc={P#yvZ-7*Tz% z4n0Q^?I<$F7(^L+*DF?c)!BIBce)$qU<{gWqozp5N@pu}hEPvO8Dmh5)$j{1Pa*2dlpJd7WeNu99yWoI9*LJJ{i-=8!U3-_g@5-x#ouxyg0#e?VQ4%^P>06 zb2?2CPXjsyf7eoVn z))f$a2XQBC#ttd-Hk(TUJt;0gFF}{R_;ikCPWuZXK2M`TZ=ZX1scv`-b+2!1;P%K< zMs4RZe0AW`oqkNyDQiJV;&RsN!2RLQ;6b@+T^PAyu-vS|1g8BZWvEh7#`p+h*zx(G z{s(@kk=#h7;!pE0y>4%lBuxB7{~eD)k7kK>nN=@bOtGY8+cyI{cZ4tsmRwZP{$5o%ObnQHXYN`1X;%008@I*I?#AtU zU{~@<_Yzv1|MQK2X;_N5xI@u53t#S{?ALgyj{=`W>_rr5-^6YKGavd4WoE$q8+}o>a@r_9Tmc=w{mKUS;?zRs|RARG0$`Asz|A6BU$)* zrR9|k64ZrX;>=#U(kX4}p*Y9O#9JRsG)V=U!f5HStYSBd4v#r6ubqg$5cCsV!Eu&@ z3d|x6`O0x++=sL!_moK!^5Vc4MXI)#SY*mkH*PBG_0b5N zdga&O4v(HuOI0QFtMXJ3d&|N9bJUJ!-^}=Vo&JKV&lI+)0*1>b?2A*cN4 z3MAg;*R`m4+wuL^ZRc84!zSjAgqvRM-BQHhGlswp_3Z2V+&~c@OxtA*ljV|K__Jo8 zxcmQ6ZR_8Do@-{vxfG5*wjz*^*v?ItR5`t>mlI*tB6PcCfpV$!JMyr{IxkVOBqH^@ zLxgo%2Iup9WlJ5Kcc5~|t8Xv9WtY!(uV44tOK>p_>pr1B)$nUNx<}uzjh{E5soGw! zE5CS={@5z~EK0Gq9s0Af_w{#72j?eq-cUBM^P+Kr?qR78Vg3`;&lQ=Yw5Q?Bms`?? zBvk8V;ZLNoXA*X~8&=#p-8L>c%=AZa!u$uN`1~K8*IMk4ZK1e&x+6NnB!P1Xh@0?S zCCJIXv`y6Tzb&B?=$e}`oIv0Np^@4EXyihS0V6a548HqOSP-djrH68WpAWf+eV$Pl zm<3YW2r~;T`Pyz8+vp6bIQ$OhkoY?Liw9Wrqa~M6@oq&=L-2pqpFQ5 z7gLrq!2A?TPYp(QU&Z(~5D`_LroN77c&8l#`_bzcqQ~80Q^7QXwhloe#we%JsL|Jj zy<38bwvuL=OpHddyizu<)mya)AxyMTm7IXLyDz*AnsQ&b>EVvdJm8ybd(Feoz3=Mo zb=||)9(z#&Ovr-r9bEL;W49rc{10XmWZG8w$J@y~VbaX+-r^k&)5v6^ql9T;j7^aS zX~r4z4vg6Q@T9jvb|gN>QDI3tn-P%ERCz%4L+N+$uLKNk1Vo!wTWh6@4b@YwK`)nn z->dnyS%Bi_KM2x6{hr#Fllm$TB9q$)datT|K_C!QC0wm3$7JF zqiRuLwgdVN;*WL8ad3m|Q*6;e1#SXx|0QFt0D#h75e2@N=IrI<3fTriWz{uD67ZiX z6MrG~wIi9c=g5N}C=+&k+@G|@&$FjzoK4Op4p42)_wn=MYNEr2V^~Vh$;v%#FuUg& zd?1p~UR+)$II!n1521;1%we~HzmV{FASHw?3}lAvG>uguCdx?_VhGjqhIv}TeU+!A|!o4 zXX$>IpIG(tx~6>pk6rLk`G41|t?)_@R(ifS4{?o-tbYvRJ#eV1W`v_l*aoil2?|d zjviAg^?72M5Ee{x5^Ap4ZuWAV@`!rPKvyO0@Wl~n@nX;2Nceyqhp_xfFKFz3C z>=|Ae!MCyE!^<+Gy{3KyubBbn=Vth;zmWa#ADW6r&%EOl%WH=}I}@Pg8U7121Z1wu7BvTWVQw@1GW9MKm3TT$}d(PHL+NvyVUs z2c@g#_O!FC5Pr5c=Rra)lony5>$K~B8I)8YQP!T!OCq{jZlEBy8!J8aws8+Vrd?35 z!V4#=Po!j14sF90_Qr1O=Ism`?$%(EK-#SbDqlbkq>9<2;g68{6EKz|JEcWfd&l=U zE_#-tPr_cmHs{RS4%yu;B4ukeb?E-2o0Tx^ofPHKy?=J*x7tIIf2cBcsIpjr$@v3y z!$x$9Z@BS|DsytT7Md9t<+Rd!DEMboSlkh#&pN^kNkEebwYOei#3=~MiyAm65%;nr zEhA-;vl?1Z{@vD`pYLPL@e|qA=`M|qIN_*xXPc=MtuA{gh~Jq&ausjsNH;7Y2LUVZ z8*+aOrB5nNXTBmr*36Wo50ZfGfP50ves_RiG$=8o@<%}KxA+c>Ilq2!iOt7_CgJr2_PdfTqsfiPB(mk8*X@C4 z00LOnd~iY3NFsw@*Qq$8qG3Th}E&wB6x4EEC7*FEq@T&LQJ{Aahkc?xA%(^Yc?~tk*_5&G18aL| zQW#_y_k-i!|1l`F$?0{LZvBVV=lr4<*Q_tGQ&e3oH$l5QO1*X`t&qooT5Yf^)I zI+K%kcO9ZdI$2G<8n3jJ#71L&^7;aqXB#58&Zm`W*M{dg@YaUi)ViYP>{2K&J-G!# zQLpuKc()tZ7i=Yc;!r%8X4b7a+UZU!*sDtaId z5$QJP6=Ji9`wQU zr>K@Xl!dx`Z_G91AE^mAB!lC=7~7(;yC>&&w{VsReB3>*><5SJIiWz8Sh^>#C*CX~ zL!9!-t>wVioWNvF#UmkRYNOTTLAW#nY0P@Y2d@Pnk^@^W;V@*syGAnMt^``(*D1oFqoKJNnW zJj`rOGxlp8{&qN+D(Icc+`C@7hO9X1OJ*J zV?HRm#OWGA%{{U?U*47$EBs4t?O@(4;D#^w%Ix=-ZE{%}?DE2BLLaRL+l;VQ{cS)8 ze7*hw7zz`fGC)0ST)*mlYJ@Qhr1T5E@N*>t$rs0(RJr1_&wF<+r;3e&OVMb{>I&`D zW1Gsg$#L8BfulBalGZ(H%c;bYa~B1SRlA3MJn;39QR@!m#TG4ejX{`fHrM^h!$_k` zby4c(+;=lBjl_Y*(^Zd`!6ChCwJ+YFZ)#cA&vZYVWHXd*L&;n9%wDco3W#SKg9vIvFRFJdzaPQNd4NX0_;C#04bLPWfMg2M{L- zadeS(D75zq3JvbS37E?FBBLYWQ^UvD83w} z{%O%ca}~z!ks<#4%W;eFx{|k>fbr;M5H5k?hNqZH7RAj^Kl!NZ9O{-@>k?m3h$H{%BUNjNbKTOTRT z1akX*VD%{UfEVzSc7oGfd9=VKCA}M(U+86+O(TlP)D>t=Q6MMZ(`Cb4m+9N_LT_R9 z`@Lvk>vLgQneMre+|dsrP&a5X;UiusU96vTa&ef1@Sy~iYu~;##TDOju=463}y84?a6OX>a}_`)^;0H}2|eMYnM0WJxLDCX=L(~V>FRHL;r!yX zs?TFEnbQ6^+WKZ7(os>hE~#h7gPdR6C=Zplw>A>J1D^%JOrk8V=0;s$RcQP%TO&jf zGru`e4IPA9P@Yez$k2TzapqyUO)uri>k* z;dCIy?NjzZ)()xi8vOPfUJY`8$_G=N&sc>u1egb2j$h$zkyCV$^e|hQ zAGy;tWs6d;HOyV<4nfa&%2C`tZ&aBG6OrSTQ*wxeVhXfO{TycDYW8PYrrIe$>O;^K>}X=6;Ufbl{z z|4nP$oC_sJb@7U+B79TrNe{_?vxd-GWPKdTmEvbKM_3UKt^)MT+=3^4rBw!@Sp*14 zUQu#Ji@umad`}yT3(+>fPnu(U)lM!Z5X7x4dVA-DTqi#MEY~LaNWWRqR#x(~ov1ej z1*`1WlQ-TkjEwTLIc*>?m2^eTkJY%3YE@+lxlHcM<*b(7yCW)LnAX8r_qhUg*Du74K9Rp9lVm#1G3LgtZ3J zy$ckXU%Z5^KOw~~R2m_T#1KN_Wn(seacG7X3Njo>t!sowC{Edm86jE;v680gl8|$L z{@84n28gk(aJrILFU4&wnh^_15(g5^Kga1wUL^e>aTq6q7?#%mYTJ%;dp1UU@VG&t z1>5xnNwWR-EUBU7)*XV8M2kU?vJ%015yDJq(b@GRn%TyPq{Bjoik|WqUF=;PGAt_5 zm}S9zS@p7VSanhSL5`+Ck?XQ_W#h}(PzAKpm|_}45j(Z&nm7#4AntfiT83i~YH zQ>0^>l+vSoSm%gl3X6z3Ajgj|?W$Q;FgcA*<0*DUZ7AuUM-5n5$5y;c0 zo~39PFW9AAQLNG`Gj^B63uEx@3d&ynUp`(=sz11Op~dVl=n;w&kT-1C2`|$`5m$=) zHD7)H)B@EARAZwc@jiF{d9&X8$7`VHVMbXJvPx>KENobkVqkyt_>P&!l>4{NQg`GC z{j1W*Y13^xDsSzYB4B|q5;L>*icygoM@!y)PR~HG;Yh}n-YwZ<0){-&R@4}pW2qQ@zD%rrO1O}SQP_xMf!xip`F`D?v8D0o=C%m(0V88`?9ez z*cxvYFUz)p=L<>)wq&42B8@>gQ3a_n8(|;0e`ROFv6f+xV{{=2kDl(m86>`0tTC+d;h!fppqhz#h^ zHtvm<`ZVKy(%oq^pDarz{jA?3u{(b$K5@oV--0`UwvKQL9CoFu0I{ zmg?gC<*>6!mr%DMvlPg`DlJ;7kjnGK77h1BAqnN4&(wbHmlU_>pAf>e;vq`1La+Nn! zs$7Y@q-P7ZX%jl{J*}7F>rJT^_%*yx5@}e8Y>4{8utI)xAO|L2J^;F|L^D{npaPCi zAEVI>jBS;6@U>Upnk}&v_A!FnA+)w@6;pmY7DQX6HE5bW2QqWP*?UteXkUukt@#6B zL?rgu*AZM-PWrrkQj(<|}aOb;qV0ZEh+j+se#37#X`U_kt^8y{XDmEEPZc zZ`x&5fI<-GTng2u>?~=*V@FAu&M^1B&_dqCNLK45RA81W!iJXwk6EIxj8ZS>SUv65 zh{sY%_8RoS(L8uj#rUdc(n)@jj2Ux<*A0o6bdT@J*$iNTjM4n#d6Lq?4bS_UD(StM zQ?93J{$3JoeCqSMYG|g%0#~6G2|V18#<7vS87F&jQTU4%x7j&&uXJ+%>!_1}&zD4+ zN8+bW-mqM52)Syq^#(#WIF zcdF5GAuEG>5~y#rQnjKN;S84aa`^2#FR%7u)XYO`p^7FUEePdHDAm$jaK9G%(>QBqa{!oiUl*G%(;+Lo zuO!->JwMTZuv<<|jXE z(UO-w`;rb>?{U{!u&UgZBqj?|%ODEvs<}aY^+lGJ0*DsgTGSx8^CTT7=z?FZ7)`!9 zuXM6C$8wR?3GDl}NMaXU1|-e@$$)6vI2*RHK#Nd;esH@TU2Vb+M6>{LM$Qh5qyBC> zP{=?f{k(7|Qiu*&DpyU^C3OBMLgGdCpLU6fw@5@2NkL2SZXWF0^^5$jD`z|p_f?8%HA!$Y=fJMrOgg@9JYoSvyJ0PFqMrU zh_)@!3<%>C0tzzVADBhS(Naq_wXVBLWGeZneyY%Uj>HJ(rwXUgJc$CPj?Pd9#98J7 zL-Y32k*pTf*L3gGPbLP^X#tirY;j*lZ?ejyoU*&UX?d7GbsfnZV?jg;aoh3jQ)^R= zodhXQ4}VW0FKZi^aMIAC&_#9@lO^jzC2Uwa|KO4bs2H|^ob@nnqHvi3FIt}zvg>qH znH0{WC`h>2O||GtYd}Eld4)%<3p(c~rZB@5$+`e`iXwz`QamoCXv&f7xno!HI-z-j zrLNjXauYwYxXc85hO`Q-N&VmiMZ!#7W~45^jZXO|FeTYpR?W|DikGJ{6)oMYO87$J z(U9*3Kxp2()9(e0;zDd;&&!oTdfZ%OJL}?i1v<{=lS(5&*oy5{_#MV7UJpt6pY zn`%F3uk+?gNXIkZs!be?`ZY1*pP%yJ+E?%fCgbj%M1qLMdqH%ESx*B#E68(#cH_!y zTRDQC(pJ6?q7@Zo;gfGzx8UR9b>!^RZV^tg6|yLEvAi&}#5r`vQAA|{gGyl|)&aTA zg_R*cALPfAEY54vUs&sa{PN4=kQ8l;Jy9=nACb5>9AEJicMT~PJ3u+7IKwNJ!C3OMS~$Xm zh3PB3PMrx2@NqOhd3!8}UYV6qFTTXDcCbFhl9FIQKU$_ki@NdTf;9*bdF%n4jN2@g zj%PpW*-C6hLTHz~A3~{yz8~5ZxVT3`UNc@fy+eS2qZ$tsd}NDcNtBKqx~@3(|2R7L zcqae?D%7d8U2$O7~*P2nxG_XWH4%IdzT}h+Th9F<2Im<^Ut{qXBr( z9JnSh0^EWwVsQ-QCiUu4n)B>*@yzY1fot=~*6n&T9AMeqkvJ*bZ783fDEJ!ysYJIM zTR(fY#Gka4$x#`n;*~8{ySedVifX5WeQLa5a!wS*=ImB~8e-dILIlh*Io((J{TRWt z>H06RDC?{Xx|iYn87~mTQo<8pKFw=I6wVHr;#WD#EkbQOe^w9Fi2z1!_#&dgbiHZ^ zd(N|8jQEu9izLDvr}#fmzBusyZ0Rn9b6olg%SP!Crt!DbPLf6TmAR@cQwYxj*@5xM z8b}XGaaM2NS?jHj$fQ_ABl8!9osJ8zk9}!$$DgHxEb3qMh^AI=$6UUbqE*D#&EHR>x7tpU&Yn0varg7D zN#5e)v2mwKwe;VZ+XQ!)+KZo@|B!KGGae}w*RGfBo{BLmXn7U0<9z@^qsgO2SBOm+ zgpTa1{d95h=AWDUe2^&=+~(FvPUPuwdoBt2%TGTeBJHcUY?oEE`X;7J5A#eH$u|Zf zF9|vd#kUMtn z5%f8C8VPrm{)tR8>C5?!^3_w6X>^y#`JRM6D(jbY2=@hf6s>Zet?1k}L5H;pF|8A6 z&nFucFbHU49N8(O=PC0#PZ?rJ3R%R2cKx;qx{j(rdK}q40%Y|WNbrSOI-j~enAV9# z?8H$$9;;TGuGE#%2ejp6FPy5x>Nb*68c?rU6kO96vjF5_7(sWE6Gy?R9E@%xNp49A^A#@4NDoRWim&hJPNqQ{L{LG{67muc#dTIdBQ*Jcook)!VnI zS6>@t0qV@oSUA^z2-H&OEO1rWYYvDJ{)74TO>oub!UyQn!0yS9IE~f~aT3a>!5V?J zOMOw;3_Sk{rD;tHwWiZ@kb+EFHr`=su_GF`wy_jREPmwePzEV{ME7ue9x3`n-(7>z zP7;iRT+kTeYU3h5oJN!!E%H+^VsKhQE($dSs{jHh zv!ES4>p2S;Ul2p1lXk!Xz+1bx~$gRc;wJkj# zAU=H?rpwrZjF0W4(9{rd&MaJunhk)N+BAReUjw>UmiG>OA{ZhPoAk8OIKUo)hOYo@ z$+hDO{I*gkJI1!9VJppaen16-zSEU3!RRnO_t5ciPw2l{OJLALf9h$lnXB$&wVw>Q z&W?G0Zt(*1L$SS8pjkB0Xr?dE*w}Km$#(Tj6J!mqgjN@XMm=C&M{*_c zLKB1_+h>7(NMOPteMDcVw16!~V>N*kMa8X2LI8I-s|%w2^7|lX?1MVTkmA-*ifLgi z09awI`oV?^@1S?nT)O;VEffz0%s2e|+@_rx=ry>c(JS;dhzxLv7|-}Li4K=IrWmcR zXg4omfwxksD(v1h@lv%05zzMqs(Be6bjR^nk0Uu9PY3Xh97M-kLbdXHkO?htqmE zE;}+mP)^pj!8x}-I(%UzQ-b`8YxB;fSqGN39gRrZK72`L>kLkswQ#<$LI373ZKC_R!2&}&mcbsr9d<76o<&0@)t_6k`eIhz5eQI zH`5Q0`_;SMoTYdgKss)k@%mkkO6oMGujg_sJ0)zYXU}SvezlG@xay0g7>Bas5%CD# zyY?N)fDJ|IAX|`M9?kXaB0|40LTyL3?jtGQ4zN9%Q_9Jz2YLlZ!3pkW?zkNsT|6P4n0@#_Ls~Hfb#Lsf1`1(-!2M`?=?ZwtQ!%r8By| zleWG|>JI&|lbrsBYa0d5@j8KV4sQW0A7r{`2eYEbd(>VGvbwp74yNk-?&16feD3{7 znVVYq+s~h#ivH$nQFpS4tg)sev5B_DeVvQ1EYWK@_yM}&S&2(g{bEIE&Jxm2RcIJ5 z6i^B(tV7uVdQfxd=|pdjIy=MOyi+mAVa7_^ z71XwF&?!ZXTG)|7&$l~i05=xyMRAPJZ_?F6*@)q%A<+HfA6$JUH}}Mj4Oi~I!I!TR zMe(Ry8gT;$a+X}@P`(kcKtds8QSmA&WCto9R4Xxla3#CTff>5T*C!g%r7@PDD%wG0 zur`aHCgWB-(DA9&J4ra@v8>)NBmOMS{~ecT9P5r`zeExT>HvB_4Tv?*Z2857Oa%hi zHdHMjiolp-*+KRC$bsxO;C-Dvo1>?P7c$J_Wmt!jM0s&2Ut5{0O)al1$etrq54Sbi zQ{O!H{6Ivd@yNPm5U~rgBT~}v9&mYvguXsYPJbHZYml=f+Pvjy$N?^sz@5iahH|3S ziyjguMP$_wa64&pIV#c3DCZVizKaiTSvc*6TJymNN)1pVTG&cGvoPb5>;t`#CXQ^V zVQx@(z+LJOlkgfSfTxR8X%-%khsxML)|U6f+!1T?9DP#E-k3i;(u(DzZ|D?;)*SqZ zT9`=7FV}dO-@{DTtuHhLTzW!(hS~KVBj+A!H=LjBfB2~Vj0l_lzR-TB6_4vFiNzvU84gP zr=X5#wEGWQEl>Ur!n-~L#;%h5@SRRYx-QNO{A7^ljIqlO@t=-frQjM*%T(*f-c7gU z2BliX>~GRHzMNUHLr|foH)f;Us^w-Gxc$g*lk)`k>%REW8o^L5_iYa2hJ$H7{b|US z%8kX37VkKpjIB2P|L2p(A9EL*dbh}5wUhi?R;e)`>eMekDaiPEE<0rGr8e7BKACg* z$#O`F+lz^Is&%|)z9c=?3Kh6kh8y{Oq21G!+Q+SIMu{0dIFC*|beO^A9KruhFBv%v zj5;kgCwu~sf!p3*)iQIQ!EMwPr9?~JEIE5n&;_)_c7nYq%5SoS{sz>q5+hB78ZBeE z7M%vNWnbDdU7(N$&@-MRM8E$%jvY|GA$w>*Oa;$s1vIQVTDwK4kY$a_m`*9fD$#nX zGDTe$x@R~pJredvM1BLL!~WzQ2`t$u#}!n)-dH_(;|dW`gS9d=*@PRZ!{l`@$1Ak!gQ7ua;VCbB>AIE-@YzgbBYi9lGc|>uiITh&d!@Fd+3>Tt%z7Y=np2C!{ z=6jgiAkR?-Yn0J}vI83;E9!e^e|hfz>O%No#yWuLvN7cp>OT>C#m4`DW#w& z`BJ<>%z-g9ByqTaxHs0fU$Du0|{->-)~*)Zq7@T>Yc>pIi=SovC=` z_VGGrIQ>z5K`@`r^vwRyatD3>-#Ex-_vKnF#n*J28vxrsESi z@#vkH1p(~0JECr-JSZQSFfk$-YOzqSt$imAT<)*~=UH>OKPY=Y^v>^+I|L5-S9Pg< zN;J$<1FZt%tB_ly;G=c7g!p%H2;*bisNx~`4?*)w6C`a(sJBpxoNq)hY0Dznt1VrA zMQclo>akI572wg0L{dm@n6mz_yx=m3r%s3Q?+H z%<}vjFPH-;%0`ehmU@5lpw0V?YIB@A(boW3Q9*^Q3ao0&6FHnvReouuwyk45pEyEV z|52!r@8zPo9~X_B_v)-P_AwR7q(qMyu)9z|v0)Sob=VEwa2VGQgSa;1med5_GvA5r zQc;)}fEwp9X2klX_MM+N_%KbJo8=5(-W7l6XW0r{(2WO$CjL!3Xe#V@1bh$D-;2R< zUhRPt09{kJ$W#Nn2rk>y1dFyHY}yPHqf4Jw39;kwpTseAqfZJ7?5|FX&E{}x>?nQQ z&1_JTiIcP4Y1<<8Znrnmbg2V4gEKSk3PSWoA4@{8Zc7Zx`se?!){{0B;?RH5($BVU zyjPg7LmEVHBL6Wo8PB1*zzWk48=nkH^yOXfX|wCu*M*ok6}fH9SY^mPtsPub z4H*V*4d^=5CVf6pw+9Hn9Y9C@T*6M^%Q}?X>5xAjs2&D- zpbq<1qPlT@9twy7ux9y0etJ?V2Cv{UOjrGM!_B>q9S2HypjfFSC(G5C$_xUt?gX3i zhpZ6BtKKB-qa#Dnsw7WoEz(|(9Mgr zj^jpu*50gAn#&U1IxzXACv)a`cR1$zOH4SWQ!VDr80K5M%YE&ezx`(KdE#`FkCE=) zw&gNiXIxGEiTg%}*mInJO^c(6k zae_|oD)jYvp}6ll$GMVWzbN&v28<&y zm+HOhAG_%W8t%N>&5A|Q!Av_vxYtS{K2M9(zX91mCOk5ifw#c$d5LH^0S)W16-VT{8x%73tOvAA z9+${yvW;Jr!0Jkco@uONNq*M(qUPO*0=>p|!$?Q2pFVxwN1g+gz{y=!xMbo|GYYYh zJn#*tjMa^?W;p8>=@F?+S=(KjV&z&3DzlPx`o`6}@Vk}Lo>M_bh~(|CfvUC{Z`oyG z$)gjI*(o@k=)#geWXo?}#*PP2Efgz%@3V4Zl_Jy~`s3va>uJBbiCrC*`v{g>Px=0> z{5fqdw~{ZWjf07Ft*Ha~#e*2~uMfw7wCK5I+3b16rs3+!6T=gIN1XGRVcCcNx!PK$ zUPSBeE7UO5zS&-RzvGkNMsK)z=ICu_veDEtM3p~R6@TrEj^RAK>2!$Vb3M-hnYnR` zMeXTI%I-+|X|n-?blc_1&W+OZ&lm2gzW2W3G9=ySuGdSa_2fR%JQYLu-K%t;yB#&_ zUp`s{cEV20TwnB?g+<|CGsuCg;DWcy^+tk%!S%5Xs24)OW_j!p=$euP`oVC{@)!8;civlSt`h#bfry@929fRWor-;n(pFYk_ybi#vI z!Akl3MFZBXIv@9#+vRJVshv3E;kXD#(xB*B4__ehX_rAd)ha&G+R7#%iS0bjz+tdV z=T7v~CU9)PAXGHd&uOYqaf+6mLbQa(-q6wj$;LNnlT~YMxr)$QnS3LzWJ8m^I$y3i zNq~G1V%_X&HrGerawcT|W0hXmkK#)E{2mD%$=&qL*T1E~%^n#5Z0mF$mNG?qdzF$K zc&L@Q7W{D_;BfdNf8Ek6rQGbGaxPr!Xz|tJzPxso-%EbJ(g5B9YQRytD7wOLs{5Bx zFXy%Ks8=1)D&WHJo2FkC^hW-~?3)Nwe(;LR0edQT6xkhz2Y8L~t_@+Gc0K^tUE~(kcKBu2rHAkDdPFUv;oB=n3%rYjvL!WllRisUw7I6TV-C7|T{wx}|_88x!_|)j~?Sy!#RWm zFod50V!;`~w6`sbir>Oo7Qn6BcczjXsrk;jyEXVOlw7a~eoT4=mS~;+gvb<2SKFPF zZg0xabf4beSqtrTGk8}SBe1U)%n@d$Q6E5ZUOgAAc^2BWL5`-w7au!TX>E%oEz8sc z%2(BT!~}$D4|3PbB5Q^%gKxmYns_TiN%0c)7b)|UtNFFJ2^YVN&%2SGije(>T3=|- zI}4?5_F!U<$n#%z7Msm;JkMQlu=YM_?D-qr@;OQB+u3)`WL;1cv96Q-{BD+4s!hEk z;lw^x?8nP-5h|}_FZCm`GY#0O)!7TTqfUakRnZD$Yc7U@I(O>AZCWC0%f^?D46S>* zjeX|}s7ojI45soz)5&M|B90ZF(tV%1eA}T3_ohl3I;?plwDC@syKcy2+r+J*uMg%Ba;X&Nt-E&bmDBEwWj~VQ*)@Re!GW zzv4c8dCHzSK2Fd~I-c)i7?<38*Y$Xpt(sv|FY^-8&+-+8gle@33t$fL*CwlWq^HK< ztZao2U`tK)um(ie>VkaKfI6&4u1N}W+pYQlYoP% z!UgeeB$NC(6UB#;C7=q0mfQnP^4QQE_*Z?YJJ?H8@;#D9^Vr{`p$=O?*d{OD0LVw^ zJocj- z*cUpz(9kWSK7OD#$sBl87j)0E;_xG-`N1-+BSt4|zwMD{PJgLe?R~93Gn{)PmI@^2 z*%4O6wOz)nZ`qCuAX=3*bl$K}WJc||6XL25PT9s#lF#G zp{{`KvKvExzkr0hJqP1|Nq+yJ;0HhrM~2UF2=W_NBotnO{vKZ+cKWV1fov3uGF<$* z*v0E}F+SXV23Ib-R}(Ah1n;aqlWKbZRy7LO*V^es-@RD%V~%+9Y-ySB$G)9-p6$Ca zq~@*-2f1@@Yrh4#KGNx}h*@#ksf$;LD_0jtgB@E}q%D2dmprW{mtY496_|Hxvj<2` zrOP4P3~qqu^&o}waN9?TVDpJA*InroNg>f;nv%@~+MMUo7WuUIoh>!8R7rK}^YI1# zfF+XY5o~%~J86^?ta~{+CG)PWSWDheo&&d*Nq49qkS9f`|DbnIdebL-Q=?53n7x|k z?uwOx28^b^Lb67)8q7m~*((gP$uFKn-wkUUNBZ$sgIboN7lfLLGt6yUtT3Hu{-(ZK zIr=xB&2ULkMnsOsNPOw3lgEyIF_f_PW#i=|G9200RUM9<`rd}nVE=4 z4fwhc$?D(V;iY82o+xT7MSO*9o2;Dk>KDr$3y{T0E2!<`LJ6HKu5mi2i^(xB7piw zH%Df4^p4o;zAk;&yZUbPPrS)^p5`toKjdj5$x&;jE(&Kz>lwFE&qy_Jy=Hf`8Sibl z*$=r>(GQQ*NdErZMV;|BXHM>_D(>JKoJ=J((Nve@iXON6Yhi$JRHJP+sD3pm(LOFw z9F85o0VubzF<+Qz+1gU41Y0$GSa2IP9Z}2|SmyQyH8o6!z6{oAC)O1l0iB~T|Hy5z z3XX44wK+=ck3avgV&zYCH#@|DxX$(^}L0( zJbFp)U8YXa8NFBFH&VjCg3-?rFkMtiZi`CMF?&Yf(=pr!^8a{Y+R$lAD|h8F*w~Ok;iF_u+?>km~xg>9}SI#_Zv6Sw*_v54EOZ+vNWu181 z5NuE!q-2E}=?*tvcf_IWmjUm6;4PM)dOTn8X;jF;`#XjI7)3E5dgvXYJWNWOb9059 z$5ru4dI{y8?PzWn94kaW!LJhGKEW*^5Vl|e!6U8)WHuSkaiCLd2h{Msh0-@V)sLE> zpcPjnDcS_xnBb~)L1>LBox!PoaGNG0iNNxqz}eHg!BtO*v(BG`q8~+X2Aaw!eamT3 zXTO^|n4{8eJWc3sP7=wSe|EzyU_ z2=OOt`Z&>00i<;lDM){oYRpXiD~r_XNamRZJ`A^ya5z#@a_(`%&65R)`fcLjn?_Xw z=r*6tJQ^*46nP38BszlXY&}aHeEf9xUiBXW401`t zxZrsHR=fI@q4rKQN`P8hYN<^9j*fKdc~Z-aw|`yof@sS&9Aa_B1N*DXYTeb4U2Rje zz&K2M4F2rE^TihY4I|fm>B=$&Ait$o_k;iA18ma910^qzy{`lgh}PWiYbzglR2tqJ z9Po{fkgeKt%BI0|@g`||zmHs%AG2vG|1bggz%2Ptlh1M%f#8M#3vj}ljP3WAM*W2154Lg=;N=)du8HRP>rrzZc2 z%&Lx4N%p5~^t7br`zK{kJUlw&&^!gKM16EcXJMSmGu!581w4*b6FEtelky7F$e8Z@IL$37(^RR(D$}(M^%Jy>7gl3)(1s zgzQHYTA2{&z(!YtLM)2;+Th~P#fdB9x~C`MPL(0qfo{m|a65fF9jZI0euUZVHMK8p zpgd!4xBHB1`b6Q?C)H14Xv{a;?sWeLg;;q0TDU-U={OkTZ`K$6Z(GM#vv|2J@;PC3 zNBxI6KPqmtU;~fCdjl^LoIMQadJpOc@x10+mvX(|$}!I(^r zM#Z+v1HE*-JN|AEddk&qm#mJfC3~rz8^PO1h_86{`Xgdu4J{&vCE5gUEH7aOeZKki zZKpr+2u|IAZZ(W@8HpEKv<>v-D#rPk$-L%OD>eP?!n>sMU#=;tV@zP^`TM?8re2=(DV;gB zdFxR9d2*$$6WH)4SayZ6U++LkDxdGzGg13C){^P|f|ADEVUGNCW%8b8fn)F7*L9(7 zh|qc&;W|y$31pW&Qo6;geyH6hWSo0q;=u>R1DW)Tn=&={Nw zKPUyGRW?|y(jjKw_1=z>u8tP0;;z-6*46IpnCbdA7CVLNOJZ=Ur*-LPZ0K1D*f>V} z6Vt60;{WT}mzc47t1VCAx&H0X~Eo)C+;G7)eP886&EgIS=9#O^3%-RqH-sT7j z)u_JfpKq2=GQ8()pG|O%03dIs+bZSKIlZ3UQM@}@3sA-J4{@fu-dIb0=iOAXJzhtD zwp*wlI>d8DHxCy{Uyl8}7yUlP8?rvxl_;W9iSU7LX*=YeZmRK(Q>gbB@mMF3zZZ`i z&u-3Pao-lRReI}SRPYcqOBBf5+Ki}p0CqFxnZS@WQE_oSE5~f_hDkQEOFs2^k~Zp- zmgJ#UWDHJOMz`|V-uMrtySgc}J}+x2I{$z^F9X5c{;6!j*dI+jRKBb5?&$E&=S6AO zj6vs#tACE&=4{{Xv`x`Tv-wfh0RC*v^T~enE&HpVQ>(*Qk$ojAdVjjTodm#;x?h=9TR&9n`1~OI?~3>km;s+2&Qbajs~RV|K7KDU zuJ~2MN&B+H{|4U3PJ6HTy7zP1p|edom?^oBQ~b{gEeb>xZ3eH0--t)S(|A`sZEfKh_IP zfxPDF4^`U;*Je0hZ=Ys|W#(g7`)$e(q?8b@$P$$aJB@LPVH}QWv1n~O{;*E3yFmqr zmMT3sA`Y`Zxh7$<@}xWRO84*XvAJ7iHm;d6lTJl;`vVUj@VHTNu_v@J=aZrF1zvPN z)jf03xT>`G_tS@Dlee0F&d(6_e#0V0%!p3!$Jtz7!G%c`A8W6PokC<;RR2;lr6rZE z9keIaFUi4N&$~BsW|h=O1U3dDJkSPpy{cmEX~XbIwaZ#nlMVYW59F*BzLGEh7@N8O zyI4|#P7JZy!)ms*$qpa7t@z*roH>m}nK?YZ`}*(QdbH&3=FLWj=1t3tB{$fgb5aAJ zobX#fobP7^!rI>dOnuw32DWso{46@{$sX4;r=maHy#MYgmIzP3{(>rAy`LW->b?`9 zOL?lez&QT8OEc2-3MAIW@34L|JUp>}ck|eH(MrDF`0mdK^0!y}U|6YvA>L+#IA`bl zS)b9W#_i+$5gYtN?#(TCE;cLA#z-fBHgxLA<1WOjcT0Ui@LxLfPN81hG!&Bp{GZ{RdS? z{9QEdjWqn$zk57v@~fp29((E5xr)?=%q_TX$)%}P1@WKyb5FzSLo=tdR3$lWw#d@# z#%{j0?+^kEn&&hVAN&74SQ&R9zEqc%?HIP)qzUU!sXo`~L+g3+?(fH$FmfGRMLdIh z$fo4uw6lktq~aO;&ZL%WtNpr5^^|8$V?JA~7PYE;almU*yXklQ$Lh(SGugZEZDMf_ z)_VRK`{}32%iV&th19g@-x1s7a(3<$jF zg=j;l8O@R0{|ts(KKzb)Jx%_{a#3U*PF!y%vpb4&f#(C3tH(!rJpZ>i@Hgpfa!QP) z_Eqe0?nL&!5aS_AxPd{1XufNXXe}d9sU8@hC-T?!q|K8k`Pm`SDIdy+u^tHMxoB61 zCt@*nxD+9I`JIfgQeneTBaA&PNn9+&TWM$tCaHZp(zp4>8;}S)>4C^uJG1ZM#UV!p zamd5uT&IlERmlb)0~W2{|8?(4>#lAVlHtS8j*)q>radSpbtUEIuv}pNwL;MK`j6Fi zH>+v^mATgz{lon5*Q_LSYjeL0yY(q?=EaGg)K0bDVK>5wv<~y@QKl`1*nWq^{bAA< zuWy7_9a#Q=L@!1hy=|&Z20<~Ewng;eUy|e~@L1u`_X~G;>y2df zvZ3$eDJYj51$4KB4SU}u+lIZ=)%$Of#ngZe1ThN?vr8@cYeW7XPx(Sh{a}f#!8)rZ zh%fC^om;s1Xv06Z1(>!nuPTR_-maGoS~dsvDyEV+-f5f1`U)wF6ZuHV8T5IqJ*ril z#PW%;>^eMJ_yj2BYh_t>z1{m?F%)B-j`=F8{s-N@x+OoLKCt<_lj6ZyuNtX|&efYz zrQ>dsP(X>g(-Ugo8`+OTTdwNi-6b~){p;C>#*NMh*EdqH*k~DH0b~6o?noqnqb^Qk z^ZR%Sj2B8#91n#`V@vrjDPPIX;daFxY>ROU&KxW#GpeS2$nwCUgwI0l1{p6zZK5&H z=p4!8o*55U;r|}j5TIKo$_U;zS�?@3$e}j!@8dUJW4nsD~@1B5GvTTUp{aIl%aB zD@1_+IfiaFdpUj>^&3U7f)$BwZJoaZbCcWUB}Ibptm-xZ@Re9IvCSu|uV0tXkxv96 zrrp4Y_R3)jHq<)nyK%j>xBm=LPaPPc_O>A3mR-+nv5|r07I)loul`|Lw`F#S%QG*# zyY{gEkKI-i^~r&<^Nnf`)US-o`+2wyn&G5|z0Ti)h%3IdanCE(>B`vs9;G?1@T!4z z0`xbGavUmkU^?bV@6|Ja(b@COMe2dAUATSvv>~q{=5Q}%_)_NO`-r1=MJdn#>_rh1(k3N~uh7)r~pmk6XXJRPLGJ zn8gcO#i}KtgLLn7QY&9kRkYZswvpVaVG@n0JcUgrWq??khJ44K_xvVv^2%Qrr+*$) z#fF3*s%5`x#R2hI`1FWc!$hS{T$enYtn|S@W>@z*O4T{DsW(#!F|7A@YK#@IXR%ru zuA={-=T^lZbPM9sKc$rY+Vjg#!RqV|9^;2doKdoIGj_7(v~Kjl5SO?oC0CJ?zYSvZ zxulj%y~)pNT`A@6LX#oH83cXO>61#WiLH(4_Y@I^w9>ac6x{2-G`=V@RCDlbx4r%8 zS-EUDQB85BQ~ugscm8B9A)ji+JbP2sysu>cf6!(4woH9%4x#`fDi5!VDKrdkmoeCQ zD#8@ZE45j!`r#j@WNdpt=!-6+;*M83oZ}KeKYk!uX1#za;nmL!kj8D10cHb{Jhohh z;+yxeD14^9Z^%{KznV-RA8*J&SqyJ5H$ShA)s(j^5SwpCH%9L8ah4K~B#d;^VP%3y z^>#gDH&{dY@IDjt%OQhFAx1?K!0iqt`o1PQ8_;BH3Y?S zq}^QY8i5A8E8qCDUZ2|Rm3?fuO?PfCvm71iU^e*hzQOjU4@g$k<0FN_4GWz$Ck}?n z6C2~qwX-@Ljxj48gQ*X>E4dL^YlxN-<9%AAZZ@03L4b|rpF>WX1%w_*T{k2wJA@D~Fi}82tAtpT-%0hBkn3%F zhvB&Oxn9-3f*AkoWZ$Zs*Li!4`2Ek)^_T}%FRpqh(70(n&+9KU+dqymw1wShB!jbA^36jVOav!IUDqnP%E2227N^!Y*>jnC%W7Cvb=Aj5KacSiVCu5mICA4I3s`wX5$UIMx%Yt6 zb5ofzH`^J{s)so-t&hgE$U5H)wd9~cy(L6sF^!VHolA;y9+S|wL_38*vu^X92>IiY zNI!ji_+d#n>CzSTMp0g`QsADKV-KXn%12crQ6+L0j`v1B+TPiy7|qkHwB`C_ogUv~=2T4kP`tEqGO>w(g%+M`=6xlx?FL(Iqz2?6H5ixlLu`l(iqb zj+8E{)xWamsntAQz4hgZ5r2SElH7?veLR*!>r2b<@P#7ySKejoftUQLYW(K>)J)#9 zqV3p^+rc%iRMEDdV3)d2@rB>1kOCWc&*?3irwUG_^<7tHK4kEsJ=Q+0_CRucX9=ne zL0f#?S@OtU7mqzHJvH{w$Jv8RPD|kbd#Ti*IftVN5!e4*xd8NY-6h6Rjj|y>%*^WB?nup%4ZbI=c8x1; zlRvn`^BwM#1;h-|)$}AKhw>hG(d)cnXLMrL415m}8(kR*gj&KBV;~=Q zfBZ<5ppn!B;V}o?@yBFn@#Q3Wr{`B+;UGU*2 z^7cJ+MGw&i23N8f`2M&Px$NB`dtOre3c|QRK9t>~id0PPgQGuVCmYPtJ=;e7WL@{M z`nE24KU=E&!nFziSbNfUCRn+Z*F-7mQ#6S+AH2~htR>Qui)0e!+)uK%s}Gl5PjHJ4*R}+XNeY7q3l&qZRcQP$@jIsY z>_lM=Q|C3H<^y&jK=VlHtLPRX!A zPkgkWbHEhX=-AVcI)H{v0^6;)2c6+3bNY7~G=~17=;P5OBa=Ae47|JZpwC>rsGMkR zNJNfDRpK6}{p3J->IJyQ_UOR^m32GSLJZ(vwAW5NEc?_mD}O!KvVLf}9^G}V_=H^L zd*MMdN`c<8c>1p%XTP5GezWDWEPYXJ^W$9ibK7bwYB!%^@5H|<`r92%UGB+U5E)#2 zaC~#~7EyF)+&c{&?%RJ)VQ190&oMNNibKlYw0`jRc)daT<&Szmi$~!v>B`%!JlDU5 z%yWZL*i%@NjElIgLy>!WqQYwfYo4(n*7)r7(sl2bFL5o#X_q@xOgjmzh};T)&xW5uJBR1(I7Ow zAh3NVqLVEE8bw$u-gu;}UXQT9pM=R}(b21eZ=KRgC96$Uc#=oEA77wRe&k&A$a7Z6Myby@} z)t8lPcP>V75BX)Ke({$5(H8&|Xm0e5#K2{V{d*5>yC+gxF8X*mhOBk_h^oZuaqwDw z@)ky(uiE>>r00W88=S1}gg_tGn*o%C_>2!~M7zG-dIw1Qct)pof#_pcfR(+4?W~v9 zSq56}U###XyN`8q&i8V!42_ts+n|r&N0=N5_ul6gXawuyMnYFcIk$J^H(4NXv`LML z+|reX^11d$HM@e>0J4(hr6h*7LddlwLuTf_sT&ft>33uOxedbMjN~~C$*b%3P71L|3mI-KssR=Qow>3uit{X( zyC6+)95g5*q-DdTAPfB-Aw1(D8$3;vi zoO9~C4w*^mth7|=&@w2ElB*M{rn{jYQSy`_hkwpnOKxpx)LA6dezleqgq??YrZPvT zJZ)qNjU&CnG{@d%Jso8|6C?E%MB~c^Y2fQRS>i1L5KPyyH=rUVxlaBd*&f(gl`KC*ZvZy-gMUw@R;s(VdV6{udj)_apQ9+%d z{IB^iOo!^(857p!t09nyb5#JI$WEb#EHIo?8~Lg1r;?xOKyvG3%$oPd#n- z!+M|xKN_yhPFLRNC2nmq(U#l(l>Kfa$im&@&wDy&I-uV1C$_&oi0=Cv3P|ZUR-Tlq zZK6eSLu2xZZ_gLKDm~x&B_?j}iWVIkfYIozw12%VQRBC%jHISE=|I8ZUA#?l3OzPO zOG(f#5#y9Gh8QjL{(R?M-6B%)Yvrq}Bm%*nq!F893gb!`gN1N)0Yrq!Q}LbdKxI)227ZQ^3BIQYt015y*DE5qHm?*2l4cLBlQy5KruDq^1_A~dO%!-V@U~=; z1B1bGZJPx4Y$8{fOMkr~IKu1Da{X9ek$&w!EW@$-<m#U71RQoe6Mb{i~F<{}Q_ zj&Xw4Wq2BF$mitTKV<|_{jIH>!k9@pchJxBEVWV(rIW>n!lF1~7Ly#eA)G3UHFieL z+_O`@0&57BkNcIqT5C+-Ubr=8Q=Y~1yv=bQ3*~1<&OWCbdh@wUC3`ZCgmTo&iF@V= z1GjA3A-q2;som0lC_S;SdJ>$|ixS!R{+72n`^hWsEobGCh3j~#h?nM$zBLw@pvhbx z^Xidaf_ibGP|tW%`Js+A!uk3cj_ArCFJ$jUi}!w3ZgHvyYSd#da~Dh8o@q>z_a>hw z!}QKwALJq#E%meeORGe6M+j8cvj*-2Pz4A~vf=h%s6;rabHtKf)$U z&KvW|*jm8Ek$pYTPb7b#qPxR2cLzA1x5oP(=xx&pso1?b5)+X!{b<8Py4}QWqt*wH z9)QFIia*D(2eX6UZ^>cergmdD(+y~1!STS}f_*{ZSSHQU?6$LzHRl~2kmc&E-TK$; zUj7a3=tB{Y-c=lBmK$GTB{_$}*vswqa72SkU{%MHTn*%H)f#7Grc>s{#oL1BH6pZP z^!O!RY;K#j+REU^qP>FwGhH&~caD(;OMa;Pe<7)!Fp5*~DWWyUY`K@C6X{ftaQXje zI`42c-}isV-a9mi9V0Pn6MIY4OvG-B*hP&}blI&mVk@ztW~`b;bnTC&!Zdey*ira{SB%B&wz^LYy z|Bn639PJ<7>TgnBioLWR-mG%v0?fUf*;jjye$*Cf{6BzWz*&UpR+`I3k#;o#38HPk zV%seuX_yfgvHgjz!6L)w>-RmL{FZgcr;vmMI?!tS{{U?@Vn;(%{<{CuuF$6rw8Z>adB)=d2AD}DpQ`OaawjJj2Z!&5)A*2hZyxlH}H&T##X<*s$ z_&bl%-wN)D)jjfi=rJOz~cxW2le>L;Vp?lfq){}+6HESw)ih+$?%rz}pJjj8LbF(uw zPvsvNJ&*(aNkac_y)y3*FLB$$UU5R_lZkq)tr~tdHBC0c5cZ;8@`l`&c_$Oq-ja)* zf93F89unUz@1 zXWfu=wSz$Rci=L4zk+>yFP(j1o`o(k%Uk#^D?PHAUvEo&?g?}vhQuAgvidv+;>nj_ zG%YUxk~*sT^FcbcZchqE;BxB#7aB##F*+O_3f!9uKN?Q0xBZ?Iu!i#lWFpq>dtC*i zBkdc7eYM&Wr_$+6*Mh^DhbJLBteI{_!-M`MvM2U zFHmwX>}KMnGOrY@P!bi%#p}fMB>BVQ^Qz@B>Y$kyyDyCC4TDv)RHMFq{^%Vt%g8Ty zwQwf?=pDhzW&1TMFSaK77Z=(tOhB(wz2SLE+n*9uoFseLm38KGiE$%ev}>zpywk6ppEUAYq=lK$ez$W=_d)Bcob2Fl zXY9`?Hq>I$Lxe`j#pLL#`y#(l`~3Dc6I?+t1$QQ`X0~^IR!4=YLdgUBG$5h9Cp9S9 zie+3*yP9zoziw~)vHYUy+ax{3YDfu)d?dFE5;sd!oKe=kioH>4W2F+)6~?vh{30pJ46ytI}Q!=Is_^qx&+8 zJAb9STDH+kPh!rlM^wFh-)1F8sa%8)1m`{c3O!I9N1S>J;EK!5{wNwhA6ln4X>6*8;M*VOw%}gbp`@eqEM#;ZK)hoz|7;-9Z$#_{lL<$bU`xV143Jc^T)qRWGGvrf@qQ zp|wQ$P@F-F!P*(O3S)9|1m%%eQ)HLZ7vP)Me;zj{B;Iipv*LUzC<|(Q&j_!CF*tXY zMTpQxZXu2SlO*2hnrn8(eTnH4JgF69w+MHG&G^}7TbKs6L<8rW)54GNLKN1XA({GX z$qy>mop6p4R5UfU zNaX>dspN5+wfU#b&C|U914QRqyv^CgC&q)zfGZ=fJuf`G-C|EOOOhIa0|o!SI5pblft67_0#q8TpVdmZgKGXmZN^3=aEeqFgxtPGBC&q+mwpV_CudhPvd9uUS)|kS zSdo$wmy!MAa(g_QZbY=7$lh8~}ciVAJarZf8s zd`eHQr{Iy)s@}DaoRL#=9LJXD6x_CepVCPEWR=$L+dCCw4oUrP#aT*nTMVC>h#exm zdc5${M)*n0!(Sebs6bYU5wQYdm22kq^P1AP?cc>^;dSZN*F&}G6Lzd)_QgF~f5~Go z+}qLWeKpXn4(#8?sUr>-!g2TCAj+)TS%{GI+uYET?L7>`Viv`btXlf-6j`n0WLL~i z43m7$$-HCBu5-6e@bO-xFNTaggMT!1q)T~nq@WJekvMh{(a9i;lCO|3wfXE zwA#)w=(j}$l|5I{+l)CAqV2A}75dKlg?8`@L9<2i4yOh-^m;Hd89^Jbi&+ zG73y`&!pAARi?%XuRKl-Czknh_WwcN)$#pQ2^wkC`!D72{E9)x=mS#R^jX5Sh1p%_ zjSaDxx z-pcA)eEks{Www}`erbstIR4u&8gp6`(3H5Dqmh1DQ?fiObmRp0Yv|Md5%9<8tmaM% z`FZHK`OM|cM*qJgsywlGc$47eN;C}g)|q)gT6?kMIuO2t@EkIQ0uQdi||`r=IvL?(kX(|E_EI*5Q1n-GNJ4@IVBIL{IRYpc`{c&3;>p z=IYDrPSz3QGMW}+Hag#xo_oAjVzBGDK60iot3~}8ZH7+AeI&XvOK^7IQOs8n7oON_ zOO{=KlhohN9U#vVisvI1zqYQMy>D+gxz_zjDLVYx(qPxWCW-FzaoNRK^1Egwe8`{a ztSM}x>21=Nk%o!yR;N{`Ptv^x{?-U?=Ij|!t=!*ts=W#=4Dx*SG=DB7f2L~zzHQ-Y zfSd1+l-ihmT3FMVe)Qfj1OnhI}C!_ z3OYT>1Zd7bW&VQR*q$%;L@j%w8Gro`AghsccX?WRDz0uH1gbZYXp?GmS{@qB`xz+v zN(Ip+2CY=}On$5D=ywHa%jif+yHn1hA2_hW??D9{a&t@h_3l{XoLx}2FdE%%;b_bO_){hcgPt>ZphiYY}BzhrWqNTgl!v26dFXl#To0%q8@_bljyHsOcO#>QRF_PR(u0Z_k!q-h_BEd4klSdY47 z;d&w*nl&}t7K$QWv#mZ}IF#iHAJvC#cz@uHG`5vWc2Drsu3hBYXk+KHdig&?z6@#CKzWrVzSZ5Mm>rDLgx}qh!%{zve^LkHE0>{LIx@fr(5NBWt?x9r+ z3^4AHJ#`Ra&;90>%M;2Krp=m<_Dd>J8?UG&hL_E_ZO|TI*02Suk|&$A?2Nok3mU0g zaagx#;iaK+I@Jlh#|YvTS_9()hZ2K*X$aH{|4aUr@?(c?_;1J5Ia?rTL#?kjeRqzBYXcXMV-{jsY+{jDK9uP8EoYa!v732pxIY36L{RHLTT;$c4@ z%OrIQ<9Hx$waDPb%+n`qb|42 zy7MFddCI?B4bz7q^;F-Y`DH&fUTsiz#EePA=-X(2Nff}-~@WTB2=-m#G zaM5YS4&5DIWv88o;l!|l()hBfsIUNmLvb^6>YMNU$IpC}Adao#;{MII>(I;A$^wG( zN9f)wEI$@d%h{vQ>aYQS+VhN#7)PA&^Zl2jH zE)hqOvV9lxlzGCk>h8b$h)RCYZ#33ry^~g1g;;h=<&S#oj?2xueHG0`!?qWNrZACr zZYOrF15$%xX!`;wST6ukwdbQjAAUw;`10`{(Y|Juzx?+1A7c=!UEfKpds^`Jabh@1 zPJS3v`4f4{X%;aX<8A-h)pm9V6RM{bCCri0b+_r;NVvV5voI7wWJ3$|C=BGas@cLmV^8sfVsc^eHgRX zf&285B(x9SuPRsdjk5am?fPe+!pXfmFEIgqLkF1kUw^x?Er7|Yke5H=>8ez+x+TkM)^kEHOcd^)YLSKSMdd>T*kZmo&F6K!;uOr@lhI22!p7n;)LIK9s0$~FiR zW@CRgV)TYV@;yGi{j~ZT$e;OJI-{l~bIk@7b9}=cN;8H6qvLZeQ~$hg6wBh$hsob> z2|iNmr&~@t5Yp&F&*q>8m44h6eG_CFDiSNmSe*G>0z=BCQ&1Y}jXWV2jot^uRJp9# zJHBvB@Wy1u+sX;@QzQhVMK9-S8<+b_F6z!z)P~C4@s2M?A=uE%j5t#!oN)?zve6

q-nc+;~>z_M|=H*JvV?z38n`rFW`bj(DUsf679#=gBxi z!g@v2pabLM8m8lUT5mlR*4(UkzR-%vAOSl)((cUVev>OvwR_zIy|qM&;|>9i)tlr zUz5Xv*v{*ESQ5ixMFIpL=&az+%Zp0$Tp>lHRHb6&mY9~CxBUB5%jIR(d#W#lYtt!% z{bobaIn;neR)yu_a=2x7)7?_adu z#TycvHef?%7Ve(Cg!~Z{>!r{uq376hznY$X-8+BTQ$_uwF)zn|!KYT+a}6ELVn6IJ73VDR~8q5 z5B_sWHG?d(cop9P9w;bZq!@aO59?9^Edbiigy^01!yV~4@M2ct5gv>p z(AGhPoMz(`x<+vy{L&zZvD`o4msqxqj_%!WIVdEvY-Gd(Xaek2`#opi@WUT$@qu_& zj)FdZu0>7N3VVTW$nd%C0kOD1jmvnxNJ%g$nqMKpvR#zQbg!(F>+(M| z0&ZR(Qk$~B0-gv%GT$5Fzo*l}^iNA>#9EXIohJo|ZFy58$% zdY&Cre>mjnB(T?I(Y#E_0QJbKO<9(~+-PP$Y7bX(Q>rO|rdofUZ~l299c}WlQ!Xc0 zBM0kaC;b3=`&2{7zheNVGF$JmecVJKC(z+Ng;oTpp`s`?VOt3K)$FTOm z$B`P}IV;56oC`hZ2qz2$!&B|II&tQ?7Mh(hH4zO391fPucl$1XaM}NH^`Lz%#72gr z$6apu%H1Q@pXu>#NiD{|lJ*o-WtNFA&k@`t=I_=nXWM9kDly{4nE`A(8Wr`$8P7W4 zQp#13&QP#?B7n>=GJX^S2XZXq)dv0)i3{Dyv3}7-*V@1>Bh1{#Sk}&seZJz{`HJ_~ z`NrnKRq z)y!dt_%DS1&lz}@4w_9MnExVxEwe`@e(Ob0Ay{2p%L9ej>GfSLKh_-M0}C;E&q&hu z);=6-MO*`8tL$1FC|kJbg$>1aYU1lvZ{@Du)US)H9ZYnM)=VIgKu|MNcU3r#w!a5E zeoolr(8H>g*J#@G0%E1Gn!Mfh`^i&qv8swO@8+lEkVa8LF$?Xm-J9KHb$|OlQ zLl%q{O`cV=Ouccc*pLmE{si_W@5bu91e}$J5)GdUrcDqpg?^v-};Cu0_b^URz zR(F$*=7xNcs$5nq&5RkNA{lW$StaFz05Hx~(mX8kQ-@w^j5YSn6+xl<>-RtURV!nK z-8I;=)U7JfZIb=jVRlxaVQFcS)Eg(nSba{vji9exvA+f+7`V4I*eJeG{rx%IBuKXV z7`*OT3OjzKo?vN(|7}4uXQfW|bpe_l%;@CC`v&`Kwa$Ec5gX+4dV>njKY+5dJOS|d;PT6{6ciXTm z`)`0q1MGUUiRNm>tzNMIA=!jU!IDY6dIHYJg)co}n1=8|etJYO2;0AnbTADSm!{DT zx6anmEkx4a0kWBVumI)r(~~7LM;CAwxg^_x;%6pKpJ%^jp2-wF?ETPaEEqi+!CWsf zyq9I=XwiL2a)z0Pxeh_`_Z$a2L0j?n(7ECe&gzPLA)lA;O=*Odvxnyau!e4VjRTR} zj`NHuowTtA?bU(Y`-(@KC5d0sAQqg;2to3uNed&GXvChR@ZblMWe7`65i549>N*-< z46V;)f!4P&tePa`Dof1)36)$Redw>^VywJ9J%^y)bcht}?Y%HLnq!lu%``8b58aVO zUTa>L85T;51@#sLC7fMdE5N^}7-A|70>8$Hz-&glivR8h z3GTTT#kBy=YFBYa{{v`AmZW|rxmsPmvwFO{m3{Bn+I!lwRG@NstH#QtMc9JJRD5D> zCYKSS0;0`lyeJAk=y&zx*B=KM%Qv&74A)@ChxLTwve&9%T4}$Q*J$Gf^!DTswHA)q z49?D(*+5a~zfeYy=d6708@f=zp8-CQ%-5`B;6LQjj??P1QXBdOlSbYZ@Mc>RB+o~e zrfrAjPiMqc>Oea*&B=X$Q5V16~;`s4vW1KdHhg zHWqKzzhLRMlc^*)nJZ9-exLH0_Rs_gbkL|}6wN=|Qvij67#ow`06cuABs00d_i;^X zn`)wuI|AjQ5yBm6yWcml8P9+?REv$Q1SieVwv)hmh(|mNa5mU`G@Ad$rY46l9pS&~ zE8V1wUiBlE(1!uIQBWcUg$oma@2^Y z#n*#o_`sGg*W;WlLvI%TsYAh`UVIs@9`C)JSkqE_xmuYsR0G2Jh~tne%kfnzKirmE zErj1V=T9Mw|G{vE%GFnLP!|KLH1wTu3|`Xdxt_&y(d<_?P+@USsb6-oOha4-!J7%d z4~Dr&aKgBOAgA&mE?3Wg!)rcCDAtFL>NqPDPM8w9-=c&`U_+g^df?DKlj8dfne@T(57UkKqQ5`Y2T={zTzl**j7fB-IG@e`}Yo~`$^8!2T7QZXECC~1IK(f?D za+Jf@glBp+hMGT3ve$2KTN6T!&dJq1X~KRHEA}!9H`S{wjo`KZF)QrINexLv0*k(l zO5?|auA?rJInyhoOMI7xV)3IcMX4yg2hdfDMc05`BTRfzSzDwQ_Twg$j#j9_j8qCs zOEk@X6J(Z+2rms_yeaW`3WcbufQUYTbuM1du!UI^U+LX8YA}6evt*8#z{-~*t6+lX zoKU^C%?J7cY>%nd@fiC_UUq<*S@Rx9#K!0hPcsOa5l!hvgt1>Y8kbqF)#osIGR@96 z8Rrzus{9#VEq*^E6TJCc#$|-Cm4G^6{_rR+!s>;rEd#&;6n_Q0S)!25sjM70VNA9E z9Ps#}KZyj;G~1>`cQO_qTQGyc6gJ+j&@f94a2CDIN->W9dbS3%%aelY?|$Y@2_IRN z>N@@rgeiWKA*Mkm@kPSVLlg$|Pg&qQ@2;PEc{n7T&c!+u@u8H$uxold%$1G-P8|&| zaZQD04PdTY-kvYs<$;R?uq}(1_&=z@;cod7o%(*~rQ>;^Mtan!5x>PR#8aHo$Nf%*G*X{Jx zSRiJ{HubwyR%;FYRuvNB1kh(J$C8Q)#|0HW%j$QN8;Lf_d^xC5PLK7& zZEG{RkDO3}s&dI|o1soWp&Rro{_zY(#vb3}=E7q}HdJs7ZwH=4vC^#Hsjja}nw%ja zz2!Ugs2dTwEoQTz!R+w<(z7H7dG%n&vfR6kg3nk6-KrzFv)dC?eeOnBKE4qd$}{3`3hFHNSu!v?^5{e8*}ykP^OwV25<3PsH6-sZ~}=7F@dC#}jRER7-)9L9r%^j^ee=z1=4Zzk|P zDCck1p*(%O5>=;S{H9Y|vI@2>I}}qX#1hW34Byh=GaDNGGw0JHxAY1JiINkhhVY~i zSLhl|qZCM3>K?o$GeHu2fqjS-OtA!5LxzG|83aKmht{d_}Y8L0||NKTIgS=seI$E+B z|2k;fuH4JiXF4K}?X>0en{%@_sQu^I1FWS-aiI)VPzDT^;Fci-_3sjp6#u5KXu#7? z3Z%}M-1KBx84Ugx1?H(gimB%PNGE2{Rb8PqD^oDj9qk@Gn5WHe7o54y?N-TWWnel) zUcFclC87A7#IJDvG_a0Cj}gK&Piv5Qp5YF~`78F!_uJ$=v@6Cv*m-7%!&!w4<{K~G zFe|7SpeMhQKTh-}O@(8&N^Uaf%z9-##m*<5{tOgMv?RL7@@9BYEHvb^1M6>ZluVyi z8+%%m7aWc|mofy!!Sy=b?l)+X&np?A;&Od0#i(m=#}RzaV#75#wuLfN%m=_{akNnI zeYEZi6PR|XS?-p$hH};o{R%-1aloEOG%5H#iqVt9YWguXJFAftI1zZn%V~TG&v`UvwrH0P}pe9uIPE|KwHH~DqH32l@{zVw&k4kWNElQ#|xwb)2? zeZ5Suth$a1siebrc6qO7WjRTuU!Smp%<$Q8mip4u;f2!HT$Mj>qdnZ}q1(jABmPte zl5}(rqU?5Du~qg}+YS?VXV*^Up>f-_pxSkR;HXDs2B6R?XWT}lj>P&Vh#gcp5frc` zhYbBI$KS)tFsKlDT7Bh_8i7II*Q7TG4L30Yk<6Vl*HimxgXKgRtPkru_028j%c=fm z+J?h{rIsXIitN*I?}g10#TLwpUp+IwbJj#4u#rNcX6l*TuuVZlP|T1wQbTPB9j*_p2sIkF@G|Mv-h7&_ z%6IpeR`;|Xst_SJ`L)i1<{crik|_NIO24%*O&G>FNY}r4|Yo;pY8J$Q_y`HCl_WE4y{U&B{I%7ovR|mua zG0}y8X(n%~ExmCd@O$)28)07Og)A8s!PB}(IIFH-lZ~L?gers459*zP7J07_kIO}wX?)w=fWLOOEp zi9Yx_AJe<-$hAL>i4zNQt%@mMu8~Y|X`;qGLw>R1o{B~rL0#f0Y z#QGZl_2PlY;(vr%Evdfw9o(}ZRX{j`Pi>|9!#b|?T06|7G*G&O<9+yn{of4FEh>?< z{7aN#pX4xJv?SLE}uHC7YK3yGsCO->cm5@Jb<5CNNzjJco#_VLz<6bx1=cTL|BCK!W-1X~}XldKfa zIC_0bgSwp+tf(BwqzkikJ{!anr{Rsdwy{3kzJ_|}A2^&gp+}cE=Ta_z4Sx1O5loE{Wm9I?tQ!ZQ=1c_VP*B@M?F-yc^7$ z`M##y+m1;RIfA|8bW_v1cd;*3gIe7ivhzXx<|?{pRE%ewR5pSlfr9T)+e6px922-~ z1Mg>bafg{(JsyJ}pp^lfxvc9-du`nsZtkr(Q$-K2c&?zTh>=V0%(=A2Y7?9#(@eFn zm|}0xcqc|Aj_neu6C!!h(j-qc^szIzGmH0oD zZMxixS2)~vX>1o=mT}-y_S^3un~kr+ID?3SS*mJI;@!&_2xz!crb%D0!l5(2?h}`S zk4X2Vp5wTxLi@3L@RFTOyc@sw-8_VEzg?)5g~VeG$-1-Z5Jq$g>8^3X`t90LF`A)UKZZ6Tz>Uw>;6|WyvW>u9i~v&N`@`*em7$@x6oypAHlw?;@Skee z+TYr$5P}9C?%OaTM)Pd#;=IUC)(vLl+D1R$iJ#pYWGANTAdNN*q||s1akX6d`eTq6 zsy|G)6KLs4umV_#rb!xECqK``VKtIoD0UPJGi72su&zvhr?pB7hF^ zE=SqoH|6=S)Rjml|1_=8DB-q2el{exHeJr1`A8bflj5xw)pq3pgz`r!@} zJ>RMGY=L>Ulu)M847WIIy8VAbDGPgax2+xxjnE9;Zd5&2D5~<=8JBJx_FTSG*OY)2 zoYV-N(QssVB*YTPHN=uH2>%f{K%<&un=SI;gv9-l= zP{S%(`Uz8`O1Xb}jIa9l$fJbquZ28c6Ig~teoDN8BD_ii6y_e^id>%k^5lKaOr85O zwGf3V%c~sTHkBX+CRsQ}@!L(H5K>uAH#F$~%qFWm&uNd`Lzr``n)1cNEIrYL_Uy+; zg0^vo)))ihHKMOP=i}x{{hw<}{eAF;A%bw2VTtP>Qv-_BAxWq^Lh>W{q*h6-EWbFX zDZE(BD%$=XBm&A@Ct##=S{r(wA|SE@48zADijx`s>r&c8&5N70Y`XehXU zNC+I2x2_;CXc~QF@Yo~s=ym-v#1-(0yl7Yc8R!erw#^gVFdCFBmqAbq1PKe-Ae`;k z7narhfVvI?gviLj1~aZCbG9xUoq_2vrb4mEzCwQ*I9i-LJ3T{{kCgUgo@#%ij^rKnzsn$8P1SOHJ}@7WU_Ze%lF6XYKbYYa%Qp^BbbEqV*6D+56cR} ziQU2}%R$10AB&6x`>NFqK7aPs-ogBv>qxb`?_GVx3c#*X3e!R;d(aM+Z=l$9q`$EkxQm3UPn&07*}`00SZ~C z>v!ez7ZkVWcxmgi`1l<^>u65rZ8rx6e>!-T%5k?1t#~e7z7z+t+bjm`*N}Yi&@0E@ z!+qaoDBMW0q1()+^!41(2L5>x{-n;qQvSj2A?li_^9B&uFuGg%Z?$6W(KrQ{2z3vt z-_lS+9@q0AoOo6typc(cGoKv_mwq)m7e?b(3mS!a-#$+WLZzF9Y|>fHGKO(k1J*qXO=wO*7NdaRxrUdEJ_SvLidH3)SruvS8B0b7t=_(Y~S09q;ukG9S>Tgs3>srPa+?yZe= z^7S2=>Do7dc5033`jyVqhxeQEK0Ka6+3>|9sue*8(ync#a+*7{-E}g7_9s8JYoEU< z@%g&~h~CWH4UDCg*8Uj;$9i^~4%G`BL#Fp-iXat%4ksjMxkB)%-U<16-V}pZ)?!0r z>)&5+{lHeUCbeQ7^Y?2rcF(f2#HSZ>w`sUs4|btr#iLx^6`sOE#qB|WE1Wd8d^!>YvFLUFGww`iw z3g)xR@N(jyoYbC6zMx~wDzT#?{E{?n9l7$}KCjccK=D@4pOc+#tD3`CSo3{cDS3K{ zayHR^(#lIkl=WEN{=NU`_Z_G}g>8b;zU{+#yUEs8xP zNAcM*jZs7(dvL5cMtgsOYG6PMr;3De2(YPAaGJ&Vxll(2rbc&J$@(EJ#FdwF()|7& zzINi%>^MGB&7|OOiiHA6YJ-l*W)r2vQ4^|z{tEPd&5o280utFY-1`}awVg|gsy%a zhJa7(F*OK6w$Ig3w1KGJNx!<5eEQ2`i}g}-#7)H>Jx5zyE$#83OnLfKxaky{z9}HS zp_pgKr2Oc=x|Sg+kW53r%&+j?N_qav)`|YdR>{y~TkS@Adg3jHzBM9^F2AVi^vcR= z{3I=aF>r^y6zg-@zTNc%A8Bl57Jfb3_8)_7XjZpKJ$#{**5@v{!e~tj23=71UHP&7 zriWq^tO~wUw~NTK{6&}x8~&4x_#wyVB!!?>RblWIr3lzueX5{r2Pah{2^5ud^o-~L zbrn72kNG_}=t(0#Usvs|q?R39u2QWZ>awpm7gKMsc7Ch$Z(XkZpO*?O%aLgMs}uSu zDm_;;6Qfr+i*?L^s;SF_NXZ-?uZw8R= zxl>aaFcPzF|Nh7Q6l!zVQ64loqFnEP4wO7;+?Q6W8?k^*qsAw# z^7vJXIZFcL1;n=!jEcHeFpSLAaFm69K&HRQp|!njq|sx6bc0}uqMmiXExg*wh-ssa zQAV|%HcW?F0GukFbJJg0E#z-_dMvR1+tCKToHn83L{#QUD4ybQF`}`3oiSf=?4lWt zGOGgvuvXDa8>}Z_S<~HlOl&`CWw4=#jUb zjy%{g0f-`o?tb@lN))J?1Gt&4760X)BO3aI>`{DL|3cux@odM2s5;&cC`74_=X|Z{ ze5J4_9989WG{HQ`f88q+F-uoU!9`fVK37SBX64v)KAvmU!Bro&y;Yfv%kv4KO^gBV z+Pr89@nj`%MNb5YwaHyPzG?Mn@pXT1O)uu*#g0+K*b>RQuCBX!qz3l*O`y0%*ZU&| zzNOSm4>d*vL}hi^l*JR;)NWw>e*sR zW6VUXmg*aTpH@1`U%K=wPrZ|Tk!}1N<8b>)Slm{lD$*6*v;wcZ^`R^`EPy{vQ)vt< zLvpvw%ytK9gnk~>ivq6Jh?D=X{Zu>s3IOr5;wCdbv-CaBM%g0(j0G+6krYQWflR0#COyS*?}TK-GbmQD%t=#& zNJ!Ojq(;spx5(=FZz|M2A};cS6tu6lae68ro8#Q++r8pl*qkqun1glfQI^$aB4!z3 zGgkS5lN&-!8Vo2#gCM3`MBBRUc0wSp2J@)HgE~V6pX09;*M=r6z7rWn>~!Si=s*V! z$Y!PKzSHM|$@mXVI~Zjb<5FAx#Vc?n>)RrIgR&3o$B;%2*KTnL!YeXFDh!6!^fU+a;=O-=^S3*O#-){fVVn`sWXfk?D0<#3M4cH~ta zRG;HJ0prp>HjqRC@O}Z226r4!r&N|1NqlH!#%;ukhL9&AQIM2GRFGuuR0|y(k<+5L z##nwOfBA?o>aFEZPH=Um8ec?ja;52@Uk_2fho9CqWfXh>-~h+k#mY9r2V1V zMaX^aL10EG$R}IBPGlVH8+X{RY_-wC9TREa(VcCWBT2fFa>d`c6t>s#9?!U@&N(jF zQ1npDzK=PUS`6r7e6zI{EANkfZLh|Ie*2L% z>ICS)VnK|=7C*SRJtj=eS}qxXq9Np-teaNDNPTeTE=eOYzb~dKrIh(Otk`0-kDVidF8q%r zn}@y-ZK~iRLA0)7F9hpfe$(+yVbJhaOvzPY((wKQ2A48b>5j23&?TUZ{$c;v%Qs6` z$igfAAgs*@RXjm=)(3-4FqRIKhT5j-%}KvPOPjns*^mW+(Xe%43LLb8$=av|4QjYj z?)N=*3+m1g+%Tu{{>;1uiL{IQS}{{w_47av^Q0+W*mxpz%e{18_MgyAMF7q%<=IOy5RhE66^*YPS+mx`b?qnQXwCe-Wv*a-xl{3$MazH z^3h!cIV43>dw4bB$Mo~-j((Y%YpHt}mtv^Mxbl~M3E@N=+KmTn*|LRrA*@k&whrp! z2#GrmjZgW-D93{ee_hNDMth@$LWB3~-zyXoY)lRhhNKdVB2|R;c(_|8;${ZpM4Bsb z2@R%^M4w-OOIYv`&>tFD6Zi)NWB3kA*`)vRnk!Es^D@)8t^0t5e0I1|#5b&Y1t%vg zZ=Aezgcm(kziZTF>Go`VSt}gjD3Hhl_=2rcXsy8>Z<_zYvfiyouRp8NGGEQ33 z&P=3g^E-c9Ba={UCeB;3l7%u;MfVbnku}}7_gEJO)KDb)^?Bdg;V-3XPL)OROm6fu zZ&T7Rf>xOZ9Ue<5E1WP$-e~b$*UhkywN4;Qz2GNk%KOuCJDNP~4K*jBFVUge<9gh* z37^2z;lTASUk?JOtvUBNqyXZH8SJz~cR4zI7o-pXt55U7{cRfx5`fNvJqMmk!$O-(OL(m&4*Pe9!t1i^u6;)wT92D|y^_Z&92 zsP?h=ya7P%XnZo3sKgLO<5*YvAn>|}<)9nRbU7^2$|n=dmxaTc@~-+q0Cp$!P$j;r z{f_stgi4;5un$Y_<%k4aeMWxpeuDFBF65RF77iR5c>&l`Z}n-Ssr0j&mgN2*reUst zlo$q*^H}fb zrgjm7s*f(@+l3@@_odWbM5_vqD&%KMnAxe2s+7=plO`3^px*ruedt0FM}(x<9tO!$ zayTSdZ%dW{lm`Bxf6!Ga41{n9=;Azc#g{F`thyx&x&FvhWY4+M`uw&>W&ad7S81Ua zYxD?dGC;ff4fXwN*lchYwKz_)7Q1S)NTwRMbtIi_-QNWzPtX@IR%Lsn^pWCKSdO!% zR_knv{6JvLLWxCKMBI!#Q)WG$XsVk0r&3#1me~Huz*+%RyjoEz?k{Ws-*KvHv+S5W z+-g)=#?3^loNjQbI)d=SbF2YY&-Lwjq8 z_~l1xW=eMu{26itD{Obl$(k*%k#Q8z*AePrvlyLE`276o_Md?(8YZ{wokY(@ z;Qf{g_nZNq-c^Y=b3+YFt|@(X#u=ensQ8G^BksP6wfP2PUh^YDbwwBc_Od0AhN1n1 zl=6K%rpG_ZTXWsf+DWqOU~F3#g*`L_esF!6F!s%Qlnyc2&J~Krj-|E7vSIE@Y#6ws`L@xsdknEHPy@ z54`8`7y1-}3+u&sx*tPeVL>j#i*!81syP;F2-3{wS#hac3)16LUMm3nnzj%ZmI9bAG07zpkJ7~I{1yUd^=xVuXdERZ0< zJ-B;@%x9Vt;VLb&NgDR8 zVXI}7YqF57wKCPL)1sIPFAxLc;g~LB?U5epu#8x^VeMVI(#d|x=Fzza%Ip4FaL{D zG_TJC2VqG4D!X}`7X?+NYy-220t9B1eTgF1GtQTuS- zmVvgjluuQ(Q)j*W?Y=66cuk1D-%fcu{FP+jDk`27XSRaC^4*t49`%<(ktp!_ax0t5 z{8?n-N<`x5%V8-XoY)l`R1>O4(^%i>L*7#f1Q3~ANt9KUd~<;arYGZ3;n@2pOn6%$~p^ z1yX~qgol#1%ZV^bEJb?rsF1{(3XRdO7s_j82xNWX)VPb9tUgXMqQuhs%76|yX;6KT zKljm)ge*zaiCW8Pjn(SJ$c5A7!@}^K^f4na#<}}gx}}~0fD={vG+{ZX5PlRC1n#d) z2xnM;(GUpOi@!N-OHR9tji16Y9L~OWM4#H`_>y{n9#F5MZBk9UjxbgHK5Mn6jd9^0 zwUOIKQrG~0uoOLv*a;fJrC}Q_B%KWiP&^L{*@HJSGHpd@#w9yrFicb57Und%xGXki z80bU6N9=+~Y>pFi{`k_irw~lLECNZhn#kVV&eb+EkvN!5zH!j^N@!A}TrcTzS^Cs# zD@nwehciO0XEoMTO|EWECIt1P9}?HA4GdW&$=*{=r8ACf09>D&8D&&fh9s4GP17z) zotM^mG=ERgeH^k|50B52c61|}=bJ3#bd2x^%!CzuUo~g566ij?ZDqiZ<1X(v&~y;h zh4!yO3CXoVZas#U%>L{-oi<%`p%&=c<@~QuDzgSiX};>kyf(NjKp+EGpq9MX76?DZ zfB(~&e5>T@Ly=JYnU(mLS9ZS1NBHmbU46S+FcmlXgUTJK5ufqarK9 z7+;~YY--;FSdG%WWyddah!VAgEoW0FnB)%`(c;>@2DVF73j7B7gME!7@{qEDXlJEpNWp9#;$dH*9w-P20pk~vR$YVro&3H{Psd_}tZR>20HIu) zVa@o6BSe}c`m$K>g=VZg{%d-#bs!u|*l*#tm)th!o0CNeAbdO-69h789tUkNGE5yT zT5h!H=;3F4vqg`m+q6!ga+j>)f%Pma{Lz`UaqdBx-IC~)hEiUQ(B~)jkh0lf-8!IC zp^?#@%^O{3 z!HWXBj2Ra9A%ut;_(3-E?L87NcjY0R(n>K{3cT2}nOooXxemk)^0)ao*(oOEX z4zEgC179&MW=BrQ%&L!Y6o{_={IX>n;a2*^g==|6*GNc)pE{A|rIXb%?4{cXhbij2 zy{Z?VD`S19ShiOo~@grZo&|G-D!ydQ`q{|16r8c8yP> z)%+Q68Z@F(R4t#;883x95VNc%v~1@RJ8u&`ND*dTFTmVtosEtV5Vx9K1Lhlvtf?wF zT*FAUL~2-@GCyYr5%plOxbW7Zq^)UwA1tfY&=1X}#OWygrcxy%uo(uUV1j%hVD&jF zUiW9{IMBFhFv^Y5C<#0OTn-lGH)34i`1|w{d9C7aabR9ujCWnFuTGKmP==+!`=8?` z^KA2?H`BBXHAn*midLsX*4EU}dvxY(8%0nQd`?&zFf6i}2UrQ;*7_j#5A>oam@h;k z%@L7$mRj94dz9?o(9`5AlID`4W6ZBFy+1vWb5hZoGM9SkU6Avsff-PSH@->RY1MXI z`ISpu{(aU_9h$~_3>fQa=+lD5Hz$`CkW5Io^CE)LkyMFjn7z6CieIy&nBSlg9qDl} z%JuInL(ieQ$(Qh%jsi){*glAT=YttFs?GiAxvhfQo1~hzh1?&sUM)MV*a$_%$Co04 z^6#c`kK_3Ft%%LtJ~dm4Fy6JhfBdxjICys78nMPn?@?D#!O??X8LO` z6F0;neKMQElRRQ>kLeLy=QUDD(-a+VC@fp*BV)iJWqjF*El^VRqJLDb9BlG@W3HT6 z$0ZlxD>u?$DDJn7FsHOv=+nh$KO&vgmpkFs6MFNPB|Jc*(u$-*)SKT*ICXC-&2S4! z`|P$Q3LNhS~OxeS;tU~d#FxNhXsw8BF)5XM9 zS`N1!DyWer8AHR#at2epV>xXllYo);%c4X6x1`U-5oW(|sS;bpsdU(;7CNa%IxA`D zf5bhWzB*X>vJD<-lrRv zv>p1|*V5=95u4V*;5a8D{yc3y7ie_ch`^58lEixH+fjbP0&eD9XAvuch)Ee(5ScI3 zR<2HE&5W^#Iy#L(SnGfawq}-!Wa4crx#t#evzjElg7NZ!ckry!iY>@ zi+?Q{S62|fZpTnC)=R>lWmPsVY=>qdo)@#aQstwmJS2oqpRZ6w8|=BUwHTRde}(NxYmp3*<>6N3f;V(sPc3+^9kndeQ%*swr7r- z(EFXx5ELmT7FUTiS;~!6pUz?+@-xn~IG6c|CNj?|^KL?DeG0^x8a@t1)N zD^#>x=dpxU4i5!I`i9}I#Y{!a)Yc==hK1-PvdfXGy`Vzsa-a_s08f5u<5v%YsjF`Y zHSp-{5Rw9>bhMoGmz4E{>tzZ9Tc#DZy!=BhEf(e3T2RdX0*rKjoOd?-N9}agY9zVM zna!zhJ*hUAm$zFh3(?TBZ~kJSH!1o- zYlIV^6gD60Wcw8{kiw&YMM#t<}N2B7FjL? z^Z5$l_NJM-G0%MBF%k+*QO+}$u9vx~nlur_^#rD$2(qMgk9y?|XAFd*OI&-bdpni; zDDp@f?Ouw6abh)JRo{IIEw} z-Z((>Q}nAI71Zs3U41ST=YVJ%1Eb>m{rn&Ve_M%f^6hz2#QlVf_$pS(1KW(ff-_k? zzNbna^pu`i<}X3r-Iw_I<-M~;I|#L^+=x_5KWa4-S6aTKw4&y{R{Y$^G(Jf;drf%R zBW1szKe=4+<0<@3VcovM=$C zbUQ_`l*;IRJZiB=p^$$+5cIDyutC_fbfUkCbxL}efmbjBVKy+1Qa)Y|jHRqA4>D0S z^3h@>4#8#EgXUvQJ#QVOPOj(qu8lNTT#)M`n-9e$ae|{qX+=K73(hyHq>0%9wJPhJ zeb)T+G3jMKm)p)|0g}AQ&<4e4uI)EXPLS!6o@bsTuf7SFxJr`EM>li1wm-T%8D(H< z&8r!aTSEtZQju#}D(5BWgH+6Ah)PB{zr%?@Wa+ICS`llFv@qn<`-=^krOr*c`?;Q* zMx<#@M3i`H;A95Uu340oVkYHE4(E!j0m=_Q(L@LV@-nd9xGJi~@Jnd7c zChPF%!hjP`tz-xdpd^RXTx}(T1Vr{bRU3a{isV0wwMHFIM59L7re7?h=7<8ks=T3Q zlCFx_gUS7S;=|jxMDPLaq|<{(L>$o2g92t#uzCvJSI$yN?2?g7Q0GD2sWCGFu$Ae_Z=tUxpNm+>-Df$+ zq-kjw7zNGdHZ(3LFUqzuVU%-L_v^S9Px68+gTn0W(2@ISXJ!~y1fd4y>T0~>T2rw* z4qBIE_-4Id>TxEs^qsCrZqc>zhhD1J$}kchsb|DD%aDkalpRrOh|_A0$96YMK5u!) z_+A>=KA|Av>K7fU$@8wadvJ%uFm+<|1guTRz9Ob>fqE6NCW}a8Gm7(Wo{JyNrwTz) zQR%}}8NYlbET;P6i7@pt6OhTC)o8QFw#W4sFJ1e>ov28|bvRtohE=q3$!S9d*fr!y zEyKb`fyuCzd3I}@)oawIS-%Nmhri$j?OizFI~J)Q4?R0qHuwIfB8@!GH?rzKo;uxK z{5Yep_8};&SM7A!UZ6+yD)CKHEp?+q4Y!#j;d%<+aEm)w+6f(V`nwHYfCR58+5@1V`OpOQ|Kx_=USN6m*sKA4^|x-Tt^DOU1OOTXL1A#Hu&+~6rj$F{@<#5 z;`=x7i90<)Hm8VPTL7HV9!PRKd~~@Sm62df$w)68Mrs^D0|w{m$U{Le9$FWsO*XwkK?HKw5td{ecY)g} z{21>Sz-uAP1-rj;r%7`DQpK0@)Gw(h5;v9rMJ&2XKN;BC5Q zMS@<2#@itmn(xr((?H_F5G_%gsxiW#3oV=xIC{+f4CD!~KHRjzlBbh{S5#b;e2d}G zXE5Rjgq&-PMET!MV?H=XpBSl+oDpYvk4o+I)=5zz51Y2B{xV7Mm}MeDL-|A%P_cj6jL+G zFT?d5D1)x3CVceI`-fB?c47g{PFqva@(9b^0bJNEY8(+)Lac zYl4Y}as(BRaD-Z+qCi0BtCU(}^mlBC&2Q8jkR~r^p4y)wl$2eAzvQ@k(7BJN#_08j z^=i6$qZW%nE2V(tMC^M*}$8H55G%MKL$xa}G{ z6&Gj4t3Dcm?Qrzo@SjuU2^eaTDI>I8C0Q&{sRf@yP9yKb#MK%>4R7=ulWIYj0|&4Q z6EsSe>5JTc*gzJm8ZI|I{MQ~gNz4_YNs&}hM!mT$h$?dOaSCOO!Rc!L>%z2)vIDgN z8dktLRxuQ@5G6=lr=9^uWSH=r@>drPkIqfZ^_tc<)jGaqPWe10>{ui_@CI1ks)}@j za68#jL{X=;NUF-kbRE;=~kA5&DO zpsBk-Q3}al`)xAgbz-fE>3u)Y(4+=CJkQ`rby&tQiLv*$?>oyXXV#OOHIy#~B!>u$ zov^P=gs6Qg7sVcOjuJ{=@bca??J1~xWb}R^>%HVJ6E@M>ExjoQD(yR zKg!}Z&qA~X_Oi+JFRS&eRguf*zn>;$kt#aKtU@?p5>dTrYh0$a0_xf zHfYY(h|ZcSN`+P;n8=g^Az9{Lorn0~YVKD7Q?q3(4VoS6iTY0B{RJ8^I;-pm-))wG z!C4DSToFfyAO~y=4D_%dAC6E_vCNiz9c}0_>D#7A;{%=Ru`dUuWpF5Id=6EvYuE8C zGWo#naKBx^M-sx-BPwhe_KIkdEsjc!-$pL)W^{}Hy8K0`Yr_;eLR^4!ulR>!AusUh zb<~K$b9TT6T2`KxYT9VF+3VsB-Zdu?H677}#w3UEi$H|RfAw{YN>h%{FryL*j8NYA zmz8>NLP-L)D^j|p=*xvr-@2MnIFxO)dtS@gaWs(v8(BsJkf$*qX^_H)lVw@G>P=QB=Txl-R;xyX{&FW=<&3QD zf={gCn!tW%Tmiedhc*Q!UKl67l2V%H4>!uFh78w+KA5V=-CF-5V@G&f%`q##p zURuTS0k3>8A_6FiP*2L6NQpdaQc=cGs#y3Wqm8c$smJP@fiE&HDl=CDf3GJ(G1h?K zIZ`Y~UA<@rDvUKoTKk>+zsX9Z;o<-c!p8V>{Ah>E9t8)^wwE^grRJ__o+Avk3xPT5 zz3IVqF1c(PLV-W47r#)aXTeRDtm4KvPe(E$ACBKiR;}SE8 zy`4VP46bEae)Wd1r2PZG@hvnV-Q#>Q*8_IH_xzQ8!ho^5NaWT=xqifRWku@fAo4Ud zWI^3g+M7r%XzglwyD+pNVBU3lvc?G8RmyamQR!|>L{@16zju|SRmBKnDN4ca8|!j~ z2!9r2)X zMpp7o;u)`u)ZBccP}paxn`{2{6oWS>~F5)`pm0F4Tfd*y{;7u+`gE??t zf|l+Xd|4{tg)*Dn7)0;1&mf5+9ZS~Gqg_Xh7YNz3AqDlNesv|7LsI6*@kURs-?W^} za^!&OxbeX0@)NDignZdVs2Uf-OK!mMnf8z6=aEz#mXSZ2EX7n^4d>8_$$^n-u{DC! ze+0m^kG1R{Yej1+Ko$LY4qE>H?!o5l-Omd!)@Biw_ok-V zjogw3pF)UXU?7^pXa9h(5Dj(|q5~NAa!KsN&x;Z-UcQm1}}H}FH6IJ z?Ao9`o@|KY8`pKh+X#I^!QQo%5Su10cYe$pM~h!3H7ys!$X-QJaJ;sW10IzA3=T!y z^P~&l0drKp z=dsvm<^6Gjj+lZ3c=6t9QhflAY1qu1s9zMZJZ_WSe|Vw$h`VkHlYAw9)Z)h7jC2SAQV`{8c0|85Xt0jXCl0wXL^ zxq~aLntl~LAi9@@QB3VUpCHVzo$;;WR|I6Fe#NgG<)oIq0a2&DPr={thNT8!L|1J8 zfY0Z!(?j*L2(22%u6JX$(k*zGI~RND8e#kjK_k!ee@u#?e8B&Eo-@ zzyMHI?rUs(F0(uv7Fc=v2{!_iygMM$5}wmqI2T}@w*?t%KF_V8T4}`P*m~atC#{rq z>?X`n^#Y$s5n_0kX8zQWeJnlAcLrPBt=($IvT+mSC7ry-7be5xC{Ryi#Qz0^LH+U8 zHHs^Nhda~hoptW*crq`iF8XmhKYiF+ZSj(z@ky~29<2*KD-We6OLEI1dr2i#nkw zXSZrNB3>i)(dr0L5hz>u{sdZwY_+Xq!RS05W`)8^DThcsN;%zla2_Fu(!Il2H8K>| zm?Mzsfop3xwIrF&Gse6AeJtyZlT^ArCDRSp>Wl=ueLut$tWn#L zX4k+on!UCOPc=y&P*NmtG zUe^&gLD0`}c&jz~5B5r#9wi%%PYdYg4rZ=yF6PGef6g3DY|yzmDcLFioCpiEX>jqQ zbMXV$8f+Sz9O#@J|KpT{8=Zsu >B|IGF0sejMKhtBs;cLn~#U2a}EtBUz{vr=II?q2SV$)#5}bT@JHb~0y^w>P#lM`x3Av~zUP zbTT$IXM1JtVQp%zAuEZ_rfqHJW<|-%#fQ!&XKrn2yey_2JZ zxq}-e@STjcotwD}+bb!pSLUXUX69^4<_?xXW=<|1E!95FjG?Vh$5T592Ng~O{v84w zH3%LD4gm-5sT)KA(1-;0kK+%$e-1c!1Vkic6jU_yXTSrs&q45T2ng_q2uMhXh``-< zzWLyb#6k}&RYR&*u zuw+bjWd|A!m&PxA6PF2e0$T2$bfbNsjQziSErKu*;DE+MzyXPY zE>anC{L%kgsc0*eL7cNcCa9gc-NK(XCskL{ff;^7V2m&y5hvOO6T||ZH8*fD;&kHl zNp%N-HD6EiEFYG9&s&e7i&VXIp#g%ew~r(2=6q@Nv|r{kFy^ZEWBAOxOG; zB>ZQj{rA4t#wqG^v|cB<%Y1Gf_eNi_{_q-}O^`ntODpQ9z}0rM&rYhctK#>j1*^sK zv`HdrCeGZhjN*`e5e{*184$0}zJ;yK!20@`Uje6ZsGU4KRsFWA8g>CPm-Z4Yjf6~0 zu_pA`yjHhAQL?g&0%YbdzvB<_pE%j6JjEPNtXx{&cRGxmASHdC2R}09{IZZ&FC@K4 zcb|7QOCl2;Z$js6MUXJiPv-#^&`K#B1Z;Mb?msbWh*DPwd z(?t*DW-9En!aZU{Eh0h?4v*iTnF=iWM7U+4KMG36NrjRk%QORCX`iQ8OgnGQ1nsT` z-!;vz>gOtg$KU30Mx5_s>Yv)DuUtjP%y;Yz$Mw-CwXjOosnV_&{}@`w)Em_YPim?t z26MD_*E7DH5hjIP@@FB6(zbfJ=^Qa{WE^PJalRd^g!*f^9u3?Fiz?o%&p6Cm|4LV2 z;ju8O!fQAdYrZujxA8j+Ww~s{FVB5BI=CpOJA}or*5VGRo$(Voe>biF?t6^5vVQ)q zD-lbc@L+r#fqw4el|zcNHDTgw8M#SX`huT{^bg~h;)`3CD=X{Pu(~QKORCV-b(0Wn z3U4itkJ~`WEo-o+^;fw$bmVmN?RP=jC=b>{&eQgrt_NC~61;r%clRR5W%YR6<0Fl5 zua^()m)A(oxWtLIMH%Q7rr7N4F^>HBqAR)VA-|0S-zA$~mJgvc`@XXMofEc^K7^NO z*kUw`U^QoLoh6evyMHw&X&YP*hl5PQk9a;np|{Tf$_e{BRaok(9y#JI?pAX>qpP!R z+}-rn^66+n4Tz#Tx2ohyL_fd>N6JFlK^HIgaf4sYYL!UO5g1 zyumVf)sF`5<}EF{8|=zPgdP-!6qf8p7v1oFxp^^;)akb|miZeKI*q4uirIGcHr08G zd6VV{cYw1QAB9eh)#o;KYN~8g+2V0uuBD-~&(T3_FEt`ov7q0vOwjlu0 z8F$s_FjACC3+wtRJ80WQC~KD26n{~J6wQUt}+hxw>S6L$cwf1VyNj-#ybZ$2gzA_{&_@-30F zFAPuq>OkyOA-n~ZY=CrBaH-~dm&M&uu@F-Mo>IP10>h3N)59S_N(_93P_H{QJu4SnCaCM&)t zaX(T|zl=exX{^*i^p9+`i*Vny%?J|DSnXjJ`$=4tddePnGf0?hc@mSp&}ZkKg}Ea8 zx>*^v+ND?%ws*|(eLV8aUXAO=5=AjS+T5kUiNn!h+2NuhJL0z?Czw2m6)k0-iWAxa zY-6e*yodK%9yeUB=G?K-31q+KkL)@Qv#2jLST%gjvKl~;4QyC*RwSsqcRAWkS7A&!n8xPJ=J=7_di5_+|!sLBVOE|lB=n2{W97Z$zCPu8h3eeSvviHbyok^ zi`IW{W%xf>23$(P(&7khQg7!fNi}z63XGC0u$h6bGD9-x_sl2mB@&N>tg5=ue8T8F zh5WwnDBN|}PFKecNp^wO;)H$uv_>BvZmyh7Npva09}Mi#6I8Q$k(h7oKX<*F zTF_URz>qPdGYMLv39FX|LEniED%Ljp3VAfXY36#B-#1a2ilL;d83Rco|4lk6oxk^MX}}TxbD5LkV--)ZWZSeUa)r7$ z_z6^X0i<_vhrDeTqbKwOuTw6UA}m7PT19QWjbpN-YNUJ`cX-m$6P(JzR0*i976RL$*~UU3k4C4^zyMM74< zaL|i8M%LM*!=uHm_lG06Nfa`@HcVD_*|TgII3Jo~88S>t{ku4kM0Y|4uJGR%_tDB~ zH-?&YA0R57`FShK*StsMd$<&T!H^RM`u8+8vkV?lY`Z;2zgaN+9`bvGJc2Re!eCXX?A|2NI@`y=^g88MIa-@VB zWrprxYACD7FM(1wH6;F;R#6gfmi5ZoNHo7$nQukfw-H7Y4@rd&afg}4wRgOp-l7VJ zV-?G$JT76NLe`|h5l6C?I^HUY7q<fGA2z1?xC6bWP!m7H29Kwheg&veTS$u~u z(C~Emk#VfhPh&@(`BaAP^5?AC=~~hAV{oDOOe!TmT08Z#YhO7Q-tD;S z0g@%de=TJ58Lc}9;0f_N z?0ZbVM;_TF_o!QxdA~K=C(vn0y)@~eNM2Z`{jAt7h4B+8;Oi5px9G17u-)ABk2Nux zM@@YX2!~?7c%DGNXDI&4P_hDc{dN@#c~=i0BW1n&_=pU^&=TkVl|w%#(t~_bTJZU&0wJ2A7wPN}ha7FQ(_z84x6IHjrQIT#YTYF&n1d@g}G3*#0(Q@`_MDD}t zV|nYFq07e65ecJwjHK+>WSm@KZ8|=M$Dh+DPieK)Da8((KNw$hy$_nKXOe5qwHiu6 z0;_AO!#Y@TS9+!#qDL4}1a2@Q)ck%3+01B7Wm~bN6RR_F4c`TfBFGJ+{7id~@8FL< z+A#g*$llu2!J$wbBL%?p%Lw>_5;q6Ji|VYg<&q?-X>h&HINNZ(>@Lf_P!mH32_M-$ zzU2m}$NE#_>E(W7A(=qsjscZhssePS^V+XBzowo*zXbkNCb>uL6G)WU?-4}|sJ3#! z&Y4T!1AD_cm8m1DhD5JagCRz7_{{9ftY?OQJ()W?+qToC3N-i5pXOGd9^tGENnE+rQA(q=JlHSZ-f)%7kRC#vvrm%$2DC%HFYkbN;jN3AE<=rxW}|t>)e} z=a@aoYg)C@o;HtI6hg#E?Drh7`ih4yA?sZA!t4HAE&n-pCBHKW;=Adj7&fzvV}7fh zcYnl&F!mENqtF8=K7aH1Pt+GmgDkuk=k9-7164x$r{RN~%NT~NXYEj|P6#V+E!f5M zrgHq5bXI%b!NpPzLc@d|*eAa2=lMK=E1Syp=6tSmUW}`QTG&E#pV`X0T=# zR1z~hQnDRaLxKDRZjYNkDbeo%ef&}IOY zmFsI|^zJXNF3vKpn#Bynni8tzqnO(PYVpZh+srw!O@Ttcx!S(RU`!Cjl3wNmf*sHc zc-nvw_1BfGG)VrTw)hD&&I@!J1bsj=t3l>-D?oLAac3SWpZlrmbu~_F=MFLl01h-* z`tI7k?ci+b2_#Dga-UWQ7R@%rkM$BZOJ;blztSruE`rU@{=d{vBkz#^V23qQFbEE7AJ+;{>>g%s%Hi3KO_ zmF?#t8$EM^6S1D@J%}DDv+X&W8VEu7mjHkSHBNk>~`UqJMG07?aZC+k%CYP)ikpf98LmV zt%W=PBSJL$YDSF?v#q+p$Y^tkP6y`EQE&?^R^&_p+XE6HFWsZ5o|bacPtk-iY3tCPtBr9HT$nNuPz2$Mp*QMy5N`+JHxKhxrw(cd9iem z2s*cRvEvwVqVH@m=5exBpMu<3?lq_*OG;x$F5pY|d|v0Dgk3I$7r`t8y(08)P(2W$ zMZ72y?5&%SlkycN7xZXdzI8;$9z`itzAW!BceHnQ73Mff+zL`y3SAa&zjfXdCzVd+ zCVxKVZq>nQUGFkDzi+}>)h|Yq*;#{lw*2)|?SW}yPViCLyz5yOU9!*C6DYyWd^+F)&M`5?}HVB|Kn)m8%(|BF3SQv zIYgI&yg8jXZ^~nOOMy{#RiDNBDHeA&Vq5HY@XDJ#4p5Q=46XAhLnas-hBb}>?SPGJ z;-iV|wpe2M92Hm1duT3xLJMEg3+KK%U;iBK<@ZL7&-x^$FS4G2fobATvH&n~X;`iw zyn*Rs*AVD^$zLMH!FiBY6aSTwFkbr57ao z*{xh*gnr7bx-pSYZmYiGoT{11_1rS;G)A1P)l#CAwyC?xR^LFHQ^p+Yr-$GU5h3m6 zC49ru5R+!YT`ssWFx53m69l zcT}yCV!to(DD&PEm?lf=Rh{YyB$0+4Iq*o`R9X7PuE*bumaD-TJT^Xos78byTPwsa z7;LjD{0yEz(c3`$0mC_pTQD~q8CYE$3Htr6?#JbgJc;3UI*^?%wS>hL*`-eRr%_hOf25ZAKMjUT^@^#;zScR z1H9FuU&v~^gyEFpjNjHSbD|hLCgd8VZHA8#0_Na<*3b}#dR@Dt&B}&4ri?H_oWd4ciV4_P0@&9&{B+$PS;e4RpBQUW(gG(m( zj`d!rr5Ig_F5v13G$j25va$rUEXUO~N4h-EN}G-CogI0K)ehLz)7ztE&@L)$t`(~) zqq?qnWBF5U`w`kwRTtri=o&Y#N9^|Aobdo+r=s5jXdL;7iV|MFolKd<%quipx5Ekz z{>=HA>0JYJ*D1Q}hBzn6jKkOYCy>Rb^*YjLDO#0rD=#9&7DasF1&Z#=#n0TowEHbY zlD@A@tpZf->?q=lHir?UOOPAwC(s3P>l3KW$?vpDxbz8hi)jd~&kbU~SM+kisa!d~ zCip#pBuanWU86jKNOA`OSv70slLq1 zRIlo+(qmLJvpi19Np3veLj2H`@rjxj(&@nJ8g}?G?|@N=|M9`cz;D-Sw$<#7Uw;oE zj~gaY+>-Ke&ZpcnS8@qT9uX6fX(fn@FZ*JoZeM&wU#JaKEL|*X`p}b~9-i6Ko#y1+ zr?9tM=HOar8a!R*aFL0<4^t#0DE0&=s_5W^xC=R_MNquaTZ{!3$M4_npi%SXhg;{% zHDO!J@E`;7w759^7l}@9^pjal S79OO1hBQw^^G#hRrghY8!&YnvMsmSmAKp?7!++ICn!(aL#Wn)nvyL34D zd>=#h{ZTi0E_p(uG-=ni0Lg0-_1ejc#*F~wqYvi-0cn`KhYN5`2!WVZQjWew2Z>F= zE5%iTqkK5M$7RQ39rV_eAS6e1>7HTNL_zaSL-fX}&5tis@jJ_WKhlNU@9^(X*SXDS zU~*0pY1_qghII*apu+(>|9L)Ft~Vh>+j$cxgTmQ94&t~*aUjeq2vhl(Kd2n6DxbzlfhB?!ICk(@n0P&H>rNnxQ z`)c&)`KQor#)xQAnG>;GPPVH21CzU0h6ikd5LqU!4^RRF?);X7N0BtyJk@wl6PblY>F4Vvo| z3Sg+tDOXjWrg_ZHe(SM!FKkG~7svV4MP&Ff&hK4q{pURA?m16*rqCCg%mpwCF1V?zvFvj0Z;jQn7saNP zQ{1`Rg#CdVDO02sE4j{ORtVqt*cm%g*}d1k9nDq=igO-%umKCR#H-!DEr~iV zr%vs~iXSWOC*ov>nq8uAQ%nIOO%b976L!J`@X58b{hIRq>Gup?=V4oJ*t7dtF6@PP z(P3hieFi{a)&b6tC=1A8U_MKC5IeKwsdjFNz!JYg#P6 zy+EaVPWoJV8x@U$^MY_E&37C{RvN5^Y({a$`NMB6z3uTMkM%5R9fzS;;>n0_@Pegd z)XR0brj`{C_A!-9%RAhuN1uI)-|T>{bbS{=rMQn&O1m+^eE0}a;q(dQE+t>{NL&AK zuI6W==Qs9R>IsDWg5v%)EJ}7NvQXHTHTxaFp+!& zx6LPJp3kX0fjWZwo(R89P6Ldd5)%oPRcd8Moh_Vxf$cmm2Z}A8l=T zDALO2KIizIVe3Mo-*;+|G`Um;8?dpTXld^m{k72N0P#CiRJ}PU@>}Z!_BY|Vf0GM8 zGHJlm6BAHLtfbT>qB-P*@^GPjRtgPu&04Ct3TFMP#++AGd%xK*--WQVwi(oCWYhOI zRfu!9`H88&SdKa+b}F?jf68CbXWiSf=~LCV@&}^w&LQGFUhu?hh@l(UurEmEhi*Eu zC)tKKlBt<~9qqdyD!KItaL#(8)8YL7TK{N=N-U6>TlZO}!JS(cX5HviJxOJ+ZD#D9 zVdNQ;I&#`sfBvKPTSx>(T9gJ;cG(DQnybenDW}&f0Gi+r(b|AW045E}uxn_zR$YBt z*obka6E+^l04UA%$33Rin|Di&xA#D3sEGmHI-Ih(Q)SQ64qsuT8xHAOs61&JygdJ7 zZFVtbBC4rLhvEK;JPhKUB8by3y6!K8&cyY1&HYnDXKKbWl&cqpk4OnaUI6d#fFCg= z?jc*oHiFO^g8qZ68~F_IqT?|Zf?SE}kE66leA~Z^gU|DMH+J<{Vp*rl{UCuubie!@ zA3Y|rWxHlH-3m6MWS|>ubQ3iYyeM?uaRPk;RkDcfRAfJaf}TY^vPS*Y#93$-lXjMT zA^J{FAUpKx&CE20_LE+b5>#$QTf$@VUa^Z}YL2obth3X3vhMW8KKS&9P(WQF;*Nb! zXyAA1_V-u;87=R?70=fV@nS6B@*uKGKDUY8%(hC3v7e?tvFcv` zXHx4#%V(h@jb-lA?zyU_faT~zX|<^q0r#I5lao7Y-q$Oc%WSs|V{vRW!aHZTnv#jb zdsaDN)ye;^=>78_l34hd^W(9NrR~B8x|k1WBZ`0>?$;s52l9B1J~y`-b!iK?VABI; z7RN)jJRu{st22(>3}X$nt7U(`_Fy|rv(I#&b7P4#T5vF>NTWyD9D+qW-$D z=vt_n!PmZ{-gpes`}lDB4^i&#tA%e@cD2&b$9`an%bEpR{4KEV_3r-j^_88-7Z!D> z-+v_FFKR@-VE^wC^Zs@;OSWJh#^+q#tK z>|I?64MTe6IkpvP2t50g;>L*h$&hVUtntlk3C~LZO=WpZzA`d-6s-(IP`g2lcn-+4 zfX)*7P4Pp$v)fW0mx9FTdnp<)py*kw6-P4PwId*DcJcGYT;7^%z@`z*?9qYcYcx-p zG^QEQ#_1abFYHLRa~L*I2BO{ug@Kyo#3_TuXC1HXe>@;xV&AR*0Hk5{hcBLhsN5>` z_#0^W4K2{`n%ANvwnAPdvJ`>wpG#pIF!i)kmKrjf^ z!=<)c%zcXM9zeh*&b{M3c?|LaTFUW{h8a{p?zUvbniV$lHas`Q#De+bE?WD+5;&2Z zV#@6<#u=F42b*#75;o_*hc~3X2e&QM`(2Psi=Bl3QK)GHu2sk>hg6I7*3@AtqVu(%dIFX@bqG9wL*C#0UZu8JZBeho+~J$P3{9vH+-1*E%sd_TC)-UmGF-`VH9&-1+3 zd#>k?xtL*?VST@!TI*i-x>unj$ALNJem?|yjvsI(cEw6?Ag-r1eWmmo3~mKIb^!-1rQkI4?A6?-KqRKsmdehuFrGyQ|=w{`^P_)%s}uZ{U7r)smtzJeI>>b!o{0+!O}5%@wGd$pQ}S?hrr6kq!e#CDgVlzgmb7(qbux+6 zK}5cx`E85bFdo#vjO*!^*EfSv7Lx57iyCMOIffpW0! zS6|aBW%{pDN)5~SvQ7U(P@a7}MpsUzJbpWxN}O|x1Rvn_Rrbp8OqWO;3-|t#Ci)Md zF>l?)*oD_)`%NwqqZ$T(K?WBocMo7YkBbY{MnE8XN`t7zL41ga#xK$B79%jcdp?t^ z%qDv(R{b}`F0)t~c;fP4shlAMf{c0r3uoJN+v2}Uy<#@*DkALgXAFy)bN)6Dbi$A~ zI)pJwm3Eq@efkHkz3t;{tN%*eQvd!(U0_X)91?IH&p*&^&%m(#HKCf)j?A>L#W3pN zcONtpNISoRJsIAZ^Wh@DzanK#SNEco=@pXZ?k&4cVSix|WCx-H6dGK%M5A=}l7ev% zl#8d;imkpzB)!Ls#B4i;QuYa?ClP*HK8|TMCX1qq<;g)J{s=cVDHXY9UrBr#$%27X{5BQt?H5HJpjI+IWyyL%XL5LKgsw8elV9rXx9@H=2jT*9SF?Wu zGX87WX#)2E9)qsOQ6liga7>sgK2`&spYpA5-p+DI4^x-BQv&li@TcNd!gZy8gUik! zvwxZZU``opCusLU_wY7kR14hIYqje{+z)KX?)n!nqURIssU`!x9lg)+hHoOm2~{aR z%eut3l*~QcC}$c0HSIlLxVLk;M#*tjtm`(**_vP0peTljE?5UJUa`bZ@zJVFu|?wh z08$oZ$cE0YR*UP<{Yksg-^cfB6|=(YK;J-vuHcLG&D+t>k|9r4F>v1WoWrDC1(pD~ z%4~ACXs^ka@q_o2bKT7Cmnt-y4S=Dqw97Xg(NF03Hu+}F_pfSCQY5Co;WYd)aW2g9 z5>qlAFnyC@gHyn5#Onnfh6adj=Pu0P3qD1-U4{v4iR~BUZ<&k~OsjEnHhg*Y*xP^1 z&hs<%{Bu-6&Xr#feOSTT*2!UEMb0k>cPWCbRJrA!#M2koE4X-0?)8HWUvS4@J8x}O z>nXQ^SCJPcJdkZVxj992>Y@Qqp@T*4aiJMG_raBd$Dz=%lyBRj%y#nuLPbbXhWaQ7 zw!s`)cP7JkqCcbX$=@5i=Ir{3?VK4^R2pH4K^r2QDzeJ1Vdvl8(_UT0&lYbH*T1mw zFh7(jfUYd)PV_?Agh-=y8hN2S%s|b#a22Loax7y#?^G&;mY@&5U6|X=w9(I4WGhPgipfTssSGMO zre2_+VxX_@CSbieL+dkcv6g4oA&i(e9=ku-O3`=}-w536DwA==06wo=Yv$Id5%lmG z#FAI2@rjh>@tiCBxm^)SWpRygx=G}V{~WbmfcNYdG{n*M!+vRj}t}&w;M1=&!ex*{pW$%zbyi$C79tc zvva0>?z`pYw)@8ej^E!s8FhavgBbr(m6t;ZHe<&0_N zB!Lu%BO6=_zhjR3p<0F?PG#D0gDbC54pboU^s1%s`WW!N{g#AxNGksgQ-v)3?|E}z zuzIHE&d~`-hIelc#J=XeF`?OjXRf^&CeU=XNun)_ME0nv4q0Iy%*=%L`M&|SU1*A8 zuZR0!3!ILBM{Cb!?*Ga6m1d5G_r7+FPa1DgZwvBRgj&u3=s!ht>ezeDCOl+Lkt ziT&G^@A~>A5Tq{b{s*rg+d6%WV3o;x+{v&XR`f~Y$0OLJ64L8)(*h&%RZ%GqI~_W8 z%ohdN01n$A<-r~doZ#zv-fKmB5n6$_W|MT*OT%U;_nY+&lv^My7qZJXe=G!7nlncY zUiyy{0XQ-LA#1GEXJEt@JaC(dv*wc|AV9!nr$D@I@vo3u^1-O>9!Z?KP@dwlnGIZ6 z1*x8FA3?0B-e$No65QK^>T^@DzRsO7X}sv>Ano22cw@#SbYgUL$<9hVl2w8Kc~H66 z67rR+LPe)mW)`G99S6;1vbVSB9u+nGc=@7&@<|d?pUwSGf+HR}8e=kf#HsRg>}yl+ zHJy5xXzZ>Tgv`y-`V;aEp%3fOdGR-`wo8Ue(A-P@&{pkm6(unHwE!RwQF>1>yrfsd zFW*(ZEh-$$oo6#nBU_OdLMJT+M0B>i9*hO}H_}we&Oc?<=;5YZ#bUcdr~Ho4mc||# zQ#E%=^=J?|iAZ=jNm0%wHCp){@>W!72&Tt2@}kx$x`GPEUmt5Um8GJ(@DPTx&Qn&-w(`CgtIA&QmNyv zmU<#MzftaX5*@cl0pH=EPoQoQK4e1F+;#&>3;gxUS@r50Jb@jqyt%eaAzLggEVj{0 zk|(`i_Y&EyLf-7AaO)jrnaadEWO^sAZ}33=f)!I zv!XD;uMHAU*yyVYK;m#MCt{C3$xvd5pqFx@QGQ(nuN|)0?!=Z8WfDq^O&6g$;xjq^ z1MiuXetO4#w!X6&+ZvDK2l;(k->x4=$I8N3W!}a2d2d^UEJ>jYs`1>Ne4@6tOXmE# zqh)P+K)+0tR)R!DD~YBWwkSfnUn;LQB5i%&+=n9smZA?cHob~d%pOS@>_4IYX+Oo; z%Fl2lcDl&0E9Loh^e9?=^1i#Bi=9&%?sLedd%?_yWcG(qGnUy9x|A_hJF9VVD}3KF z!Wra=M`-X@}cpT`TlOIlhJK*i zp7DF}D#6?g=dEAY)%94ySsiX(US?j*_!N~$c^@{J>oohb;?Bdw#Eq1S(X*j4#X88& zxh;w|G}|bX4d@nkom7hUHl(MW1*C3!$7YW=GhSom`Ee=+v3SreK1HFVB8c?-TKZgs z(wEZ5{-nIDJc9Ss$ud7}*ov7)9AW|yZjjNf>|M#- zb1vzam^ZLH>}FZ*)O=~xr3`08=0xD05+U3Gr3;zi031i?2w%X!^A`p#RVZK!0tVPG z$U7Lwr6!2S1M*%o0{>t~ke)PIuSmi))>w*hn>0vgJu2x7v!<@GYlw)QR0_TK^@hq0I6)7Wkb)GMh(mE z$*X)jnfyIGxvZ<}t8GNDvhpeHO1Jmm5pS?R>Azy|8avFaDXid^UoDGK+=+c=%Q%a5 zeRS;GD7|OL6UrqVJyk-ZIC1}%;lDdr9oBKhR!Y>KB;SZh_=RJ+Q~b&0e~K9#!_}_1gcV5Nk}g+O z(ox~VM|W1}`vvKPf{1*!6cPBO4E;GefV+Is{t2de{to`dbNoxg>4FQGhDNmEFro#7 zCF8S)+lKa92vf@wUJJNJzvpWEZc2N|Xm#kV{DO8Ch6zSd6c*Skgbh-3L|#f?B=g5; zWsKF(CUU+-Ir?DTXs4l+GN}4BR=2C{|kqM_u>t+EEDP+JL$94P}~@3|bnQvC&q zHwW|j%H$bdxJPb^a0Y3dlj{Jc6G1`>^MZJMNBjB`RAca_SauG(DA+r?=$UmMf2lY9 z>(AcMQXd^3b&higpPsqiOT6f3bHaT8*}a~&ibo`qRJHfN7|`_6hDyVEQc{e!wZ}!D z=hfY_vO5%Vby?2f)+N)@a8OW7=#A#bzn53>_J$+csWLM5p zC(b`BE)Tgz{~@xJ-`|6P<&e^(_`)SfT)agPgI|yr#to|0mO-muk|sv4?T*H{gzF0O z^xQVVV|5M{l5LY|^P@P~Tvn<2%i%%4T~O*yq8lKX-_q7`Pe$4{J-KIPwjiMW$5r(F z{MWC`7CmA-)}z1tr7;R6Jz1+sQ8XVAC%WQ>28QJPphKW2rrm}FrgRBkAGO~+kU~Ncc!Xyg=;uQaYBe%~4b`)H0XN+R1ecpFxndBti@!np5GIA!nmYNoKr+}; z4;NC1N>Ur@7d(>L|NoYX^IzI;O|RDoZ(&3ts`LTC>2EQ>;sBK}FfbLTYc`;;`AEAv zW5?WKqc=V-J?D^kR3A|9!}rd6-1YE-Py(s{3WIw~gBt73GOvVRqfIF#SJaBk-T37TZHH^>^Fr1wpk%UkTL6op* z`yM=0;iKw%;nlSzO06B=^_mnF_4q|8tj7N_f0 zs9Cyv-x)|~L*9hQ()OK?q$NaTw$9w{goO(L)EPkWPaaH*A!2NqMYxWV3{g*x^1?kR z>)nL?HQ~`V?Sh3BkEy90Lyd@=)Ja57tm4lQzCS=JG@Q+wvi-$;*`JHm>O-2`yx$T9 z4^eL}@Zz)`sZ73O-6a=(6ws=ugeUT(L3v+aAh0#~0HZh;*7#0m_YfS~Ni*33|0uio zdsdD)#;T6nDN04Nqw8@l<-QWvC)sIf*d+JsjK)3Ks#9!5Rqs!+xi@Cx^plPEe?gu= zzMQiP6`EXT>Pv&H%k?qJ>rGn351iwL+*uWP$`~74yRY{{^fY#*_+5`y+eU<7e9gav zS)QGZ=i!sfd2O`v8cDK5(OwQpcalhym`;d2K)jlf-qr=B$$F?@=*bftb2V5gzLx)l zdHgpe@eE@!(ord%U= zcMkyFqk8`S?f=n{ieE^Kf%7ZDhceo#fcM%6PFMJSov_X1=?F|i#oNA^z~fD5P- zQGFyNkT%_n$G8(kYx`L130_+x1p7@i#O#e%!pLmLCw_x&g> zPz?f!pPI|0LS+cSIM0lB{DMdg$5=F2#T|p@>y~Om_e{!DW*%5tzNO|^<>yoS-f7{S zNikSkx)1X&OIdes&jny719~EfION)mB=?a1kVgkq+3_iu3E3?J6bx0w0`XhF)#F09C z1G6;>yXXqz#r30T30<6I8r|0!Xx#!e5%`ecu-QrDR~ugv%J!_qznt6J=H?>O0YCS#t!Z(aaygwHAk7?`U} z<1nI1Qd`mU>$X!hP8FS@E*9rPZw&kVx_u2NY4*l|*WJ1Mqb*i}$3OD{8$t2wvG53R zY=rHj=HnU2c@Je{j?Kr9{sq_t&bv<((cy1yz@FIHK~Ph6g#10T{}bGML=u-9A2cV< zn-aCx>tcT+hn%(REB)miq>`5bq4w01a!U|~5q-Qi3Z_sgBH&5N3;k5638ptge7g7- z!>HCKByz{a!P0E4{|MnvQH}d8Om3s;^h{JJk;QoE(oc+8Q9zeM- zEI;GV(gpyISFyfu-d*&oE0l_bcfqOrH=1jY7vEYygb!m@N6`8I@)ysqq{dzsHCyQM zmWneR!+u37{#+PyW+T&9_GtiPw$}4Vz!7PKcKcACnJEL?0N^d2}WDM=lumab9zyM)4K{W?pBYJ z0j{&~5exwVt}}U3Gw_#wLC*YOBCxWGkkZ5q90dkXenA$&2d)6$)-I6Y%HMypx%~)#vA`%qxx=p9o%3Koc_Kbjt0uoWeaKUtCd|Cx?d&bSUyz8e_Yzb8 zgDuRSa&U;;UC08HDd!(%{9%GC7a^Cbp^{vue;XPDIj3w^=S7>ke=h56|AM4}5+9KF z*&KmXV{$+n3(!MoJM0o&g>Oq?Ro=DOdJ!NvR#J~Ftf@?S@#9^(17R<<7Ps^cTv`_6 z8{7C!{K1`4+Bu#qk)R5pL9JseQ1kBSU2$^1D~k9+01~;GWMkwqHo&P7ztNy)X8XFc z%tcgKpjcT?+AX7FWpbf`xXv^#fMlPtDQ#Bd79uo9FztQzE}Qm}Q>Z~orvrm$>s`*bOtkF}N$S+IF7ujqg_zGmXq*0ke;uVOFF;WGW$ zC-EYJCIhAVv@Y~STY#MGD`oyzTR&jBY0A466=jtQ#8Vk}yloDO7IL8-TN9RrVYso2 z48ly>UuN)|cl#r171WaAdX7f==hW72Ty4N6#ug=^oY6dOqpy8hPzJr9r$2ya$?nM8 z%79`)gN!M%xHFeK$vRTpemeU#yX6r@6nFVy@Vy5)V?UTksPwkEkn)q4GHs}e!>UIR z%>=c0322!7G!(nB=_Z9wkDMpsZCUL)T}muT{4rX1Z?s)QnelrirZ_;j{H%w|S$u$p zC|HDz^xj?BkFJcu64x6CvP~kS(u`dw3j@Qwj>b8c9Gg#MobMEncM>*U`%(FRJ^ zt5!>Yr@VhAV3&i97$e$`O|XEvg__zy$BM5>o#4ZX7093V3(D}N6pO{_FrjSZS*qY= z$RFe(Z-Oe)PP)^U<&oA-d#e22B#A9Tu0uD!{CSd2iegr6#)6O*=|Ze&5e(L+8^QAt z3pA8<4sbl0R@n5xjEcRJQNOad6g~a7D^Z!orFaL{k2vbBKGA#5`rOL;{LuWqgjTH} zBeE`*%ZTJ!<&cGWO7Vw|jZTU|CXa3GR}v_;%km=*Aw5gd&u^Feuq2gSn+-I3&BN(x zJs7|_SYmo}C4FYSb!FzQ!e1bZI zG!^@i4Syr??y3kWsYS`-(3I^8$LO$MEenE_l zaS2?B&6vh;7${;{?i}+t7O`1jTH;S5pr7n)Y33A2)C}`!vV~=FtftJN%262784|2R zf+}}CL8&7ZB}nk>L?wUeVNHuFm1ad>8)}e}lY)a??H?3{tOcDdNH1)8;La(E@+GLz ze~T*i7f{OiLj`}Qv+y(=(OS{EJ=d{TaWXJ@U@@-B92Z5aFj65(6z1+2mYaD^jpIb^ zCMb}Au>9sTlLT5jT8A!skHM%|WD2<`4>lqZ)$G+fZ^OV24%iKvd%4bVSdFM@>S7_Z zhR!X;Ao|`Z_I=!CEi9`EYWJR*28}n`W89U(FN4( zGJ*#+c6}$hZ1#?GJ(PDWwI-l56gx;2gcT{zoc8#3uiKY(bh$N1?NFqR#M@>qmRJ+# zSibNPX-QGf6SWX~HOKSm``)Wqs7yfjJKfs^g(MMA{q(S650@LWZAi_F6b=TVAx1q? zG+yJPEHU~rR)-jn#f5*X32%|2@u(y9ZCbu%YHYF6_6n{2ZnLm!riM$BX~t;OO3KZL zw^BE-uaR462KoZ_;WV3xO>xDIBA%dlw(Ww4+M0$GA3+bW!FO-D_TDghC=k6GW6cit z*?X*T{|2sW0(R9uDKg5vz`L~75X7!MmU+!?>6c2p&oG+S;@{~ma}os9OTRZNiV)ev zGLzF^^%{{Hp?*y$F?KV=VP{!&`L9{2g-&`{`@<)zlMCCdiynbd)`9aXnScF}h_CS#xO^b_LE> z4*QIpm(I2N)K5-He3Jd|Lx!f@9-Ja2V6owv6Dc$VK7R(E)vpZp?m)wcda&&?cFs%9 zSUhTv*%mXlM6Giqmg^#rgLF>yxJAX(Xf;ToqI_sy33 zb>*bahEN7iPUNO`Rf3loE1h`(^?W`tF~!gx!N@Pj1)4fU_R^{;HI0Dq7pMgfCM|*N zOM)Vdzn04f?&wkn;?dkch`=;Gp94YiMT$W^6(Z?|5dZeAX)kj(>cYJHlkcnj#f?4N zpfplQGhIH<@jEdWR3u`cTa@B$SrGMn4&)nL_%B)NC`WPe6ltb=jwx|`&8?32@Y(N* zDoE(Xg+-Q|@kYaje5Fyy9!?Vu+0Br-d|Z|L*vk%b&2Gua@@ZVfxj-JXw@2`;eHm{%_b z0mL)^)dc6|kV-!kt<1@uSGq)$D*;pQC*IvhfWo_)sRU6m@BpzjkjogH9Yh3%6fOUU zf|fJvKwB?%^a|xK49gl3qywKao^%gu*FNyMrwomGGt=YBnjKqk zNM=5zQ|NxX24~#;uHBJUBmRy%@m$DDZ$fpeuQjfn0a1dRO6<0$^xZyVCWM=L)+Csq zMOIVeG}C^h{xc8gIF#19Es5QFE(2u>eSN}}B3dRUGTv1By7HHfx7~PNojFzmS;;q& zd!7c17c@caF_3u#UhdcHEg)!0`ng$-A4l986`~m#W>3H@?PVY^8Px8{Wv^;CPlvV& z^NGEZI(h?;fD|#g@&TJsem_;-ym~5qg{&c}QtI5_2-hF=B^Rnqx{&?}6G9Vi)r{M} zrmL1O@crh4_z8s`b4oYB@NBTIj185AQTe={1$(91gHlb{%rL-&6u$;A zl=qIP+dZ(3@P}1RDEh%B=>n%fx&43c)SdQ(|2q#f3~3Nx21ttXQ3)jy zYVVReG0bWBu&6VHy{r$E%QIc}uUUBY+e;dJ!1X)v62k_ZnLkOM&6{|*dIUZ0E{*rv zzQOEK)esnMFpPoZ2Y#fGMitD@VeZKZMHlZ1*`kY1R#Ys2_MW7iME{4=XriX5U!=w`&&2&eu)d; zn7F{NZUWcDDViJ_&ZTW(fbA)8RtWD8bRYD(_S4_j?R|;@0*AH?w}acduqQpeT>bg# zrNs5@`AsVU9g+aDrfs6vr6N3(<$&husG!g^D4bNndkKf@-6W1uC|y+6Ba?9hWeL@mpYF1~RtuGNGN zjXvVE4W?GsJ8%;rE_W{CbePnPPz#>m%dUxl{2<^*JS;cyr}Cr^dFjI)A%a{cN0Q&m zP{sV@H%8s&fe?qTA8msv*)^9f(9)X>{i-8Z`OeGZrQOm@(mf)!K)LHPOIRjdNdJUL z4u$7`{oXe(uCwz3(}1T@mG$`j&zswS(r*6=2$$wWD`lIOm2c_Dz(NMIs!ThhX+QeS zPyJt0o1J~6DOi48Wt1wKTE=SY8a`mBpV7cG(rbE0saX@L89euI`gsPc1vV0&m|VoL z|7tP(tM4gZF1Mf_K@@Fc7b#Bmv4@c%vhyAv1vHAdWL-4GDsCtP)Yx;K$y?>F4gh(p z$@?8zQ9I)?2CnSN&~~ALozG>y)@ft5x;fS2D7c5c`u$u7<}+mxM+1ByqEMxI`dMee z+Cy3>MbDy}b-$#WD~aQMxKi0(^PDToUppQuI&wgp%ba2hXmhRA^rTzwXwJRsV@<9w zeO!4alhu_4*K}6pPr#VG=&)QY+3Wwn%|hlC{`@NtVIm2lh1a81;ot|GM86%_(iC$x zrNxD11sf=2?DBt0Ko`E?+g|j9|JiNuwtXf<=CDRrb*2;5-_*;fdUWeY7s?+_)E_o^ z@3N5Dc^iHOdT1nm58x?{C9+((>FN@8C4r6>rEL2zjFtG0*sVnfs{g{GOr~^oDZ2r0 zM~gw0{m<%3Wk)&IQdd*-UiD-VmGl%nx`z_3mazYQ`aiqRiuG{gZD_LPcGP{FT7fXTmG-rpLCq!-b_C+mQy&yoMxy-Xf3B!*^?ofBKHU{2JAFD*75rmOUe_ z){?xgbRhrxoueq0AT{t&>Tri6vtXa_HiB8)!6lUUils#Dtk8|Kms#V7(jIkM?XIPuU@o zE0V7-Awhnp&o0F$Sc}u*$^{A`{*f5Vu;&!B)^(?vR&ODsIaS*lF9ZkV%x0#o!j^hs zL{|e^h`x{$g-;wbX1=tIFoaDJsHaJP$jv@ePYYpfQ5H($!$*3Zp|hwG?OV6ca@)ZJ z#c0l<3Ck}q%`fh<1IzM<=GsQcK)r}mKmHX zm%GFNJpm(rBfxla2LQ}&0AU98fHgqvr*|HK2GHdC{^m<==Oy<}1iyL;5SSMMe2Wb5 z+iB1`ul%(X+3FWPvMe8pH3PCRckJuWf4DkkdjE?viLF~{x}WPX`)8TY(SRiNFNivI zTZ-b6wVT9VYW$vT@oD+s%JAsCV=K^;DD>+>%4ozdNiS>#)#rp*OEt>O!h{eP?$?EP z*0~nh*q#n@R4R571?jzd+la@cRh2|#NM5L6^H-$g|NGuQRV)543qK-VrmOy2l>EOg zLe34O&HpY!&czD^$^R=NAcJJ1%$L-MTItKypV_y}=|su5imII3 zi+m*3YM=$-LWkDzJt2&{NS4&CwkF&0yA~yF@M`4=sgrt$W@5(SZ zA@WCtqo4~F-zlRKu7@d0%~ToqHhn4a7didmWT)FWip_D3~#;6!j!oCb4HcEpN#r&CeTU^Se^4`D6;{X41Sq~=#h!5QEO}?qX&9w z#C%63TR5lNB82Ji%f>j_M^FUXR4}elIe!YxE@aN_w-14F09{kK%cU0LHKvm}46tM> z#lW)cN(@wv*f%8RjIPWQC|owgIgzQW>g;R-qX$Vw#9xkhHUJ;w%#!p=ER;gAZ|OPQ z=jmahthi>;qI5jl0eb=|6;r&_LW#(9=TOU$Y?t2n-FO4@k2|B){QKi)cE7&NLSw^# z!{|HIb0gfy`);elzLaKsjmsj03-HS5T?v4Nx4=bXPQGM_ znWzKh2)9^ERdT^vP+2x>$=ucY8Q%ub8|L^+ZG4=+bajH;XQ`ioa+y3kD!j_K68A6~ zkdc%w8)KG~#R?T^U)vG{`+T((AB&s>~Kjg+5VqI@~Jm#I@U ze`+}V$v}{2y~BC`%=DN`ja0v6jdY=wGiP3EsOa4b~g`YnzMI7mmxl5aVD)Nse2)HUni|I-Ar9-wX0gLnuNleqH zm9lu1r1y0-k^hXJu)rXy~V(94NRlH||m{qeb|~pEyx^{++A(e)X;+ zLL!zjcCdAV*G0?dipe=#@}Cg||F`@;GlQ-!T7N{nWHiFF?pe%>4ZHYG0u#7NP;o=J zrsTtFb8s(_` zR>Rr-pa=yvDOxQ6DSifOHv&aCWm3!6#kHeQ>(&{DRU<+H($qx&T_fPExAaG(MEtpCoX_$3>+> z{LQ}L5=%RgYF@X0%A`;Bk33vQvX>(EHc#X2|tdLV8+*BwJu;ZsB_OJs1lA4Kg zf+o9>vG*a~#D9e4`Z1aW092LVBaqV$Ty7rP-U2fjg zZS*sW9o1gF(#t6M=-?DFd}Ts>d9}gNPM8y2EYS0=M7cIATh%6R$F%w#C9cv{@S#PG zMa#B8!gSY8tw&scVa^jUX z5RsXF6T=N#cH!cKlpD9(U*KSyl;aN)y`fJH$#NypttKl)z4dk`4vjn=Irp(zw*oi1 z4@6ns6)ho6iBLhBJG`@V2;t9G}pnLY37)%nhN%a zhS*7@XLaJ?g2KCj%+8Z?X|UOo&U3-gLA22GquRZ}Cg8cGYE;2p$rWe#{s};|v4252 zljHXRa@XL>T?xDf>Va^ez6okc7OoU6kwG0+*$(}kNKC-}Z=(upl2!+| z5D-Yaag~>n0RQnen<1iV@a)=EGp|`#%TB)#!&eG*)oJF>HPm z6OZ_+VlHqr!k5dXr7*K^;$Q-J=0#MuQZQL>Lz_y)~?#7klz$+)L%I1d87+ zchl&BY@267qpKrWBckbRI&^IGlXD?&%$l3vVo4dL(VV#xkJ(cVC4-7Eg&yD95^Pto zBrx^?rSX$r=tDkuYM@J02t+s~V z%#3)w8}MXeH>BY6>3i}EV#ss#5rvD^=w{5D=^|Ti3O3Rs$)Ti_O1~@|Do;LcZ%1p? z+`y@jIio4rm1$ndDe6`1DVs2o3B4 zQ4YZmB_F}Op#OO)O6f06@M&1*Kpw1@KyM011BMK{XYEHonChgZq?AD&syfJh-Sn&W zjO;O2l_pQu6KX?E=aXHtfhzy2X~tHz=1xpsiWRVmYlAC2`gjBdP4B7iXc;Um^=g)s zlvb1mH6*Hzbi_tMJv$0v3?fN`)St_*(Fcy5b$L`SK9s$ZA54jozx8w$Z;6`G(eDvAV~+Rg_<^V~39xK`iXAyjgwXD!e*<=M-H-J&Wj#b5U}dtj0=q36%OC_N`fHGBtUkv9J^s|Mkk;lwskhi!hw80x zAG}|iI9!fa>53@&^7U+i5lF(CS^?Qr+x|>2*DeF+ki-mBzIM!l2Aah??eQ?@%cp3H`E3G@a7pW9yxL#XTlP6a17my#eB6X*&dTksnxd?-2G~|3Du^=x^wmv<+EO6*LW%jjY+T=4&q^ zt&Xy45D}TDJ$~u4v{o$0vCAfel|P}`QdgrlGIu*bGiF0@!HAU6D7ppe;JnVw^4?6d znKYu6^KBg}a>kLW1leJ5=BoY}rx!8JvbJ^VcfogempdBfdPdfi9Wdrw9uBcr{Xm2- zbW4Ul4iW!8^NK{xhH8gP3PZAPqrYwc<}$UTwkW|#aDrYeoWoTx12nsLC_3gYEsGdW ztqh=d_=Ht7&#hQ%zh@WuW=V5=^jo8Rm}iJcasdC&-b$#Wxlq&#F5VlhcqTX2Y+fnp z(f;&dOJ7~Tsc94)o{S?DpFJsMMa-H%R?rj}P^VX&ZL(1Avos=Byp_|*|5~-n!(I5U zNlwzV7JEmBy2{an@x$2QdMZ1+6$r(SgG__g{aQPf?F{vY5&D9nx=>0lBPSDvl2pQC zxc1ONGr0vV;SE}Ghtjtdn&E7Lx?<)B@GVnwhL)n&k@hmTz27T$(jqXh4917qlcuvZ z+Bdz6W}n72+M{i7>qwM`YJ~6`qL8z@K#8WOp@TozZZbmVa4HI+=6jkRyauTuBm-^+*%5@?uT z3&9}|6wEZ>D?Lb)+1|}9)p}TPFIi>jN(S-$C|Qc(&&gOc#@wfZMa}DN^;B*?lH`*5 z&#j6AzAPRNyu0W9S?XcId%16X-${1KGu^69fw~{uKT@^7kd?MdqSri&Pu+0_FUIjk#wN_Kxdk{DI+e54V2Sv01s}-we zh7`-UBNAozWw$bzh_5Q7eI`!85!#5Y_MWV@Gf$gX+#Cs-&}b!L71E2@T#g<(X7B@N zHBAcma4HC}MvC1VMS7B4pOowcA$x^yT$K`(9mr?cjIrnBu5#0}f_GFBiWblv<%6Q> z9i*NS?}#2;o2Gpve95M}Df!J5!x?Zg@z|9grpZcW92wzCKUwsG1Pc{^$E8=)C=%Rpa)`aa> z&#ZfZ_e3oRyUV_zEcG5P7D0)-h{vFE=0RoW{TXHf20sb0%9e z(UnH+w)%vv4+p1fHkJGr*M)1zUL)uf5?;hJ#!wqi{44W)GZ`61pz2%0-2bP$bOnp) zdt@VHT@|V~FMZ4eRAMcwoAQc$+Y|x|2(((>c(?&BV-e^=k32lmY*w;veqH3_=uL5q z9D(OH)3LNSnps~r<6F|IbAV1@oP%h^(x9J6MQ>Ja{$7P7J38@I$y(gQzLLF-kvi&9 zFFrkTJZ=o(+ra0>l||v@IJC!=V17xS^Vv({k;mhR4QW<|W=u;~^{w$Ryr^Z5k(5MN z>KhN)Nv-g84YX24lB@s;#V2P(CT3s9*py7qD(29O?)PPDfj=bdVr$hz*SlG;de4*W z1EA(8B;RP{3Q3kMX!T#izxvjudEF=EZ`okxpkI*Sh)zW1n(z*v$*Ka-K^_JS!PrK` zdn_ehc1qkr;M~rOT-@*f(g{Z4>I<%J)6R;hnzDk*WucxM`{>g|&tp$z_+m-oc zpF%OnBl05Lhh2>*Qa4|QDIv+c*<6>`FfQR?Z#OoywCLRTv+`uv0*$Fqm`p8iVPU>{ z98_g54%(&dHtnZ9!c^I0l@kvZPr~?+fV6WZInk9-D#_SdvPU{~_(6a)Cl`h^rGk|# zqNTU0ea|va!;!4?Q2WX1crRZA=ejCm;?(OHQk7V9s*s7A0U~lzK4r-hk<2i85nS}! zL|A-awy^h7$(IE_-L0p!8`wCkQo@y(%QxmpAZuQd&B#bkKu3+uD?Vl{eZMl)7@lX= zm@1%TS8nbfEif`XT2t_9iU!$!a3H%|f02Nn`ofbx($Z}iZnh) zvQ>IbA|nLnIrEc$6k%S;0Y@t3o5oX@JBSZH|12WNfIl20RsMOM(KE%ZOH$?vUb5j? zp_fVkQ<3jb4&Bys2lAJp$399w5m!E*F;GDpihg#&>79;Y|GBHUao)2DG>9WCAO)6T zd|k}??VQ}SdaWlKpa66Oc4ojlhz4!^t|{REnDLNStD@edi+`_hwKBl|W(ZNUoRyz# zGer?nb4j@U3;VrzyhVF~X^&tl{01>mK&j8WEBvHqBOonx%)tZ7^I8nwnv3G;WAx^c zk5qT^K}No&wimWQ35QL3g6w?e9pz0NFYZ^**50Q-h~Msit_=SD6|88;js|mFh@OC$ z_xtuOKirk=D#Uma+1FE(v!XRIh^|bn>_ANG)^``B%so8M(V`=LWvd;Up4@)#A3k$L zUJe72F)xC>LR}?v9a12R`T=w| zpgjLVw(#XK4@lzx@`5I;%M`GMt3VQL#s+rrr4tWDd&FOT4@LX?LVdtT+!Jd&y;=-( zVQ~<=5*J<+zE~MH@yR?51{W@x4Wwd0D#5>BP+1KQ|xzB7!kBfU3PmH#FZy`KKD-_~ya-!?Ur3EJyaf*$mi1#mCPE(kV1&`tbf!Y@fXQ=rdF%}1Cv z2hCF0p}p9}fXF#-M!U4TryhCvqU4V>bJq~hm4~%8y-5|pz$sJKJRS(gS4o{x+O-6D z(o5~rLi^#$_uF>6!$oVLJu4`k%BGcDBq|san->YXFGacE$JBHp1~Rc{l5lqNb&(n# zV(j}NuX^t6leLI~l4qt9lUcAcZ%+(}*hcK# zNk9ue>NkxiFd@Cp?BLaa=l?CPGBsWnONRyDAdo03&#;_+j<=jX$1g z_5R$T3q8!XDGlAdH_p-|wfkMuB@AgoLsP=h7`2V|W2*nlhvL}iO$b|VF;iB>ky`FA zSSTNINsu8KB)6QIHU7aDV?4(lJA2MTQ}>2yaA(S3{~ojvbTENLG>Y!5AEg6O!uUU6Po>ticC^FVy310dK<;02aA?upOlTCjCj3e8v)sK9}z6 z&(hZk5?Jq8hThnS)$itjMdj=s+(fl!;GaY}@6 z>1%&@_78bmbF6PV<#c{LLQ$DO`~bE`9}2QA6_jULm!#vHASsog6?m3yQSrow40Tic z>w%sm5M^az2(~MR?M3n7KLN+9hVO-cYV=eucTk=}Kz}L+YlK)f3!-ugWNlE5f0rfv z`H}zhwR-e<@rB;3b|=IGuw&=8>YP%NgHq?eAZ&rihn=>Uy{Elotcac3YzD`p2mvA= zMJ3N1uFNJv`Rmfi2|+O^bdsIm_AH#uF#(cd&J4{YsEFBs9G-Ys=IT)L)WaYb-SNgn z4em?5nl4D-8;fD>3BVfh5(Axm;46SNq7)?cw*5}LxjCuZaX}CmH9s@F^)d@n;-qH*gT>Ss zKX8JmOrO~~@4aveG|~0$iO_zMSPuc)>d5HItF<#Lf07fu08+Nuv`)QtEqi;*<|p@9 zS2RympCcoV;1hprE=UU3?nI?*uVw>ok)6WS$Nc>kOqZfysdO?&QYaMAR5HcB0Gdk4 zH;JETJ%VN1`h=P*R!XXkJCCZ1O4{D64Fj=?M0IW?OENLjGaAu{K~{LR_>k0zC%6`7 zS-PzvZLwlNI$FOzb}w9L=uv!6_{5GDJmqTz6o&7AAB|FM2sp-7@P5!!m||zV;Op1& zQ5dH0eIjAyAqaRQgDT`OT1RN)jC!KaPU1`XHlcC(cX#8D#woBkX3HJ1M&z!t z6;f1`7z&O4?rwakjjUTbEMh;QP{2Cc_*%=PxcZL&^mlvX%WO=S_{wXRYiUt3Sxenf z-`Q^m5nhKEi$Rp!rRR*_9-9Jo(Rf%HU>9w9P-fFAm|UFzeeVHJWvSajJ-jMA5BHGt ztU>jqCK^RN6M;5#Ym5LQkuG;Db8dGD9_+R%s9Fzgew$4cY<@;9tJ%j)kuA9~zmsDB zmB=K+(qdq;o<`<-W4GN6*l$aeFSAgRw#p!~v*e7LH7xC=+c?R{anxVVcqQgi3m>#U zTKQDfYPtuiMlz43%^Gu7qdH4Q&J4fQMCk{SE!~cU1Auo_dFK`29lgMYJvnQweVK{v z0~0$9K4)`suhqN&%t{18C^HY7$IdFV7Z0T?b(gFrW9m>jo-MADk_;eoq2l|xEqmA8 zHL$54bkL5E0)!^}Ve>OW6YT$C?=7S1*tT`i2?Plm2=2jyJHbhC2p-(sJ-AE)!QBH1 z4nZgG8X&kkK@;2wPLP>fWaaF)vUbis>%4aFxx2mge$be+s^+L(qlWhWeP6eP{jn$ueI>wIY0?3iq5e#UH~iS%;l=W;G7 zrdpk6*c6@m-4jLdR5TMF+2sL{B<#grPAGE?LYVF$)t6lT1D=EcvWs4oOJF(o3(}<| zO;k(UE2z3Ud|%xP;cT&nVnl9#ehWr;*pI8A)G&X_j5l8C82qU&5E$@ht?XRLu27f2 zKa%T#TsYO4(j=h)JQ)`Uz%EhZfB4+P~{eNA(^$q6$o`<(1 zf8=v4**98QXBwlP-lQGz+jH?Vz9=3+;&VA&O{arv%x-wH(UR~Gx5??V3w;dPZN9=U zzs*E{AGTfvF!M*vPN28#ciDpe?apr)w@g8z#E$d|cH+q+qsNk?Z(M6R7v<5!$p+Af z$39D=2B4;FpCMKd6M|Y^oLN!?OSL4eu<+e`H75m3)mieAEA;EX+ZX^S$3Gx+=inME zQi(&35mHxA`{Q{0^ZB~7;zap=sq|e%jqKT@VO$C5wTF~5fYM9^Aap-=kv}z^;COUe z;)XvWA>nbT~9YCwJlPVm(|Ae}w?9Sn;QfMMAPe8R3Kp>9 zU^E_z-Vy$2qAq#+3TT?6G@UC57YnUcl1&;Z2}R zjr}zo5T?wO`w39{r4-=75Faat)%}-c{|`PqT`~AibsxQl2H@|w$u3a={N42GEU!$0 z>ibbneF`mCh1BTfcHdHM5i)a2`Nk-VM? z2mGXVSUu5I2ZJ?pG zj`w=OeK&u+vHE2)%l8_P!)#?;g@jAu7~jL)jNzu`KiAbc0^m8nyY=0!`R>;5(O( zwNy*t&pu8B?j>@pfti#hR3#hZ6&_c{)RO5OjFuDKVbwal=+2Iqflm zALAWE{nz9qIfYz*&VHpddM}*}Ae#U_`ESMWgc=N9o!?2|n1U1C-mXf;j z8CgfyFk6!ZZTw!;A`dFh2uCf^7u9@{=NT!`&~=Zdqnjrq3i?*^Ofart1C28!5Tjc2 zlXUG|3~bDgdJ_1=J|{i8JP4LG+-T3GZdrbi(@?7t_L76N_tyU8E=z_;qr*!7G z@}+5=I5@LBorU-#QTRW7C>I+yAFZER6yf2wTTp_+?<1>_bcIq}Xvg{GzPp|7t3-5O zm8jOtmG`w%Hhay&mTrP;aUDBZ)UncW%AO9qRHLi&irf|@;xmvk$f05INL^DHLVSNZ z2hpo2e7Jco^mvH4{g*`=+3nn-16djtWha(@|tk+PDZJ56el6s5LcfJGN?j zRTA@Iv;;(<(@!!dH3bfrh6PQ3Vcvh#5Y0~`9_zd%A?{RrUZ>R-Qd2OmHp!Gz6UP-v zo@@asRk%kc^QQZvO$113n&Pj$kD*gt(bODw)qly}MV09h`-GsKvVfvgdc}vE|GaXM zV}Y?%gVejx z*1U}NaHCNLeZ(dl)h#G@WuhE+tAy8E<$VuT01uYvLz}pjCj{A|2Oo?|thAsR?@^qc zA9r;mg&QR;N4)GQm7rToHsGQwI_Gg*{?y})^bp0b*yi!0_c^}w_Ws3U>G%u^*b-LYK?4QeG5mevB#^|=Gh(=NWk(l zz}Lm9NbA{{&N6SplO%^PfLlpTpc>G5X}Ga~U3|1=loST~EMWdcj(tMJ{aF6fyW+)W4>j?5BVe?P)0Rm2k!@ld<^$8-Mg z8EJ6>ORcya^yX)GrpHKxwiOQ7*KtMMRbpTDcu((33SjDp8KqMtaZHhj!d(&$Gtm|d zQyeTmAFmM!HMu%G?w62)6^(awtS%7 zj<0TW{z!V2EYE2M7f;1XYd8zeW82W1hWmMgrbCY7)oT8#?j)gFhOL7g)1Gbio3mI7 z#pO3RMs$w?*DSK5xD)GmRY47BLhlo-==N|a%Uc4JDuWI_U3AhPsN7<-I47ys*7|bK zL{1H|BFOr*+Prc;b{%>-eLkwyvp)Znm~AbsB2y_t2f55K*RoE9bB50+cf3wL4hKjJ zfWu~~UqukQN;I!Mg17@VZ3yyt#p9uj(5++q1ju_Z*ho|8H2wKtYG0KC4(f~jnk)zI zQeBBO{(To}c~AZvpiDa`9{8-4&&2qhYN%~yO17n8ltgHqgeDA~k7QPnimZIb*N%#T zIW6XlRU!r{5ehU)qs@qzTQFfHS!X&$VBQpDAHsEy+AK<1py5G4RP)1b-qP~<4mql%Pcij zrdI-OS%|+J5$c@_>@xxlJ?v-!)q6?Aex6qIx=-L~GdO4II{3j61TL`J?zFxx=)5IvhR~pJA5X6VYlTx zq~<;r9BM|GGD(YzMm!vIFPdMT7xCV!SY60s8st<@cd=O=Ga#mt+yG-$F06Z;NUbJp z`d*!Zs91$xE@=Y^8kdSlg?{H&#if^=Dn9I-@a;XdNN!H49F0{~F%cXfF+E%+Y?>yI zn`5A%HQ6ySustgSWEW29tX+SZ)3|EME<+Ry0DR^oIeibX{#nBU?{2IDKu$sRVp1Xi zPY(o|%HBrb5}yr(U*Z)iaam-CorEE;ACy-6s3v^v*5G^i<=H}YylK4&m2a@}s8*q3kv%>lKSZ)kYL4PUGxizIXno2ch^M2}K z<+6;ni1J3R?k(GiTV%#d^cKF!befqGB8i6Ts>Yy$<9$?2QMh0u?Wje*>4|MVn;6M^ zsXjTKxZd@1IP@vIuc9~k!*g(Q=&WBRAvB!y$rx7JQ}HcHUwkd~w3I5PdSX=60cW@YP1${(fdn^Z)=( zQz@ODq`L`ZR1`WShBWw3K9f^pvQk>laACV#TX-Co0TPfrwAY}b)7CU%mqfgyT; zEK)jGM|wqe9-_wj;;9)^CduoPrgyhb$<=l5J(#EIrHG>Hvn|MyP*CZj!u_iKNY>pr z@IIp&7xH~U1(NN?w_!bSImrshMhXwaE$>Mk4cSchYGUvwtgXe5%y2o4&pkO~K@=-J z?v7bt=M1e0nM3N`Bq=U>D>aeda4j~CTdDBwTO?M}&5;`E5?(5AI^CQ`)p~=XCIG~% zwMu)@@ex>=82~I1I=Hv`-%zZU&yL%!Xz0^3|NNyT3=DhvDA}9sJBS>7?E$D2jUB4} z9vh%4@asjt^%s5oe~A=$#?B_INlH0GIa+{E~|^ZJ^nQRz0Ck6WI^+)xRdP6c(g-V4;D z-C+hI?HMjx#241##ZnuipAx-$zr`_w`fi+|oG?>k&!fbWIODicqu?0OUy}x90E*KM z05xNXAKFqXd`f4<7q0^h78^jCKD`;TD{L+j5Wi@waoeQr?20sr9kyqoxWZ`uj-a(& zL&JWOS(LbIn0uvhB3lE;OquZlDVl)JE;1|g-Yoi|)kkO?%#}KtjX)l=MMBEx7*Ouq zS@gH7I}a1!5Lm7DDboPN!U6u_JusAC(?=`wAj&^%6FO4@9+?V;!V2F>j_-T++}r|G zLdrX-ZXt*w^Z%hs3N|OXwB4yvWt%{;g=WGgzJQ;+wi>WWmxLOpZ(D1ru*mXAx69ce ztB2uSonOHbT3Pyw{gP8f@MEJ&|N0^SeJ@f&$X(I(#gX?NviouyUKt}yCH&@n&2Z`G z!scoba2UTbz7PAFZ^FFw%esi7Br`L{gH6Ug&p2z(Cms?y;}1clt1I%ri^Ne9!Y%f8 ztR8KCEiwE;V%KxwsUAujHS16@h+;z;P`5?j741Ku+v8ShrLt4`(J8hsgGpgDK4Vl7 zVL6y04g-C=;yF?*Qw}PI(s2}!{*Dgrmt3Wi%GQ6**_)FI`=^u~|M*-fAZzX6lUoA` zQ9dq5*Q^NKh2j8do}7GL0iO0O3RKkn@%ox*+Vbq=9lI`9ElE^48!%NmVLOwaSl*9BI6GdZM zyKwD3A&=-nMz1158jiYLvz(~B|MnBC0xD0^)vvrIKKx2ETnzfv^IiFjrYRz^??}=4 z&HVW285o{V=BFQf5p7`+6}%8Wn5W?G5_GE3f24tzEfyWnA zlmB6cCn?EkzGvVY7WZfVbV;t-Dv43XdB4a6RwD;i3s{-Qv9iPijgPU!&yi6kHhzh9b2Qgf-#&XOoo>(tW5oDm49e*QpH z1CfG%`mg)7=LXn4?f=*wwCGO8t;n(OGtS!%JX@g|X1(NB*bK}2vnQkBH+XaaLk^S- z0M8EyS5D>YBWYkCMis7S(L%47z5)4jt&&k3Jm{IeyO;h5xF1UC_6tMbj;n3XjKZ=W!_$GrnPNolg@qrv;>_-E{47@N!5( z>HtNnxnelHI_AlvV5>Y39=9G*`CFPf7qeLB&V3y}pDOLzRHl~lw21f-f$fTolnbF{ z5iex*Fk(ZW{T~ulKDmF$ix;nnmkDZ5RU#&O z?gR^0NP_fa_Y!E-hVJ}O@mb+z@Ga8xoPQCF(MMF1Gp=BaAmh3SNre2uE_|v$=?`#1 z^A<4PfHUb42_CeyEsqd<6WQ2y>l_T!Tyd~eXk4$Xqcek+l!;_)yP5DlvGa6RVtd1~U{@cJ_iiXkIcdQ7`-y5G&xlDBjT^hvcvJ6FGvmp3Fe3O% zMCr0V5*G^Th_y@I8~6+U&*FPmYrzoZQ6?8lP8I5)+?djf`G+DHyuw}ILDQwFtMWms zinT3F6ms@4c}Sgbvq$5}a^>N2)wrV^l>q&SJYC)k8PxZ+K1#*KnKQ1h5cl{%tR5a| z544K?9fa@yk{zaIq2&M7a;8ETA1Her1{n|UF=zV z6#>X!D038n29jr`|LM4oyTr~Y)Vs%D%AfI-2YDj-d0tCn^(4i3%D#C+oYc+iUQTys zkJ^ag9HcIoBGFaHiZJn`WQmiGH{|RCj@gNX|N8z~n6#~Foo;ONJye$WNZoXB59K8S zy0FNr<+x0%7>%XjFj_i^9Wb;C&&A3sR3|wrsHEDzgQ{(b@dP#<4|Pde18w2An%GAe z*HP`p>+M;|^n{b>F~2l9l6`{CxZ9j$RC#33>a4zZ+)o9Kw0f{KODSqHXQ6WM9DO{7 z*MEEY)$>ZV1sUb7t@6HHk>*_QtB)w`t=$JABrp(^MH-?)qcp0dxfSZ!%8prnaHAKd zY`&$#_C90S@sPkr0-D6ip{Rgu5xhI-CVf;HfOB;OeB*;;S6uXGN>jj+epvYGTL2(p znFrGQ8TS4qiPFzwu!n!1&6gm=DwcQ^IJl<*}qnRXVlQ z4Bi6R^8bf`JsfAnc&!!l_hDCPusRgvIxEh}V|*fw=5?3`wG(hmsdb5hBuHLFE9t75 z?(p&HJ_oX$aL>56J2a@nWx5=meZC$=@WJk`n=*V7uka99wAr(NhN7#JL3jwGZ(+)W z57)?UocyS>v%7PE_@(v8Pu1%G+b0<;epvzxjRAz6bLyZWngg+G0e6=;V%9lc0tYZ( zQ=}x+Zzki1OtuKtn3Ay)5Z>k5{HeD6|DOc*D*qFeFh!yd6<7rvcyEMHtyJGx37;Y~ z|5P{6D@Fl$9g=O*O;685c-ci~hMuF7HLMBSScmjn2b3qRstk%Eh zS%~9?PJb;fBs>&|&#lL~Io}G(3+{Y$<%9I~B;tgTmQmg(_Q7!n9-$3Ro6j`^J>wyj zcG|**vEkA9G?=oW&06%-BvfTK7{EaLMV z3)(exU%Sg$9nWlm#I+l7NQa4eCkM6wa^4kdF`@8c;N1`8d_K0PUtO$e;~mbvPTNdX zzvz$(Y81_)culihqjj4vyel*~&$eCX>wMT)sw9HF9<9iIRHCkShn&^ew;6<->VA$M z93LS$;nWi!0wDE=aPw8TLbHz1cdSetT^6~yN*!%T-I2s7oAaqHkk51Dwd|Pd;05l! z?G0NADzT5Y2O{)a@e4(GDauy0?PpgR0*vCbb<2hZQ? ziT+ls^9R-8H$sHJ73;iXUHo0K&O6xre@CqI2i4(ki**822l~G&)~QyIiTwA)I`1&{ z{|&LuJ1)WB7VEsTbr6D_UxYdQu)+$1#Q!5jPY3K5e*c%e`vRXwU%ndkdWT$Ev9y!HIm8s1a$WIgo-<(T?ImLQ=44c&@AUZ6Fbn-0 zb|~K$33eZa!i!8~u;mo9@T8`=Rq$nL?f`iCek`DCgDlhuX1Ti65}^o&CDdg%itGF0ycW^}*LBa0^GqhP8YcXh0WEP8@|8jj-UueU4JZS~Qk( zMigk#29$E&jnX$l3c^PR$FawA1TL7$wHI#)BnGc$DeOwlxyXXg&Xsh@p$wX=%NL!W z!K>ZXKnvz>gyapj%Jdr5cYCKK0MSZ6LCN~w;wkv4yp}aR)xpQ~E}f{KucAc{HTRNJ z6ed)yOuME8vS*vfLMcP6mX*uiSJnRF z0^u5c56Y_Cz&+7c6Ji>p6m)==TM;Wf$lPw4S!hS|6U(*fd;4BnxD!sW*+L(nYd}~t z53YJ3HFK)-A9brmb{41C3!ZOIh#qi#Ow@U093fa?7~^Y6e9TL-s~iRzgm#pZxzH$F zFjMKTO@fV!zy+<70Nb!GC>~HJTGV=}h+zK7MG8E*!!|6)Y(O9!hSRfV0Ud1t(y2r* z^7dcEO*M}JXzR~BYiO3h#1CPC*e9mWy^Oc)1o@f@y>>y|RkKRlcx&rEKoz3wavd+> zD%B=IygHw!dTrXBv`d=1qHXp_`71Mb{HPQn-0hd1iF$;Zzq{`G^L3{1(9vlVmZ6$g z$l;&flVkPVj!Fpjo#GU0rYapDa`C%f?>cVWs!l!tvvxvZEnpg33muK!jIFILl2!CL z0x@`!@T?95_63XRxWe+Wf_#nsc;Jx^JJ&E4mfrEnw$%FJ>M{dzj|>WOr~I zwvE6_B1=)LkoNdHS$p1BbEixcg^v{lb>4&J=-t;5s3YY5bO1jz99V1`Q9IiEi5=V! z@kHPy@kS#N%l`J4id0S8M`*;h0tzU2!$Nj$AYo=YSb`f#$9wEct;ysQ6!FILhfq3j>C7Z#e7i^H*2mBbrX8-OvWcPiEGC_&%dw>8G+7V%W03$lOcKuEt3Xy6HMzX zxb~^*315e{QnvWdxUyD=_UYH{P8YQ_OKxf~2$s}G?tziWz=)Cg$C+sNYf^MHBf0wy zmUdVKW$Thc-Z>2gj8I0ruq?A5J1B(?_Bq==uCsQvfnJcqqw@J{dR&yG+(>f;#pZol zl!i~wcLABl8P<^Ny$y?khVPyh+6Y&b58k66;jJLP%g2oYnK^dBQQ`=O&NkllK2+=yBi zcUl(cEQp$tr>{Jyy#Llof?78O&ki)A=M}H+Qie&d^FE$>kMQLN>x>)G$-0Tp>@lzL zjwD=qHB5FZxpgrE!OLp`JDTRjki}X?FL&GhfCy5-ou&A~G|_#wAv@brTa)AUka7cb zn0uI$53F%d^e0~0l6K5Xr!Fvl&TEcZZW7lcm^~AKnpJzV&pB2lXy`#sgXAtAZYIZE z2&H$HW5Y18ocmS~$TOAosmTwp!Utf;ec<-_aK;5R*uoPQ&HoA(_%yCcf58CPoIlWh%LAV6Lvr-<3TK-0=6XYgs9TZyV~O1 zC^!;4AyaYEEb4|mfaJ*7$ryr3o38UA%ax+IuZ^(osuyu4lUWI>w z8qN3sql}_qNQnH(H0|wjC(hNvW9yfdH0#tDab0!MU5y5#h?%Wfro=(K%==^AP7sQK z4}GhG!JHNPS_=G6(I&B;=g@G*;KFU|lzlR=w#U<{rkg14FMgz`DH+2@x+upd`@}Zu zYm=5Ju?p@S$qQI#6m!~E1uf7H?$uanWYMCC9gwCi!2O1A%8NvA`U-kHjHkks18-PQ zvH&XuS3WFM)3JSoIKjBL1jR3#{vxZL7t8aQ&O3>z*_UYop)rl%bM(inJu(U%&QSVN zRv8bA`=p<4E#R`=H!_Cw?hxP`CPerPKAu!WFiX&yTiKLzHGg31t{EjATIHwUjbnHU zTfNKvaN{y;edeIuE|v{QHyt;7gMe{^q?Yzi0f^rPCH{O2C!;`XXp{OZ24RPq-k28F zWVbrKM<8JK`k@xKBD^-ymVGu8CjFLc-@^z2+pW$DK$8-p$}q%DRETRZ0^g6y_%*E* zF>6n<;@%5V-+c3~uEu3C;dMwW&UX+tEm`ah9h?Fj`D(1J=GR^Bhf);R&$;fch4UB@!Y5Xf=-s8>DPt{$z6+fL_w&7Cp4)e$Z=l{cM00xLOg861bWnUW5=w z>--9ZN`-@D*tLf+qB(d>(zC#P^6&{j0mqNNsj2T2{_MAUA{?k-{=U1KoANI6c*Rb0jZ;QPW1=5qf(V(tMofgNLQ1IZ@H5z&Fd#NxSbmo zJ~MBv36-R`t|BhIz0Gp7?#?o%0VYx=h%>z}!$t5Kkf5PZTGiHtfuTcfZs#$vi%6%# zRa7=)6h`{hyVX>!ACg8etQ_y0#VH%R1Je>;xG*}vn{(HhtwHiryl=VZN{=q<7Rf@f zVe&OE=3Yso<;7^0y@7qOX=4B|d16PsT%LR=81ziLxZ2beg1fjOtjSAroO%6Ove$MBGQo=0Rmw$-AR)>57j72s8Z7zx;QO!SZH? zt#A+@Q5AR=7Z`pc%(@LUXxpKTn;F%9euU8{MV1FFCkQe=IhS2Q^llNej+eiKo;?F= z33V2rr#1)QZan}1L_oY2)G@v~S$0~?-@v6VQU8jXK86-PffzMlSFNpb)Bdcn4YGmc3Gnh0HUPPJNrE3zqo`~bdEBw6x^NaJr^8oC)9sT{gJFS z+W3JyUzDH(nD~YMr!nwIcNUP&>f}c{D>EQGB}^C$MH~V0S&j9RjuDWdRyVAc`^fJ| zOC@+XP_jKzba`??NfzAVmN+Pxr`<)^gFVwnh)NGR{Q$FtaOHOXQvc+r0Q}h-K!NBI zXYFH-kLk?(a**uTdpZSIOUjBn|J4$6@xNF?!h|yfHkX{+R78Zfy}wJFwd>)QXSk7g z$SAqY43mU;`&n`cu3q3eJ)wk)b2uza++c@53V^4OAm!z1+>JE<{3q(>jFVPU_po+0 zM|aRMV_}(TgA5U)ii~FL3?t+h&2qo1vS0zAdH>3r)cps z$pw<+79+9i^^})ha2e0XoZ?1zUst4Pk?)u&#bq8Nj%R3$Ej=Y|D=7XD`^I)$@|}z6 zX25Atr{SP>%@-%7dR7<|Bi(t`!2kdWfr=|NegIoa*Yb_|6!-XO;g`on%T9Eq1%kdsXsy9m> zwkxOega)x^Mw6vNy7C<>$8$4emJLC~rzgbBV7@qBtQQzW#aUbZPH0XXT%~Cc{h=}q z&TWo^pzZ7vCF35HWqgP}##4hz-Gyy+YwCA<7%>4T4`GH8ZLW;c+97ED&)8W#mB*e^ z-f%0NGfJmFiqlZPos5m~4P#KN^yUF(C!njB72gS%Lp0ME41m}x{$KmCnsA8xm;7hG zYjwsBXLC`jXHT_pB7v}O*|_lTSAZHEYMCW#2;ju4-p~_;H+iX|IXhz0dlKB)pW1+O z0v{b>&sM^vpnVQ$9*85oguqrC|*4 zu+FJQmKjH^ZR2*7apO`7DHg>wqA)Wgl~1;npB9I3>N09+7S=bz7}TkClo9X>`6)S6 zjAG%)vVqX01q&%-sm0wFb@5Hu-vwwydKKU_RZZGV-LG?#{!E=CK$Z~qgiBUzisU7P zxub)+zLB+9I{tN_pvKh|GBYk;k%@8-r{R}aD$%hRe_=is19wWO_*?MB8W0y7g0V#_ zJb>)`zYSdpc2i*M*gVPgKbZR*3;&Tlwh!q`TcV+R6n-h!BEsWUX=6+3g(!B6etzZM zMv??VlZzzoqdDEVtW@4din%xh?L9gxuRf8G;Hb+t@TA&8`alHP>g29eW)MXwRY8$G zZfA@(l7%P2hfhSW*oqT>Nf=IN9JRF#)cD}`zuIm6a&GX5>?T~R?ABul2+a~s{Iz!@ z6=a8vuCt%zPa5D}@Oh>r;n7$-M)bdSy}*eqSxEEkot@vh@L%smVH)JeCH3HM>u8*# zBXs4hoyf1B<_dWug|*W6NHawq|8u~Qq;1i%*7gGp@w`P687d7Ci|EAISM_brjT*z~ z%5~NbUb5`VdEP9E_4^Lshq)-@m>j5YiQ8nU?sY4X2bYnpT#X-X8=7;iR%^1*qFI-Lb`x{Dvi@%+8qJHKFv8?gC5=9KlIo?$-Ys`Ns!q`(YWQ-n~O zQ}>^rmWGAFI{^LW!QmYZ@NwJj4lrm-wpgnv1OfX}?B%mFXCN){QcW>O-d&PsxL;n& zonSyWAa*~q4X6VH0=P9*8gl?*>6Q}Oh5-#pO2w`<8WYDcXH~nG8kCi{gU8@u?d)Mr zY45M?-ub4-#Q;!3_YH#~&gDK{wn|P-z{UC`VzWdn^_J9409aREsZdlm)l4)CdNY~D zmMA4zz(T(=l->tjkS5M3$#gm6(<(Mkrhj4DTMz59UEmnORClBF%bECE@)nKRhe&?H zg`YvQ`Aj4^sa^gXc6$A8J>foGzCrzzK|j6;;0kKLDUSJikk6c$(_`tFy91%%h*O@7 z9e8+aU6K8Y#%Zo=uu6B!Gs4s7TJmAP-Xj=x7JLG|$$d%1mT8-{@`~|81CGdOu1R05 z?DYIH0d)m&T#{Z}13;(9c6GQ{Ny&K&f!>NPGp0x@<0>3{byEwBzT4_nN%_$1Wgu+X zcIv6vLozlF)KALzzna|sd=4jNMfe+TjsDfiTVO@Ym9Lo&?9XDYRe{lrx9t>81QQ^5 zX7%6w!l_(aXD9WbjL6Du`e?rQ6&3+2ug(SHc!?;}L3D}Mr-j9q{j`ns$aOexI|K)* z9W?PgJ*~ORa6LR8*7in?qm3szH?611Zi>5lloN*KvF2ez5hwk@^v#A6Ua8`#Zd$i# zH6LS)JeF9_-Xm##1Rr9KzbC9ou_muP&|V19mF)kBx+)myOi0%dYQM@i>5A3kOeu>U zlO>SR66bO6MT|yCI)5)BypwKy+qE(%1oztS`r*7Iww0Cb!BM^?;@4+)onw*ztyP|y&KXJKStv(j0 z3)tJzbZ^&dpapt>csrFFxjzgd`S_F|y)dmzb+mK6)C&ZcxsS#XQQf5~}n$9G6HvmkJP{&bHZC!YJ?e%(w ziz-zr5o(T_8H4fMiGC@%xN26HL~fk7#Ka;$KKtEE!?WCpvo!W)iRu#<6xGMD2>P5R z4{{=0hMe6LN1VUxD<~r!b-B4$fz)aHR5~%Qpx9wG7kqE+A86_*U~8m5?oFF9OFNZp<@7pYb#+U^}>KGV%4W(>jDr~+=pi55Y&oJvh zn=)?-l_m@Xf;`{>moH$^D_~(X8n05*)LeC3nje9Z{F=UOfPrp}%-*xYt5i#Kfve%+ z2s>yvMr@>n# z?q%dx$+@gmF2~0YV9yZh5?0tV<2Fap8_u(PG-_JYAd_-v9i@l#?t?b!lW>#jYy}Ev zA5)puqi%(q8Eqt!;T>NNGe!R|4nHM zSdH`|=M{bj6#&lsvH|;B(nQxnEAS2z@J5g4fsr;3)p3!830p}s?a_a-<^3m2gJvtm zy-RylxHwyCU{*)7RH2GA4PA{vkc8JD{XB{wMeZjFv_cehYXUsEW`5JBwFE@DTYL|| zEm1jTzOPlUMmMb5fqPNBn^Q{@fG`4_quzz8W_szXIC^)cFSXGon37mv7i@qx1t@>N zXq>RIr^3?JoF81xk;XT^no3lCfm{Up$`AAzP;P|5RvQ&XjKyZ_!Jr%vgYnqykrB1F zvuzzT2;aNBqrEu-v^Oqn7`^fS={}h`?Jn4gKFmy=TSukZWP=%DOKS#WA?FSJpuMZj zX#fMEbJt7gvI`e=SrcuUuw}i-zdfwPI26u~p2^(slUe^UNl{%dEM(k7oIzAem~gwh ziA<?BE zc9dKMiCY1`#!E^;j257BC8^kCj+$dBo6YG4GZTe!#iyiol#2FyH&B7a>i|BLT1XhYR_4sYxX zrE>&TCowg@gT6*v-nLHXjM_ zh>T0g65$rFfA|#sd_Ba94uz8T*B_C6jn)8rUi{ol?rMd>_5xwJ*Pfl%Gi`tDdL?ft zr^%LD{=@Gvo$Xi24*o(~4m~^k>8SujXwQN#%D_L|BsB$@jDODx^o_6AMB5|K5%rQi zNQv=dYgn<|_1Y+ntN6(bh{kWm=|7Fz*oT}03>)eVue8MRv0zm{oErvQP3Z&AE@%(_ z$_IFB?#%fAPIb|_d&!L)QluK*emXEoRQNn7Zkf$!fr(9D@IjFkl&>Vx@f%79#&2_3 z^OCcY|IB5r%*BPw#RYsMyNg3R&ckB{se$m|?HKe8dSv;FarjT4!T^X{XN5VEPA z$z2iLcfb9QvUrer{&JT4PiMI~khy=B`KOz*|I6Ze?tbu}7SD5M%s6)2`3#vw-O}Wx1vw7~+dquWhA&OUOpWbLfI|QHuW0CG>ntF^qUdC5Vrl%+-ie%z>&FdUZ0(%?DE!CW zoyj?bgjk-N+L;6Qe8SE8g!3P{zTMyLrQO$wnE&1r>?&(Al0@}*0B1%XDb{+RHQwj3 zNkbA{pI(xVC1$A2Ose4Zuv}93gE?%b-lX&O?_&*Zo5NtUbaON1pxtX`rzKtiQ(A$ zJgMi&H#t(|l5cQ5zH{rTCjC66Slir6r=QHKbSxgr${TmXC*Sq{k5f}N7n(T+!?6#| z3!80>bWX*ZK0ToRP9Ikn%7R_;!vj~FDxtw+$6`x$ET&Gq@{&_cg)oXL>WqTCnqPd ztNretBqZB-6Bk45YK=;K`Ba3{T$~*4g(_~oJ=O}j3{;6qnuW67`>AA<+qTu&QD>7; zR~R^!O8*pTP104(%uGU}d(&H4Svdx(zP0#?BY!uE8IlQqR}W9INt$kWCqrySIupA}1~CU$Ml=U#$wq@V3^FfV_h?140CE2Q&5>KlU^8$I>(^gJazwX_Id zOPQIOsj1;c2{&JtyRNT8(f2ox;YkFS8f24~H~G(rSm`(zPC9!q?3bFQJ=0FNCur&7fEsh_J2Wyj!W*n? zay>b3=H*~eBNxv$Dw-||ZY#^q@V^&U zuU4*>EBiQ3`Q`I8q3iZe$>fnVgGgKkwdb<3vI=E3Esfni*QX!bfEw9P4W$K8LN|Mzps^t9sJ~dbZQ3{BM^8Kk6s$F2QQ3`tg=^ zmuj`TE2b_5GR6Y)@ocbK^f^kAG zOOW|Iv(v_G*4^Ztk0cH{0m#E5(55d_b!`*X>nV6b# z+01pju8lTSnL9*Mu(8wAILzpM-{@jx4Eyr<@R6gp0h#h6mL(pc@V{fWn&ot*_+ZeiVS zQ(|H?@?_QxMG@xYNP|~&hISW{Y`>m%MGcj!4dIl^L$tUhjRwPKm#T<(Fn8H`HIUXVdi+v0mt>$6EpEt^n(GLwfz{W6A@pElnz{M`#*XY+p6$w?>q`sOZ>=70rK6JaC{bRjmvHs@VU@ z%j4cw3AA0=nOdW>#z?)l`!vxR-ze^ny7isVrhWf(r(`HhEzwaDkH&Db|MRU~_e7<<|w2m|}!mm();;bn1} z&UhV{dCXC@l)<4;o))%~MfJvG;58Srn|!PvP%qQx1!vb9LPC1!!sXlAE&1WRzissG z;4l;M*hVQxaTeJ=u^&E-(RMp0LzVHpSjx2{(SetH%V`F0%8cT)DWLyU+zd7g3up_0 z?20#w)y)gUKuf6OV>@UN`&5KLQ}%I5I948;Zoo+<0jEr^xnwJx!sEJ(0&}K8k&1?< z+nUFHx=@{kgTLx|3j1u*`o_AMiAk=vjK}r4?ajbth&iU{)h#Y2=5DnG%ww!Xm6r45 zyhqH(88{{Z`3gM6@(5hk#C%TP=L>?57Db?cN?hna5kHjOaCw>;4Y$%w+XLaszb)(L0Ht{%7!26 zyuq(pTqNA-dmR5Yf5L27{K@uQ*YRwq!5d7^%>x0+Mx8|gH@T8!Bh>M@m8W~ABBtuvwNN18R*J1he*`RXNFrNj0SD z;kbh-PlnaZo;HZAhlAzOpv_KaS3?Zurqj3=$EpLaX~pWr{p?5@6nhkt9-l{JQ`-2G zM#qkp>T7*kg<|aF4-(1`=1ixKySl`>eDyy^RA}#1I-G`Njg!P$qe8C`_jJ}OOR7u} z>k>=5!tu15mYhGui3eJgFSLdzAhh}(srsu{xP8x3=*ZZgZ$T@v{v4xZ_Wlh0aJjIs zu#e}!DPP9tB#BJOJHp)?PrLo}^pwv`?)0=@sNN^dJ{^^e&tc4e`8)FcF4X`P9WnW+ zw&k1M>4J)QG;0DKUT_@Fnl|p59()Hp{9Q9S-@nO5)uV^nY3Y%M%?{}%;^RG1s%^}& zd^agr{yn)@KWSi)L{^Pj4cDA(`Ma?A@!`wY6k}ytUDhXR1H)=VZ+XBt-*+4@jg{Dx z%*<%8rJbCdo_Rl8JLz3oLHZg|2UN1?+fHG(K{VxkFrO)tO8 zWs@G8;;}VCV)mY9g~2SmHVv3W+MG{}@?>x@g;Q&H-jID8cHj!u6OQ&Vbai!wG`6it zUIa_oOwS#Uwu-FnO;-tX2f|%{+WYpusC&z(D%-B_SLu|H5a|Wdh=7vPEh->NBOTHx zozf*BQX-uqjYxM1($WY>cS$$w$#q@#^W66y@80_z&)8pHKOuv)Sm${hbI$+#{pWGA z+kl8&xJSpz+F5Z?_*3ChrLU}hOXMuSH|4~5-#eVLLEd3ti9*;#f2$|oQlnJ2l`Px0 z5F5#1_72L$N0Y-$_dAyHHjh}bb4M#;M>x<%^3>1g+7ygKHHY(*&QCIRE0OJ1I_yUl ztbTHGeEP_Ho6}CQ?ZyTn;fI7+wkfirIHLxV8o7`Icb7x88k>U0+-jc(hlb)*QP~I_ ze!d=&3VSMVKA2r*xtmq>UD~ZSM(|D_iAGCf2&rwppk4Qf=jRMTgawXyvHfWQhyI)* zMRcHGei2U0IO+C}h7k_0N4hokh1V7FoSmIN9)AwoY?IgW!6X9N_fK6|uT{PH2s^zIs$QaE!r=rt`cpmKifFc2Q-$m? zIxSY49d0kSFFS^_wMA6SZU-`AMJ;f>X(N0Q6ie)`ME~QGg>d_amgm`umCqIe^zaPk^hMmy_Abs(k1CF+R5oTKe{*QoWFs*XzEEz?zJBpF z6J0ZN$o$f2kM9g>s~SS;7*Dp&>Ear?W*KUMon~xOQfih;OStWc7kKDElP3LP98OxvMLcIqbl?9ULIEL0Vmz;tos5m;8HqM_k3iB>;5l)e1% zLPC0~&Q{EJ91WNJ&ABlKPwf8Vcir)tgFJbD(TS`*qIcZ1@r!P@wNsq$)pfVvy3`poNZ1&O*kWLSZr1> zdz~v$j~_~B2cK7;rQo12d_=jWNECN+ip7K+^cBCdJ;=a-M4voZ2A3bK+5zU?}*z9V-W)jwX59&Qe`X{S%J3#ON_pJt^;cwitSPhDHk|F=EWJx5dRATNn0nWBk@z_Z-W7C?9Fp z*x9>ICkY;26c{PK`FX}a5%7Vex&TMOW%i&uWc?WJ6}MVfyuhmo(4_Mki0QOi!SXOF zUQ|x|0krZ0ZGr85sMHl6oE6fcW@%@FD3$_t%{@n}ev$o@N`^HMX(<&gLLZvA)EZaV zCm_<2d_~suxIacWrBDb}jDLHn?e&93H3En7!9~XqIcYBicaHX&v*dG`+@uZmUnnQ1 zvel}#Qiy+BF03q^ipd+*Zy28JUGCi%e;E8YuH@m0QHGuRUGe~@G#mA8fBL6)I)dqm zf{q}YI-l}j=BPf=X6NAL5M1hXOm`LFNe`Cg3OyupUksVZudY5I=W(&55;2}n zh#Qy~wi>OmKTU``I8bJg9b~f=*gf=PuwQ#j!F&6ZF@PVt$j)J9aJ%Kp05Pk|En&my zZ(nYX^~i~hzqK#)>P?avF?>)%^x(=zs%-X6cTJMgJAX`<6oinzyDcnPMHl>Tq>QpUQ7gvrtHoB?L}rDCZMaB{cETcQ zS|ip|>lvu6A3nt#XeNto7ZQe1{Ys3D9Vyv*pYvirocgz>xJ-a`Ugqau$&TX?RhlLX z8Qgf0Ha)*_0UROe824d+>!fxe;)*@rr5aH&JxHXp4V&zWXi#b@m5ogG?{aHCKhk!1 zYZ``7Hs+9bBU4{Cs!Zr-o;9-lw6iT#h;TmH+m5w1>b|@9B5Y6VI=f#y^!;k(6nBUZC}=qop{kN4_$)C$WCM)Oiht z`h$sY4)Jnp^I4O)-VhNK9JidL4!A+>dcOE%;Zd|d&Z@PD(Zg|H%sg8H0wrYsu}$0w zeXXUb-n`G5nQP0Yqzybadq-cs3@lAgAF2Chm_x=~{$-wCe3K;|?~({^$B?p?{v7+M~^3Hh_wVgH$eb^S+D z+i2Do6efcD78i_c8G>okP8(y6__nd`!^Vs6zWAW;u}k_8C;Ub_C(Lfq3!C$jkQuJ# zXj`Tkhi1~G>t$bW)`&p)<)IhNwjQy}BAg?0ve?s`lHqFh`1)jP3S}_}5iB{~e=}(p z3Dr+XIvavCEonmOUVW86L-6CI+WRX;Q8`yJDc4ovxz&}C;r8+{U?9X#x7+drtJ#3 zPf1%_d#J4av&tmL2k&vrpj`v|`2e2@d8Ve++VK<|1XTdbM;&c#WGRN;*G~dNt~&Xw zEVmQYh`=cgF(Ns6`49!!6ZoU^FE8etj(fS!vC9NUb5~YZS5?0}Pm>HPJf@PHWo^{e zuJw2`IQqptbS**PWT~8&hDG4J>uwqAh*h2QE=lz{fo4i@BHBTgd~35Fac!Tv#(PeAGpqOD94x|5BX5`@k}Q%ZZ94 zP1oarJuXq){Wo%M>u&&nymDDx0st~UH%?etfA-6|j_^lhAKfugXMn3ys3NhnalJm# zJF^junX2|P(jTr(Ia18yYyyYx6lBjbm3;DrsrJT0r?_vaoP|1NEI$pT3AFBtK=uOQ zlBK(dZ4##NX=R6HG0v>hIOFqqt}M~WgTIK3TlsU|yrtS<^~SFEsJ2R%9{F)O9mYn+ z7rC-Y!WCb1+5i5j-og7^k;%--qy!(PGP6E>ZbV5{qyRbRYxNnG5i( z=I?E{;3oYBerG@})gq`o}66a7`83bv8)VuCZaPgs(uUnJu@&94@j zP6J1s3sLF`;iq^_43Ep|J&xH9$ujct@)q+2*Qdx$pN}h6=&=8?o7mhke>QT9>|(;x zRM(T7;vuG|fLT{deSx-O&Ikh4EfDAKQ*1XL>re&R$ARu)11~ybom{NL!WFVD)y#*2 z?|_6EvHs&mK#m^C<5B^Vhv58@Q=_(tSf7=Xw)kaj75Q*wT->mP3t$d-$ni+QRC`B< z)nra9_1YxMi#(=#_`!~nDT{vC9)|~$-Zu_b_Q~`52L~ljDzRg=v{WUfrC$_0bM`-v zB4|b<&C@oj?KqandU3Tk2~rETd%0LOBMgmpSU#{kct@yDcXgx8g?KLZNAma0Rif`| z|N8kuN=DOlVdu`HF~&)(X8YruKc9Oa4(IiBcE$^@9llxOcyzy8Rq?J*KqwWDp>8kL zK7?`qC!6(mpzo_AN}uFXohxEQ&gm0irNSdJC@bf%&5?e9#!22gNQ=7#Li=Qiu% zf*$P7sGm~)+$O!r0uC4}8-n(ln^hIBBEQF}t6P~5*Mm$QADA;g`$0^UT^VTj$>Y%eQSCy@F)gmatrs>mAC-!i`*Ov=tbOS7~gVF-~`l8ZhxsD#G zd{L4)BO15MnC5T|qCESRbDl)0xi)zGx@~qpo;OC@|Dh92%rp>qij`r!sw zp3&R6_Uz?hlEgco7H>o?oP^fLuxZ+_j*2<_D(X$b)GQJ#3)AA7_n+NaO*J zIRz>4-5KgQvKBFyff$nTi@N;>7g6epX^Z5lJ;kZ-0^hBQIJHc^=MWK^%#f=768YV+ zWK}C)W5~Odm0P<&mH)E+Tkuu>LEOK8=^PlT5RtJPo%gJnkM1~;3dXgC2<*b^7#|RG#{*_o#Oz( zTHtgjV?F_TU%tFT>LyO1LwZpE&Z7y}h<)zFR!PCeZENe)TM_0-Vt@XIp82z%89 zj}IDIjlr(bz5iOZL1Xl<#B#=Hg@7JjQC!YmUCFi6>A8Tz7hj%LHXO*6H{G-TeK4IY zI7Y(5B9K)oWfGKijKw1UC+^L4L5GcBbw+)CN|6ljHbxu8n{L&4?33Sj+iTaW^SF?~ zJ0IKUjR$&vZ1KCwvo{QBl%||L=mv{Z#}f7CH@Ogp9_*#m&P@4e@9$hZ=4a6t&odU+ zVtZegSD)Zf*)A2b&OS(}xA~!Wa8_@v!=YBqb#uYxMZsUuIFt6}j!Z|*D7uPSHX{$pyLatOZ+ieWiz59O!qQMGQxk)c#xU#Ulvs0o%;LWDDy0)k7T{>^WFa{?wmD~Ob zBu?|BFF`?bXJfL-0+z#FD-I9LRqE{)e(lA*Y2G}4QRHC6(6P^w{7TbL^PT8w6}j;Tc)tv zL*bc#)v(pB(@0wp;W>u8()3cRNfwpghRO8%x-*rz%KpZHe3g&eIhN~Qg=TNvp?E?0#6V<({aWol_~@TE|mD*GF~DfBn@mX|--d)5SoKFHB_-EMNG{8i5S_sad(o*N{2 zPEWS-C8s2m=DG9>d(EI+h9{!2gLM$??{D*QAq6^M_#=dy!Wh$*ynkXBIAH#|~O;znp=Kr~0?lEL`o9JfH&g(b3b$_;|y1Mp8m)lumdmL7V zt2Jv3<5lvj#GXENuzFhd?Mi!e{OEBZBX^%|7pqpsR%iZ4FcC2* z(!bFj4&0G!3Z`e}b{}7Sk|BF_Dc($kDY7JN`|Uq^NL1*L%7>Ql?hwiOpy5(IbW+Sy zE4CiK`R#$n*-^1Un@WM!@&4LK2noA@{c04}My1pCERZT*tBGtU0x%_1RY$0VT$nyk zQBvjuUo9-uDb{c0wf;@y-FlWnn)xXDwvdZmzD8+UTH5=am4VN$hnw)f)uZh>)Z91Q zv#so!W$VNF@q6-a9!&QV&R@SN(5n3EvcK9KfEOEIlD)A+K9#Flh=zvd;_B-8WC2M{ zL*uSiMbWE)tg5Q2U@Z;-0fBfP%hmC6YtSn(?3#A>~5aF{Iv2v+ho_h6qOh1ET zV^tg3qNZ6-Sw#;wCuc05Q{BGJB78`cT#m9WM3*o7vfhK+w&OWRFYZF;3b9s16sxM$ za$oAB*15u#=H_%rfCmQ$YB`^Htv%-339zw4J}V^WbR;1$eYim>kRt1cMNIU#@LA>~ zH#avWR>C|xg`|hCCMvc8*2N(jw>x7wT=!QOR#y0R8{QhUg%PJ{cm?*1OnK8<)lYQ6 z-DrC4x!6Tk$zShv&ec|)O^hkvx0Y?U(r+qGAobO1Qb5a8MMcG^Bg)HCKK8CuJ5g^+ z)TPlgrrqRT>(K^_(W2|DXnVNE55!L!ebBLu8RyncSsM}s9ckiutbemb6dcvu3EU#X zl=^UTylY)+A#Oc&T>2_9#mBX@v@}|U9*k1PrwM(1ec2kNIY+@f4(p?1B__acxk0cp zF=6!6KG^THMvdjr`Q6)F2%rDGNT9>0h1fHiTDau8y1LO~BNG#90lUD?a9L_-mOnqG zd>;M&eIMMUmKI62^!9h5+F-?+TkWq7$?B9Chdw*_`0=B!pC9e^P%a0xP?H%kDQQ3} zYLFY%dZ~;qxLgzlG7Wp?u9lFjH-KV@5_t)oO_F@u%0< zyJCAj#Z)5bVp2wUcz854G}KbRhf^mfBy`ofY)(|Rx69JA2usljK8j)c!Q=Kg;=aY` zpPA->w6of2j{39y0&PJrhvTzmDZ4$ZsXBKXVFxFFe}A|0g?K#J!;&;#l+w|7);Kvi z)1^aQP7m0V&yf!Hwx*^gC$$w6ww8aU6S{W)u61qJFff=4rxrm_>DIptJlM_L4dp`u55|SJ&ov$7t^mqR4GOWv<+6(p&9t`*_D-aBZZ}x-aGWpoEoG!Jm|L9Y%$u z=aLZ(;{%@+WQy9hKirY8f~}V(g)MwJ$MQDPHX?>eNxv~?00u| zvL`rN`s0v!V&CEG2Cwt6>Eoo9AQKjgt zBN23P0>$Q`!FL?PNHx7X)37gA*Vg7(&i7Vs78riSYL zWz+ahcx@B8fpwz|KPJXHQOJdzFwgbLg)ybL^jk12M)2>U{94$>3t3iEn6YGQyvg`< zK88E)YONLN?_GOATX1xGnwy*3%p!b>x~?ZXb?*PWX%v@IU=MZ-B%4G5dwtjCrmx8y ziPmnMA_TejE(sI~GP$_9ja zzo!18CvwkiF8*o}wazP?icK5H2{#_~YHE?HZD&1>^VS|NH6O{aFXKa+YjV^kwRlP3 zdv7+_@B|0Fp8aCBFpNw{zm+St$urEbCxL&ILQPY1?v@}GhK;7?c>U!?yygJs7C}2Z z8=DRL4ADsc&O&E#O5jeRnpQ&vlDc{x9aGp7JRY;YBd0Gfa#a+!18+j!Zy3tW6DmS+ z%{$p&n>&IXG}>0=evO)I!^9y;&@pTyKub%j2-(2(6XFFu8)`1HieZ92r+6U&ZP7)? z{W|H;+v8=H%{z`uJ(RwykRc630{ULhG@-^^UnBbNJ^n|IiO}%7KyG@va+!sC9R#OO zV2>}sLEY>pIb%=MMP!wi7M7}cYF=|;l!E#Tt=>IC9W;9N4NjaHsty(%+oYOiK?#2P z^`iBXXTd1x%^5sch)+$uw{PD@+NYt=M?)0st&QMCC}dp2Vj)~Vr9J1I&@8iPZ1h4# z$L|j&<$xuUtgC#pG>av*F7x@`CAEmhJJrjRHI8kw)RxQTfJ>BS|M3Ren zA`F8oB`Q}^gPk4 zwIRYhSileC^Zx=>w%If*BcuJBj&9AZ{$P|;>_!~cLfp=A^DF z$OK4~l4v+yqC$|ody|BqQWA@Y9T|M)TH=-%bEUTte2RX9g2^LX^4Ddc+xt_+hL4xa zL~emW_ibk-QH<->l(Ixn&ze=kAJ-RqXOj)2n2!{E{H^#6a%5BOqQs(GB)?~r_Ed#8 z7Rv`6&vRmP((j3K=)AnV@1lwj5&U;oR#uSKFsEt|fk?X`{1$EX^=AVK=xo?ipDo*3 zJSpl6jQ3{6BG8AAHhLFhi#DTBZQVnWah9pf6wKSU##D)bqDMQ-gnF*{Mz+j|9OnI_ zs)}bIjKlx7lTrnag=i|p)$jHbHQN)!ph&NgY1OlaC4XKOO8-J0U`9nuE zs{yaiGC391O9&(2gTNhXt+tpuVCq2LoH!+Q`!m*C{?*CF zMgIpmm!a&B4|j^s8n0Qka&mL~M2zwmyXI54U2)q$bc65j_-&@I#bQ(2OV@QG_S zw&;IKNO(swRqKjAwKK+{izlHGK|_(o-^IF~M9^F`Bdvh_)1%I=Zo5^>&ri|oV{x_P zmh>3p7OX*^KQ(qM&v3{Pylz9esvI-q>oB}9GC1fP+xNr{S6)Mc2{S*YH?Td^5XpG7ZBnNQi_U zOjZ0M@(iPgfA{Yb=@V#I+s>htnV~Auucr#cjg)?c!cH_ZUTf~N*8TgpFfHx%5!$rd z!=z=;ra#%**fgMFtOVduODBE%c36(o->Y;snJhvbFH7jTcWLPZ zB&r=8avmH5Lo2JhHmo6&lrvA?ync;;RH?jj>=U=Xuz*UcM}CcNsXM;yE?L|KX`oxv z)v_cPQVG|eUz~20m6hFcR3pE6(`UtYrT>ob62_62bzP9tV)(N)a@FW>h?)3u(;H^h zdd>c7hbi^NdqE=G>|PBO?KK71_X;t@34$L*hzd%ih7=k};oe<=*wf=|dg1H-a-~1B z)w-6&9FN3ko>b@5gT-t(@AzojUf6P1}q^pR3S|q{D{3o6LLKOEj#%0Cm1o~MS4Ef)zwUw`O+&1KYsjJ z7jyMi~>^RxzF~prUIrOCadg~izY3{%b=*_cwSx* zu0WPs{Z-29*dd^qtCF9c&6MB)$ra>3{7=B+j4$@H;g1i6I`vOMtMkM_BNu&i986BDJE&p5}{QmtrtYTLe&hJr>SkTNZl%>%i z?LHaHIXX*`^#t1{un=xb5Cl_Il|b0x#`xiEE4DA#nv2Rz!6*kpz$DI&cYAtzFh-$o z7Dqg-#E}(aBN}0HBZ@)jX$#veD;gTopL7az63IbZp;PBJ2Dw&2q4zp6n$7F$ZSpZ} z(9%ht9&A`o)v=!>BfNy(bKu^-{}#djdcJ+|i}LY1FGSq^SANk7kdj+wbSQh2%ilP)MWg?M6ea({0xj7o^bHax>|>vtbD+*8n~ zdpkR??d^$!m?p>h+5;pvE4w5GB)YMcyzX-_luYRVXCUYv%7u84x5zO zNFEd1?y(-o3ia}8gq$rCdVBw5-`sYbrv9ompQNdT*FqLB?nz)Sp;Ki1GY-3)`0JUl#VYU+9QdJmz!JN^v3ysC|1;Pjn+ zb5oW|D=Z8jI)+|akqYBI1dq%KTw`YxGq-NTHMV87HUcBtE)z*WP{~5B{5`7Ds z4gP}l8bLozdy4FPY8UanOJX@7LU*;R>@LonQTT-oJ|espmI+q9ETIxUj=&+~qJQ|1 z;!~m9@lFv7AK&QDpApf|R;e&`gaZ5CGeZzdanR<iM!%-6O-?&f(xADI>#p=ML)Y zn^_&}vOk##Gv?>#Q%FB56;bE3H#UmVB=+I~v&aP-2d6pUm9eQQhAo;=TvSwsF2@y( zG_L!C;CI}ls1})-o$b$7qC;UJK`t_*+o7FoX_<$+f^mlAI9dEc%GCF(SVBV*vEI>- zNXCiW{$P33L0mXVi zRTGr}8{50%>qyu+vJiEXlaoJw$W8m>D$_569Y=cq{{884(2ZHLEhXJ?-01O6=H})O z8q zDN5arU-Kn!XgA<-onj|r4Knq-fh1jPVu=SRhk=W&~T;q z1GB*fW=9{%D9`YD*tPB_dl3~f-Z$=Qmf@h=yn6cdsfNZUCXx5){BbJ)*hr`-gO2_A zucf{+G$bM;3sT16}JkxGiBVa$lPb`4_ir-~Xp+7k}QL7-p z9Ob^#(Vr;VEwOh}M?b|_m@Q-dE}NlyPx&~a0%!p2MJO@|i(3R`RA z>QFAHf?7?$jkgkpS)V_D-mUaj0_>A<-Y}vw<4XTg3CKh%a|Vt8!h#>LeWPMAqLI^~ z7g#jJEp%M$Et0#7-D7X4-10Qbtw7R@=7@JYIXTh9lqgKx%OJ*V`U9IC`ZBk@Wu+EE zi@haW6J_A+u$^Ug&V!pT0%qUnSnLIaxj93w=be z;UtaT-o`lZy?Zv0jQ)tU;74@>_O4J3+2sEKNUMS89qDrnh6d2fW1qv0`;AV-QtI9I zMZbf?LL`A_^agGQ$oQY+ykK7hr?^OY-`iST9EPm~^gutL%AoCrDeCo*R2=9sQ24!> z!UPD=)ZAJ*?cOFOQSDv#mXVhB4+_F$^-c*Cx{D-|fmb$}=drDDISheEPjA?lB8HTl zBvnnwt5IdQ^7>$1eP)YJPEHOciJHs~_V*v$zb`2kL$(?A?j4k@Uv=))6^QE?2Ea~} z?&*0yHaH@})bNs6-`KcGNQlp&hrEaWSyu9RN~<4e88jxIo}LF5D991S&+sI!F*nq8 z`4mz~E*BLQ@mT&!37<_C+CDgdJr`3U)+CDIXlLhJcQwLf`Ro4X9l$L>S(=XtrH=ZK z-zQnW&-ue+;V+7Vh1Deg@gCBOo5%E8VVBG8`=-}|Fo#gRydO6E<2Fz5@bYquvWtQ; zNya+qQAxwkRxe@Li`>Kg%feB_|Ho>{rurX!k%Um92W|~f4HSNzytrbkh3y)UovClH zl)pU76qk?~E05#MsE>c4{_fp7fC;*KdZ}4i2SA=7c9QwuWHppB8--U^R_5lio_h1O z@`D0WRO~CW9G5)S;pDX#y$7=W;Df*aci;nzk3SZf^itiyjcpz|jl+YJLwjj|8!1Qw zVG=Sj=-jCwi{j$qu85eEtq55OVBIHAy7}KM5>-XOere%N|3fSXCNs)M5PPB}gq-6k>fn;lqcfx&W%rsAbB`u16l* zPu~JMq{A7>*8~_t`Wcs;r^fTL&dclisaFG_y(9s9tlt;V=QOS_&9R=diFU@Y1KNS2 z`U*6q6w!|=`!yQs{Jgx5DCReyH6e?A)v3J>DI+u({%m{Xk%Jo~yIJ(KKg2%(jDxGh z^=9#L&<+UXo&EjR9zH=q@^N=p*Hh3+N*CqzGLn)Y|2`Xcf5ODXgruvdQyID;?5*-I zW)51bw76Kz1v+r3YX4}kI!76&@j7=`keU$bpy89Eqwf@znACq!0huHdP9<0W3kU!- z`k;sC8YJ*4tE#^4fxd<)x=ls~sa{rI-n{E0XWw-=@KNKu3(Dv!|1SzNFc=SJE5T~` zW$?M5d@C#C8ALwq{`B_kwQR)i?PKacYNn=4r`lR*31zPr9%T)whZqKJGYf^?Ee7cO^XpFZt*Pb={#ipfh9 zW9ToqA8v?|2GXUwy-w%#F*u4NpT5gN{|YpHJ~M}rKmpQgUX{{_S`Iwt0zlcT=IWk2{Fi$I(^-N9M4-SC{iz@ggdx-Kug8KILt2Y@~Ye~>^{32Y~ zD%)0_mD#@)xD4ta{O4rTEPi?Cxsg=CYElbio7 zGzOr$>E(uYAugs+jNx8+obRhzbd-MkrnYSV=1p^fM&lBv5}t;PniNgjN*uRI!OPm! z*;z#5O@ecX`-ylyB*1yZm)iw` zE6mDS4al+Q*;ZatHZrDy~wLUf7dzdz%@fmlN! z8GU185)u*>SPeMT(4K!agmiR+*-fe+_-8}I6-)-Bok)zd(FszatjsqFQAzTT3bK}%vFq~;~X2y%DN7xp*^4cyM9u>}M zDy@LSdi&&-l1fBM4-^arMn(xwIJIci{+@RIj<13#1|1z8st7q!cr8Q~;33b;^KvJb zWMOwO2MkS3N1;PHJ=`jhREz)g34Y^qUz?AEHO_Cgmvl2W0&a&u!3qrQ8yIL-LqS2w z)2>#5jYlr?3Otq@n1RE3MPXq#zG+-hPZl$u7qiy)Y?DiW4h{KH5nkqnE_?RQ4ClO% zC-A%)8JVJ$+Ht3c9cpK1cmKfyqbV6U5+dnq0*JDuXMKG=C51*%Q1Bq89^&GdzzJV? zXmId%jkC`^V|{&ZI}8HJ0qA@YqjYs?j1!R=Tw`UHnt(@WWOUJ1CDj)8u1iKoM&4wR zG?f`OIOLanNRZe|#qLW_iaa#Cu;7>aqoZSIcNh9fszZFt2KggF=N-e!BzoxM>J%>G zr^Z${HWHJPguxjl{&h`iHdY~Za2OZ|QxG_7#E&d5IcZdYz(SJ2;LI`8gqH;(?Mx}r zgK!1eIx{l^@EH#iv$(Vr_r?vCR3X1y*#_9XVE5l7B6_Yyd|~pD+axS5j!ar>$p30+ z7ImpUUDoAb9cW_E#%m3YUvMvhLcB12myJOr2Xykmg9okk0)D#BzdTz2<9U`kl;NuB z)%I%) zyF-96R0?0ZAN`rp8N;If4>fme!E_DGT?asCHa2QNEuOl&xiLKc*azPPw+%Cji~B85APF>B7`Cgsgn1>ywSPjpmNS|)_W z>G5$;T{Pm=P!92Y6J*}Huf)R8ip?!7lsfM&HszB98}?_&;o~oV0#z8vs9)Ab1{{AvjAK2ZB@5ndt+h876?uRfe!4uUQkeg;FLZ4-CBbb6&<%&38%i~SFKmpL13Nwf(FDH6l+r*u&_Ra@ zK9>k9E2}9H(}ydn_2O1?Obl8?+iIa^`6fj9%=Pv#Km~*Nf6ttlMShVr9H#3~r4OeP zGW)+XEn&t6R~s%jRAtBYQ9TnA^g~31H3d+DpyO%y?2tqr{xkPc6%!xNI&F5fj*J;V zJ;TBP#$q+~L#C(iptD<9Tcf)TN)(d-`?~$b*|Dq$sHea6%iC)~6@H2V1{vk%BR8D= zZ%_tT6y)ZPe^F+fCpuS%5cN#Klnn(+6&%33;%M1-*V_m@cWy2&MOq|!^Fu)L(2alO zG71g~`T^qu^maJZpaj(`Y-RvUR1yXHCnO}$O87Ut#<-EqiH?qbK*%OjjWHT{;#8_t z`5GKKu3RIyec}pGCCe?xAtCk>VVe2tdSAQZBCB{eZaCQ40o$mOX;Q_r@OkW&h>uXz z1|iaQ$t9)(tr}DhCm@{AkA+k46XHIAp&Zc2ZgZx_#tvYf;7~tuc5&eW&zhN8t|0je z3nzz)tI)HNAf6#G{sPgEWR(2`hqd1s`1z6GWQ0R!bH&^XOOkL1d|> z-(Q15L!-kI!O=jv*KZ5e0xF}yH_dcuTok32_T^>M41?k-bF2~IYQ0LCBuIaBUX1C|sfJ6D0y3GYDw?BHvxAzDdg_O~G7oV$g zkI8)IN)Mfc^u!0}a9`Ijl!!cNXoR5C`bYbSy?jY!PG#FUI(qBW-d7q$UXm-wB}JBo z4K!7NWjT=gj^KJ01f#jcO0UnV4+}f`V~%l}E=Q@IelFN9mDWILfAD9ofl>KgKc#HWd zty;#L50Lq@%Awc6zVdp(^MH&0bU`rpA!;}QA;F?x5XAhu<8FE7w=-zOKC*13mL4sza(@t&$}vd@G12ehAk=pIbq=Le*PMLSs4U z>2IKkfFGrmeywsfB0@n(h*WtGtjNFR+T7Jlq-)qbs9y*bXo36$yc!`fnIt=q5c?y< z(C6mnAmG4*gGz(Fe~q$%nUI^i1Z3tdGP2^sBtAF;H`B#w@STFs=4~dNd5bHgqG&dN zhDzcJAN`C4e6%z68E78-!CpN2OhQ6g`+6xv=rh%t(cscz+VMsA4GWoZ94vvnh-wkXte|<%^+M!P$oPM zvK*Q&d=i)@1$}vIweUr5Oj1(Pr%$)Njs9XsL88^!JTx>Z;DlnVj?Shp1tz{ezmqSU z^Zd)~+FHnRQeq+{5s{&Z$>H&?$wB`JE8!mY$@jk$@vc^_~Dj z>+3~aNqn#S0dy0n80_t}{{D_kb|x2HAHl|!2g6o>k`T$IGs^T_ZN*|fXwZ22u=puT zY{Rdo1#rUe$cn0gbvOEgt^DiC72*iL;cl`^dTd@ zb!&NJgZ;hCL=U(u`>+{6D*}}B@bG{@UoX$Ix3hy-9)v~%SR_p3b|s4>pVPnZvO73^ zH2VZ5H6NJvy`_w0Q{RDBBfB2b+3O90vdenTOHA)0VOpuQgump*@FurO4^eHXRG^*K zG1|F!2t>g@bFkPd$Wt8HB=+a8J>}IYDuX4PdZ6;aCn06-lYkQKkMNQvSYRc_#>R%M z1KnLp&tF7GA}TIyjpVD3IV6;ujg5`4^$k8Fqv5E1HN=#>;>sW-*e$|~&M!lc74TaQ zF_{VFq@LBeIa|B{2^^Sj^87gwPx`v5!O7uP_(PaH0VorFG?@S{4n*A`47t+Mrh4$cOks9X&n92Y>eEqb}KxV4Mqv zx_}9YuU!qM*sl_~u1r+Eal-u0wE0FsLE&TfWJC7zFCPjE3o|qCumRJ1Ut8;LX2#MF zlUYD>Pk%ODUKp%FN=QsRUM2mrG+Jz6(wh|8_y{~j zEG+#EtPu|7i1s|0DC(coLN0?@Psm|{CvK{PV+P$8DhNF3i5rp@MfwQ1W&wN+oO_ZG zE}Gv=Y2WwgnVFp&PI;!=k9IvfSRdO3UpC`PkTiOuHqAAe)PLPghTN_$8zBpk!dBdJ zxH^O#u?RM!^Zx3KXU_;#6&E><#qR$z|EYv4t_PAP?W{fc+C8HVqMJ7(;r7e5x!M+m z8GJVX4|y@gs9T#;tECFmjB9-K~pqxqUQF0k#nECg4 z$=$edqsv+m4YvPd1%<=ILseDPB@b)aX{sQ}bEFH&kap+8O>J3)Z!q|d8TQNKZ?%se-;g8=l5__56|4v%b4~*Q3zO3EH+{ zU$L>Vr3~2wI{>8$6J-L?D<&q!s*=}W3%4(I9{OCw_FBK*P_?<}+#?jj z_q`|b1tCV%Hmt4{0lAQNK5%Em4wi8JB9-N70w1Sd6UzKNR)mBgu@Xol zIrQgYlld?Rc=2Qs^fLHMuzcbZMeluPycRH2*QEtkW!^Prk)_6l$Z`pIwR@`OceA1=TFFFFk9;G?r!@I0jS&u0m+tNn-y*4 zcAd zHp;eR5?kyLU{)5pZMY;NG1p{g{>L((FE%eV1bas;M=#Y#XkcK&3Q&imGX{%#*_q>B zk*f~T=~#|9$lo8b4Vrj6Bvi@cUKCwrrfoTtyc$J%*Ms%OgGBk~Hd5a`?!%*t8XB(Y zi)V}q5w2hefcW;sm!y%DjN9r4ZlRj5L2OCuoAJnzy&o2^~rFiJSl_BEy($aP_IBkNr+_{eDr=Jz0F=ddzVS1WaK_D(ytF5aJUOdNVz6 zKe1!$P-`jfD`CVUxK(5uKy<~a%tC|~ewCV6J_{~v&!(QCXhbF-Cg-&RELw9d7-eP# z)ZgE(qMx5B$fm`>PfXr682NqBPe?wJ+y++-v)=X%TxqTAp?C#6-sQR;X2ha75vB_+ z2lI~qjj7P<*|kt$ft!gZCctb7%s}13R;ojIA^EU=h>ZNHjIsi4R}lidpuh@Pv-R40 zUa(`XTx1x|QC1%K^XCu9f~H!hXpl2&qzmY;`KS|xV6ajC3-}v4LVW&=SQNSG1 z!-1C({ka;S%FHx^O*occF)^X#Kpk@WIJBVPu3h||i6wo%)NwFYbFe?(IaaNA5c*h0 z5~tZ@)q`MNaebHFv1StypDP9+)z+IUTXYw;K{!a zH3Tc=ugSpHWNDG=gsK?gXuR3W|#F6B8$wdXwR@=7Eo66kxw8jOvMQh&l;u$_`Ya8sTgFC~98p2bURYKA!j{IPYS zLUEZiK40dkia%q8>t~D@-ik3G1>NL}PQc18kv&jWDlzVE3#aaMd+m+KL|E?@ob3_) zr*`bPc1!{vg%%<8%idb%&WOEIHEE{a(?Um)oHgQ{(nxu`>y^U{RK0j6tK;?`FSX|2f$@ug!yT* zFl7)a$4hXTE}l2@L_{8J7F^qk8?3 z?ztXZ;aYU`0MNB_gKcdlO}>~Q;~zS#e-vf@f17WMuXEWq)74EWFE5`R?yyi*KU!yd zD}*ZTQbx3L#!OTX&*eN*1$h4-aBh_5e-qAObp3zAxw>U&!>ch zlrmMx?m7?MKj+3`Vq(U|#(+A0EiZ4&&1(l52#!POyLY!AnECz=g)s<1j4yMSg78P4y@a#!G`Oj#ZJWE;c+Zt^Tq!cdv6|1b=&`oH^`JSgiM+CR;CJ> zlZ3XNRLC5eODNG`NXSg4Eh>_P%9tTEAd!$pB2pnkN|}=(!+Cw`zQ51&ozC~W&N}Oy z-&yN-|M9HWeLt1GKcDNmUhmg*&0@4ZGyCI+*OE_aii+F{kQ|`!-sy0l_#{n2XnOR| zVXS@vH~Y;ezhYVjckzx#+kGRoZ*G(OCShJo{(J@SKQ@+i9EQh-m=}**!4Pb{R%Q(p zl2CX5=}}u~5YG0!FO~eK>kP8J4=kyA>Z&9uDJd<@5;Q&7D&>#`j?B_hU^YW#JD~^{5Rp;Ad_pDV^;Y58*VRz$9;tXZ#~tm?e@BHmUXI} z-->VFJ_d#%Za++Dfz#*K3oESOi~Dl?GCeDu)>dagcEv`U#kMr6^bFh`0Lo|{1pMp6 zVb<(UUH^yM6FL3Bl382pk8*3HvW%r0B8V=*>)3E^ zGA8}DtEC-cT+f&W5hP=wyW2)bN5@1r`wU@PQq)#%k9fq|nwXUIbZ&FNb3}E7yM@$u zioOwi=!0Vp2Dsp_kUYP9{rWC**9Dx+OM7LPf{C_2e7LR9R?BD^yD-WKK#J8eF-l|ZbmB`%4}}y$N-H*HHz;(gduwv6RF9T6{g-hq?4ONmNB+V3 z?FiQT*Q_6tnbgNk*Mx%SAK#*84xQUaH@IWEJ}OZCOIv}E=!1ZMgjspU@N9H;?)-ET zC$s+YNO6t`cj-qJ#*O$ImO)&6e(~>c739(H3v2{0vG-FK31DE$=~Ljxj=!P_XJMNg zUu@qxQ79gBYVlP@gXsCd+Hg~C$CdZa@saAeBG#v5^aN65)8k#_BfrURqTcY%@8 zAF3cOTG#(TG+n&zUj33y>^mX?MV;9~?iEMO{t_Ha_5S=^Pw9Mj?dbem^_Kl_tR_uP z?W?>t_|+D|`D=(D&}kdcySG_;qCtv?#R`$QL{voHWVJ3QoilUAz?-{|z}>mCIVPkg z*SnC#&7}Bwc!WdJ)P#i}H8$q(Q3A_^De(B3o11$@#&xst(2YsTF?)o@$#@6TDt--@ zV^7drV^(diARUznH#1)9AT`@?glINf-s>J7-t;pkodVw^=M{#xFV5^Moi9yZ`guQ@!(qL}qDRE3ao)x{w3PzY`ZsUZMC@^WgN+#n8R%~9{4zKc?KaODcd`fiN*J>?4`5Hk@RXJH zLxJPP>0Hlf?Jaw=z4{7h-Fi-)6)LHkj#lqEl=U7q_+Fmk;y4sgPYeXk zZg6PK%*)5V@kb4(sW$q-eD)zh7;^TNm(DiA>f`$o2aLJ*157JgfTjk~Q*! zZml_q_wRep&rZ^w>+0$XtXt>Uv9lD10pu*5_=e}twO`TROA2h>L#ozPftmDOWnP}N zqT<`Gu0?ofdTv}&0{1y{WUwXM>Uy=%NqDf{#a(D^bvW4tNODwYhl zvOatE=34A!6e$o~c=gtw9lixiOKCY#5r4m*BVDZK2B-9~j6Pf~yFz zV7~2sbD*J5uHzKpn)vzN4I^}OQo!R= z)6Q>U<}h9vV7v1|0>Z&@RV=64sEi`PY~usxD4N7CK5CKhznbC0*J*6{7ur*=fB*ON zGlN+)c}Rz`+ZPaA7{HW2dJ+=QxpU`|x3gtLyj}cizW?5X2RN;a=9b@eJ~2Og3WGbu zz!zQT-(j>fGi%=+W-gnYVU*i@v#)&Q;TBoh>ZZKTVXheeqb-|HRb*y8cQ=YY0Y(S; zJ&Nv@hHR=4h}hF2b!CkL3mF1gT%}uu*oab6Fxg*IXs8gz3HUINHoNwuLf`uS=c$frs8XS|X1cUPloNhtQYvJuzS zYXiY?$sv^VV`PK_stubzeq6WvF+PHAk+@$-EzH92F|5=-d6GSU42H&=SFc)O_XCUu zB#~YS@kUVtk%wI0gOv|rsnJs8`0?Y)UZZK(uZ!F?E#irei8)x}L`$C=_<}egA*h&` zl;MwuFAvU`#ssO%!-L2Mfi-^L-k!DKc{+bmc%HmrLxK4n%3Sk2blf6g%0-T6F8MZe z1P!|YS)QE~+M(@#qi&DEf_3wq;$qjMN4K8*VgoT}VBk_*obbWfv3jAgW_X7r{q=%^ zg4oMEL^dg?Kk|SExd`RPb=1mY~OBuXs+~aY(~`HPnYp2WWbknbqU>C$~@Mr zBXm|ClSB&3&Ye4pii*;$W@bwTH|I|_2l4~5ER*~y9%RAa%&N|Ko&9v}nUTt= zms>{~5~SQcJZ8b1HL2Qhi@|w$AF;hgNDYXZZ8%}Muxvm@B=ct)EsLMY#P4z-wzgos z*AS_pNDcJ&OL(@-?)C#(gGeYYAyMsmp6M7MR^<5eFeV?&=;)O~t3b>1`eY}otpwd} z?f_2<)sNbap_A~B>fP7$xk>TSO1Ydy(*#dkRFaro|L)xk^al7D@%~T@zqVvw7*uu& zj6qO>`#uP;pILMl{2cwNSC0wPNQx!LY;D~qJ}+L~Z9HGeWwd(e@tEPJ+8eVWy@65f z_yc-+dJsR_wryMg2=CLpkFA3`&*AmsNkTdh_Mu<1vv!Y~+{uSZ!Z*IUx|N}HXE~f` zm$&;r^qseey=1h_u-?E~AVJ>gbvFj@#fj~UL3Gl7g2WGM9x1fNrFShvtuUwv&vL~-tu|i?|@tx7-Q4!-c0neu& zQ8B$%%??Vbo%Zw$lh71@vXN7cl5Vn{V>CtO1o{zcYHDN}uK6#h#BVz|-+#&4XlnMy zn|(#%Q$K!i?#rFej&|N=5!(xLzO*izxq0K>y|n?+LqkLUh>+bI2cjIa0sp9V5 z%_gl>9C9+H5{&~NFeciaTAkYt097yKAGI-Yt21Co7xyrpgoj5lyt)^i#C7`3&YC=? z)~-Y2=pRIvC~(mS?3H1^-RA5hz9g*=QUM7kP=VnZu;RAfws0X8`tye}50-XaHqNM7 z(B*xKV_K$T{IQ{kvf-DQK~2j;zBXjDDHw9QWlyX4FQ`TJL1tk-V*ff%h$4q|CSB|P zLAC)16hRI`7NU(p+}ZBdsWz5dku`&~$EaYDX=0Rij$nSh!S^iQTO2$*lD<rE^~S)f$3<9L zl6I&+d-3AQ{=7ojXQp*jT#*5b|N8CHTpS4Pe@}nFcBzU26V8&bNA{451hz&6HE1RG zZZ@tmAtAhGh-sbT2Ul?x_oJfe1P%g zIw=sLTo}RUM<25?NB^RhTwM8jM+Nydqhw>34vsU%ZbgH)c^>p;c9M<@QRS}(c*_%wor zP^`b7=PK0OMh!c@0+8?dbVCo+=J=|#v(O%}9)N@)qeX!heFlzXRP>3J$ByT)m@k_;y$7n zP|#gVQC&NAaBj%W|M4c}Ph&r6_iZLDh~u*(W0;TW^PaqDn6?g@n4Io@bPlhec3w$0 z8^qJvWveIF8WOz6`N&AlewAVv>0c*c7PK#xl8|sedD4i=&omhJ0=84Z3!B$FMdgjJ z*5$2v{J65RvdPZKC}CP!;OiCwNiw=aI-33UYda#0H!TB_)@DCxZ&#L+^ME=YIiAFq z9)((t&Z2NreQoqnO03{Ic$@$U^>!vJD=P~h($dmundq)wo+dJB#5gn)C#Xi(@(Vab#{`cEHmpqol*flD%JU@5O2zKXrQOZPS!r2FB4{& zOPj2ku|AejIL!BMY%N%`;Of5ct_O1u_iL*2%DfWhl`CO{vH;9TNRUUI6p-hOs<@#7 z0UpO2(`YT+_%|%8S1ZcNfz)BfKP)UQr?mU52{_sJiYXcxlTqYB*na^!ouHm*GB$0K z=ODo87ePKI0-T;?{XhHLOC8BXsu<@1sJ&L_Z0GxY?cG9)(_t2$;MFTEpNmN*-1(rx zyhd^0lXPPAQq^YQVZr{j&>OoQwomV#TBZu%=X(hA!c3&LmrC^la*^k^s`9IZ@ec&3 zb3eupG!-Rh%|Wv1!nlSWEMroh`RfeAViFQ!e59bDYT?1o^V~vy)7Ojp@IHe81D)tr zF;)joR`PzEOEsk8h}&mpzurphx^WSEE@O63O9d?tU19jis82DSxjmd&KmHa>RIb5o zF1(k36l(3D<%l14=9Pbs`wzkezMjby~CCxa@+4D}Evde&o{M>z(YSc|tdhgMZp6=z~UWoKsxSlTEh6{MsG z<9K1A{!Mxwrqep{b-ftxUR_aQ-DOlqr2|82)|*oXz<{x^3gN_5KO9!r^t4OIuXa?P zQEE=i&p!%IgoT9#8};iC7{<%ox?=bWtFe`KV#7naxm&go=ho2o?-pgQNms6H^&0KQ zS<_$?BY5N1EikVi>*_wk4gixWzVO>wIxh2H*k|#H1=p^<^_klunvP~8E^PZnZuP2| zz$luqh0y}+&9M5`)z;dmvC}h;#b;-K1(_0t_9ylLrahNsuBW9v!j__<;*AagI2+p! zfxH6)@eLa|f{XoOKL8qP7KsyDL1^&v((a}c-VNHP(AyBm;_E!4bmYYzms}>i2HFC^MI3W4XLx!R2~)IyA3sjwu+MyKA;+;KZUZ~J@+#AdZR4KXNj-wB^cIIX?Cz56)O2<5}JJ2*`p&U%vo!eXvmIe<{7 za#s`6YbNNzz5{eQ zv3Ckvx8@T2a^|r90nf740?KUJVq#)D^DpLH+5Ti1X@!GFF4T_`G5pMfPA7J~}f^VDtScsx#P6H$`Dvs?jvK|K5~mu6j`)?R*# zH21i(^Pume;90bjdEjcEEWJtf@vKp`qOvl|H#X_He7%s;v#Dz|sUJU`n*Zq*ZAmid z)CufMzH})}jX?yXmb<6tcFbIj+h@OIAlR$1IpIv}&$HwPV~o7}H>zRehawjk7|7Y5 z)cN#jb_c}+?;EIO$%P5N2&4IB`IP3r@gUoZCshTsN17fdPW<8U!gBbYf-*-2Ttq-d zFn_9+uwc1$3WRYvm!b=Orn*HpWPmA8e&fb`6or7W$)e2Tc*%KTT}vfUN}*R2O?+iGVmebs;ZQy6v?>?x9sBYIFh)Z>+k zvD&sgYcxpUk3bTj!}x8KOk7{B=h0)G6<_=Njh~KmI4N*^cd@mVb#4)_^@f0fiQbu? z>BBM;y5;Q^-dh5p?g#4;A2J=53fr-XiT6eJVa056c+pM51L10lSB<&_B3M|qCL|<8 zS=4FS9?zkUQ`iwA$IrOS$nh9ne*K5YGfHATCZmh(KSwC|>9q|#eg};i#Bf$SPk-ZK z;(kl)v9mwUiPzTE^@z2lhioH#RBU_!zG&pwrgfIS>p49}+UsUAf5iG0lQYopxs zb3Fo3%Nit~kdUCPsw(NCMX@e*<|40`lQWD0d7uRZ1}>v+2$_1|X1u{)tTZ&1C~EYF zZ&<&cz5ry#FcvoKkZg=QXXbCU*R{49FMQj{eAKh7@!AITE=->f+GM>^Bsh+5;FJP~ zrnA6x$Kl~&5Tg%bLfAA11%M|OVzH)M-o5h%srz6x9{ZrEJcr?VyyRwg3e(awK2U!h z&OlrT?&?d6p^EskECTtpJ~l{-ycmnIQ>7v*RWRF zEG{lC?Xg#kfJ!k=*O7<6ZjYD$A@EM31~5?qkM#jmlf=YUezyvD5LkTSW_&+tYHJ-p z`~5*Ge7cBIp`BrdfE4QL4}DH;LXQd*V+bG`kT8OBE56o7hm+Y0CakT~QXkr1yjXRg3}&%rqxFtCi&(d# z{HPwCqGe}GBxgkt*o)b%WC3NbXq7C2FODTJ{lSjJy5FBW#dNNO-R|q zci`jB+%kKhviHWMT3%t5JjeKh{S%a)@82sxEz+Z9#jVq_^g*optP>1`_~WD{B_pGw zLsU7rxffgt*6$G|kzjExD$y)^Y`0SP+&Huling}R697dloK5{d8-BnTjbgVfNu*>( zyQ|@>ua=LDE-Hlbo9%QAF&S}d2>yvZ7?eQxYkdNq;_AQCis4%Jewx0sWoC~~3L#aP zccOI%LSlq6*WwXLvnWvy=>^33R|~44^dFHn^kqCqbA#%KwAY(AGN`Qc$7T==k z18G2!Mg34SvNXFVO$U7u?3L$;fJKV?8|WG!vlp*kU5d0`FX-kr0-^c>f-Ker(U2^4eTv{IWf=d(X4r-Y39%Pk#O@_`TPw0P+%Z7}o9EyEils8n*ov zu);(>sk!1u^p)3)weBh)Zf~b+0m-XD(>(~ zD}Vlp-aWs0pXUZ%yL4}d1JX$t0vbf-;w$m77H^00c%&5lE3|ks-@(Rm)5$&O_Hx(b}h;VK1LD06Qd*9aoB?AxBG7aMfDM%Ku;DqZ+`XzbMCFkl* zbH`i-O947Z&;A@uatHNVIwDYtHI5VU`?To%ZC4x?L6%9}Ai4bc$hh`)3~dik8wC1S|*LE(A@`0H@cAhlKdnxqv>>XvJ_8i zD?U+Ha(bgyasf=vt)724f#rB37=3If}v13Q|gDoe-}(idDVB zM5i+LD=#7h7i{W3)4#UW*|;m#qJIA&-^{@#)nk`sM+Y%gv)5rKg5$bXG+Q!x;EGYX zf*sNRU}patihm4=d8FGPt^I8p$otuI{#Ipw#%#fYm(;)5&2Ys-QhiYf)C>Ek2@Gs& zRy?HPP>&PvEViLI&kBCoruQ8k@T1xC^Qc}7Xz*o@h>B6-Fv<0ro2ptoiz&qG2m}HA z1X!8bUQyA}w0K#XZGONcgULBSNVaktl@RLak{F^Z)F4a2FI(BMkxRjrOqi_TU5V7m zL|5npV{_;|{k*5}LKba4#QS6Z&MWmZ16Ms|UJ9N4(FA`USN}r~aJ{W7t|ilKh7kfr z=TE{BQ)l0}CJ_cGA&=wiXwhdKXQfW4KZ2()Ou0u^a~nwB7+iH5TUxjIL=} zT`RT}cf4+;&dJR;`}lJ8^B#M1b5GB~RSv69vhjDbHM9`D%5XVB1|e}}cb?9f^yN01 zDd9tI=9t!zr54O{>zeYS-|jv5%fzPdxI0Ka}4(IyxH8C;sM% z13E@|7})J&qQpP%c`@zS!|rq_5PchIiurBSgX(@WF688TQ-jn`tN*5?3uwZc?JB9F z3X!oSsZ8A|n%)(~p)esoeWwpP=_(5rTSOfgNA@I5+4sNlPns%y>%PD9bm-k%P$DsI z$Q&^J)pOJo)2pm*060hn3+~@Ms-6 zsuy!v8sp9FxP~8I*Sf7Dl@z(>dwQ=RJq@e*A-o>O(K-fx8Cx%2#*_h2*!XI5W?ZCo zBNe^Xvi(S4G$Kj&MrfJ-OKlAEj2u!{?gckEvOPd8^)3I4d0r{|LS!5j1l?kK&ZApe zM^+0x_^)6(7o+vk;s48SbzPwBJ zDK{r)+LP@I)64CpxT^Hjmc7smI2r!=_(9vrD9gYVNCj@)r()h@`Z2QXVH?FGNzly}J^yP___py&Q9UJTDLAsrLE-skyPJ=e zxnN8*TXG%R^~d&`Sy@yAzX&;S&+l!%^78Y48yQ*bd%7k>`=9VK+F-wh?StfZn2xrpi zIYUwhm8rqRvHUs9epY4!f54P`e!^LEFr)DB^6}+toK9GbC6uC`MVffktW+ydSC-!y z@PlQ5d_umX=ZY0yEa+Zky)4GgRIyaz6L#@9s{5V;E_37cD=UL;wiH+kDG0CHs;U}k zMMP>9HpO$_bj>`_RFE8LontvTE$S^ic5-wLOx&mNN+{(ihB_Wm>E&#F;I`Ly%Hip(CpA_HN%=4AZY3!kTO3)O zufk8=dymwCnynN;P!@@N0!i+1s=!u>$qWuJ0j*AF8)Qenl;L=nrhh zHZIq4k@hHizoDVgKye5C{!#zMDSvypn(~$3)Sw}^?k)fzx*%6(diB>JConfUXyZQz zj_hNMA{Ps^*0hN)RFQE>HCY_PvTSA&F$_5_(6_zLu6nSFvED*kq-6BqD4} zi5U!nwTai7I;pgrvAMa4R|sB$FNI@%Qi?IQf{amN9GeDcW;5UYUpEH~GL-6qd9RHw z37$LhY4Z^KzcO_Ee}h~9Pni8%q0tWbyo=NI+gpBGf=C8O`HxX`Sd3JL<^^VEcoj@x z3qr;aXULVym$Q5)5!gM}l>P+UteNdLd^^K$^WTHqw0?RTAy7BeQV$K~o216Y5eJsU zwaAxc&aG(pbn%)6KMo}AKk-6oY;3IYC{A|#09Qa%z0ltEhspL-gHpQUAh_fy_}N}T z`ro}`3r3TGfB^7*m=*c4$& z71B$@d;d(qPhEpDqKf#Gj-`01IyA(A-%{PW)n48Yq!Q>G({^1kno3uWMPiGx(akDw z6$exK6gmFl?mPc*_i-j;_exUuWI1X*(Ix>1fw7B`={;uC5U-pMOT-#Na$-bx?%|F2 zLS&AMi;G`dH<{c1I}ShbK|sB=?^sA_=_!1Cm{u~T@6vLfDhTbEZK2O*Kff0_1xKbRq}G}0MhSP*R?lO9#?&46 z|FGvpQHnA$0lV~mv*#L;;e_3<0AB-wN4b@Bri?5s@=8jv=g;pir=SdE#bV*zyM*N! zCR*^DT#}T)yii{gGqdnY%y5#eB?&Y}4i1jEfW&z&N;7yryfu=I1-vKWj7CaoQ7Pd- znebUv6%}wPFRv)=8ym3qzqOFp0Xg7k;`dYv1YfEgygvbqqo= zfwqfZGGa%aL1sdU6kdvjytD1kh#a0O`tdXRCqt2)H@lj($7TIni`aBEE&EZZ-N)?h zPvCFIa>rHv$2Imj!%Wm zbooXGbS?l$q;`=rf_GXegnMxqQhZz-R(?q_7!!wkSt_1xG~ z+L*>?tJtu{?2hOv^x~S&X7t26r?qiVr8s0R~KK{b#^ zAfZr;Ane!9_4YM9BX$D9W`&|4Cm@Jpxi?xCvQq+&Ex@M&hUd{eTm`d|WbpC(n|<4# zh<3htvtKR$=PkvYNnx#wCgQpScZAJ_FY$0YW`P7~c-^>?oPMa}JUPGgGjxsGC1X3i zpas?LXK8`XC);h_OSFq z`}5G9XBX!-47b3T@RLXvvP|Z0BgpQ*jUa6I+2U!bslx*UN`#1T<+;_m8fxd+sgL-s zcQm{n#!MALd(?^vFKmTsD0)qPKo0?JiwDmeVYH1$kB95Imcg+&C#(AzpnFm!H^+%L z7SNCYbHMiC+(vy}jmu~_SY@~KS|@menVr3t!ssZ zAkG&^H_68X_6tinRZ@r-kxV4yGX3*BpEWi*bmY)}Q47m(h2fg7-2I?2@Tk3Z4XJZP z8KZ_PN7Q5d17GibezS}o?(GG<4EBO z{TxAuFT`FBqUgGNG|@fwW(UuIkaww1S~B{pt6yD+B`zaIzllNaK!V@OL8z&bqe(xpoP)*#CSIhnueemF3C zw`zWs#0wPTgAU1|1b&G1LS^L>tE^-yFOzDZ4<O490>XbihEOA+uB}M-oST6dDe{c z&_|tOw=VVC(B2g*tC@}uwn&WS+h=>^_X@wUhW(l7A9{Q}>|KibSs%1;&UJ_4T?iV+ z=T{dNw!wP_^#_+D)z&`Zau5yWMFXmaPTUiN4b1@!1zs$yGD=EeLc-pEgpEk6IL@NF zojqZ*Ht#kLnnM4=l>_37^ANp7#wtx8vJ#FqpkW!&5%2|@%RpQL|As2)e9y-tyA z=vEkL<>gOex#m!o#nr)G`vX2pmsONT>T70t2RNER6E$24U%GHzo@3{X|0Wc7ZUP@1 z8Obq4VT?1s?xRenzjW-CTIS%6(7n5Nf9tH=I-527@d931z=zV6oZj*C|U{B47Jy6&-|6GWy|9*2;Zs<^W(bz6 zCu|AWebl9ySQHgwrym;o~`HH)DJ>eLK<=)aVCHVkEN`zIz zW57$mI8IAKCAveD_S|U;yv;z~3f7q1Eh@ZVw{u`Sx18ZF51l$m? zj1-rZ)%B=v-FgNX2N?*n4@{`U^#qNFwdnj&yY+r{@psICN-z?Kgmk z`d$c4^y}6xmI$i&VSv&KW!Vud69HulX0(RdE@-{DsZ99=@LOCPj2@EX4~(j0PW}N# zPZ&u#e;m+}z2R}kIsaksXq-EL((EhVdss(!DuK7pPYl4fsByT9iU^n>dm z09FZ>I*}2#gS&V~GG~?EdPnlIeABHZd;~6o@1aQ>sbzHV#yCjWlR+?)qdtK{Cf*ah z4aHZ-Z-6k?a;4cU={dmSqpq$nmW0+f;`{){(_bD;ueA+@t~+PkgITUGz?jJ*tO=&_ zScp|_CNA<0JbmialcsaSHoxGkNV4pg@K=d zhbwP{libQSSsF2j01vNq9Em%_O z61a=< zPu%r@&{$R~wN=@*P$Toi*qsuKUL9^7rst13I{5N^L0~Hz8qU}Bf&;?EWYE;qV5(^^ z_uOo>%YbICYtZUK=ArDIiKWlABJCLcQaWD8hbh3H*Lg~vqe1)N!PF~P_?v&?)GU0< z%FJw-a3%P{h5aEE(cxv))-)%s#fOx@iV$-2Ewf#Z_ew6Vq7kIxi+sG6^~iE*s9t(N z3G}T(*YS%>SQ46=HPG+I+L6wB$H!|Fu8DE-4-FMd+46v4)I6LQz zve53^x>}5Uii@x|IL0p%Pbiz#4=r=7K>$0yqH^~C6Mb49OLzLp#fxw6x%Yy}LER!A zOIx@FYBGw7#u6m<$K~LXzK|ch0s^jo%oPdtD^g(exlThQN@P2>oT2t2E%Wf!MI5xa zYs2=)k%+zoyxwkPpr0DmUqHX|{aIfvUcW#rg4!8%oO`BG){xm$i+Loi-sFkXJ z7}E>bm2M$uFbuQe2Q_Ddwc0y6OvcMaMwdi&!mm3IE+Xe5L;)`-YVem0zq$1aSYKNt z9aqKGG9s;G2tnF-B&aD$Nbw@vHc3f@F(NlSCT0N(+;Mh=%Q>Ez>1km}7NS&{U}&=* z&~Uu5GKarqN4kgIGCwm@dq&b(%P2=k1}rLkwDdv*i`vsQ^{FQ+=eZY*litx;PkvD& z&!4wtX%MHzMUFq?_X+VKigsjREsCsO zUY1=hhDsM~A&BCG3^x-;T;eJJQyj3{)YQ^QNX70rK+V!A(Z!NxJl;wpoJRBf?0o1ILwwdn*Hdj)HDHwmU4*fSK66y;rlDE0@2P#sQlarIii>H{`$NraN9laign@j&y(CU8? zD*c_)`rrH8Q^7tWUP4$GSP8QS%JQ)rp+@sgjq<~V*>C8u^#w`Q7>_c>Z{NNhFgLFp ztK$cgo!fUXSxg}Wj!VSPFs$P8m22o*#STzgTkBj>4kir&`%1X`5?wt3#87b2+1Z&B z@|OoT-8T+>=ZnDhwFp7pP{L``aP7Q>Y&`s+06I@=YL>k#0r8pm^da1r4dpp1g2dO1 zYNdjBnp6HjfAu{}P;Zbs;p6j}o0hfMA(Cp60kbN{+O?N}mM~?DqkjWtGQ9Qqy4UcC zPx+L4jgMq5ek-`3LRfO;(cci5IayUvEy6RDEoaSX|$Jomvtz5eh)ZPTW`LwrGS zJl(mY6;F{P(iBM7V;HPGXgHbn@%eMT@2$v)A(sL>Qy1J&{rCXy3T>AU-beWXg;EF0 zw&U&N^6=uFDTTLT+cv8qv83tBii&O_1cQO{SXQmV>5{GagoZQ z*X5(WU=OZPC^N70IR%0b66qpb4%zF8Z{yN+?r79Vdte})dOpDEh=*G)B!N1>Ebemgnbik77s%EX76R*m4Hfx^`lUn<{Uf_6JT&1Pw1KS>QWrQzw-`{2*bA;6QHQy(rtU9e zY2&kJ7a}geQSQy_Jf_YO2QmV6yd}4?L|(_U;mZ$qE`$*2kN^)gB25SI zi!U%QKcAh;W23W{H)5+koBY=@CL_b(hshY2(EA_o=H^GRdUNm|=UHr%;TWUs*}FHU zVSXGoW!%uwy$$}RCr_SONS&h*`Q;Zca2&7%MU3I<(`FoL#dq#tn2m<9#&$~suk@-H z=vD8LIO&Xv7v*GvxtTNOktC+7qt0V|a2CFUZ>dnA-kCqCm=cwV83(23@PLXs($mqI znVTCsk&}l^%wk!xgi5P-$2B;1;8r&^_Z~XA2OYyQ9N|r1Z{Vu1w6Y4h{ZyZqw4)p% z5f0r$uTnpP-q4Pz)@EsU2YgZ9Bq1RY{s}VxZe?U8NY$z{Q=3xleDO$sdq1Pv1MuBu zi~Wr!1jpZD<7Hi^S^^ps?b18%FNMz;KTpr_syQwu!?6(;a$y*f<7zN@Z7e>d5Jjg> zyLvUcBbd$TGhc)xwuSStv2AT_myUSib2s!@z~0G1Fh;N@3I+z4 zbz!Mt?nmFvD|jGYQ<06t82BeQeO+1&1PxFEO&DIZH_gqsel*vX?3IEEKR!NCAIBZx z(BKLE?XgGc&nY-*Ls|39@6elD`u0+CK7znS7RMhOClI|pv!|ygW0Ge7OB2Yma7P9Q z)7=ZyE0;k9-sAvwO>u-7GiR$;Q52-4R)$gXujgD`gHIc1Q4yPY?;cNGKwcS=t2<}$jB%*cCgD@LijL=e2X|5x5FbN<>ck1rKHY` zcB3^lb#zI#Pi7RID2(VIu_uD0!~XU|K*j7(rVTxkj<0Fp9n)SCL)004haU6?6QH1p z&CriZWmMA`yVkV;C2?czmmpU4I2uz)?&<3{tgHNh>$yCe)%@nn=C*Up6f89IFrC~0 z#{j=goVz7Jz^F5}83eA8p7sV~^Bt?&$+Z{xnu>(LhgvV?s~%gndf+o_KU#b@yBX%c z?tL|0c;IZ~gG6|m%OBY=EIOP8@Ug=*?%(}rsTIRc{6AU@25-|?1e9fPgA|@V*k@vM zl+kZvC)Bc2mmawMj-bp;X#6L+=)ccf1gR4ipAt9B;k-x!DT&ul>cj2{|2zMp{OArT zMfOkmOd74Z*ER3$&J<(E>O9;!tNzjU5&M#>m{~{+zfB z0P)OSdU{41Tjq9ZC@ip0(zCQvoH0)mWv>`Y6WxB>Q!{<=+YJ^(yRqXU`pR%bpSsxQ z{ZCf7d(8eBW=Qc4il`#L0ftvQeiOPPUlThM_vVAHZf=V>HBrzDC%9yz|1lX+(R7TC zS+;oZFl%9}A|P9!H(Fw_ChhI)Ub6>BYr6WwM~P$A{J;TRxCiz+cHLG*gnifVMc)>h zyjSze)uI>erh;uvaA4pvR0aJR`R#~d#g%*Ax=N=e(d?nb(k3EqZp6y>l(KvGGt2IsD&n z9ITk3QmGooU?GEjgM)*Kc2mrB>&7N0cP?@I0_sDC<1$?hzKNK~$YzYO3kMPLZ_NN*-1^$$QUyn(wU4KAxa{_NnO~muSde!?4hqWj#OJR_7(RNCouGDWrR8Fhh}FzYfOrHEE-Bdk;pq!(T4 z@biVQKh;64RUk@j;eADwH>5L6xRaEsm~yizy|Y7xOTTG?cR zV+x23x6G&dczJ#QSl$Lc<(u0KHX!z%Wh8TShyiw&jkFi_f;6-xgX?(9cNpV0g!42z zP4nZ^wnqS2V4*a2+QKn2v@|)C7XIoAo@iX77HOvKEScI2LpKl`bpZTK2LKDY#?n8K z!SqVX$3w>J1U~Xlj4-z(oeLpiZ@+CW8^$TcwvXvEXBw?ZAm1?wR3CXAf~_;b<_xkN z;vt~b*ce|ZvlC8LTS@UYmTde8$n6kUh!<=7ohhmY#**?Lkj9RXp1GGlV)|bu#TsH# zJc%;Ozb8fXMyq3Q)+9B(dGqYmtEs;{_oFze@qSz31`!m&f%`+kse&dv|Bt=>I3pfd zIC~?mTQs$>80_s`zO|Yjk1SdJ?1Kv0Bc4&i9Xpo#_CR9Nuy*LtmV%XrXK6+7?NdV? z#viJPvQan<(9dRTn)psI&7-6oz%)mQh{>HwRy|7YQIAJHkLNLSSGCwv~5Hn(|=3Zs3k zW~2k{NGCtlguoI^odK}wQDyjn;(&DYxn^znml}<6$}-x&n&cuw4yB-CZ|TydS!^L+ z++ZYeGG!AK9R6LY5&TfvtT3%+$osGq9{!+#XLMfyGhvpnV!#IqHd@N})Or<>=8J1% z|L0%+U&;6VCmw|VDx8S?(QsE)7otpRxWTsx-#d#BNtmZ5#fRH8;Cdu2cVD7EKKgW{35q$7_`E0IbkS8AugrqioZH zP8^+ZYlM=c^Kc<*LD{)O!N_*ct1s{V54 z(;gl*iePSJhzg;n_1W}&Br-V@OfC#A%E!T7@*HRR4lKxa^snRYaG<}2`6y4h^46_5 zvp7Fi|I^&$hTsfib{s$@oy`qmZ2EEYUyV(1C&y0W-3R{yECD-(e#~DHy6OjApeGGP zZlxk>GxL2TyfbBhW3eNspD~Jr;0`wBENOvd( zjX1-u%h@f*Th%9){qYx7cnyxsh68v%D8nEAJ~5a4J~27mr|1_VwX>$D6gb+o(6E<^ zmxcRX5fWi)SN|u2)LUYZS|Yp#sF=u%!$gJFExiNdlyr#O9Qp1!NOJ1K#IZhjIYoT< zzQJ;u5@K`q_dvdINtrazK|KmKivK6RwaE(sey4~?@ z;K~lo(mQv4q56|{zdzamJwT`=DfgX`^L0Wnw&88h6=}mEJoz*KB0~om-YYNHYT%Ug zEJJm$7$iJ0`4N-DA0-;xg!pchA>aXv!71#XBjQNjus21c1aFISpfcST3u2Bsi;_HI zj!J?ApvRuB0&i$5a&jHW$tgQHuQDcDtf*EQ+#@83O`Aexh0hFiRvs|$^Ipyx7m9n$ z3&)`^7s)K|Ba5H^tDuT=_wRzL#C*{;q$iqo2;&^aHSHV#ycjLCv>wBF^~Ze3#2S}_ ziZx-P)DVvxmw-SOLXnk=BZc`8t~fa-PxwAtR6wG*vqtL8!6adI@3;t`rZesx+VRkI zZs4vz1h|#5v)w_gEw_(mmHstLu`QDz(IWRt$x)WAVrFD~M9iXT(`fSJ$)bie*9?2?vK{J#TP-~yEf1A2;A|gP!WNTibHMp@7^~sx_ zEhftnW5TYhiX86$TIc(BhlJ|yLqfNc3RY-eigJ;|Q;t^65?q63@8WVLF)`#87!iOo z1v$Cq*(;SeHiGXxqJm6X%g%mo2nQXseed7OUuoUDztp|U`rHD3X33S6^GIoObwpu$ z3AkxX?wMGR10i$#HFe>X5L5igzr?y3h;@G_9+a4fbbK_?m;jc&+S<{MyNzli0)vPb z;ZtajsGzyF7cM>WkVsTS6PH&V=Q|0wzf`Op2D3G~wsv-+bedcCYI`BaeVMsYL2K}1 z`4nM%kUx?xP3t=7ItsQyw^L;|c7JhV27c&b@9L_Cdj~Q{;TaP7NdMm@)BZ?qNnkC0 zYi`sU0@2XD{`f;|m|6MaEQQx(=FooOIa32ORHbfz7^V=%N4Bd$qnSyvo zTJUER_0C8#gZHO;P{TlZD+t~t^zWmf8}ZkH&botZOn~Vx<=q00f*y+Uy-|J8J&;5o zQo_EVf>3y6$j_VVhd;|M^l)GSbEBS0(2P z2ae-4QhNjFQZ#xs1lS_>+Z_-0Sw_FgOJFZuBL6nQfu#zR6jK3V@$~iaTswJms2`WaI7t4K~nhJGHfgQE3U6XS%#c zMjWOS+cW5KRW5?6(%9T`O&xvv;itjZ78bJQEIa25mOOn9Bsk$al^lRbKR9N#E*jUW zf4`(_iuESuCfG9r9ANgg11K#YDyl`~wk7{pF}c`c%(WZLO>9A6R~L>b(U z%?j#6%}$4L_fSa43fG{#bAo}!H7_B$WQc&Fh2fy%t{dyqtmth7)u*OvLKZC(NhgKp zq(*uD#JV9&Mr&-=vb#eqVtgKH_ymh!0=0^o%R>svvA2439!Pm&{w4nW)5w z_(iuYI+E_3z}NOvB)$NJgK7Es#9e{x&z`9I0c2*`ig89H%*#z0Ql;YI0R{XIn1aHdE&-oJj>ATM~ZJhpujgk z)EfZ=9ND0%@DPe9`*d}Si;BFlu@-CKBP^YU>*9%GpgXWV>JO(uq4Zi}5d<4%h6M+w zrRa)tNc?gfyb)(YCbk)P7`SfG1e=%g!qn%`cy1mE5lC9Mu?>_YSBwQJ8Id93=^+Vz zdCeuQy8(h8$B*ChUsON23x%5)L$3b>3ysk5JtRR~>^ZO%hz1RJkyLQ}f(#=1j9M@B zkI=|uGH!wrdXM{-G}v}NUvo}IO>GVjRDZ+Z4x`;W19zjDD;HY~<89{r5gKM1WOs3b zU2>_K+ZK;}1t{hSXiQYxLCM*w3$vB<}#Rje~G)c0xh{%Dh4nC<}04D|(h4vU0JN73F zUn!nQI$8lx3#QK3OEDyj|NP0l;=%pSumRU;KqzlF>WA z2;v&E*@4@lkX%7yV3ON^_VE5jzwDFf2t_xPmcRcZR;a|YbE4<^QL>3%rD_z1A0NhD za}JGQ62W$JYyxiD@)= zc9^c=0&s|rhNWD`Id>-BKeqD?Vd-!&dWxIxYF{QRJbU_d*PI|zOF;UMCJiK`;6s27 z2AT!B8KK+W#_NT*>bR%p-O^HI2b62W2DkhV>fSt@%D?RzFGGgP6e-HEskWh%C=D{R zY1($CO2(9=M3f{`gdMWAB~50wAwwaFq>!NjQKBeAp;Uw-!*5;meDCLekN0_h@A3Tg zK7YB7?_Jvax;~$CSm#>ni~!;yrG3w_L3=EpZCw^(F?TR{(7G=W!SP~(@=5*zT1_zM zUadQ?lk7xpzY)C(6kVW7a5Dhau=6Ir+@F+2PU;fW49e@)VS*3`$xNaN0~;l9$dKzcGc<=Pa{Rx!E+Z#OHaXc{w)?QSy34?KO z3=l$!a1yx3zWj(WlZD3;bcDiJhH!XUx;1R(=5N5k!`u@i)Enw&U%!0$9liq5Yr7ya64Yi8NLhm_u!3$nRI@4$OOao+v=qh1+aP+utI79rBT;zJM0%}f%!31| zvmV0J|JBcu2lRstiF#01(RLyc*SvVKxUIkJm=|y)5LIP%$4;k@9Zej(w^zZ{%-egb zyo7*2{84rSg`9q}jwUutxh0VB zi4v9CkLV2nj72go*f9>%CG-!+j~rPlDr)}Cx0?;465tvOFr%uk7vQzQ93O|Da<8zE zkDve7j~{-uFq5sSPtY-)USS{uSo9ivRnMP)0y4;bD1G4Puh-Y{0lmXNsM&~uhVH~uAS7GY!@B{#xOC(A*9i!vM4`trxAg0TtO7bn0}LVyo`Ahk|xx_ z=RY~(Z1V>9&OABVWXUV~K@>yac?mwiq!AQT<`C-&f;+64KEkN31zYdXU13qpYI*r< zXxl)Oz+r+D4AwYgx($Seg;jh8GsJXJf;i+>nEAXUL#WO>WupfMD$aD5-k-6q7v#Bas@+<6%*sON3B(2WT?3o*mthgpUYJT~SW1 z2IoeIw-4P^JvpPGYDGMy;-?JpLi;__L=5%fT48l31v`{Dfn_Al!9RFuRC!8Fu|Taq zDU?p%cjsVem^vz~AWK%gdKAW#Ku7J*!iERKoxpif#RepYRlMz;P^a6j zy*N0&lN-+vH-CW2FwtZHu-@wZyS}5t7x}NY0`_Eh5#WD!3hcsSyt|&$NvIAHJW(d1 z^+G?5B_W`0q=czMWrN2u{q^okB!~Fbpo38FBo4dMjExx(h&S;l6LJVVBfKoOAY%Uu zDAAUKsMf*RQXbv@Ha0412rb!~{e>tU3C#;8av6sc?vQJdb*Aud$KU|1UukAiZq^6Bm zgor(5i%eu)6if(Sz|^k)DzyE-`rl1LNq8*xv4s{>Sj1V?D+NGJ5cj>O#y;0FQ4}P@ zG0M_P9Q_t93#usAbCHfU?hey!--ywjuX%C#bPwt2N1(jD&df3R_g{ozByLn&O^uwYss{#Jq=xo(A56zF zj|YzijnE+|nW)541B9MTxVWO^F;((~gH84P1Y?4sM2MDtK51>;ymjllCr`RCE<;WO z7nN*uv^k?0M+|42;2r{vaYmDeZ~Ua{Kga*H41cN*_PS*`;bNUSHHsJtU^f!rQXK;J z;}?Wujk@|I?%L34Ven9Yq5;zMfiS-V1vG*#=y|%u;9${36fVHo$kCCTb1iTr+z(e` zw>G@zKoLSR3r+&DFn5`L=RP!pZwrs@N5}u{yrJ^w(c$wuicL0wkH|fLK0)u_cM$YR zG$CLqD^D@xn9{8B0k@>H^ME zTjAmnDQSA)jFMFe;0q+OAD~Kj&9ozxAchEjKs_z3n!9?JKdIc~V zbnCTZNSP7V$suvPw!XJ36fQayQkWm%@(T4baTMwzrAst|5!A1STQxP{x!zIFV$< zXHpGX0n#ncK+u6?rM-7J7Ov`vbE{iL1*h_kazz?`< zkSQSM!T!0BFYvr1=8;~6KRD1!#3#jF=`515QkmtJW`EM#k~1e^Cs_!G7T=GLImtql zNEkGRTt}}m|K2_e3ykz3k+L?ox;&Yf1(r^p#LXj zLaIx0#4Yz`bTlYBF|o0s2X^m%iP0`7akXQ_NlRBjM~QXtwa=gH)yvDtY0>@twf5~3 z>&!1Q2q1O}hYw@6EZtwH5QT=KvZ@L*1vBG}1&GqM-l6jvgay~Z?zhg1(fRG0#Pa0} z)sv5xUZE3t9O^~i7@85%i0%FfLcv4z&_Mr>GS&bBtXvgsg)8bxDX9;rTM)B;Y2<&vmJYCqt*f?+?8JQ-${sWydu|3$i{l78`+1`n zs)+NuqCu3PaMEPd5P8<9U@yVPo0$BaNsjWJ{?mc^G(O#Jcb?+M&CRMB8XD^ArC=uD zm5luSx#h$Mza2jE1fbXbyrGPQF9r~DnIXU$M1MDg5*}v(a&*TB6 z9uqkT3vq`Xe4MQWBqe>3Vc-YRe~*qgyPv2|aV??Tu)_H#oF()nuyht!ym;Pqv?utdmoHgzH7-u6KN?N9i%SQVMVatcamTJOeJD&D zQyou3S_T*yxN$bkrjRG+_u?zcZBHUvFA~2RUlUZSM@~2hOBrL=i&Dko1oOR)kRd$ zC;tJ&e6jasFei}KN9&QQieWOrmw7_e(SQz+WJ0~PR2~uiJ1a0bIT@RynEM}Yrj0pF zJUL4gaq`dcme3Cm5BKeXARjMV+8K_I1;}8L!kCY%!B=YtKBZU>a_!o+#UdhdMk0n7 z!1PNtYu|)p|NH09kD)HXB;YE@85pKx=gUQF-$~PhRC6I52XS}^$HjHvu%mZ2JziYp z7SC>T28A(}In5>xB0eTs36QImYTaF3weotdNTe#=fvJM8UUf|gu+T;ps{owiPw5>+V_imW?y-WjofzoW@jIo}{u9-xEm~-2Qd(}hlF`+e$pNOm2u7y9d%^(D8 zAYQ(VQ*-S^BPl)XtiK3~6$@7#Un^h^lQp4$BXYX9(m z`?*Y_NpOm(g%hj09fEb ztkntYo)Bl?5-o*y@9uwairD&tzj6kmD_mXKl`Cu8fZ(|S;DV$EuSDU}@way>o0>#;SJ z>387FS#XUXVv7k--_xgmLFDQB{@!**d}=Ol>zAFpeejFKd=keg&0z|ZX8h{i2hLDZ zzVsK1-1)4;qV!{FXIIt2-nA^2+j{dpwH1MpM)7C$Xeb~cnt^Bj2>AF2NUGWhsW}Ra zHT-5ruAX9NV`Iww({`M8bzSGKk0b2k<8!}9^MuXwG(`h)6i9|Bu)`5N(kWC=Ab=p{ z!0J0OMSZ&K4vSnZjF~g$AFw~7>n@j%Lj053+Vb`-v7-wVa%^^b4eFDyErHAHT|lOS zJGJRMSxqdqxlmeq4o~^+-MdI0VPZAHeB1v4<1Hg$ZphytSFt}2E>eRgPc8Xx zqB*WJ=e#{*wX(8M2A_ChgE9B8HOQwCs>Isv$neQo!YietU?e4yh{83dC$T5f1^Su?^w^QR4lBVl{6 zfI{NELKFa~sb9X+rxEJG5sobL2291{i|oPRnK+>`g!#yx)T$ zNIvJ_ufW9Swi7coStbLG)B zXlg}cg*UHEhunC<7^vccw*{rZCo=xFqA9MG5`Fg{G*HX-FBr%j-YFdZOTL~4b~@;Z z!A$?lABn;*RL7KfsBzW9l5%=%n>aP%qovi+^x)*J*%NX1?oW6PZB};(Q4VG?bEHNB$)0G%|C@FqGFJAt<};S2Xs> zCCyp8#l8<~24{gjL3d&lwWQ}tk}*T-5HUJhbR27shSY@=g9MfHvi0&T7VW;ec5Z@p zt%P68#1noE%@tA_^vBoKRX1VNffFmd4V$)KD?}~bb!3O$4Wbi z)L_9^nCJhx#BR+nf>5S+RZA6MsZhsJ{EN7~!baNH<(UcZdRL%hNMN#}pe;$3wlR88lhy4P5D`h1e|6EvF0%q#C9@FbKj+=D@~{ z_iELL$oJx&jG?u>;8m5jfzxbc=Ix!?UpBeF`4@%y8?nfh(4K^m<|6pM1)Po$new%K z-=>WlMYW2PlQ|xcrO}9kkHLFDL8#&a){msG1jmsK0}cGq7Cs&xY+lQd&`abPOQ1l~ z&2-sTJTt@6iIe+@wg%&?-{a$nBDCs@ zHX}ax8MaF#jHpMUtwZO%Hb+O5KKr8har4%Fw*?N!Yn)BG>~rGL|3^C`a!t4fO6yaRe(;A3o%x#qP0|2fzqpL zu@N3Oj`?Xo9U>LEH98OY6N@LM39s5W0YikP%gx%8wxhtbk{cZ|;*A-^-~%og@I}IU zV7yS=wdN#Bd}Hnj15U`q7^@(lLb~b{4y*wiCF^T+$J`?=xzbl!soU4`e_Yfs30%rZ zk1d$+qTY7`U~NVfx~T-813~UY^b*UNfBj=D0_P*Q;YByLz|JPtO{%P(22_l?;qZ$a zgF{1&pUM|*<;ls|cJ=c2&zOw|vO6G`r|9WsJ+ z-IC|6S$o$fP~w;1noAo{6+1Z|`#IfEu;*9QlI}FvDV%a#&yr|7&8oSlks|z$ z|9;~~Hpu|OlSmeCW!lYmF{Cuu#Jf4&#RIUkE&;-^9h-p82IStw)`yb7xd5*SXYWP? zSwTgHkf5M+d#N8gW7U=|;$z6NbKl3C$kH3l*GSEk&cM#t$ z3Ozaa8RgqEItl>cl9jq2Mvl$LqMZ3VAe}nv)eCy|EK)SFk-+3d8MkVX{y@I^GCxm2!Z`1?5awD zKY%L-=w;aPC4hU(sK*BGbvXIbGc%83eGle+1%}`(|67H`zT84_p%Z%E@k&u^_|8v2 zFGYd!s}C*)*duTq&6!#DGc^53>jn4+`h$}vs7IKiG1pJRgAmIt$6!)f_k3^j==Or| zxV8vGM8~mF&hi3ek*Mn)z;Yc3Lu;5Q5GWKUgjSTraztGKmr_sc5RKj1`o~&kbKmrk zkItS>VrMYxMo^%@O{yuq0yhvI|JsAU7ZQy%0tGyw*O_{Jd$(!BhC;vuK%%cd{F)v} zLIEYZ3vBvZSNc$y6C1-!6@+wqu@dusQPBiQ0@@6lKhRSAfR7E@bfBC_4hqIuJ9J|* zTzaSlW$&H=LJhfz`QvTxi30HOPfUV-%!2=>6+oWLV?as?SVcC&{Q zzW#h(Uht5lmIGXx{;YWP3uFfXFBNYK4CJ;1Bx`zM2#HQF*G^&08a&B+${M6|GbNQe z9R{^9oHzlUXR7hRs>j~||8)`?Zk=&J)ba-}f%XVIPYBpqCi&)V=(Nw*2#3;q7U>`e)I-Ia69!2 zp_YJu&mGiA8KHZ}2cw_;MB)tiJ#-~a;`tGy6{5k)Y({|Y>s^&RbCO08BU47j9T z1H}H1`p@6XbEH4oJ1NNu3FM7F<53$hZT;M*qX_JOa3)i>i^@&g3qPt^lKd~|{sOy@ zh)`Fa(4@7~Eyj?zqA#!w^dfBl`X|T(Q1dB|L@)i`-&Jh+T~OO3{bAY$6o*I?Abn^X1Z;zp2R!e(9jxm_aJFvz7mt$l!;d)RhJdukTEkTWva7GRBv5ar*x{kD%` zl|64In&=~=6*(3brtOFgaCSJ0Z1iODUz^u`Kr|&hO$ceHbL$a9(hx%Y&Q6Y0R}=`4q4MLB#QYn>O^2Y(rovXoE!YUaizwPc}#`Zq8h$liZ1yU8PE;(W-OK*84!Gp-rh z!}6V7nDFCAH&>YF7Jl*Kc^lJ*wbUw~*ij*tf)M=pLsxjj-q@UHooWTtBjB|lO?(yU z+T)i9GEs6|ZoKLOUV}3vEn`RjEA)!;^0|$Y&r6XroH3@FPlFOjj5ZZaip6#deX^Z~ ze9)BdNWbZ_NpQ$aFPbjDBsMA6C7JG~GQM#AyohftdF+S4NIDF>(LvGJ;O`?hi6fz_ z`i{aiZ|h^{psTJBo>uTD+goY2R4oYUEt*XOwu6BzztHv+6zc^7Z?87})z?uXD=e|)EYN-9o$_>A^=0*Vtl zt<()P&1Ufh4#GSnYq)7)RQPP>$w$;oVwXd}_Ppw<`?%A6{8U+s7#%e`@l>m#6LW8m zp@|P4t;>(mJiw50m%b{U7~^_#*VmZzn5t1zrv7Ve>eDL8oGa(YOJcvKnYs)L5Y+4T zs{C^CQD$8s1oWbN7-(+WBeMgn2smK)#!kqcm^zA>ORZxhmzlNnUfG zy;$-Q5-^MQnhqIb$uWz`_#GAS(TB%pSU7+L`zuVE?9ixGEr=y-#yjhB4zSvk9MTe1 z7GM(;Atq`A`j581Hn#5ld-ctmTU%R;chu1OfE#G8{*f-cjHGRoy7+rmi8NsWWwNKV zTxvujbiTDi* zcd*cknK~#@bG=Q;_mXbuIS}(kkce?hOdZc%;#jPG(_U11FYIVzcuNhiTOk?9l2yW} zL}>A}s=QE$blA?=LDsqHn5A#TCR4o!7Cd=XS=j@O@Ty8yR+foghOompLd42IM?+P) zC<4JzJ#T#N)-AyD2cGd=y;QNI0nWvWU*R_iUs}OR_>GxoTZX!ajs8b>adp|cy;$qG zS6Z-d-Ag;O$GU!cWuD&nd^bTc27Ab)34NaEn%s(KFJDR$B$=@wVcO_+xhRAQ+uEO_ zqZ_dBe3*-!xjyFZ-SuG=M&>07X}a?7p^6`T^p~=syW?W6H{rAqXt-#6$H)WrT;A86 z!ed5qvd7nw%Z{@D;uBM$j6B#tdlNl$Y3MnX1NKj{EZz$FSY%8tvJhFCzmJ~ggHy0X z-oeF%UsS7Ei>7I{UA@PI@=G$-btiX2RR3A0^J8#Y#YjUuX}R&jpBJynUas59tCEifVG)CUivKZQGjhtPP;plSd1N?}uzO5{^KErSH zRw;#;jIC@htwwp`#rHF{|CtDO{K^Tf01umNT^DU=z@bffB)ddHVjH1XkXox5Yuj%? zs_iH|cD=|~s($LZnPL{G0=4gKs8bR(z%DAj&-mYa9FUtP{O|D=QBqDm)tE|9+*$gN zHaXXL@fFRDQXH7qE+f(2(cd_hd7n)<#l4;&3-WM30k5T#i3ZB{VP0$I2{uBl9 z0#jN=8LH@~0Z!$bjckz-tJAs{Y_w#p%^VKip|E9}gpPIh_sgGD*#2(0@wY2XrqmCG z)6IYQy@;Xp2N>YnbQ7^_-9eRcYa>QHZK%um&lG?yW(ToS_s`f^!h72R{PKErlwvD; zmc>rVXk_z9x1wI=m>+?`ar6DGjB??Lm%dYr7ICCXWc>u7Y2s39)+Di`wmN6?uhKm* zA|i}c`Zq3_3eaQ(#w1?*z4-0)z3$sTHJH4qA$SmdZGh*Gpw+PH!B$611=})I9x6iX zVj=x85qV}G&@H?U`NO+`d*-G)~rns$xJ6C9jJp7t_F7 zQVahBr^dg51-VTSm576Egh~RhcH4;$n$d5%o>Qk&b`cXmlU1gP|JyO$=CSM18RusP zgAGdfGf|f>SNeLZIJZzIE`0;V7xeG*6>u%UVhS|d9P{RV`uutN<=)q?v3miJ1K>8% z?f}=WEHii9QHB-bwVPn}+Nemr1>EJVmlrkxNWuH(jr?pGf5$r)hYZ{^U`x1p(CK5H z3RI0PZEY^VxDnA{Oh;aNI9)yp+{2}5VavCe#k_#4n05$6)iB% z1X(^H6TEh=9*kf}WHP1OpVZf0`UmJavTtY-+{4jH8X6fPp;&5aYT__3mXh>M8IIG_ zO88vdXHJ4I8IO$o3ML1R!oA-+X;b_90?1iS^;lEBpOJl%QvYs*~KCutjq z2l9|5q(^`-XjRdbX*0+#zt5H=m1TX`Vq;;bRRe6f4@13K0tQi-%`z}5G`f%MI1TG4 zz_@@lFgc5Gi$4O6f;o;KtWstef?Ec+)WiJ)EOmf?osCoi&?E0W@(di0I41KT#+p;7 zwgRcBs=6?Hend_GNQ4RjZiF5KdjPKKIl0lc1Dy&M z^wlH&V(x$zet~i#npJckj4}hZ%O-InA!lW&(tt8r-Vfpwsbwdvf@&Vi$&?Kg$ta$O4__t$ow;ryje%KNWcKP290(%8UvapZ3T2D_8 zR8s1ye_?8sSfIs2F*F>50ddUg{qT}61xiy1lLmkid)`g1H39y}xIMXWR`MGn~Bt#!u4}3fNzluU(Vh zbK}J(EJy?B4)kFEz;0I$kA-}E5^5*nH}rwq3K9YK((i;XkK|U*c=n4TycS1i(GfCe zLA$aQSW}~oj=M4Rt@M?I+J|s3$0q0JcqIzvpKuXztuqEUeoJmGZDjq~Lx;!Ch9ix- z*QXU&PJdFyfBv5^lHra2XN+X&_aUDr#!X^96X>OJ0HW{i3H3Tx@ZDV5gk^0wmL~tn zaOm5=a1*c2%y=QeQcQQ$Qoz~Vmr4+E@Hvacj$GA3<@c$xa|nl7Ap^9V``Pj1ZQGO7 z|7)DYsiQWbA&v$$zVsE0=&oG9EB5tGOI+qY>_L+cu9gU^Z{$@ecVci+_h z2R2y}2$F}Pz$_5>j^Ko0+B!4DdibAlj>$jQF*vr#l{T*BJNgfp5-m`g>lq+# z&eR`9Qm{LC3Q-EL2-oFBO^xwH2j!9j?@C=oHjE2AAf`e|xZpbO{xW)4*bV4pOp1&0 zs~8vVd%#`{XLp^7N=4XT>R(R-!t*9{HKF|?T1Bes))}vHPyXrx1R6{(vnvSX2z-lu zo-_cQA)F6(-Q0}8IUi!}K8oTS2_WLE(t{H@4ZDnU!on6n3n&cVgWFj#`ey@4N7@Pp z@Yh6Aj+SHU|Esq_C)J8JN|xEYZ_)fcOU{cN#P~hA)x35JaZ*#_?f(LxRK?Lo7hv$b z^Uy5&{m|+yNI@1~K79Cr=Jj|>uGWNMK{nJ&G5s$?vQPr|Ayk8(PXxj7cJRzHmYHmo zlRE;`96Yva!U+SEQBCy{uMwltCz%0W*p6r|uE*wr?69<4q7AIuuNYk*<0MZgtzV-u z`q?P#bh@i_&&GNPUa@tQPaR0o^RkJd`Gs}23l=zxUpFa>5<4ySCoN1exnH42GS=Ng ze)A>M;xfj)AQX^Y0|Pg2-HNcdD9wnBJb}3`us=W~Zjk$e@|CNO>h7Sz`Yxs|0GVn( zP8EIbd7F}VfB>23&H*}k{At`uVf7{K&dA-oJbEO0V~si?GR|txWj@ucR4cE4TsXvP zn(nemV0U@s)1z%rI|XqQm=r~vE1tN3>BWtDHNMhFaPSB)G$Kig^oieeyzK+-k)BLo00yJs%Da*bK={*M-ebpHl4E zEjL~L%)Z~}$(o4^SNA39FC6At5D56sUfWM!?v0)pL#(WS(#Yvu&G7DUpUA=MyMzt( zKIherY#b_#kNZVI?Q@~>HJn~@2R?u1TG$RwtX|*rpxyG7!#Tp#ZvrpWzQD~Uqj8B0 zal96PsRK5Wk7b%~g-x?4y1e?F`iisQ$g`_gFCEO7vzBjNl}Q}O(R|4>QdF2BrMs>{!P4w<A-L- z!ehJ)+$(hKk90}OC0FI>>m|D4fxmQ%Yh}(n@fDx)jE3>Vspse%nbVlHYq!{KD8JzY zROQ)s3LNgs`?;1c-?v0tLS_^hq>~94Ol!V9yO;wwlqA7PAzShF*P!SF<_Z9x%k_4o znS^NuW%H@8A$#Z1t#&Y2N>x0m#yt!7hd*-5x?HR1uF@L1civp+aR_Lp@5j6=mLc^^ zY9d`N=16OVX$@<0KUEg{;<@y!iq*Zu*(YE7$ND`UH^+MCS@Z-ae4O1opyn5Wo~*Mt z*ku_z8l5NU&+)~L+rjxs69U5{ah&JNLw_H3eUQzCrG+~#_Ez}BddVe=)Brn>YH!w* z)#PN%-6^#vA|c@;(Ad0IeMjSS114R+MNEbzc-}?4#}0c|yNvO#vZf-x$f*98{{pC1 z!J&ImX%pO4lCUlpn(@-o(weR5d5S!^KYzCq%)sC9jZ z4<4*;Ng6B;;4O&JY@Qy1b`(-Rb=r4^W7lWp$+_G7eYZ{g&`~S{hn%YoOi;aDBcst} z1_1>tjh<|{;a6<4OY~=am`3w}Aj=>EonN8~^r!9be8$eo_D}9L7TXJk`c@R@L9c&N zY-~YZ$h#P+C{cE0dr-SfESNWhWiIvXCEfSav@W)D`%^WJYP3641?iV1tbd|?^5n@T zw$FB<))3wM2l?F&kExY<)sb&5Yt-~7tyr@A^W5-BgOvwv);_n7?se%tmT*nj5MtzY z+zInwrU%^qV#CF$w6AX?i!I!GK7YO>rrM85{LtcGeXqFYtGe%n1x#2mrU|e)l211H zQ0(yqXicsPaK3V*`SZvIsWVVX?e3DZtXZgJ{Y5M+Ky|_ljok7VD$#;x+~Gk9zd2^* z`bGCG>GGTb$# z*bI`hDTjWos2y_uxM7z$V*#md?7H<#!*_Z2Rlu6W~FiVyA*1Ffc0a# z5-J@7wFUF%pU=tF1>uH=n;SM4_n%R&+%W)Q>6nt-^wIo1sa9eG#{UMim@3JgH7QeX z!x_M*n(C6Ard~;H$Md&;eSSs#LT(<+9fBPf|4K}mkb9+Jyd}^d5JMtIpe;n1uC?f~ z^9l>^-Fqq=_8&+KXaD5V1F(PkH>kzm=uz=fHqJBp5z9h1xOsR)-;ZALErNU+t~~;e zm=F59IAsW{*%J+rGuqBVEqac_WzUKt<9zcaztegsV*>z3B3B|51+R-VqaByi3Hr1! zoXC-eBfI4^s{ibKuQAl;!0O#<7CNQhz6LOf<`Znm$$X(YWD}+B(|rGfiyvRlP zyAON5rx%)=w*7oFmo8f(++1<5da7*2_iNJ~1>;etuVm01QP4R^z*Yi%@#jyU zNY^PxnplJ$E_ZNz>;uj!?+zXO|KEBuW-+g5a0L>#`FHu4jEVs zD7I|bR^U+06=0$eAGfM175fxGA|}7#hwkCsY_fJ3ijV%7sr2x-_E%V_9>kY~7V1Y8 zf;O1a-EKLFE0ia1C+ZoFXmZcE~d#Q)}kpPhPLPQ9D+#bzQ=&Q00~9|un~j86w61% zL=;3_Bsutf3QuQJZ1}skgPajhfwuxGW3s~n;hI36MFMKBM(E@arVkxIj&)zFawzB% zf>yFnvcg;+x<|w&H3?O0 zvyQ2HftF)M;(945%~&=)H&}C%FQ8|-3F~d>$dRro8)vxjoL3s~oT)-!6+DO4w{jv3 z{ndy$9U2+Alid4kF{Xm@5#P<>8)E?!SL07WmVT)*{SF=Hi4(cndJL%y>08KDU0Kkd z86DVXG_x8|z%P14gr1D?HU6s^vwgiII#@tiQ)LQCi2~bh-nap#35YrAzdJ0rU&^jp zWiP6K3d%$rI9in^N|$n@Cx324lX+ocEy4nD5F z*jsuui@S+uqR_pMw)#~H^}9>2Jah{D@KF_@{wz2f==_ad17q~4- zb;_bN%Lyf8W)r`-*Em-)19s1pl?Q71X(Q3{Poe&K9(?>YI0zx@$*}CVTzyoFTl%|l za|VT=hr0UOVUq{AE;{i->*n0uK$2|4XczsI;BSX-#rEm+dTxjFYW}JUkAI*nWEwOR z8Zg;ydHJjN@Ck={9=seKy&}n*$&nFk;lP&xnL8|Wi_FenI z&av2pk&;5dy%;bloP45B7BcyX(h2B#KnF+-@Z)eQB&OPe8klP5?eD{Kz#b{>u0*&B zm!HCOmtOO6aY{O7jRt{c?NWj(x{A3Q#kOaY^w`9uylvZ|^vj)Z06snkAA0@4^Ht-I zKP&fWP9+BG9QK{*X7-uEW2oIV!<0epkcm}4durBG1H<~KVDy15jfElmEG2#xf!Z3& zHCN1kNb?9cyMRiqu7_TLKtOx|xA7-;aum9Ig4<#7f|%#e8>=e~CHbp!=XFZ(2uDF2 z=UJ*EBg6gx-GFeO0I3Tz9mpg>eGIm{d?r(e9EB#}2Xec>!J=;{(*jBUX4f~JT)DXS zL^?E=K+g~_D)x%dWNAH*VyPxn2|A54G*e+W*8Ejw56ufr9G0j-pvQc{@{dr1ehJ8#iOlD}tKaw3xNVW0tc>1L@cg(#F9BzeaY1L7=li~yw~P1u+2 zx3p9|x%y@aN_P+75#0AE8`rL-Y~TJQLHRr5kvT>aJ=+TW2Wy2BD7mEIRY>|DotnHr zwt{bnpMc;QD6???5`t@)E8Aa`r_s2zMU8Oc&p~+xC`G>M+l;-J@!m7%bx$Bqz@{bS z^seX+OcYdh_TVb_t|GPTa6OV1dj(S-=^kGHUEdh2KUx_N(R0)%VfSp<0m@Pn-F7#G zTsCzDA!qxM8*yn?Vfwb;1%o2yybH~|M~L=`F(pbF|Em1=KSOd)to{oNN>!n2TT>8 zT@Q#*j4|gAjS2zgbATC4gUoO0QQ*3kZ^#!l;okfRh(qPQh?GXvajn#cv>weW2$;Bc z@;l&~ErsR4wjuz~$Lh;ST36x9xOA&$E(%^V7OJ)LW|4VIY9GN^&5gr&nFDD-$Zz_w z-Z^M^df7QH&1&#mc>_qVi?}Buw^^LJIAmHj`Jam4$gxqy?ERngx5sTehgAo%(`RLI zs~43Skc{}|&p+Cb$hk{6_Tx89??CQzeqU^A%9srT;;bSlvseR8T8yI<-cj}Nr!(9CTK|ZuHEn))aI6K179_F9bzx-eSyz~vs zY3l`eXL_}hE&g5H+A zB#@hSoHns@b}qr0#i$q3Frd&p11S>?SHf{)#wK9H_Q1**yH!^TLnJM}l6<5pz&8}=oY!D7ac?`)oeA3p6x{0}UlgWMsj#0~G^-z6 zGx&+FJMm`UUj>PeJK%7{=F=xmX!>=`)?bv4yNCI^V`im{5IIgxP8v_bVP&=T!*`91 zSirSw#Og8dFUW}ap_Nhm2AQ5J#x)2~wN2&{Qu?77YC4QQ@CTpBJ3OEiJlKlb3QIf6HqbfRuVa@3 zkoG*Z0NN&nDCugGPT0e1*9DH-)z)!Nrn200Flm$&6?KPq8W~}{c_DH5^=9pmm>5xE zeaM247!;<0c1gRweDu#imOHkn7AACHpReG9ZUwTCnJUUpumrdKqGQ_DCahk$Isgdc z_c7GaeSPT@2Aaw7Rv`rzNpI5kJe?7SOn+ZAk|s`-rAk2h`ETxJJI*<<4m=n|B1N(O zafd@E665&ES|O3;0OiRZ|# zgLeqzZNiNMYc9d@W#V)`R{ZYca^o7qD9jm4+nzxdQjK|zf}}mRWsKF)ZqqqJJ3B1% z#-Fw>|KgDsz7VqAz}vFaq{1|o^wPG9T|#|B53e(p3b zZml{TtI@VdDiKS@#{T@tlx$>C&=_FT6maF4t$-ZPgZ(;sB0PcUMMSZqUHUjP6sjZq zFFk2Y68&;POOo4)l7Wl7soQnNnntgCF@KXvtJ14A{UZUqpfAgP1rB>|9>%Sxn6=I1tyc(M%A@XSE_)>d8MA2eKE#{pDZPAdK0bYpJO9j# zbH9nEIfm8O^J41ajNqKeXSbAQl{X%M|*`grXe)p?g7W=~%U2y@TYWm-3;K!bx9#kv2a_#~Mm z#iAS+cv0EW;*@WldZ6h`(7^v{U!x;0m)v&X7QJ1@UtA=`SDC1T!VGRlE4@a~KUSCM zi;ri#kfB7V_K*Hm?Gs|mXXn+fUB29fc}1dtCA_D%q0HoPb2Ta94A?E`7)?ouAu?0$ zCp38*3PGBtD;T|((JHZqjn}v|tk_<_dSF|j?N<2!Zu!6fuX8x&rcu*lLTLbB?7|^!E8T6)U;;j`1RlW#GY!fP+~3SmVp^iPmwHAxrCh$5YX@qktJkmV@TX%(&|um3kEqHl#eD$+G{`jnIx9%cg7sxq>9p|n` z2}ou&ZA#5+Xd?m7pqT|C3%N(d=S_+J(A-a{lySf#duKJ+kNk6C`^|d(PhQUA|a+-Zk#%# znRU>?;f$vztZw?-7UPfhXzJ14_nI;M5HWKs@<=OJ>YH;;9lMH+$S9y-y+30DMB8Q} z+Z_HvBov0NXaY@rHwSU!^$hZSEP!sZG$X{>N|TYRMsUCsv3Ti&1UICAp9(k&j^dXsyb zdraCqnnw(x3m-h3fT^U5s_976N@?kjK*;#Hxv8ljf1$&K!~R2b%b=vpPWQ*+?q=PF zZ$C6b*v@ngQxTkO;9__GN=%EiJR$JXE}RuQ*xJuh4D_VYHloZ0xdrAtokHk4ffet6 z=zSk6VX!LMDJ$yET`-Zr?ZW_4s}v&;>xbTQWsk92sK2$~i|^zcU*I;}i;10a&@U># ziN5m+i)2xlsJ(%Mn4tTt^Bm3Rva)_v+`nsclQT3FOd@tXfcpg3P}7SS2)w6QL1kqc z#lcJs)z{{qifQqjaLNf7g7L$Gm+_|(y_XV5d+oH%KZVwBREG&$VC$st`S8e>L@n$y z`|u2?A4vz_<2$4v#Ztzpwa9a3dyvU5!vu0hb#QdmiWSeX2(%Aq#kaKjo%LwRk9GH5e0~@ z*H@CK4E_3yXGG2KoxC2tq$zb6m7o!+=V%F1C-er5C5b)EgdGp0IzRRF*!JZ-lj_+W zJMMJyzzR?-bZRghE^+OecWQ>&79UQMvrh|C2QElis_vD)0ahz_$35om19K%Em_yYm zBO@a)OoplVMOFny-itwPdNq|GGC9jo2<3Ijc<`9Ini@Pzr$T6Wf#B7@o7I`hP|+9Q zO@-Qw0?39RBI;ZO$PgU>!~Lfo0;#n)DGs2peuB#_D;V{YF&dN&6Ka*>P zIv&6GVOU2p_17wA@Noab%60L$MJk&Y!Zedd%3)*mX=>pC8bIU5wBBw8Jkr5!0X%M?UiNP zkC>Ebh5S>p7B8$|X|LcCayhX%o56a@vs_+LF>sIIuRD&q>Mk_a=euX#P_7kQ#~0O) zpxhvT+1|6qrv$tU>1;;4YRG1*<86ftzv+q_G)nD?^*r_MT`0q;M8C0VYvwNnEa=O~ z%7To0Wd9}YRz}Il>-`pLiFfYb-_#GfDq;AR zs0G7x@J+K6qklOgCQkzF2Xzc_5?n!xWK32K(!Jq>h(%*4Y>C}PPQA1q-rLK03K2V` z#L>UqyL)#F&=52;``$4e!xqI>$e%$Z^_(xcbhA6F$XaV9@eLO}dTwHFzB^W#Gvf?^ zagY&}upcUYp!&OLI9(xnclw}FrBWp#JmKq$ZW&sT-a!sw>#r{M~on+PVpb z!zhE06I8Fq9F{Za?C-zEWCpgw(HJN6Z1cU`r+L4`y&GPI0mC|T%F_#INy>1&>=IE$ z@;YmKCq8a&7K=so*$T(Mwl?tA%=S$i0ensZEUfU^$8 z1SmS>3L|w$q#-p9|Fn~L#2edDWnfvbDbO|S(xqQ;gNKRT`c}qUB{30m`8ZlvbiX+- z7Z+C(`0TcRz(JF17Pa&G)4_<79Z-)W`Sl;Uuao z)7E?$Sc8N;c<|s(H_Gr@>ne8-4^?cq-MQ0rGUVB!Kl^yYCpU-;#8Fl`RxRS~Ng#GP zHk#nCo%#8EBgTHO&dTVRRU3S>AfbG}hd%3x| zap0bwudAu6yRPP%IPuCNd0ZV!iy*!scJ74l1QQFIH_!g-Rilt4@=0!Uwz2V(!jy-) z8mEIy<`xH_#=BsFu8fF?2qu~EsD$USa+g!Tr{G7>_UG{}^Bfy;(53C)znyq`x@UVS zVw;8ht6X-g$h)J?fa5xhXQY0hlL9%oVnZ#U`9G~kb70dU!3Tr>EHyiOmxnNFkjniixb}U*ID)c2Y3G(GQ0fUol9DVqT(4ej`Y!~sjk0u4~w6JCMbjYL%d*Ux zsty4h@07bkG;HpDQE;nlD!R7WYXAN=xWoa4w^+x7dHACwR)if=<_THuqJ{-{B1f+0 zA2DcbaybTk-OSQ5%-2>;m&YCFL!fr`w}E=@R)2ef8wC1OtD{Nl7NOWtgK#m}10M$4 zBa6Mmj~l~09+If zA38MJ_sZam(lOL`K+t-+yP1dthYp=WNp+PyMW#V5J2m1LWPKt}y%& zz`jP|#iF85p)SK>!X6|L0x}2+(!+&is!2)3CnjpIlt}kUSr+R32L~LoS#oGZgjJp$ zrx7Fxew)EeXT`wM5 zB7R&WB3dN=kNdf=oq^Q*vZ+Z}9C(Eq2BUa4Fj8m;s|G-=imfgf$~k%e0vYMg*?Tuy=s41(p+Q>QlUi!?uO%Jl>OW10j=CdQ%%PQ$ zk+Y7UkB<-7aTNu{(mpEH&k4;PIOL>T`S~hpxk!VSMJKd2tqBvpz~5C2%{hV|ps^+9 z&`h8c{Q#r-oE-kA8z5c7{qX%>cHqI3j=g;u0jaA!h<$&X%6L;Y+JEir(;xSYP0 zN?vb;v)TQto*uz*^c+j7`v)K{gZt=C7R(K-fBcv<6O0|eQy@#Ov*W1n#P$iCY5<2Q z_=(ux>AQ?)!a!S_EvpK44iKMZh3QXb%#mGW2kYk_85!~_S8v^Vh}pkh>3Y}`1a5S5 zcPFd_*(H-A!espIA7Ld)EgCME+FDy%$DT^=-`=AoeQsvcJGxw)FTW>`>MM%Y5{_ju z%}_dQ!2}RUZADR}I(GRI%U4f9RQHHxv;S=?0!x@yf@o~D$Vi0jtnV^pMvwU5(1;b5 zi#HehOcqaY5eMT_1N|4n58id2o}R3_7GTgorU$PiPT9?wy1C)lzVn+;$aX4R2S{bQ zQ^e6-R=|^KzlBV8#CwI6Ep#Kj%WJR2#a(h!{I%}!p)FBJVBmGwwxJk&F>hWkXs@&Z z$351n{JcjD+)!G%zIQ}r4;cSxk@K-*>k@HHfGH*7aKKS{|PJZUwMl=YR0#1WIIwVQh1zs~yu#&++8N+|cE5XD# zJ1eU~-WN$^Ef>|n@h3(y@vm5yJf`uP5(*ZMpO^8^YXLC`CR7J3EyY^I!XtFw8a_POlG83SBxRmM#tb|EPP*xT@Cf3)BFlL8L@NN?N*88WCyfmhO-a zL68PfNokN01f-P^l@_E$K#)d4O1kb`a?W|r|NZ^%{c!L7aPKF;y&}xoJ2e;hdLi za-tg{0g*~NgzLcZ&x#{k9#8CWLu@WU+7J|I+n9yGZ9vL`#TKk>db~O{b^g3;8UT^m z(lfjSjMFec;pW~z=7QrSbaQ^?tEDIh8J{bFp+LEqSXI^`O_JikToHmmrlt4^5WfCI zD&sB_RbLi4;Ns&;Xp+q~q`IlZjAsnoDr`ege^s<bylmcW7*PAW8$ zM?DzykFlwQ+^oR84b)w|cHpH(dLg7Utpp@MFtREhR=HecY-gDYl=b32O-uU@+z}{7 zuCK`hSc;Ub1KRottQ%xdirwf`yu;jdbgue-1TsfeE{`I58;-x5@t1x8_zYqLC=cGC zcy?3^_-73SB@k+Ofc_d(8{oAPh4qbvon3Ao*xk5nK$0R3T~O3wP#U0vG59j5*V_%o z@f5HR-OZVU`4g5&v_@N4TpX+h?RG3+pgrr1n}eX1yZ9$GfPf?<^WANFfIAS*W{ULs zOAzl&zYSV4It3Dnq;(n^r_0~I9aP;s4d`zTXz5LLG&Sb{cztrufd~3W4FHxG<_Gwy zEMtINQAr8gg~vF|AaVimkE4nZ0V&}g1C+o(){hj6dLSD>*X(&%&|sOVrJ(_hf&l-N zw9tp0vB1pOSVd3I2W}C{AExA?v_?`=(wON-0e*m;U2%K9L}%Rli&JcKle+v%@??XF zHu-&sctEL9xJ)5hG>ZfI5weMcZrP+$QwVbeO3B28=;=wkc?&0JrY8{ns1dV<6L^5<=!m@FL~^ z$VJI^YADwDS@)Z zjIe=$0d5{1!Uh0}pp_HxMQKvT=WALyv_A(62Y~hf`1|+vHYk+hthcme6LLe2#)t|! zsq=#^&i2o4Wc@SSkH&@BLY3SN(6E*RxlmEz3g*;FoMtc)z%rk`fS2bGF!o-@LFfvK zRB!^_f35PO9HJ$K=LZ??yV_bt`{*dzZ;gIFK)F`~t?C5Z*zZknp)M5Q-LW+{N4+=* zv>iy;>ZQMeQ#@>nWEtOtp?rmuB-ww6q65|h&}JOOCOS^q?;F02jR9t)m(>y1{`Jx# zS&X#rq%^Fo0x7x8HE2QG3MU67cJPhCntx||J7ii?Kao{u`hOlC0uMnV%MA)nz!yP& z1eVk?`%onfFcj2?1+PN%52A{fNUOBg{IclQzPR%8^3S{k(Z`+ow5lF-RDQoNi$vc+ z=Jv;ejnaMzZCzbBIzAL;>Wk(ADF9`2I@;QdinGg+n2;9f{^>-Ri_@P+5x%E)4Zu6l zn%ydbU`$6#3zU*^rvVRGH4d-@z~u zfAfGTkuDBU#O2*MjeGYj%*{dKDZ5DTCJI|cK>@lqlI(mZib1)PD&P$D%n)!qnE-I`}DbEwr8<>9G>%tu#t>zic;v9-5y;OVpE(3>tHW32P&Mir|4mlb&m$uOw6tbG@HFw8B8Q~h5j91} zHOKn%s$WNnL02&=2!TWwr5;hVb9FJTV8F={>;}~i-w%Auz;9F1t#iPY4i zen^*LcL&>oOkFtDL8Zf2-_X#P2tABVO|y#Ll2 zC74h0TEjiT+4e^&G-Lo{eN=N1HLt~gA30N%(4_-ToSn5}5LJLDy`lfUIUTuZHq&4n zCS}8QK~gxGDPWGlT)d2ic}-XZIob0+sXw4ou?n+-)d#I708Ry8n@%|6%6mg)ci>C_ zKoq9_mD?-et)Fu)3xq84fLkjl=l~hFC_hgYelUb8&n}IKBQ-TOoiG+1KoLX()(W3t zjSE4Gb?6`z7^^CG_6;EVZi~9Q1&tmAu!HHQ<2t4OLD`Ij!GqtJsjS3q73u~~W}hkd zM&6l?@RlPWCWgJb6zDD_H;0Z{0G%%`!dZ2eC8Xmj5B>XuaXQC=2}cM#9MF~YbahGX z!(OSbrIr5+o0#2j1^TE=O;H>24aL1@%p@O!Bor?EdvgxLmF;WnrtmtF68@wNy+6CM*@ z3$PRrcsqInJlx6(o%xv3!2lB~-`C*-t zfFv)=7r-#^RSq*YKj=(h!VN8gRzm*Tf#xm%+HsOqc?i@alStA}4ot?LpltKu= zX8(V1FZg#C3)FrBo($&~^r@h2bXAp6l%tvc+}@rf9?=|t1FY)B|#kZdlffC*D z&LGAAi=PTtoc`c$#Nt+Y(%U3oa#c?0b(kRS02dMq=-Uw&x3O|`l9aGv`&oHw6#7?o ze)$4ykfTd6T>m7gH;yMzHY1fGWG7}8ya@EF?Y;rNycS(0)5qnX%y6Br$`1+At!*m} zgfS93k)OTfB-~Y#6kW=a8Lg)uuWJ%0M^yW`}dhJ$3ezWKn%i6=muBd zK?ky5*doBf07fndVJ?^<$^QNyA|lKdKrfZ?e-k3&(5~q(Mr0Dsp|fp$4vCWFctV8K znsXAt{W~Qk1ug=m*OGOxvjhFQy}YgF^(3OHa6gW$RO9f%U*E)9?gDBEht}V@LHNSx z89VV2AF=@`rhzV{tVWIczS2u%;ZPF+aWX_<=UPHI*bUwi&OxdV^6=2Sf1L^uAo;Yk zu@M5fGP;+vGzu$fb$p5SDeEN2JYlz_5ODed3lP9O5R^&EO{=z&#W~ZFZCxh{P~W2E zH7wjgbpxQMf7ogu21W7cFPMpqlk@VcebAp34C~Z;mIH4Q8XD@!G$$WJDGIe*QL7*j z*acv`tE+2xm^f$@1_P4Z=K(-4!Rk;M2VaZ#LP*U~M2yS7GlagBotXO|M1)5Gu0dd? z(=7Meut5mCLm)d)U83cRkru^+lY?x=vDYF8Mvh%1)%WmkT4dAfI>X;c7pjN^R(j-!S2YtUj|@W&CVU)^GAR(5A{A z16TKn2}2P|ojyXj>=V{W$mM_(y#3b=1sn`y@U+IR-k6iKsdutdTgAdBAP-;nf=N7j z0rDGoY*Jn2(VAkpgti`l{6jzraASRN*i9%oalB>KA_qQ$f3YE>F|sd7zRG950cf8Q z47siil0-y41rHb)vM?W|!F|z~St#HZf?g7X07?mhV5toJ3S}BDI=Q&02@!0IKsL3s z@llzFNgR08&e)|(V9LV5voC_IZU^Kk-o{X6XJL611CRYHc*er$!J`k-wY0PZQ|((n zs3UH-JaBi1;mcfc-6w3V7~0xrcEy>5ww>TW7#h-k*U41|#@tm-j!gOgPbg z5Goe*C@pg@ef=7Og-4CdL?r)>(NM3-larIHw84_DuHJ!;ACRL-Izu~|Gmr)w>2zvl z*0PNe_?$Mdb%t$@{W;IaIB-;z{DFgm19^Wh`%!RzoYm(?8b?aqv4fsqP44HFdA6^G;4j+hT1qMEn7Sn`u*C zI`z@l1K3_q-9S&T!BtOyqQez^O9CJiolM9R5UfT-_zzM-Exr5y^`Dgqv^vnV3p##* z$Y3zDDKFvGv(!|?+<^rk{<*|GJ8oHAI9dR@neo^U?E#q)_WZzl2J$k z!JuZy1^o*PP?zB2%FV~u)80-h>|T6FY5!;@OcFI9Ab{=AzF{T-;t3Hpz$c;a7`QS0 z{?j7@!5e$SflIBtI;RFr9v6T9gct~K`*f$KN%QMKeRI=B>ov$Y>|uph7EeMkEGWy7n4!cg`W{`lyDcHSFaH&z_mVnt_z!@5JC}t$>vk7(U<|d+iJjCm=4TRy|`? z9@hmvA^cZ{A@)t&dJFyPP7~AH-u|$J^cA4JVRjX`CCR?p$2`-@i9hR}+if zxr)rp-lR)?xGQ~7TN|>fEVhqSv2;fALxUOZDw}wqdV$?S3&1BQXH`ck+dvlz4N`wD zFMm|+29N3D;yZapg_{u3Qa}ESogqaWtb6l(Q`x5F(|ep1As>rK@Sp>6Ae0uw8hQVG z38ntG7(mu|3TAXXIr@~*F(}yrXADb$zqj`R;4`X?Kqq}Q^sxs8yAv8zX)!_|$;5P- zs?W3JLt7hScP@$EAq{GJCa5MSapVPXrIOY)TKZV;nw1SeU%Ja9<+P)Mz^{N2(*0JJ z5Dm)Q=l-9H0VTT2m1g@c1!i0Cay!&Bk;e0g;%A75|RUmX3A zEZOm}1-RxwDgyH6Y4eJvD(l{uofwq2G4y*-dWdu@N@P5RVm>ew{`+plZrngS1%vjI zTf$^rGH8ew^QFg$;C(m}4+sCy(2&}3=L(5Tm*7)KdqCj^EMVt-*>$%VJ=hG?Du>fb zpaS%!G)T2`ZUrc@B}(Q%Zy@d7mLETU0MZJf4ft$9m@i)Mv6j9UCTq#@pA*d*$uog$ zfvNXNPss(iZL2l;G6NNr-oJ1!MEXg548RxHOuQsBp4#ev6kj-_ecEDx@vXdr3du;v zn}(iKr~rsEP|U?@@J0Ee^zje`U6*W97y^V+l#dWlWf(%j~1!S1VE1yFm<%I9u6 z{llY}{N*50S>d{HSNgSow6qzbDK#;nP7VCrz`C@b$fV^#r{>I@yBmoPT&!%Da15|& zi%-PU{}y{)zYCExcs~`D$WfQ{IyP+IgBlfPP&4G*g~BGtU2mqi{C&j5*5(tqL1QmP z!vX^^lK`LtxGHLk+YDLx`C7WVLZIh@$5r$=*YM_KjCa%R!8O`IU7*Jh{noEpD6W7J zHY_s^{OtMiN#{o>w*q%9$i&U=-*-dE6xPu|dr1#4-GEO9MTonrt5lD9=Z2$~*FLmv ze1eH>0ur$46F|+(cOoU9(Z)rnTQr>`ge(bhkGjGA=Zrb=jFDbK+)%usLp;Y#00Mg- zFsehkAtMvAIrCr2fXv+j*ph+|pl$Oy&TWSCKd@l~MOTfAh)_GGAl!D@cON{IIf6Qo zV3CiG&5asoB88=&X?8+TJ{UFL2B z_pBWaQ6$KOJDvmN4KTN-w>J%j6$2mNz2`7-nv4c1!tbPV9lk7V`lH>^I@%zICxu{q z|4-!y8WbH<$HGG_*c2OlXL*P&iKd)sZ}~ItknA9%pMTU1{cqRxVB0}R5r10{L*D>-Xri`P_z+)>!CsT#y85xr0JXc!tIp#R^8=KwB48tXvfyMX5B3x^{V z^!^J6JMIb7`bVg6(&LWu?_K zzz3mXIpA~zYy?)>!E_}1Iu{MiH0({jyWc&W#X7NX&G^TO-yIYLz#ile6qJ-V)i3#6 ztxFN}d+YggZmtUE4;-HNXOK~X_>OEK>a*6@Q>Q~ENd=wr3oZ-X7)=CtxC_lFpk$uCS@SMTPeT|@#!zA8$ zuNl?m*og88A!&%4nF=8>tOaSk$D|+hK}2b8WmE}E?8F?6eFY*L0aVBv5?{QCoG~Il z`Vfa;h_If49t7rT3sh#$-OrC9-53E}0{s%wT%qN3h3V79!_7{X()V$6babCz@GCQu z3OogiCG>YhRG>XQ23dfesVNt9m-UjPd7$4x&alK&)aw)+cFF7%ytXz7#H>Mju@MnAl_YF&$pI;SDXk(97xsHs4%hH4S&|WgzzYYH^M3mim{73NKsl7-3sFiE zat48eJck16nUv%JHa|edJzqiDzm8EMd6FN;S|-=M_i$*!&XF_!(ccOZPPV_$RO~^m8;%h-gr4TLeuEqkI77@pFw&BpH-9bB{)zp8 z2$-Q-gWP_Eq@5%66R1-_kdZsu*7G4Bz&0OXuh_QmZrn+FnA853E`|yWDDTNrX{i|~ z3KE>h#h#V(I>M6c2Xk47Dp;0EuVRCHFa!lp$RPkQ0(VrV~qLYHp|@^9;X! z35V=A=mQl{AJLwV1BS2PeXTm@M{6@^SVPfxEde{ER$LPXXo~ z8~xKP8&C!CMZFh|v(weyF7Fjc2bQuB<{{iwYv2z;i3zd86>he!mnsE9P!ekuqgma}&$;MeMW#F#ZC*egp)Y_k;IC4J*Skyd2DE*iBEStNr=;9X;la2fH19ln zbxe&7>GFv97Jj0Z6=T)YH$X$SFJXbuCHoO2(Mi`{D8&IGZt4sg-0X#c~nL0 z`N!Yyk0tiZUxR%Hrgd;dv%`lJBCaSuX71NXNu)=SFYO<>=f?aQ#AFVW3o-QVz?IUA zEH<5Nv)AfPQabOOsrGC>~ajsN2Iq42xMaG;e1dMAQ-a2 ziFsxbV4E|FOGuXXTD$zhn1HkK%{XH70uWgU2P(Mevye`etpGL{C=s#4$u2R$!7jxMnbzJ^C>7KsmiBG%JJG4I zqpLwxCCH062n;|ki@R}CV-{wkq;!>ZPQNXA;+-S1cqwMbhy+)#9;PFsjgk`d$;*W;OT~%SD>_NKs2Jp2J!~yb)4}-z#TOQGf*KR z1=(|iH?^DxSr-)7vo?8h(E;P#Msc0+juoNms>EI@J#<3`<3VhR>%TO5g# za0Fxn#Iqa3Zwm?SU7Sj02B4jOB}Dg`OXW8_dXwb-#l08a z(J0<^7Tsj4Tdx{usCTF#32dF|OXPF#+0IU}g{>dJBDsdZk-=3~A%UUz7FH?8X_}8-QqkmUs>{xz?M}PITIFUE~a8yOELu&NQy|x3ZcJf4xJz?*?DTL0*npR9r7X z1MOyypn8q{m!M`)Y*KQvi5XA@N&LYRA1_^}ChG!G$xAhAt2kRavM(gjGx1HbL9|OR z6AhtR%2jM>-n-=M?eTmb_*eRgd&_CTs$1B?5Y7Z(!taO*j5)jTEy;hP2uoTiGi)1V zf9)k1T_(}YJTN{^p3$Pa1?6FmZbwVIaqn@UTEmRu@wcV3VE^991JhSR1j&2ANKngb z2QsY<#do~OHXH%YySy5izcw6db4n51a9k_=hoJazj_d&-b6u6OL#}7RKR&Z08B!MV zMJfU|VbiSenD|wEiEsG*`%1T{-CSLA) zoJ2pQ!Iv)v(}{^uN<9<_tAQjDU)&9S=fXj7$E%_uq#(mWe{(}lTH07J1~IMOps3cE zKuNkvJp_I3k~%d5qHZ%3^RbMn2BN6y)eMkq^d;Tpm! zixA%LU@z^tHX9W~A8i_p0lXc+uK2C;B(l*DH`r3j76(U2a&1=5WMf#ZA`*KV5 z34)Wn^S5m3$;Q0q;|@2)gJZ)Sy~M<~+hNQ{-S_%^GlifpdiUNw z)21(ApBGPa{R1Jvxt~c(t#py49*PoR9l!!A)`2FPzyW11XF_IlGzIk_N;Cfp1N4C6 zGQgh;=g*+a|5KUS-}19`fRNzsp{aLED+D$GnDGG&C`WKKK$=&4cFxw_ro9n2*Had`^}qN zzzLz45D*_w3_$h+4%EOOYBhq45FFk0endF<@7j*gCiHrLr+QiML}fO)0JU_sU3ncgdI z^Lx|L96R*Z42NF!&)z5_Y3ePOi9e-Hpe>?K*B6J%B&b~n{jupGd}+AZ^-I%*%b>J+ z>oj$t6T&ngNTZ{pK{@%7#$k1bm*#ZP1?egbnNXJbP@5b0Qcz1P>TZyM#H*u?Dqsar z+LaZ39UW_67Xiim^$X<1a6~y+TYCYE{ueK;mZ>arT%kP0x3aq0GQ-2$Ke}oQ{pN}? zGc&;o0eoLP5tn#qz5>9dIV#lH|2DO?Wm$pQ0<^01@`PMJuwsx)g69n=f2YkgGzg17 zfBs8Yq0qt{3KYe~n~)ATzRb{0hrU2ZR~M6k6HcYtT7l#+y?1`ifSy4Z0eYlD zRzU!|9z587&ZPe1F3dl-Gu0B~CkVo+DnBW3K zZsMaupp>in5)cd|yJz5}dl>Xk=J)RxYnNxow+iw*%a;s?}KcogWh-l~`F3fk~17jR~%}DYEgKyaQCdsi~<@3b74s3M*UX z;hk6E@i;?}24k8(&W^lu{5`{2%aA|BLpyiirvDLI{rU$iWkCW-w+jfMB67ueNt2(7 z3=6~SCQ>5y#1bgV{?>o}8c5sM=yHX;gQc|oDU`4CC?i#{eut|yK&Qp;Q2h(JU_vAz zy;+X{#e?cBs8ATVaG8ZLY@G|-Tz>8<8Y9v-KlPC>(?gw#8` zd&9!YijD)VZ@2|Vo|w4h<= zd!sL+Q2UY`Lq##DH< zyOZ(l;E6pY*%ng>2%suq->m9OQKt5fZgaI2CcrL&>>N~?k|d+(tFW&j)E^|P0MmY| zhA@tla0pYWvq@HW);F<34>m7&+GF72lxiw)P9sC9?;P^zti2HL5MOZbPYq^o`2BP# zoCoIi`}Y#yX8;E?@XQY%K7`c-ge(}R5Jp@Y_>tQH_0~5?2ye^SnV4KABAT0@fBYlU zP+P==H>W`BH&lkCuK$ZGf16&^Z&;sT>X+%t55 zYvyT$T;bx#3+*JDB;ZJPmWC8l3p*I=Fl5xA)2sw$Guiic3vIgZ{Xca# zBR|Ogn0l6+@hsJ_sEfbqarhUy6wX}jM4BwZvHpE{cn549NlQIdsv-4X|NZ+nd(#mB zWEUPZLY}N;=!N=g3ZkT?OZCj8Ux7BQysUfQ2h0?wJ5msM3D~PuI7pP3Pq`LCT4(C6 zF1#D`qK@b1fISVWi>Bo#;0S)8)8=LBr%~=1C_x1DR z^poPazsX7ztKznIj@+P38nAcO&fL~x79w$Sj0+O#up>jAGGr8Cw{K*qZJ-Y}RRvB; z>Xvy!HwF+Wb-)yAd3Ifo8JQTn zLA{#QPx((3@1O?c3H^x9U}yo<<}1z_&DTE>N`JY@6i=1xbw||EGrYc83PCsoD4l3T zz_a4Y1(Ar>jegiDdO(O+1VIdGBpV2=?Y@99gl){<2efu*_;v!JcC&F-lrrM`Sft3w zIEg?G2S^~kF=X0g z6_p=IivR|0pq=jpIkt_yTH8fJ1JYZ?eww1mk^?94;Z&gRnEIEx<85|*{4LQxV@!cT zJhw-pxP->5N9UjH%#=&ffuv;V*dcfy$Z5X-`q3JI1=LKLb~qB zn*7h`Y9F)fRo@YbCviQ1xQnAHXS}@~{S{T}i1wlB`Dkv0>z@XFHF@(W*0ps;M2N=t z$qV;eYm|k(y&o9j!V|}jqz&G%@-$d_}`NSJwA zF}8!QZ~q)%fL`Bo?cnmSV)ePc%vn1yODrhR`__l@s8%7v8&*~YPcc?iR3Ls9fUYBDJ!hjCQ$(v% z=A=4UZ8hX!d3V>K#{B`70KuZ1vvWBJN_%`$jkVj1O#;Iu>am6bpPMFp-TZ=&QV?}D z0M2a0<3Ap6z*JK51L(oZCOYKK-La=dsc$s)ya06!k=t442c)bl%3vF<1mN zTg`S8KO{q10o95t_)?$r+ttP8{&e3+X{N%VVrELfKA?J_>Y*$=l&|b?eKd1k@Rt9C z@0Jp4B9!{YBHC;jrR`&ufM_~F!K)=E*A(7sXNF07m~R$R#!7sTTN$srQes^%yLmX1 z2&Gp3A^?7DLwUYloy$wfWm~$i^*?Zc{F}XlD%BJ>styp6o$h}L0E+Q&;?&>@9E)#-ag+V_ay~sjjcoIwYtbT-gH0AeP*CM`-v0uy||#Cz#eOY$%x;(!h(LgvV#p?y7`q)TO6WS|q?; zk96G9L4WtCeWCkBXw7xLKSKKR==en0nhoy^mn1_pj#PN>+*i-L6ZqDc0BQXWtV*th zp|g5StLOcjPk5})wqCB8e$v=YM|+3yT2AN^I@DAZN0z7|(kU!OjRER0C!+SG&nNK_ zupQh*FTBaZA{7gP2T_-PA#w_;c+fqOa^nY12U=Z0L^V!ojn&GodGmpYnGvmIt;EU( zl&Yg;_?;f_nvVvGlHG6UayP4?7}bt;1*Cm6im=YOIv@bGPeq#?eJ<|(dtt-y z>OxPGkf)08xC7+S#D~LZTUrtl=kCg@*ZBy=M zDd*i}XX_|AXhm@b9DrGZQK7R!OU}X93UC%sQdB(r@d)pEN#UAN;a=98FqFpg1fEBG z&Pf)|I7ZAFTx|@pmtOQE%F%OI-QC;>sgl73Xm}Wio-+L>dYrElB8-akGyO$o@FC9k zh8DG#OO__1tn4m@;^+s3hF-$PT!Q>Epjpht**UK6IsNMxMu>2SZtcah4}Bp?t%Id{ zE5gRc27eZ@W(sGLG&?cx!P?)KJKQoTqA094Xz(T)MhYj<(S~m`v;D~iRGVUFcUHmj zq-X4n*E1Q*t@%m0pdksUq+Zge#k;{YsFjA5t_Vig98wAf1-&LsO5cr2D85u&Bv;T7 zEeZ+9+{;i*|9XUk+;?rie>=!H-Oqq-BY^P@+z5k`W8;@0^f}s8&+?U@?P$FKJp^?w zFW?vUdC_R{qDKXI%dZ5L0%Z$q*od0XlSBoq`F*0lPa z0{aF_%{8Y-6J31O0*gZw5bK!V^8W>=Wj(L^hpyr3X>~*$2^v&|+mTqCF8&JQuGzoc zoxjfrZDXz)+FABh9pZnz+;A|$g2gNRNAvY0ALGAtvtLdZ zp&aP!S8f4JZh^C3Ie9QSd5~Yl#QwQ}ApHH$1u*&l=c@u7|9bUb*W}{H$28%ZssoRvUVnJ=F;Y7j`!iJXFpX;TIl5fugloVjKCpLiMJ_HT#(u}#!4f`+PmqH{Ozf}68&+%p->vyK0x z9lOU+VWWBb=`WX{0r!F*jQH;bU-`(Vi?%t8HS9JVeW`~M{&C^8?>x zeWsad_5aDUJdju(>e{sQb%+U%kVJBU^G)K>Hrr-RV*g&=xMF*)FPA$u6QR3-(1jMS zey^3qIOW~b2EmSeNwaS=g{rgTuI)G8L_FD<_~J(QIAA+?tEWE9ea$KDqDm@OTHB8Q z+knaNKq_W(nbuf3)ZYylH`A|gU{EtCKb>iNOe(%#{Hir3@MrS57Vg|tjo(e;6utH& zaSC(+pTg>~)BD4o;W8h_J@TXKXt+PElbEHyi$=J6XMrj^PHJuUgoVf5*TG-b0cUs_dVOYa~Z^p!l`@}~D^2H(FR=iTmpSwdSgp9wWwU$c*tYy2- zEqzzam{<4b!AbKX$gE{cD{ZQK)_`Lmx?!5ZPEQnmvB~+GI z*!0ibQ}I5+H8}X5naI$w$fjfLMWy14pC(>&)Oe60(!}1v-P%amMUr{bQewkj$S7db zo~CY+STtdwr-Aa7PNpYSG`pyb_OU3#mo=8Dpz_kdp*fPHz5KVO%^}k_$|=6Q*;pfB zT6PpB@X0VSV{PGIG)RzgmVE2J=KHLX>EMK3Ejpu?`ed|}pwc+msAwY>pKz_%oWgT) z$yA}WX@K4|VGh;9dMtkVwda`MyPswo*oLSP8@;ZxM>1b~J$_9{6)gz(&e1B@+csL& z?+jA4$2wZBQNEs(%40tf^0VBU*m8WAIzZGHG#4$aTbAm&Q00AZPM2k3yVZb#$HcI$ z^di3lWsUnM+xWp%pC-<>+Cx*HwzYAoJ1rhxwe-!#kNd9B%FA_ZLVV_QKG|bzF7y?j zZ`xNGRo&A^Y>g#JuV&6gwnliI)W>KtVnqnt`|*x!Cn=UaD(U0{`sTz7Tf4?z4fZpw zNe#6dIW4XuGxZ^}!`y2*8Fld@?w(s_zXfH58c=eTeLa%I4C{)MmMc0RR!7u`p3wQR z9$-vTKmRGNeVa=8?yK~f@kr&2Hx^$X-P!ogTN;yh>OcF{N9gvi{B0bs5-$DsO(d42 z-S-;a$X8_RtGA3%`b0zrPQDj3b$_lsxBEMMSMcjJ1?nfYqn_j9vHZMH@q%yNxnd&u z-na|8^%?D5m4+P#C5f}T%oCgPSJp6FrW@V}4Sd!+t)ZU#sv9xz_R~S@VeE_38?8kA z>~nrP7de*W`?l748NHVBJ-=QXTDzhqu*Q7;3x#jXx4q717?PcdR@`c@UrZY)+vi@b zSiHgMJy z9jS%ZGA%6~gp0h6ofTrbsqbW4`y~27)04NKYY6#6v8-#v{Y;d*UDo2-J{e4$W9^{o z%e?Vbena-&BP^m+vUk&;=W-@r>8xZAml5WF7g*g`yRR-D+Lc#qBE_P!_(|zbN0$~e zdmUedrIZtw@r8gNZLhDd#ne7<{64o9Z(#ADFVyE0rC>tg#(G5vlUK-64oeE-gxXzH z_M7T%FXKJjp6Fw>n7z8z5}hr7_v15+7KTSWD)n1|y66tEeRt@aGG)J4v2?;bTO58y zS1J8TI+mGq>|^j}!<;4b?4=0)djY=83wg<%_6t*rzIu^w>FY)#YDzp`Jkg2A7ojiF z!+qNK%2BPHPD^K_Cqq;wa(!&`s1a9?!__h^h`#Pagt)ITb=Cvg&B7P)EFJNh zsY8r{HQm1txpHY#zsk2C%tdIjL@-Zm{}7VwoXiD&@cPxGd5>+@5p{HR}=fAD@9C=wnGZVjGt47i%{w|oq4N0ie7pyH1Wr! z;xMP(TqbF)cu?dvdz-1JXnmT9lxbGd?f4e2kV^>RTI%VIw@xuh6#IAgL+=f$)|X=& z2v};%H7-(rV-VIeYv60XQ~N*4$f)@hAiZ7Fi_Cd?sH=pI#G9iE8ia zuc~VHId6~grg1bQqx<|mkz?w!RbH(=DF)MHdenGF>Bib8Nqg%mK915jO6Wv; z8>U2)y|Q_Ybj$4#zazdDcUi;{h}WOuHHdoLZLV9G%}7g(rn3Dc9CKRTwnanr*0q{i zel(7#gJ_M}nkGcAV)I&lO4aV~?}Df^u3Hs`lml1-dod5df=%mw9lzx(Jo+@Wr+OPB z@eJ}EY|{pc{Q|JuRH*5(>oT@zZ4~cKA+)Q8m>X}9x-oTz55YY0By`yKYTyyr_ zOJQpn-4?T#P1N*6AJQjAEGLB036(l+T3*}?zc_4e(cyCMiI&Kd5UNjCbch^Zcm)lH zjW!N1du+^NUDQmad%0$6c|XgPvvaI{rA$9dU9H8sm#~UweB|qs?}?|Mf0m0_w(@LP z*YdIIEk0LwCgYLXT?qG_AJ$^kX}s3HG)9@zQrsogq7~`?-TL*7I>*l0+NcN*wlSs~ zR=OSr-93t80R%qZR(XEDiv3}t!G}eszW7{aV}#8SBY7=c?2FL)2dd2`N6+D~H48Hd z!LLMEtDQ41F_MR$bma@Y=p!s!VLqUHp~RH@tnE0tBBFfFeCL#Ur;(l2t&_WqCT)7q z>HID351-K4p447kW9Zvs8I33LGcs=YU?KFmQ0l(!W?W z6h$_@a@kQ3p}0YF`ekXE&RL(iMN8zpS6QzJj@<8a!H(Lc${*-rHJ)?`(~(|JRM-%< z*(Y;g&iqY*742uyiO*9nNs(wmAWzd$IHj-rj!SBuIRurzJi9V!Y*>cx2Az{WWlI;; z^xHSR^)HGdc=tH&bhI30v?|g&>65isQ}y&Y<#=7`TX2w=rb}#g)*)Q56*x=_y;s1E zn@-?P81W?g&V@F5)znv0;k@>AEbme-2A5e;__ocdz(3jfB=GUx7Pqh`*8Sk8E5071 zm?fb6@tcb0`d#ZD%=!EHr{WItdutbbU*}^-h->tGajL*t5WdBHc_lsN$kozKEcwXA zX+e-)CAE9hHD!a-lDn$$C+oY7i@W1j3(+_A{nv>WtOSJp)h2J&hoYqjd&S;B9o=}y zLV4}WzG`prnu=aMondr{DdKMQmpuUL0VxLWeX?l=WxGt~S+B?8ne zHM92JTSwpf8m~P4cCVNDUV9;I0;)z{PY)7WR_X``PPU5~16qjcXd8|g5^=QZ?NpBm$8BEKb{DX{N5 zwUyqvxIOQj5TduM8P!STDw4Xgo{VW*B1B96gXl6BV~=EhC@pr*R!Pl_7!8S743~)D ze9+_14#MB{MK|gKrXGl1cp~N8uaWBiQgzhFwkkm2RF%}>(mPkX9{a1agk(HMm^N1( zXu_vwl_wSX-DD4zcO8drIs0f6@76OVpmulrmWJ|+F`tYp@7!7T@mOhFS&eB49!%`_ z;M01lw~Xeu&9K#vmDaj)e)m~hSnU<%@6x7o--NK8ViOk%6_qQNz+?m ze(Nuqny3dQ+@;Cnhb$jaoF45k^mE2XhizYMqcDk{Ggsk#vk{f2aKs+U?$6}!HrGra z=|jYRxFS4OFkO0g(uc`soV&zsn8#%)C^pphi>U4QUEcYJQ|Erv()MizhZdGUR?-rs zoXxbJN}M*&u#dUBrg~IIw8qQPvOsY}akwCp_4s~+z)S0&Bo0#fyv70#rynF6luajL zk@sKI;j9iV{Z6#_=RY?!46eNX_AdXXw%*%hrjshFB(=ojgBiN2+VJJxZ^FhSvG3o# zD?G24SIrx}?~4(X7ZU4Sp|#g^VFC|B+T|0+X3O%Uv;}nid%yimT)1SVC)ect>=3YjQ$)tkB#{ zrZ{}Hjuz)^6)~=A7ifrz@>t@Uj=g!_)p!Yq6tj^j>~@*;bq`cQoRlx~m`#*od#?pb z-m3tg`yq;gvs(4qgtc6NcY-U!UA4zO zjpwCae!(R{dDq>rwfM}h*NrzM@xhVWk*!>DjcCA3!t`;#aiR84e4#@$?DFn5td*EY zcVmQ6loHiFbz~FFwWToFD{<09FFqz^_y`u@ViN zGwSL2otS}4>vxaXqM7Q8X-Z(SD$;aF<_j7ZOf^^No5=Oh`NZYQL>=Q+yXCFF39pZ+ zICfAdT79fU%J4aLHl|JSi{~eIS?&g=dRCh9X$2|EY3~oaNeoIRp))uXB2jiCyNT7@ zDb~tU<~W5!mWSUT|K_bSYR(GLH_m^Yh@-nXkIxgH$W(7fT{E5QxAUaeTEgir>8lCr z&TH#m*rK5>B@eziJ)PG0O}C)WoY@zL=NX18>%KK7Ob{BnKQVBwp2SfX`H*#MU`Une z=iMpui$9T1;Sxbd$)!=F{)o$WjZj5IVG%{Yu=L$d;luQfpBIP-8OpQG3h%X@|5A&U z(kz3~(hhaZ<`t(PwC*2N@zY^6$QMUXyYNKFN|!N5 zU~KJiZ^w&+w=bxk^IPdcvkKw+s9Dcgc&tWOjGtkI5HftPz!&nO@$0QrQE;yQji2@G z8jn?{i$(;k4HN8lmxTmxJ<8*ednu5eG;P;(O_Bj`Y5899Gf}u!-k)o6n_2Z@uZxcK zO9{5XyYVM`t(zVx@eQhzXK|Zl&)L8%BO+o@YC%uCD)God#c^j9l^*%#_(Bb8*9@H# zZ?gy4F!$`dqjvNDP~d=Zgj`9rMPWC4!Fl-#UT@~r*%y93w=`S6`PXEV#Tz`Ny@JRdy-tM{zG|^RIFVmm4_o^=oD{A#%odQeREu&6aWDIp8U1HS7x1U!A9uoaX?vDF+|N3&M>y5W;xc zSmd2>;bh)YuY%jP%7ahA+vsFxsd?0mwu-!tFSL!GLVUm!(`${Ugz5pGo;5wYccEL# z(q6kfM~%Es)w#dn2qRjG0Vl=g7mSZ0ayO%odpzezWstWQP9Hq(87?X;LSEE@yO8hd zE!6C-?7ipQFRIwoYi)+Bx$`rPd+kP#8mGJ%VrqWviJXYYq-HpZwGg8q( zwf=hkE%g^6As-)3&r`G5gu>-QgjS3z&PQCCld}AHLlnmLT+7w(krQfsZe(M6&&6So z7#*_g76;)8NNiB1M8spK>0VO8Vw_Msv_nO{@>@1max}s<+I#L2RlVQJ6!PJA0JV9W z*i@jgn0rh884OY2^u;>M63Hy?@_F{R}lvfN5R>9a}~#a2QF19(0H&vNVyvXrG{>4u{QmkS8xGCc`W z5)A7lr-MWcix!YedU9DU*7L)hTECquIq>I>a^1c><#VI4!aX0sAUE8r@F;H{3oG<| z%PKnia}Kxu%)%K}rWgrlJsSG{kh>_|bP~=!rmjtNT8mK{Rt?Ay{(5*ntKvka0UqhO z7786Eb{P zTvSOhGUx%`$GykS0?hREDk3-+h=nfm7@Thz$nv@OP?8}iPdL+47Y3K;d9Th`P)NvY z04Cqq>s*(FhdRmg_b^GFio)*6P zCEx$?z?TU-qlB7!LuMvf9+?7oZ@==7h4iFtXT0-?k$i{xwtLK3<2L*sF}rud){9Z4 z0xSC2*tth<@3W&;$-y(D%@klrNtoagacg`dl$I}Wd^BouDft@QK?1c(Dv5&RLXL31 zZ;a|xeKS>9qUj~QJPBt9Y^=21`n^QA470GAxM=j0s~1}Y-?*qO)?3yba@EJiDdTxQ zeryTT!!=Vt`2)+n-R?K}TA{nn6aNQwZygm^^Q{dw?h>GZAOV8Ag#f|b-6eQ%cY;HJ z(73z1y9Bq!-GkG(yW8;oX6AnP-fyj$HS^s&Yt0|M)~T-Qz3Wuh+2`4{_fu85rU7lt z6F`NL&86{~5@lEGOl;573xtx@xJIy}QWF?~pqS2F^9Qb}+II1N3aLs#$%ouC{9P>} zNj8^R3!ZnM@ZNX`9}a}CEmK4v-E}1_dkBGMJR_mib^GH?3!m@X!9s=bQapLxUp!?BinEY=4>Qk^iygnN-Fl-~>;B`IWnLeUsy^u#80Z`woE0t0j z4lSY*9a^veU~sfy86>F(yS@;SP3?JBQXUUFyBVKNt*s$?CI~>o6f6t$b)qXmfl|~( zO`-ESE=y;E6?9-FwS`A~|4FvHpP&^807CfxN5R0o4EZ-~RwQao$azfFN_G*ktN|eFW$~1e4O=5TJN+lK$uD zGmkggXo`N#aiqf#yI4$PxjcL6K1Y zS|n29Y;-Wt#(~wJqx^Dlx<$oc2m(jnIsUR<^|>O(>ED0ls04z#>qj;H#pAG!2`~fs z8hGL=GfPvvo9|v%rM{6-yl~w)*k)A?=cnbry|%yXyzZqx-G_LMAoiFBM?-$CzJGT9 z`#+B6M<&PnSs$Nnqe8$lPOneCoqV%opLTRPw$Ji99l-)2(YJTl|DTBZbN%a5qEnf#j*JTShGt4$H!Z>uh3Z?QXA z7;lfnU%j}D>-3F}uMZZZI$uG)2iJGrb2ocY0>0MsgCvrCJF)>d3L%Z-yUd+l)UW!; zi-R9}c2^8vUS0*BD>{86V70cBS=R90s+uxB{ucJDBAAal=`sBjWW-@F}q+t*vJM%ex=Q6xMe{DVX z!B@Sog)UNP$~s0ja;)sIIL1f*t{jM?5TKF;m&$)CO^G5NiSI3B>xdw!dqI<9r~RJ6 z%Yox9oLK}E zJ4!EbB!$a!F>uGt;zVI_-GaMs_j{M^K96CCyrU-D_PQ#kodUxqk#8WB&)xG1@}hjy zW7t7BB!0H-S62g3ax=Ce&Oo={u>3bXhBD*fgjG2?xk6;%31Rp3Cp)eb%J?;COfVc@ z>O|X(rL+*jFPyWe#z2>|u(Rl&C|x*s&Q?Az#4{!A0zCQmAM4v6=09At?+;7SCdk19 zR2_u&&k;yKsgUM0UuA%oxfLncbL;7bf3xW*^@vKE>svD z+|D~MTAVvmRKeUaQN$xor)@!yOD;)=e);x#k-qiX7t>mx*=k}`+6{YYjdRQeDCCas zPUm&(#_7O^9S+3)A*qwDc7k?<)*v)?6ZGUN(A#M`!7#3N=}L#Q2Yc5+Nf%0gmQUuB z_!pG*^GU46wb{Hd{L!G3Mmc?^b{R=?#cguZY?toTvpq5t&<1e4cf_2f9q)C_!meg$ z=9zJtKvm;yyGrRrhKXlVr5i^&T_MK${_q?gIn1tnaeiwf;f~<5Fo(=zj{pXRA%_i2 zXpTcX*}3$F1i=b?YPG?$GOFs)uPLWQwTHz&{wXjW7Z<5OA5!fx;$tDXYZW_97KyOvi+ED^>;x57PTf zY{ZRWrm2wm5i|gsmG^moSMTXlTFtr9tAWZ@a>2swqZTvR_W=S$OLXFzIfyqhBd2j(pc#|u^BXWV{E^@U!rD;e0$#+!fMSp5)$^- z_lAC}&d6};ad06Qg}&apO1|?fT=m5ydHZ8_bDRksRyv{QnhJz|`KQ;6`s;v;t-~{h zC(fJs2!;fAyZg~f1n1RWC-26A$HDkH-}BR9SPBlCoZ}HtgWf%<#*@T)kgysri*+aF z(JT*iRhd?U7Q)BJ{F2$Hr@JAU$x10Y0@PsOGUlOoMJ|cLO9Eoxhc)fi6ho{XuG;TN ze2pc>8XTAtaKqeUq+)d{ntkV+K3Jir%^{ezTTR{@cBiz~{yl|&GC({+_nj>+Z8t`Z3BIfLMpnK8#}XHS0Zf&W_u9KYdPd5SjsH0>J+-)Ptkd^4sRrvx_{B8T{HS&17-qy z3!EAJRWJ`zf(L7YJ?fR$#vL4{$ZQm|U3%Le61E`_nil(D zK?gz}M|zw)rtZlgb{x?1LX1u}S0YpTrXufB4Bl%R2Qjw~*xRY2e=3Nb0VKh5sbTZ+ zxUbUv{_jmVpL5dbj3g!nNJ8RTgWqzX9Jmc?VqBWIT-ZJ2j}R5g<3i!zG}~HhG zo(A)bH*QIwl0&>GgjL7&HyI;OO>!qo$ zdb41!)-X?rMt{!F{tHP2WK-v^?hn077I;H6AjWv}>#odZ!Cwz@iSSRR*U9QL(q3Q@ z22hw5t*Jr=nz(kaO~$Lwgyf7 z=UvUGA+9ErMcA)D7pqs;eVwwM*}LSkY|oAlUh1xx+P5J-kvSjVr4xa|9Ghe47llJQ z&5s(VT{dA82jCBVu#1aD1KMSolUW|K#*n9{xFdxf$VWDFn4`R>e;B>eEbOB=BKXQd z#Cj(=2RiQQT-_HI>94T3n(3;!BZVBUP%#=``7y&Xudd<{sbed`5Og}Z@IA8vkUR>1 z?d1wa4m!Ys2ujCOTbW zPf>B=whHNOe{bgOzQ|Wc^Er8a3u>$1EB=M}Z-sJ^@1F7!9$+dTAlv|nI{IN*Y{d+~$Xz8}D~!+j*AHE2hSog?Duv%`u3 z*jt5z;M2qXx|k0V(Rl!KsQF(;P;zB%i8eGYQDj<~`!ZTlotp()+fFY$JkWQ5+;C1| z+c;`4D6DdURZ5PlW8ylaHe8MO_;B(|;m4&tAQTAIVw=Gl}Zc5_cEKu`8G5iN)BsjT;j>N&Z z@VX7^*{4|!{n^qWV)@Belmn_No;PsMR}!Upa2ra4{p#OY2M)otD5RLJ9PLax14 zKS#J6Qr@W&w1-58g2KqMY^2v~q;S@1_nuX6IrO^Kg+9C=*)}V!H`n!5Ap86!wpS3m zY|B;QI#_hzK@F>c`Be57O=jg$vtqk|KQP2^RHf~tKk|41=))Vi0f!QgLj$zA$3@e? zS##1rg=$Ftc_+MugRy?uF-%4xah}VAqqdQ7VzDn-S>1v~i@HO^=A6c`g_HGG+vAu+ z-rOV8(qqG899y>Zopv8RMf=+qxeL(E;n#LYahdr3a%s21h%f4FyV_Oz&~x>%jP6on zI+US?AbJM8V9PdMc>UC}-PK&0H81XKoHs%y?c80vMU^4Cd0LMm3Ranm#u3%AEFd8g z`vM)9y&~a^dF|49Mwx57O@u0F%arC-^J7^80VT*p#tm;ARWThd@hZ4DnxOpI)?e#rC0ubu zK4VK^X20T33dpCyD8qegXOk-9LSrnMxUUhEjy-O<(CX zN3x*d=}xZ^Vu>(tQ&}q1^B{&v>9NhDR_~kY6gO`*=L=;o5x{`92!PBLv25LnCW^?7 zDw0U#z$E+yF=Vu4$6^JCOsnDFRQdDW(_mRJ<+pJGv=gv{Hwf<}w#E+GPNlB@*we5W z61n9Vyn#B%)j)g7m>6S)+?%k5OwTQ=rmHtT#4f)&Q&Ugt6BOrArNGW6jY^!J$s}IMZigg%zJ%^44s!)`6YIOJ z(ZM+Du?A;+jh~c>uebV6lq2SVl+m332@$^+h^Ip>^ZP~{*Yc#lfuKHv2)ds7)Zd6Q4Wc$|j24kXj0b0bAqQ3`WUuy|aa-MX$YcgrXDxxi_6!{IduSVu z_jG14g8rY@dk-)KFgOwxy6krx2@D*E;ahs6}HJPZfDL^RTV!mhnOCbJ0jb+ z=WmPTRKJbDy_M*btOQLY-J|iJCg0as3H*8;GW&cAemq1Of&Fliy_oyqLTG&EaT7j~jL2ee#ed@oS|DH0d{s$~;V&LcYrlLX<#`h}); zzaAd^LZwRgZrcpN(fT*lLA3igdk?(U#kmEx#mW~XUTDog8>9{vxD3eWRVZS&b5+a5 zK9!tzYuh#0qY`S!?WkW(%Onh(e88RgLXnOPd=n#HQN!>t5Jq|zbb{J~ku09}Gz*b)2|Z(<9wrCEOZ97%>s{DS z|1>tR1|Q7AMPj}2D91;6utz@`9w=!}=0@kT_)}`Q=2{*2 zPnCqTALVa%9*2BTZ)5YNq*x53qvRN%s2$miJy6PJ9(N@vc0$_m8LXii2&Sbxc~2qg z4^(wnv~61{`>L#z&!wB*HhrSe17O6T*GromG!@TMv+Nys8R|d&mZ9bF~ zi-6FV=1{pIm~KV%eV|AGdBSkV&kv!ke3gJq-eMICr>aZ}7X4 z#q`0b4UlYBBdOM&5>2{yfWsD@JQydp0=lC3V4bR@)_c>Rn{Au2~OS(14C<7@&NkjBT8 zTydy+CCommNiSPHeQw@w4vlbR7R{bc(F;*Em5uS2)2cT{GY~v*cz`UP7!T8HD zuE{-`ejHoASQ4yKVvVZb0U`JMs<^pHc=;3gC-@-zrS#56ok;XZv#)AE8vdbhb?eUb>$W0@~#N=;2rG36WkI`);V9TsktPi$DG$5US#e zQuV7W=oX%j#c<5;j;`QZ?7~=~R3_gC?vcRE@+Mg1jA3*USzwy{>sG%ZK57L+KZ7_E zg}%$mc!N&6X>}ZmcQA7-lJ67_pgSSYP5|xv{gU)rl5N32GM)GN)aBg4%i~|dX9?E{ zDbFX~w_K`KRO+DBa>%slaenW{HMVLp5VSB4@Wy=pnN77GU(Ti3sCC%eN@9b7OM}kY z#m$&+TAO3?J_=AjsBuTTjnrwz1(3394NI!7Euvx20!+X;{a;T8zg8#`m0RzZsMewC z*Fu8Mx+tjq|9&+|Q>R(egja=E=lDlyaZ3GHS#}dwnokU{bcC0-GDGs%jz9$Z;@NqF zHK#v>gg6K?VV~pX;#Ifl-t9rWPtxQ0ME;LN8uZ2h6(uRL%6C(hjoFgF8XN#31_i=J z6!25ly|;az2h~H6uQ;m5is=KBEJ?ei!4Q2RA~VcwIv)iXS$`y3(_eb!|I{gx&r6$@ z465;-q#9bsy1vUcjUndNo}br zwxrRyaAvju4|wv4>3ypgaj5okYKtw+Q3XR;1{ZYbDa6=W{v$$(hdUWL&6^XJLJ~6zvZFe*eg%t27 z$4c9bDXa%`jdw|^Jx^U;&-7k6L`^Y2*N9$}!Y9}3k2!0XfJ9^qA|^OvsMF?YPD_3% z>w<6V`|0)OCSNd5Z`)g{MIACp{o_@k>(s(uB-OlhNneIkBKVs4gfpz+7i$ooMg-Ur z2OMkO3WUd$YXmQ@C4ACN_o1z7|2kfG?QNc#tv}E|ttDR=SN0!sPnI_uZ`i0Q`R@M*vasCKDU?hBawwLb*9Ln2=kK6i3{DZ*NKOU_L8Q( zs-rH7_4?gQ3VwDG<0sf(-Bvv0+`;4gc1!B{lG}}!;zV>?5HtW#=Kc07>QG!Dikh?4 z-28Q>xmLc|J3#7!rh(%brL;A>+}CZAw~kZftw47?MH1Rl=~t0*x2gy%h)3i;*;Z2X zL0vf1l-Jjdo^C+u0$=dm8}*VM+C2?Xai5yxNCt%{g08;Eyix#RL1Dpy&h%v)$9-0` z7Y3>RBA@|3<+glcmD+>bqT3cFJBSoFd7L5thii~PJAt@^YSW6fl#8s%{>v5Vgb34C z37(tg9oHy+auL>)V^&tW^h3dKs?BJKQnu}fsmm{!ChWF9J!?@J!EyG{kQ(C=o-c+d z`CNwFgFp=@H{CeRq|udlcFk+vSr1G;lk8wNsk z4JVa*)Igk&K7kk9ahIek1p3=o^IqrB zGuZO`#-LFpuM>Ett0~}~r{-SNcV?55`;WdY+tO}(xoPFD={O4UfpPD9gSd)ZaU7ST z%|wlR>^OSZ!Ij<*&7IsaI^%Sjk7LU^A5e?iEL|eJn$Ns%zK=&dWaPP40_7#Jg=kh# z)EpqkfM)pZ?B!mgac>{QryF%9bNnC()W6hEgJ#bKMQu`#KV4(z<<@4kRnKQYwR54p zPz-iU*p0=&uD$-vmgGl9P2ko9j9p4&(VXOvPG#AUT-CK$C5 zWl|15s`_Dlz;~ne@T~K;#qFPQi*dx`@ zAq+{xVYr~w5*X$TE;H2KXQie&-9{~r|`O`UEZlZ3R>_)$N;tDTO5z&yLI>lb2( zz|WRuQ_O^6T(-huzF$T|c7-aCk!fu|{Vx@U1f43e{P|JeW4UxWdb%*PrT_g==4S!p z=)s2nIWK_w9}@Dv@qWJ`bN!2y%&h#C9r^43K`Z`uWaEEFVE(`19WyI)vmkT-!&&}^ zMEn(*>+3(4|AR!#{eMYzW@Y*JY-esRWbXgOLH<|y|3x|j$2&3l|KuREz03VCJAD!eyuHh$pC%+w#|Bwa{`b zS>x(VT(n#?dhxTs)odU0ig#TR8G${Yc7CS44W8BW75BG%THI8x%0)J|sRj>P$nCmF zhVMtO5U8N(l#{TGLUY&<{;&)Lo&NoMQjKfxq+gBU=PTjr>rad8`V?!4EZ7B|1d!#B zRr;$BkA+$Xn0)i`AO(2H5r$^K!Si{nr+!~sbB=5*cDL_dtUFfLTAnttQR0wAxq&Uz zGRQ;Nx3IV=!|l?}E)^Ttd%j}@7qnVGI=%+~=-6i}4YtV1?D~S@*F{_fm|XsfV&z}X z)LVJE-j8D=k8((%2`YuMuF>n_LIFhkY_5P0+2<`*D<-P-zZ2TxeV@(MKz@^xoua*8 zq0y6)QBg(vjduivTGzE#SHZ2|srSZp=DT3n2Xtj!9AYAP){GrFK*CSLT~|}(Z67w~ zD;kF)UN-utr^8PKiiXK>j!Q=!rUJW9DpcbU>WVywMyB_z`M`q3acC9XIVV>p(`&#fENi^ygGaBA$Q_&+RXP1?o0fz%0X&?6Q%h6$E8&$$#yK2gYi`_K2y!Y zkk!(!mSf6q3EFG=cHrwLPIq&wsl>J;w=L;oUD^1e&`-0t8<$lRc|nbQluZI*e;3Sd z5Fc+QLzkefW52JLr{zby>3RIpC>rxVm=j^PMDfFls=gUV%kR_&?sGedU>}?x+!Eaqh08Gcksf(@=I&D}Ax3c&)rK9xY{c6?>itN4qQBM$2g)!UbGiHw}O7Roi zuXh=90&R1Yb-r6Fd4GK8+5>M8VvS)5B7~_OUP}iM4>2etkU0d6v&01Xlr^(Rx%CBM z{HW-8XRqK6f!n5N4!g-5DVrqanH;K7q?~Tityb7&^~8sN0&ftN*?)W3S}b0}40-Ii z0KVYTj6NnO>1(6c6E;~^*yZPvadA1o&T-pyYy%S#tT-*#TI3`|Mz=`be&yJ>Cd}4R zIOfw+p*o|q{YkjL|2T3!P}qW2FZe@E$l=tJxNa>l*g4>t8xu2(s#LNg}qi=!}KHx3uO zjeM#+pfCtY;IgMy&~P%7N?qi~#Ne|lUyeyl9Np?iQJ%KhMclv3j(($*dvtN*0!&?P zwzoZ)HB2ccm@3EBAcI3#F5JO&0u$Tygs#W~rMvWn`hbfV`^8pivo|AWME7Ndk3FZF_Y6+r@LL)XZZ(}5|xuqpA}WCsD}cHiJwf0 zhb&|S;CRM!hu2=QK*@Qjm1Vci>DHw8MTlx816L54iRHJJw{Nj*@y7gi%#NC0g0mFEK6x^s4M&t0gK*SM2SvaeI~GFzSUd zuKI@O)r~-TR!WrZ$T_V%b6<;Y^?B}sn>s#X_Q4brl2kuXSKqy!{TwD#ju9R1AU?Ng zETln5^cmPA^|s+SWBT_^srbYVBy0mGfSqH6jO%W|;aT33z@3iLKAWZtgY5WoTp-@| zFqShYJft89UlK@f>mS}xsXAi^w(%|b#UW7n{3iiY#INn@K|#dWCs?Lwh(eKKNA|=( zGt^$OXQBVHS1*US16Nd+NRoTO>-WAHDXwIleehJf)56`?u|0nsU+aC5_Jl7QkEaNV z^y-t)X9(j&azatR!*cE{h@CvXg)gb830@Xjec{6+)hJJflSYV47LOCBrlyf!AYc$sCrLjdcwI)(UP93)0R2 zak3ZxCUp(7yq_jqEz|u9l%jie%+0Avh6jT*NsXfw@P>binpDc?mxR$g+<6OhTQR!5 zQf?cIJJYE5LHBz0d@rRveCSkMjuUqwu_{&qBtbrrec~w;tAWP-y;!Z^U+RObxC0R? z$V*}I6mjdav41!gvnMP^V+0N9WLF=Fv(q?=@;WKtr70z^S97n~!l9)};+9tL3SW2DZWB?lJh2BlI!_w)Z$TJiSh2x3_DMM{`?WL)`|~ zD;YyW(Jb537W7+V7lomy$Z99*mU50)Q8p4Z{{HcP)W>2A#_X>=)d$_L?N^B*GgqK9O|}jW((IZwOFQ6Ayjpq7`F}KOSU~l zxrI7E8$4xZ0r%MIE6YJ4YHncpl?2lo3G|#6g`T@)4MvC;5tJBxFky@~{@M2N3-{*^ z1rMry>iK_zOD~=T*V}wWR#u)f+)KHTZaCwKTA3dE@YpS2V^oK&nkY70 zsYJY76HyDL+`SW!Nrd_uy!=oQ@hQ8gV6I9V;K@>^?d&z~OQNFNG7|ihPMG+R+geOe z2#3l3dXFzUg3{Wt?5y|L|&srrQ z|2a1+kBqK^W6oo^BP=|X>vHJX^IN~?oRm}vz;R35# zyttO1+|%5?2e=k~(3!Owt-O-!Zn|PWEQ8v%VZ}lrV=QSXfdkyY>gH zEhiTah{}6Q05hST@#~HNaZ=kMU3yB_f5LxaOhAEjKhEwPTrl>V6{0=|G3X(>wkwdf zyL!jKo_C%^Z6>tt!?>&?Iw4}G5&*A^uybPRayZ_Sf5X zGnN1`Iun}0$YvvD++<4{YP`;~)mN;$Ft^4drx2)_?J?XaU$^jIxXN7kn**$GZWldA z1e4Xq3m$U@uW-}UWfA>GzPPX!G{DbjqG5RjBs zmvv}*mc!P~n@wf=NvUUR-f>Z(P3onoK-;A!lNmbQ;)!Xojc5g%Aya0rD^HCBje77?B)m8b^fLfslM=<-13$#+_=R=I?&#)$-j*L z;37VL>$sKuR3f3LTayge5rzRh{}XBLE+RIMXabrSQ4_F8-5X9P#fmlTyFhZLn!(eW ze+I7?Sq~a}YvlQS;}&lW#lkA3UC8G+sLZect=!FXX#@f@YZZXMDx2_biic}WW7_8eb|kp0wEsLdT2H%=a~zU+6DV!u)|HiB2t zRci9#`l8s9?_9?udnEK^Ywp_x!6klW2E}2FZ?RcG{L6+L1~Vby?u}-kV+ZU6bQ0&y z%VmyE-K=u;WTu;n^5G+8QHldOcV75%1@TV30z7A={*&zv>hLCV=OMc5i?UUk$Z53B zu@0+mHHT1Ll+aL}fa8PwFv#Eykc{yj*Hf7< zuJFDH3JD6RYoHe7-i9U&@iItct;*3?xTT$YF|AY4PG1&pANvk9aunQc*tRUK+46(7 zzYcIqgTf$q{I0s+<16u+g{=RrMLmGOM}8Fxc`r0Um97*cIe<0oHjaS7e))rHy(RWcAfDgOzjP< zy+*2a++VI#hW?5vcdMY8YBvm`%`|5G3&*L}wVhWBY;cX=s?jmOmXlyJ*)nv6QL~15 z)_sk8uiLqc3|;@fsR?m)#BT4Z6C8W+Mw;8Dhn>+7fJg8#XZ6nD53LhC!XGayjoC23 zE69T5lI{6}2}@!#)GGBDV(foNkO}t+S*KPjXdm)|^Rh*`p$PoIF=vQG!x8SsJ{8qDCg5$Y$GHFrzq z-g9+ahPRBQAFAW$EzH4sHdS!47s`ur-avxRdM8w@Q)tx6J5cg$v~fWquUzMMO&w4x z`Szsk%Yff~R^)x^+gu!XrE7RiIOPK+#t3NF_Zuso>y$dc1C+%s5#a>0fpiRRkCcwM z5H`D|G3R4!pvE}?>B}KV?tv+oPjLD4dKZ&DVfwn6D|S2_D3WJ*_HOL<&Nx9E=H}W= z)jiH>SSQ4N*jVj&cWiX<+iOB@lU+U>oJ!ao=L|`gK7zD= z8pFB^k3Tl@(^cscp5ps2H*$|WJYEbSc3B8yo2`!2J1F(PBs-q_X6Dv)-3N59`H>U& z0aPO4P+gDwvF<$io-dYC?z8!Rg5lVa>+x77{Z`K(obYIeF3eLn`hsp~N%k8kiHFD>wrNKRN~4?*N_va`1Rj3ub7!%HXO(k+ zJ^e2^;`vE|aOTSSaKl5B*B z>p_g?!BfeCeAP%3_NbsIaQ&(Erh=)fs7eR5cX6chgM8!0i5J<<2 zD8o08TRWO|e&qietq^Dwyzi69EHZ%a9LinU?2*q00UH34wYnnS5NpU1xuhA=hQrT! zbn*w!Au6l!k_(o4%#Dig2u~01-k&v8^t|^2321)D$un%PFrf@nKu5;@N4!3XC1ZX? z=qDtJFkPlm%{rnQBQPW2(;L6lzr0Bvob|WW>r{I#p_D#uK2N@aGOJoM8o50`%czY( zGC<9{=Lz^oKA?E881cK)X!JF)gWr=%#a!%zZG^t~rnJw@*)^uSwn+?U5O63hKS-Gs zh~l@x8Zl4v%~7|yfg$tm=99wV9)|C;7L~%l^Mq9QrzB8z>%|v76pFuc7g*u_q^hz* z(0&a}UaJ$xbFvqyyOhb;DvfNXh^3)J%7bYM4MI7Y3ksjaL(C5_0Hg-JLZf52-@vmB zfUXCNujr1k=o^ZkJm`oBxzkw85)pE>uBOkIzv%maNS1k8U<|B+i^AHA*Sv_qfA`n5 z0bc2E_EV&>E?9TBD46;%kfZdw0gF>o$;^s|U)$zhx0S<++vFm=dUE)fimeMcF-F6< zfDOpAYuMl@!^CPDHt8RLX!KFxLwrGW?vn3Ia|y+_BALjH8(qN}Z0qnV+;k)na~zRs z0L}XD(~)!Tl!1Qaie?SL*>nv5!+>JGlRd>l+xto3?g4eqT1DjLu9Nvyj&jxvJ`wC072W zqu@8v6S;fPrY69zCz~&#BDf*`&qR|IQbAaT$tYGE-<%~vL~pPzTa(yz<1zD<#Y_g-s^+qciChai1WSz6_1FQ)mTJypVm6wzQ{CX z*j^Q;qS2Rzg&{j4hyP5`xz20ogbcx2>F1Il%CI`4*wYR_Mkfu>RZUG<6qp%^G6^U} zR83UUUb=}0yNstXyDn=n5NGUGEIV6DJRQ(DCkPDTvqeJMK1+k9H2nw^sBVz5*~}Fm znuqb1DYXkr(CA8?5evVnt$m=?@jA*+U&*9V6hrZ=RV(Vbxa7kocNJ$n@1{6>n6&K! zvd~^C*%{3xxQgm6yYT#G7)eG|orVVJCiC^GbcfmRV1Vm9BfbJ{ipg=gc+6gm9z4ke z-(Q^_34p6IZTF6#&r^6sV+d1dP}E?Z1e0?eA@YHySj&pxRN$L zeR^n%&{YJ5`+*mQf!8S$8|Q?`_b-L#U@k#Zp_O`I{*R%8pIgtOd>@CoKD)i8Z^`@G zA(8+a0maT3-wfm$r^g2jspg4sC(u|43zDKWU(W1D+W~K?=Vr2{TIxyucguTEV`1s@ zCVC-#ztM+!BoHZyV!rDcs@MA#W2!X*0B(hmYeJ1yiJoNc#^qW4mG@B#Z3Y&&fVE17 zh}!oRiN9`ip5XQK4=btfRB%m!Bv}P~osUMk z>0eN;r48|tPHQ*iOOZyr$lPDEAAS?PSv{d@3n)S-Gyw)v^nBt+v!N!S@fLXDv*kLk zrWp-Vx|o*IaaCn7M}Oqs{8nX9_^oFB%E+s_4xMc}u$w{AGv18b%!$MB*ig0k;(vVA zHV7R@{>kxm45Rh6-b_7-b#GCuXu~PbeXbt1h~Qh)peN5u?-vuTSUKWq0Dv~m^CXFn z5Dw-YIK13Bd;|8F*1T1OF|crM!&8&yts>;Wd1-i*@2P&vHm2WCE4cWro7sY;)$akB zMS7ox95oWbA6AmA{6m#I@u1JwtK(ymSaI(MtcK(PJw-4%aJ6zSnFP?791i!uZW=5b ziG0&IUy89!?B-cCl32QFEwj zaKjjAd?8XjA903w%0=|D2sg_wSwhm`5CkW7Dpk8TJsuq@o9*%~4o zrpY@hV+U<-ZyNleOqrngBq+?kV~%pPlqiNU0NALT_;Y=lm6Cvb$Jj`l)NAUPo43V zo7^g$*JTtsd%r5}LoqJL%i2y|^$G>y+_`swl`85<4OVTj)%!DN`Wo9{KVyLMmwI@r z%^V{&3Xnzhl@DYxMix}!i3{Ln*WApAuGck89b)E?JPY5(?m`QJd&5j0mc?_KgwF1_ zyNW!J)Q-e7;Y)QUl6vZLTb@!f*H%w&F^9U1SjMS)Q8u=tRh$t>(U25(WY^@n5<#u_ zqmGngjY5NetJL^)mj(1AgZWDN&$H_Xp=DC=ydy$WT$*+{igmm-6u6h4X)F~Y#y=FJ z>(kk1Lj?Z&cn(@^J3<9(;w{oFK&$rfUlOrL^(s6@uVi@(K2nI-;Z?u3xW-Z^S^gu! z3d+)ugshCSC#o}r2&&8BUWW3=vMbVN)rAztJlxme1^~D^YLu3-*C49NG*#VMK4k4I znq`Y*bJ|DM_`5-#DvBcdQ}HD#Vn7OdGu7TrQoF{$&5Z4=u0oX)kLI1(oGn6LP{|Xm zuf-zG9CUmyKR_~_&5=6Zer0%|>5Om4+OW9n-R$KJmqL1a?t;YI5wx!h`HSCN9M$so z*I9otqu~LYF%=P?46a_P2nR+>4(}b=PE&oDx0uA!&3B^$7#M+7>};7n__lohOCDTP zJ}uO@!_b>DB4Th1f@H^mGRM#0N>!$J&nXat;SnP?7NvmZqWk34=>&*zyLj}0P2L(N zo*C@}uo|GqdmK0r^08nO+3jHOn9Ib7LvfdRv?VF}t5u58>QC^MUjO_w{GLp&2#_J$ zeGwrmHA8RNjE;iTvsa3q2bw*`(Rh5>ohBOYXa_c|J;Kr^@VX!;2O2jU^Onrg-0_a| zG7vtfa?^L|D|zGD-Qxbinn^FeJi~PgW6g)9q~Kr3ntsBIA&7}bp}pjiK0o`g!n7!+ zwShz}?P01}O5jrV8m?8o^Nue>s$I}HJ^a@}t0rT6#dFR2K*vJRy6B!jTN(MkwsobmoSI0YPLjD+Gnu(IZvdj5N z4-=kl365MaqT<9moNK4;bsP2=m#KA3)Wr{h#e>0yA6(h&S`y@;BN1f28He6@inSUr zsVq$Y>J9`0o0xwVjWl!9e|JAK;j|T#L2yCu2%EA7#K(kG`;&|hb= zlma)?=m&>-mi+FlbsrDUsWdl6dgflG;1GD{n8YVm3X{|JXze#ba!P7>_ipqqoH)g5 zPxxCKew}Z7^bEd7?;FYa zI*fEX1Wqd>(aW|s000`M-`w9FWT*{hUHF^la#C}vd^|2C+t5fnZGI*HZ|uEyIGkPgFFqmS2@wfFBuWwy2|@H;Qba@$ zf)NHm5Z&l~h!zA9LG(ltZ5W+VNAD%d=!{;5(S}jS{BC*P=lkS+zwh~euXA0$b6w}0 z>-=@kz30AnS$plZ)?WAe?6oM+M7)C{-_Xk-o0^kav3W-6mfNrB4d~iR65qm6{Dlrr zi*J-7S4574V6wr9QireuQ7Ls5+yiA|X)Qan3RN(EJQe2n@XPU&dB^h(p3D+lrwHY@ zk{1}_jMVdZFWhWhG~P&~IAjuXep|JzZ2XftA_K{F3Y61RYm>}}Eu!cuL*6HnpEbo8`wdVP9uDe#_#jWdff5@2VBOJ|m>Xbmf>5-bZqF9)* z1r!?oTU&TMo+?{{{~5cTTLH_l`Chy=L&|B;WjA>D`wJ$SEsRqyh`gyLf%j3A9Dj5l zN$%p#Pb+;%41pI8F+LACusbDN6L?TuG-1((y$f+)iVm z!K8adLDkU^yt!kw8&He+%AX|Dx#g7+U{$r^piil`)Vmy{s98CPgVmE&?~QkDC%i*6^D?Ecj>4tvafaK*FNZy>lIqMho;<=SwEe zy)E3Dy7OYn)#A+4r*yqF4*L2vUj5+zj|g_oTt^BIA>dt&ijH zfKUA4?qJ}2*xMN~j2$$n#KJavFxvJ`+?0=XrdkV1K3?U#drwBJasBIK{?w~A zCLVUY#5(A?SFDl8=WEr9%1_;33QV*ra@S4v;eH)J;WANomJpNg`*7_7A=jIh6p%}N z(E-{JFqc5}VzW|X&IDChcXQNG@c)_5s4iLG^^s*YG=Ke~%=`S>^kVmqS4S9sGRb!4 zE;SeUvbrW;CD^gHlv7kywM|{#?OLCew+By~DGe|__x`T`hb4yk$h2cWF~5XDjPLeb zz69)}pN*`iS{?8N6B#;q33qM%QEGmPP+8^hVHyJ|BRR4BRhoU#P3+ixG?(vQk-Jx84x9D)ToP=@)9-BY6W z(mPVk$nzOAxre^kn(yn8kL2@}GJS-g0Ik%HXnZl1>{Rt~Ls||4Yv1!B=g%gmrkqcy2p&|N_rL3FtrRNx>uQuBc|Q6s$kRQW!%(fxTJ`0*&>A%-O_M9n)wTedjMSGwTqkM_Avwje8t#Hq@tr%rCsF7=U z7I0wVJwRjBy>tHL`ED)OT{ENMkET~C6!Phtm`k2cYqpgpWQt+jwer-yH+eF8HL-?& zJiQE34x_4lMD1IAkwAYb&sz|S@o+l-DwCr2P{4zS0RqV%-nFW_4iR}86we4cQH`$Z z-;EcV3w*+j;Oczm0Qnt7&87B6zElI36j%05`QpUANixtUMb>A9OLBk6 zH3{E->Sga)3pw<-r=oeqlG^?s29pT~M}c9*k+WHIKW#%U*R?+$YFr26pkD0nY4=6H zXAI)i6-Ha@sOv*?_Gg%;YWDJ!j2Nmx8eEW}} zzkd@Gm_njl;bxZp&jFzV_fAsC{1p-UKNAM}Z*tBE-211bIRBb-M&RB_ROo-**1xM& z;P>dz|CGuGNNo9At>S;jwEh;zDlAGR{3{|A$eQza0-gV8>)(c~3JCnygAw?BF#l~^ z|8=q+0m0uZ`_DrZJjo997vX+u>)!|H{x&WFK_Kyv;6H+V1q20wo0GgiK#;D0;632x zSH$k$VY&iB|Mi%Ke(&ag-wz=nDgmK?gcS=22>>_$ny={JQ(pM@;r?f82%kg;|3wV} zVPH_ge+^0)Xhirw8UaQq{I4VY_2@rd{_oNmX(&GUE1Qvs7;qTcKe8E#+ykPD|NqQp z^sDk;$&?(g0f(afmDfl>P(d_p6lg_ zKLQ3vk%dL=XR~+XcyDJ5fRc)M zd&OZ_7L(jYC0vY4n$d*{j>$u!lh(=&5|XieUQ&a5Am6lc*=aGxrRgQ(0Mnw0E_mW3~7(gH@r$rT1k;&9V zQ~FS!cAmlfGh_2d>ixQ1;c1Vh3I?0eGy6glo1(aKo8i0X_X)0C69;*oHRUr)OpBFj ze3nT@I;TKi-m7`&JO%q}^C4gUCs5 z@(j#&6;BNe|E?f!_p`fOLquecL#pAuU6lr^4_xL_+SV(dtFoTfK(8@G+g2mW+qSw{ z8a9D!^cHFk%@p8Km4vkP5=x9-MWzUXv5FWZHMyW?v!041)nJA*F<@Glbv-k!?e^NR zOR(y(Tl;EYxAJj6U7}yIhEsRm_;qy2h3&lYP=d~P)PSkHW;zPzgzj1UHegZaQLz`s#|hJT5hMH zOLT0&-J$MnU?tAGwmpVtLP^;9On3g*uU~pD8duyL zQ!!-QYfkArB2$X1oO+M(CWeG09`C?tS1|Lz4Wc>%xyz}MB=g;jMRAVKRAR!klp;1M zoYS7(3y-3eTK(xyNi$yLnwO#+SM51(mlyA}PA+$l+Ti0nq7c=8JZH`&d))X*?-oSL zZM`}jML0kYg`+ISMHa$D4Y`a=Bzs(!eoim3lQ!z3n8el2vpa9vxT@-wSjI?&xF@f@ zT`f)&ImAh=RV>DitrcffYzDz4ow1(=$2R*lZ@cu|PhYDxNn*W9y%;}P_p-<%My74~ zp-;)1$#Xr$G9GqJ;%#rs?c&u|-mfxmKeM9s*_hN2LFn#|@*Zr1<7D1M%8bFb3wGx9 zT@xiO)_wGMC5(yabzRcI>{gy!b!l+Z(MUfHMnYrJI;U1;%6&OK#PvN2I#aI@R<>3& zpT)(xi!TaB=6N)0QYN>UJf^K)3rb|Y!cg5 zG@`?`cq6C93*v?Q3Fne*#%)-&{e@C__*lKWoaq_wLW;Wvy?xx*dJNq*=MUMBW-HgL zF?s8yaR$Q1amlWIc>=HJCZ(Fk3XFWRsw}!JJwNut+yf`tH=kAR#}X&i`8xJf2cE6G zUyj#KPL#|=vw%BvXP?TnVauKIlY=mfo!9244$-4Gy%l+KsG}ersa)Oip#@e-0_M%4 zzob~Mj?ju4&tqPQGiH0?&@8;@9lT!rDvv#VCjZFdmdota7ji=NOdmC_&as>QcnOnY zZ&=b&9C;sac04Bc6~7l841*24yS|cFmO|V+*c3DL8p*?%^RY;512^HsiIN6>@!iH* zpX@w*+Z{Dl_s+9=yCatE7`DDRo5N8UuKIObpRIl+TRvtg8AU*QQ?BC-qO9=gw$+Y% zOJTbh*Zc`%AQhz1s$E|7Ui~yyoc8Eg%{*Dmsk%Ga4r#XfrFvJ;5ST4BnazzaM3nao zv;|^+JVMYb#UC%XMXpw~$gbT?kmO(*5GN&1oLR#-hIOST9(=}kY7IpkHv1jgj8qP- zleXi4;hB}Gzz$cG8$!=rl^99TOclTk9=wGeeQO9dw4cQDKa;|mbB*{b9&c=1eAwf; zw$BtPOPG_@vys@@BvC`uTSvWJMO&J^@L{zoDukOE$*}#j=J*r~Pr}I8-XTdl{Oi5q zwbnJ0^_))@xUaMrJ9==gC+@4cA+k5~ zs&}b$F20fwD^qSfSCscn8q67^nuqSuq_x-GYCeQ}X6g4%U zVOisYp*Bt?8g@zJXL$yC&ywu*F}SzXk|uj6f@9zYgwu^r=yl-`Gj!K5iqrtm8H ze=iX}P>Xv9>@5 z`|?UhzC1*+t-x%8yC=#FTXctXH}hibj!a@4Wj@H{$#*wXji1IUdms2Xqp@hm$s@%> z0&eyGAv87C{~bPCCY@MC%!WN69VNfaqP84DBwuy*iC*)z-~QYor*}NU5cgj8D1SX3 zRpO3cP)pewU@*z^AQ5Rr*9OtDlgpS-i{W`?28(KP#MJ|M-cfhic`Cg}!=sL=sRAa0 zJ{alOMJko3!%0syxy^iUmR&VE9e|Wqt}d?2E?uj1-dX*G8ufSKnF}odtHE&LYO?#^ zv$EPOm*WHg`AMFEexGEm62y=-GPppoLK#(bxL(m4L4)71v(xtc_@bwBAcCf+m=GTf z%X{&=SdrQ5rCeX0X)ndZlyxT_E!OeNR-q4YWlI&u=c|V%N_!-e%a-!TXxNX5;mrk= zgyrF{6IngouX}ht7(s9)Jz_XUbdj2DU(q6?w(?55PqSsB62Yid_A)P|*lkFLP*OkJ zZkst0i~^^?9A?8Sm#y@w+}g??K9-erZ;wL_kV2IeVOgZ}2b<(wpCvp~$x&kkCN0eU zhFb$BVi$0O=oe~7sTt1m?;U%R#n>Ik@4&%%|1I76boK8 zh{XfDb=kz^qIpST=_<1A7EaQ3`0L_)5$14DXz_>L4sQQvVt7KomJ_l2twVNA4SDQJzB}r@tq_OtUMF8uKHkSjZ$_w_ z@W}y2gCdO-$~&0AUwwoP7sL3Bbq#sO9;0CHZcD8KJm4H@K;=b9V4tXwKY3A#+h8Yd zXR@;wj15s*Bd3|ziDPros!~=YZ%T~xF}7B$1XJVh!2`?dAgMkSn*!h9;dlaBCU|>&1sH>@e#Lhjjy)*8!~8i!g6w#4uGY%Na?pP_F}9VsHqhU9~DABED#0I0IX`R@h%4M-1_vqk&YUnw9cN znM`_FHGkynSoQaew#WyHy(lL>Ak_UrO>Vb{ zUQMs&NRBB9HmKC%dFX$d(L(JFQd`9Nj4Jx)&-}HD6_=4W4Y<;=g`fVYZ$9ho2*<|2 zxY5K{{VJ8I4l@NVeU-}0uCtBsysMCKZtK^0k>ymI9Gl!MKjg>GknoW_l(o1| zu=8LEm&AUOK-gjrpQUaGJ=hL~9!($1&MS*tR*XK(!x-&I47ptKEGt_!7ZJl4h~$7C zbf(}5vXpF9&Z)UmjNUqG@atnJ& zbIj=NF^|J!n#HBhrYxUt|ICt;TOWvyz*SC&QZw>hk;Q(zqb75>(!nRa{bBu*K9ld! z(Pquq>hR~yb*6JIb{Hd8&yUgF74~&i%nB-2w0xxP=s{${j_wL^+U9`vUeY&{1*iVn zM}Eg!8{dW^E9Z0LivV*KX+pxmTm~Wu7}w{$3a47fQrVCuspK^_;#>5Q$MfHd9;5IC zy(ZPe)cI7PkM2vSK<#kzRGi&qsXqJHQbJeE%Lw4xmZLE|+QrT2M3PsxJs-$dW2IV! zv=pV=nY>JV0KMLiFeu3uK^S;)PVsDlKu_{T5k3yXrxd_sAow<1Lg>=pVw1U?|iK<^$vPJy2K0>3_ipcJ6nr)H=?&&e7YKwnOOY(Y0C z+OEqQR4h3!GWYmvW>RY~Ei!X8DIA)A?9~g?dRTCzS4TB^AxcPTMa3PfbZ@MFC|}o? z1kKsn^5RcW3!dJS7ZhpI8aDXs0a57YT~oZ>Q~pEC|ATvarExzuM_m#**Bva9ogiM9 zQ}`J2^|nQ`)+_o(8ERGH<&5r;q9rG$Z1)^K&ZcjX^Lp{!h0>I7oR^JyGOZf$mV!o# z?xfBJZ0|D-W#%ZM$Z>$H!;hq*js$o8e#>C_^U z%AlJn)Bg1#!)hfl#Is3#oha=mx;M>g-gHHmfQ@}hFO@f+Q&TC_`4I#)wQ%*Vy(ld- zgsMC(LMcmM-kV#z`&iSTqobYKtmj_o^e%k=kC1P;%B7e&1#$LzMPRO&>0OV%>< z{xM{~Whf_&MLWv~5+4_}V{5T58yRu>YBKU|s+_iFd>LZkVxMFpUhd@+NEXK;3)uEl zN?onT5k5zO8#<;x`h-wBEtPg^;ccrAw{*EB%~xX(2q(f}P+> z_dp{KovcaU5QYy%YPwKK?eBC2em#$xW16aY2Ckt}{IqG9$YpvmJy8q;Licj&PlpY% zC&+OA(2<|(Z7&+H_0V`vNo3jHxje{TcFy@HNmPd4B6M?T0n?b0WtoRTjpw%{TpYi$ zEn;P+VN#cno%2Dc^%9sBOM|jJ)hM5MO+cH~^3y#;y{>c?p8s~G=`vG7g9DMGb>EGt zMpe_ONvC}EYS!Hcc*eU*V-w$EMbsc)9~UD)AWr#z$Ep{hJ6MztoXyEr*%H>6L% z!}HZ*BS%(8B4hqF&fk4bqd90NnD?ZifmA?+Mn2+C2$cg-c-M%K{&bbG>>;KB^BF## z-2F`YQQCxrgw+-r8k%n9v)LLX&5!%fjGNE}T*On9q2wp|DuhA;q6#phh z3iuosx2krtF%+(|^SRTI-mjofAa`GU7JhMF)`k7%@C`qhzq(v15?Zo?SUfcJ*lg;s z3Wp!YQPemc8BIK!X}1+pFpD9gWXuYnG3_a50+i^$-4`>uAiC$3?i`0`>{{!}sd)wz zbr&{A(C8OWdkt(7*So*U)i;OocwQ`s7>dHv9==$LT}2AUo6n^l_w_s~nmj{T5!(qL zTr9HDS2-U7uX_wNEklU1!1Nw=SXvtd$L`dfRs1noQP|R3@iYxbC`Jx>p2E6YC4x;5A%wT!abKyOY4NWCdr99ChBF=0( zj#8;E>~6k?y@@-6)FP#bRcO7S68>Yy#5j|o*XGZ!56N4ghEI2O{3N5yR@#l+UJpcC zUlzIr{lQ)**O_gTG%E5=sS?e*QCsJWG4 zeho@7O=YXUPb#B@?zd>oiJ1&U3}m&$XyKb4tLyVhgQcv-^#(>pTZ|9=l68&;4QBfP z;3_DLfHTF(Fz)psCJ1r;LLZQC?VHLFWO*iopSPOf)C&I{GgYAaMb>3g0) zHiFZF77P}*#F8RwEav+#D5XK6pH)&nriTKEU1heXX~zL$nUPEHPR+;#~B8{LBb3uCmS-+=EAnvzC@m zAT+`@`ZVk%HT?(&@m%=8y1s>hNC;e$Pm0_qG=!()>2-L{_DuWhmv>4L1Iju@f~5K%bl|m|fjZ5K%q4||*y$toy@u!n@D7wg zqP%Uqy^;h%^tHrXcyK()AU(_%Q8;k+%?0rCRQ_%Hu_pCc$x}2l+^j5&rpA@x?HXKP z?n8d~H>5qYW>S2KJuUnW?qsj?DFiojTRGYH%-;skf2UR6&RPE%j8|oSQiV z`B1W!NEV?S?grOvcADF#p@B~~SCpaUpE+KeOxvC?V>iwiw;c$Y+_ zsD*E6!CW8VFBcjavfJnxqHtV1(qKAZ`F1v}>Hh%aOPM_6Yt=g*&G_Rzc!U{eC{IV6 z#@U27ev#;2;g@O5Dk!$2m|)(w-AotWA|L#CWMBa7v@8~w#TQ#Cny{8pUji?|NAq26 z#IHR6o&SH>|tzL$A?811(2?;An~N_Tqzi>|t7`-LYbbGmpF>>IN$69Kv(z zfsm+`mh3|<&9a-McS`y#S}&s8T0|c_eE5(XuSC6rq#mqp=kCj6SN_Ru95<+3z~-sl zsMTJ7Ec;fOw8$_X_YThTTr+TD8;L3G`hS^rehOkL?9vxWXOUjeJr)g}}R6`FT zrtgqj-`Hdqlj~>r*wfH40=w}sC7#i7R0q`7qCJ~D@S`-m5WqMbKN~B*m}($ zebstn2MN@iPKt&uK%1Ise{1lobBrK@?0L!^NZjIz#{l^0}*iJpWj6=?*Bg6vkEIzAkDv<2DI* z*-WmF#UC>j^XhjlfFJZ${8Q7wT>tj&|LgYu5^BfDN?9aPViQDQecmC!)H6Y21f|Tz z8L+aVFpXqdfD8C$xE}(n^F0vR{#576JPVkiW<7!GHxAOeCA}Ga7a@(;6e~BUef8n~ z8RneHFT`QXFyzyhuL$-67eJQxSGY}&rwRZD$Ycgu0H(H39`d8pu}6vKW{;4OS_OYE z`Ud3yy^^ldz&G%;2f(Lq^#2_{{(~u;N?Iv*9(~lN+gZ{=vH^Um`)~R2AH1y3yLDeC z>U+#184m_TFu>!3e=dc8=EuKy864*I`$`T-bN+KF{4+oP<6WTJ?Ee>cJ9|<@SZ5XF z`xYP?u(&ViMkZ^WKUH#8U%~i!B%3}jpfKVRwPN2P$pWsO@FzCm`yj)$(|^m4|8?^v zXcQb?p^Lk}qqWPq>rN5{bTc5ve%!t1C%rrm>ysnc8~o{|+vcbTLClIvS|_sa#&D zI?b0B{<$;+km0#3+RXnl>d+|^+h;YQus>HItCUcvuGF9JCMT_f-5FH?Efn^*7W$XB z|M#I;rtWO^*Se3z9c1$1fUvR*<&lE3++_642A087Hn6Ss%SHxYEO7Ie^!QVeGCcoC z=!O?-0g}k6^bY>Lv08o8^Wu!Rnt{@IbvKcC8fZzTs{H0_6RZqs}H#8UN;>-cD zjrRj2XUOOx=!?#YF=E`t>cmbdn*|t)Csb??;PTN34l9D+C&?=8u`v}QJ@l(ABJpk*yc{8Fr9b|=;KtQOkg56kDM z;Gwt3r|f|Gf5MatfA-pWy}ge0E@&qh+5RX9s&JKBUjL*G^e$pgK?Jk|SQ6PPkSs9C zxD>&C#IOr2nD5e0Lmj>KM!D12WPH$RDKnvPSf(h!{_}N2fbLZ=g!r(eAh_Z3FB@Zk z`p@ziG4fL<#z_ox2hHSN*Qt%J&Jz&lk9`s?iBqnYx=u~ z^iWPsM@TvOO~z}%9xQoS^ZwnjLMw(*62MxPOgl^?COCSA<3CRAZ=BY6CDou+9hrD+ z!?-&^KJzp)AeRU8QmuNNQZ@9%@VSHcsK3H!^sS7zayd}h95{gVtz?gQE>DH-fFh)6 zqSpcT$FkX+mmjcn&U&6{U#cblr1RQ%bDH}PU@)vBzeezvd1YAAiXhuDR^8kw z=FDYNHc%QFq(_<9c;}|>Em_`&T)()6yYD~oQ1pZoxV^WN0?t$hyPcR&TDQc#gMb_B zzwN2NY@+WD124wyzQ&jkZzcn_+r?a-FFDA}&osZd={9GD_3NNtOR7D4G#CCL&yfyH zcM&Ylpt(wWa4De?sP8Xzsu7R9Gc%PkeW2u&9F1UXWO(|+IAi#pdRwASF#<5(b+u&v z&|dY{I#fL)JiMI+7=S01_B;Km?9_n1YJP8IyL1y``0ObxIh0e~QCs3hUWirmoo~Qj z(e^QnwSCxAofp6}#bz-v_4o6i?f#HsH^KQs+7TAS*B21+c6oauadu4YOgl@x=(Kjg zIZ=$b_J~=J+cbyy8lv%OuK6|BJI^l>WNy+IE&_|@2R%4R@!RcH&nLIMdH^PRdL8j} z$mWzpYeo}2a=mx>!A+bxFyYzRxo|2BC81MnM6$<)cypAUE_P00ZI3e9z1dKGr;wUc z>%ilUe$084rMmG}H(dfl->5cI_H|2z`zIFgOm@yqL;o%bMVg}ak7a4s=uVWIma(87 zc-et(M!}#RpA(u7f^URAII&vZ@!Y4|y_jjaNT!BGmYaSyO8W#KJ=oqC1!$GM$A00W z7MV% z5KfXlWexSd=}=5*DhI%%z$!`qVf@{xWz$O!TuwFSDBQAHtJLl}K9u306tm)cA!IPd zD;>&7`n&{gPJk;GG1Si}4g@Lhet~r8(KFDdm8yTyfx~gFz~raHQhGUE)&t~?3`a}q zBVE&6L?tLqC1P~yOQQ_Ox4c$jk#yX-gIegd%Jf{Hm9tgn8J*-Uc$HeezU;pLQk9eM z`q-1+(aNVWOOPah+ItAbG(PC3C+Amqn-osFD7mtSab~o>ju{vW<{6QBpbIut*MXE9 zCPN3%!PzbnIb{P(7k7)9M6&0CdDfVk>G=YXbXlK~+zN_!;?2|dS+<2L4sLFwX;(;# zEmCv7g*fSQXf=Y+wD|l&&B|0m8t&LNAY}=YdH*6B3lh<~lRz z*pyE`nCE=6N-*CL%{Lg8V z%A`5IkDzbl=;?oHCA=);-@kQj`rh3BCL2n3O^E4ujoUXSUa}4j(CncflwpI14si>U zcc9md6XNkIi#R~@tHWG0z-m*GyKdi!j%WJT#`LzHQtkQQ(vE7;E?-d$x&&;mx4swv z23)4K9@x*A6-IPL&6w%Tj8Yv*sndev;*_Tn6PKd8k<7M;}yohRK@n54r$A?EJOWrm=5bSuJ~wd9^C&^zo5 zf5k9x^dt$#ji4R*VO;21HPh%k4y&nGN*BQHx9=hPQ0v*toSCxmUr0tcPKsvpVY-GI z$=vvxo_#($4eiEE+2M%Y4;&avXQocx*{zTIKmN#Rsm9v!b%;C$hka~{Vc24T57fBE z2ua{*y9&Or>4Fu4;g?EwVM^8KRK8$)lE$HQlsa!Ml>7Ps$wS8qe(*+8Y_Nwli!RV= z@MaEGH2-R1F@kRV@}S{4HEDLG6VV0#$V5@FzqM>II)@jlLJz^qs@Vsypms zt>;ea2)y)U$r~h78YS>cpuTmG4M|V*O!;Ut9%}RL{jUA5QcEg{kcCbe_L7{%cI$7D zngUf|@fzy$hE}?y_8$nyhMdpM*n%(N0~KmiEGmnO88rk}xV$)j0){~LhxR0WER>8b ztIDpZDkkIIAOlnjTHpPQQ_xVsPtHP@arG>~5NEacp{7u?YzBhKn4if(j8#k_m;8x_ zh?t=Qyz7{RRJGIDz*Z-_rb73UqOA;+Kf-jd;$vm#>o06F6}lI|ndA@_@=Jd!;D6pg z{;Q$(n?vJEPT{^f!!La-f5((Saqid8Q%`r5eKW;g9uqhKDgm~xdb$VI!JvJ-w)(}) z7Q?zxN?y~G;XUYTM{7(|cBt?EnkMU*&E4>J9ia~=8(&~|UaaX$2Tbw}M4^H*MXT=U z&{)Vnxp|^BdKS$CXu1{yPHaw){1iu3b2#EU9EWt zxWZ1{M(w;fJIX(QK8*zCi2}59Vx9c&>N?W8DHWYWd2AyOng87prgd5B!?;$StV`;3 zgoFHV&IN9O;ZObMn#jJ_7<2kJ4*|UXQM1-Xg;TzeMlFHu6JPX2U>o|6kMY?o;8?=1 zub5eGz-Q2GKY+M@eX-}3P}>bBTaTvTOYo594D{Ya3?C*qw0|h_`Hqw8!$PSqXsMll z2MaM;(&ZHt^Dbr2fW3KlgPyMXv6FoVyU3PWAm09wd1-A7F!a2Qq!Km_G zKm+?ufYuEAr+lAK-UgJ@^}x0f*dsItVJ})_hWo5vWms(yuf>Yu)--Zh@JKoC`R8I{ z3mtx+&h4m;63U=A#~d5bU^u<=MCwQhuBgd;{DaBhbFqhXSgbu%V``Jjs!=Q8R6GCl zm6YDs6_sw-O;iHD1k`8iny3&E8zJXVGSW z{&<=6!Q-Y^&2}Jz&IwKCj#BLx@2l_n@iJqmHAJS9JT-U$=!kLGgMFf z+IEFyW_9k%t;|brz)~NxMk611-$3|Y0%m+Tl0#<{(|eXh$oisu31EFwoe1$y&!W_V zc*!zFfw%7ut5Ifg03YaK=NlQOPG0*yRw0;5mC4@7@PTYi|I|wkpsX>J2VR=uXA}m? z4o8ypMXh>*3l`KAT?T|^s9Kf6F@M}bJYRgrb4{*|uESkk`)l|A?AMBa@}{tp3v2#ARb{C=Q30RCV= zSMLJgkGEI8T~hyagYmhSopBxH?jPFEJh#&}MN~{$*gQWVhGQD}uDzpZx-y&SCUQlg zAguRt(}Q4tr>2Nve7D5Ig}doFFNHh_ov;NjIa=DDl#v(5o@Rt2Lc&YW)GJmGt9OZZ z)F9s~758~(=lo{xxzp${epIZp0tmFnl5fbbd^UFnYHA)sugMe3-w8j#f9RFsUWuIG zKXy*=9~sJ4jsX7Sx%ck-nmYUTS=GvGyY5Uw-4eJQYFwk`d-#0VqC`*0SbEqr9cu?; zSGb4_=oYp4}QDe_p}1aom>MF|}DvYS=da+#|L zsE7?x^V-M+!kZvBk&Jk_XzPc!^WH2`3}=_bHk=oV%o@R!zg*i3#LJ52fL=NfOxg$$ zZDHK=)RYC*X(ZwWi8N9eF3CJ8lf!NrFFw4|aod4BccVwTr#gl>vEfbZaC z7kAqWdttEeGT+Wyx_4a4DtSb-i_D@P;BP+)3|3iwk9qSg+#q#pRdmc6_a1_@SI;9q zuV3v^A{Cb2T}v@IFi>ngQs}(G>$+U(NaBFml8Rbx^7TCm)T5inPgT1P7ZkYF1wEF8288M)lP!P z*ROb5VaN%ogt}lcjHuc8l3sQ}MgE=SOZCSQ5`cU6B)qB_Kcpf|m z!%bMVeM=X?nrjOY z`@UbbuZ-?U!Lq&78CP?dtp%U-AqEm~WqtgXeGenUQHM3lLS`j4{Rj2Lc@pQnfj}3AsX_L^$2AgRcGW00b9}{&E`T<^l2!jq>+*S4ZnXCW= zn};GQ2$5yuvV@#|HD_wLUHv+K-0`)J_k{vyMU>y*2!qDwPfVwiEfnN!>a@q+!> za}eusZvd=Olw_561=?X_!o;UrHG5tkIM1uxu4=zWk?pV}BQ?j+;N?5W!2n@L14_OYgQqx1hJ0ks5NZ zoyWf(zgdC)oW{t_VtH#IRhz+ic~!GP+E&`@D4UK+nbPqh%q?g5V3&t6dPBjAEkzrK z$#G$X##}Wwr&uG~xpP=lH6gy_x^#cYz&T#VZJP68%6*@WQH}NhsI3!u8J-Z1ZE#kxUGCp=9k3H(Hk>l-5D!wfwAX1Ef<#B zjIwyxV`O&srtf>x+UK>}Y^1HFh`(-R2xb}Bt$_2}4d$2)q}o=`6kf*)M;`Bo;Q85# zmv1GGLpw5MDOc@kfZ5@fA!(*Q^Z{ayP?g&ssaNBy7l|Fwsgs@<@`;zi&W{n9E_Gbh z9_)S4N*lw(tsJ3+bUj6OpW!-vN!J5BJ*;x$W1Zrz+>F|gA%pho;l{So?~=`4hAY&^ zU3n4A4$Dn>D1jX$J>{@J>Udt@A*KG&=!zX1tZ!MrY+Z1^oJ2GJJhL>IYp|u63_xc% zI}`4j>pOJKjK-(9OSw#x3=TUh=d}Bue(>y~t z1=`+~O+y```(D$bN+txz-lS?Ss;tKrGgb~(hNs)^Q^Obdbypy?ImtUU%RGvsl56>i zu~ow_z&{!K>Qb@GUKz=lvAsdC4c_hYo;viRmw^Hf~qQq~=7 zjqp}X;$a6fVf>z}lW@n3h`g!|r`J&nEp5~<444JBu#p*gsL+Wtg)sQz^CfBtlT7Fg zOx1n~znV|GtjPh`b$En>E0+T-Xc*4|}T@_NRveZSW46jN;Z;UKe*T(re$c(5vzsA`r|i57J3Zt?Kj0CSe^Sr8B)uv z#+qd@%Z8uKofB;<+Qcwko`+pxN2^@K8ODW(6VyeWoUB7)?ilP~#GGG_^vRoTx90?P z5o&40wA!DMI#J=V(}Ws3L0ychi>Vz>eak}~S0E7GmP>I0cFidAMf9^IYvmKv#n3O* zMSngJ<8bKtBO=hh;PP86M8)7v)TKP7r?&)eXk~R{b*FD$T5e1+wU{jF* z>H^L$Jy9_0qWy5Coz2ANvl79gRhF4ox9at}H*MjcsEZ6#nIY_}er0J46SGBg=LjVm z0Uyh&*Zr9gYp(7>-fOF0y?sRT&;@r3)2gzNDx-UJDqSXQ#Po;OfBKs+q(=Zy73$-I zx&DkKr=y?B{C%A>Swap9U;`m6AXs`>?6=tY4yt94=6N;BaeP)w^aU7TDqJUR_<6jT z-rQ0xX;j3_Hd;9X(oj7!6AnL#!&ES4U z2Ctif>w;#`z)Xji2AvUL4Oy zrrKjRqJ~%|Nbjco`7I{X_Vq|!i`|>MlS0P?ofECaiiguj9Cj5{`wTdS@z#(!Wd|mzyWoE>X4C|#Nw3-XYH;y5r1}wE75V%(}~4h zLQuLumnI{nz;&Y1t#^h`Uy??AzA@~~d7H_qk=017Tu0T`=vDtRRKfgd?r=>O0m7The%cU{8t}dXHQNTYj?+)+Y!<(oABZuWl%s zr+9A0ldED&@e$NayljF;?M#LqI|p$771&(Q7J^#d1pq_H0Cl>NXd0Fi%Z6K1Ol$Xn zFiJU&Ja=4O4908XGPp?gO_f}gNn}cpvQuZ0*_F?&y_gh_1wyZ@N~#203m#j!GdvGq zGo4%SdvEbk$q%NuZP$>~60@cod*twCrxqjkUaxI?EfQ_#%fg|iY#t!r8SJogoYZ3) zp`_vN_oE}>M24*d*PU#waOln^%1{VG1^V(+a($S?Bkc^{%mej2siVqjD97SGoObg3 z-cxB1h%P4*j$!kDGZ_N{UBFH%ro6;dIFN2ZlXskJL{5QTp-B!?X5Icx)CQpCKic7z+6uxs%wC#%icuNN(Z0Y@`^pn7f8_v!t78;Ne*mW%r zivr8mI2gaqeW@D`*Db1VtI3>YOgv=NrrwZ?&@zb4Q^2p?OJaMHo`$57qIwYtZ~f8a zO>J6UTx@xvu+vG*TG#ZZj>FVl_vGCMHZC1az;)27oB(AQJ`I(l$nc4H5x4r%xq=5R ztv&Q{W~61y=9#&E3Vm?}AzuJHxFMbRZ209QY9rr6xJXmu@mxK}F8HlVLVNQz$*xHn zBq(*4+d zQ88fSV~aZuVaz_lSj9U`Z;)DRi_{8BR=}6UtIY&w+U2Uv=uPvLXlC21-dnQA#;y~Wp5*t3 z@a*lIC}`~r#z@}ROeJ;UAO-I3{ybs#rgbT&KWZFO)7I;8+*i{{XV9xAgY~Pm>&p3z{qfqY&9}) zKLP^oo`ZmZiZ7rOztyR~x%R?E@Ol+V+o$9dD1UOT5;rgXM+96HC$#{+3IeT^*EKfD zgM1<5mA}|JCPL3PRoHqse_mOZdugj9lsI$y=}G8p%z4!?!2&}Tg@52FEYxoi!oJ=9 z6HgJ4#K=Q(qOM4$elblAagNgZHdTi9TCa#M9XssY#c`Q;-jU z2-)R(a;!HG^|7t_y|B4F9L#T>MI9~H@_JCZ>>zWTb zQ0G2hxgZ&-wFo?S2)w|RkJ=0SDS9lNP39nz?v(NG#e>xoY{_raD z^fAq2qQguxdeYNy28Qht%gYi*u)Sp48@QubCKAF^*>x#ii$EfL+Hcn4R=jfI|6}jH z!8qtElc-}&BiuJgzDUFY`)*UsL|o|(O7X3bh_?t6w^$w15^nLMuhiL&y# z+ACz*`>obuj$1fyo8IhB&?R2QlyTf5+%lr^K#SbyKQ7v+mK)L_>o>oESEULo5r`*xPPX=$DYi+NmL3~fagDZaV0 zy6{P}NJcSD=?I&(iO&tdN&^pqGTDFYzLZ2#L+mE2wn4=}E+ac1kG+8|zy8Id zQe6Gqe%+Na*QtgL>5peca*dzqYw3)Z7wUs=du9tE5XcyNeMiZrRoZwE(xFq7B`BOh z&^+8Mxk*zGoc6q-uk=eEyvr>gZAtF9wP)1?&VcsS_#Ax7isROmHMs1y&;XjAIvZIR z$R@-+vLR&B9|m3L+$txv)syd!<3?~#@7Mth5_HRz@I9+m$omu>u%U0wq_EnduLc!7 zX9vN~n?|?Wn?K?jIfg7;EE{I8Z&x}TkG-uL#eADEEm6dd!7*TTh6cQ)J98~=4p%NZ z*%JzHejj@zqBB)q_*F#jDetLM<0Yh2T!>}of}Y|+mRljQ+6GYDK}&T1;Z@renlF7l zt>|;!IYuM5zkLVh6IO%vJT4q=`v&hpc_`LAd^lQstGtl2X7G9rJYde+B0w<=sdHdp zEB%qG6+Nti<*!r9wQlN5YE2{ew#JkOH80TLGq_WZ1(rVth(P;Z%dQMV%QB?jq>`2u zs>Scb9y2IHe={hG%5u_nPbXRd17@i8nZy{>&MOySQ1o|==tckx3c&{unI%$H)uSCm z@?8?sZqDwn_T`K|J*doDSWK=(x`&%`eLl%SKB->+THyMHxkPJj4uJwn?*mjd^L+MA zgm~cc{;-gzZB8tok&wvRhtiSc$Ad@)@hPwNfWE*~+WwjPT363g$e6a&b@n{2SNf>{ zBBKZ;UgNHy_cT#PnHShIxl zk=4UM$CB}rqhmU_3GN}16N;VO}=Kc&r9tNenyfYa!~Oi(DzT>ae%t-z7C7M{&lp(WV;@i~=+AfpeJ%uXNZ06*uE*H=Rhvso@QN|e)!RuJM zqT_TN`H0x<8Jm!9W=$Z>>KK4cJkarc@3`fD&w$Bl7|Ge-aEcO~ozv?p*a=WUV!7`? z9?k$Lmz48bVmzmKCC7}~&KPOQHW7iPh zg|l}<^k3;r!lG|$D~2e?X=MTwiaG5<>?oc>@%A@`VuQs8OWanpUmlt~W@^=V+m`@5 zIjwx=G7Lk?yiBL4@sk;$_bTK+Qt!8TPz}D0)W>wWzl@*Ya?iQLvJE&nf!~%Z+KzAT z&J%+YD>Q%YFad#12l@Mn^2FOP$KzSYaNvQy1O+fH0ZU*1W`g>MSw( zUtUIZQa4(E-yJcWCI3+FXr`H`6n(UXH2Gdc^!NhU@@<`eL)w+pXm*V``URszX~C}} zcG2>BHQc?@m$W5;g^vLCwm-=db*ih7*C+E@?#XaZk)E*+cy|#T$CpVd)J4d#=GGHT z176e%<~pNj@a9HnRh9YR!)|WDCoR!jp?!UC>jJ5HIH}1T1KwZPHfSUjY`YipHQUv| z5kuN2Z}28$!$_eh-0PIyow=P)Ha5|K;Syre!hV~mel_NUR=41JAkhg`GV&YL05Ja* z%fKOi!Lak%lQ9Z;#lM@Qf5;6*1%AquHcw7WFr)smeCl-8iS$urN-!rNSya|TN1E-j zFyJ!?ND&VmXKva;JbYhJ6R_@?_{2oQkw_#84A#<$K{<8H-uCQXEck{;PqQJK3<2;H zlmx#RKJ*LfPl@L>JS}(9h)ON?1+Z`hW~|IBrVkJBo)V2?ER(7;3ioQR zJx*1XuVYN5E&cG;dR5;=7sXlqz`;8m+Aq~Y(68&oipbUP8$`E;a98ohH9rcj0;U>U0npGHoKsfVTz5rgQUVZ#11XKCm|0h=rubpWw z(Gi_s^=be~9&tUT1%9XR9|L6Z9I*F*k4w;e!I4Jp0!;AZKjj}95xGq8;`T8{>Q4?B zP)R(0>>ri<2UUnBX(W1V{7K)zq0Em;O4>{9vAnCfa;zRek^y0GO0=6Q@lT9SEI=RP zOs#9AA$UdPNRu?Dn1KIe0B`(vZd<5owJyyPz!7;2pa_wAe;ZCTQPOGmDOC=0;wHm? zkm(u$J``aV5I6e7=t!f6bexeohb3$LDLqOz(}9!vk4Qb=YxJ}_izNVjDbtVM&$dl$ zzq#02v| zD?G$d80>)o%mx7d59LW}003!!(}e504hFh?3;Ifb((>TS>vQxcSc!nv#Cj+YG&4KW zMByC9$s8d6GR)Sgc>$seV=&wuXo+TGKwJzDfnW#$E7h+F9q!J#w;ApTz6%aJ`->uj zw*~GKAEgG!IRP45>^yjVjjD{`1=+9W1=)W8s~35J+5TXc;VlAugK-gDKRv}Mvc>Rd z%hM201OLK26qqsCA;T7a{PwT!|AXHc+T_gt(Q_p7SU=LpnM*g>1B&3|&VzZodVCc`t7`z5F602fE>O?TAeKquspQD;Az9;* z4=`r}Bu|v=Bkm6iGzq}!DSkXJy9?l{e*kgR)hXm(2Zsc(>w;hhJeFgzU3?4!(p#xemCp}dMHlmnXgF+P*ManL`-_}>yo|0kMiYN`>!&_(?Z+&K(D zhnMlu7HeRq1$u*ON)m|Hk?lP2Q(I1ZXbu3i<5}UTrj}Hl9tj4@Fa+(DKa>fhlE+Jw^X`77n-Uy@8b1Gb2ro(j2mL_ zHPC2Y&f1#_xgPt1RO5DP6ng<-c=^l7a@iTl0nLq^%iNg;j0>t-k2Z&a!-c@z_(IL{ zI2sl1v$27$W^#_+O|9HN@;W$*X5YGJ-8k!d@3j5NBfm3_#Lr2|Lc%Got7^{-_L5N# z9yvR6<)RZ|1&$er`vT=uN_c$dWqKU(rz%gOd*#$0a@GQCQ9V**N$CsC=0?Zp(R=r0 zqa;X#cQX@oqOtLe!V!WR`Zr#mO-wje1_D&>EnJ`JIX;$X1ZNDcrPc;|1c`Q>itaz9 z`eif4NO6%5PsBvf4mB4t#}G8vq&APAPb}HtLLmcH9_RkQmCRXwb~$p;B0`RBpCN z)cH;q3TmKn47ey;Q(u0kiAPb{Ax|j&y{<27Ohf3V>flA2kW9}x%a%O&M+(};{Uhz| zfwE)Ft#N7bL|{Pe&XZAu5lw%>F1KyD4<%Y$SzV`u;!U~5?HJEO$$_RZDRveHLWeUX zLq<4VmFem1Q{uJOU4G@(Q}_2vJ+3W%Hq%jxqr}xjzj(mXcXf|AakQ6zsEFQ;xxhd2 zi5{4_0rZsE_l`iHVV=@#cQHb;C4NFr_cO3t3C%p0k)uACz1zomuc#9iD-drJ3$(_< zm)N7!Dt7SqXNz@*tzGwaQh_b>&7wFazoDJ3zrM1abMxWk>B4f%(#Pibq5$ASfXxLw z=$J_E8@@iO;>)=N+N!Z6tY$BnAxAgcpEL6-*SrAk`p#kh6xaoWaVC-d0rF1lqR%5t z!b!5Ye&H`K!7ufrUev%ge9h{aV|{Nwy*L2p&;WC8p1JQoOod*|QCa%Vj4Is!dSWWt>X0?UEWlW!le$ixBd zJ5`FH+_7#A@F3ii5IFfD?rKcwgHTARfm12L-5ZY6N#&>rrhAL&7NXad=&!HYu3C&+ zsrx#kOrK>{YLOO%MaMg_07A51mg%$} zz7uiJ6eOL9!DtaRpK@gLAMOr~1@-T<_nvCA^Vw_^EhzsSxF7K9!sQ}z{o0%_@4mvO zZ#F+-$K1gry(mYe&DA|(%i{uF$UpnA(!5?h z6+z^1?!=M$H5`wT9L_1o?evhVf0;UcLX~=^QGb|l|0}ijf3Qoze>K@8<|Z;eBD*7$nhS<{I!b|;cTOjOR9 zZf5=gXO}vLv!4el{WEZf`UPhvyx{>vsZe-0`;SFa0syxSz}XoAI6LAeoShf_1J3UA zj_DVi{S+R~{tORi{{q0-!9U^bUO(aNBT|G>csM&(iD@#d5D#Z(JZ~Hn{JiHEoZV*w zfU~;-aCR|YJe(b?W!C_rB&48wnpXPGj-@4Q+PifvA0lhq9m%5d^+07}kK+Z(=V38~9nyUY2J-VCu#|{Nj>H^h-c(O)hdI`j zG`Fet%V=5DT8~kU+3o=Eo2~OA3Ux;)cM?qcQ%cpJpI*Q&`|{fOfYkM$jQ{-8qKf$`!VYXP#546HdafsD`?n zU-q^#>dp82j_6jo_q6je>pdk|R-q8q=7BWglMB^nt~`%ZAYE`dsaamD#QuO?t3CB~ z%2zvxrZ^~It=f>{sF^e+{7Vv1G2V>k9QYQ8UQt8sU!363*h5�jeB6cF zZR?2@dW5sp=3K|7!xZ#+uU(t}oi5Y-0@}X5@Ea!2wzOBaW{Opp*Q;5=k&~HdAB*-A z9rsCilchYuO$Z76($R*vOZi0Rs!8+ZM;4oNo}zn=^m67k!T@+?JgUgzKEwdr!(M$M zcfdJsi^`#Pv4w6G3c+2@-)5|IXj0gTBI8XHUxzlGv}D5R!UvrvH_|!xK85woLK+0$ z4rO0L=-o8+u<@VX2P(K_?=-p)?=HviVZ>9qM$l#-5X%0n&1X+|e$gH57azA_pGGMo z^iIuW(^$pSh#YcxZz6~yDs9$itN%Hei7H(wL@lBgcL+C43wt8Db4}2qO)3xlDTu`b zJFOxioZAo;a4Y%h`vv_~piK1{nj3}_!l3r1i z-W~5&;oGVU<0EJCt#;GjX^P$ID$%;tH-f2h?iZsQ_ichmk2$1~bx5?{vgqII5prYW_fJ{XOrl-(hVH1b8*V#f~d!!)po{Z6Ut01IxTH)AKS z+sDj-wPdEWaq3j;UOaYlTgcwR)cH;eXwetLUL*5MUZ#mb`1jt7?z4_$4i zlRm7i*{)un4BgM24Ic_y;>1ck$cNHZz1&|dKA?*dhXqi)=Q~`~N;7b7nVW4p>|boP z9dT<^b=5C*Znu~|x@9p@>`@kF_+->}_Td1y7WjJuc1|Drh?Tpzx!u7-*VCSl5;6V_#_B}eU_+;UUaClI}#f>Gd z4#~rJ^%Q#^?_b0XraE{#SH2dsfEsxK=VXi<$2fTVWHFVJnSYCOR~H?1noW0h9kL1v zYnQH6iI2P-5AkT%wFn%jn5KY99(@y(s$DJ|z?wI2lcC=;?WDr?GAKr?4|&lN*cU`< z(laM9m%V&&gU@zsYqlbfTeWo1Jge;e1F!A%)7{$TSk#+JnAcp%fZir>O!{U>*7p&w z4i<>(x(B-zu1QcoHCnZ7*m(ateLVvCwRL++B_p3+WD02v{v!IgcIR+=$hp(6hsERD zx?H4WyMEIM3Hi>qN=(g;QIhRUUmq8r6jMe2rDuju*3E*LyeC>X7~Lk>;wdiiZ}i6a zdVGxz(oH>A+`Cf7ogHyw)%jye3ec8fGyZ_iQLrC@?*zt}Jey|Yy&i7lC+)9h8z-Df+wCE9$LCQ*(D!{$L_ z^)>+TeXC8>@T`MiRWwX;@6k=aLF-BfuUgB4B>XP@RYq?I^oj#1`M1dqU-bZ za9k}~i&mfgTcZy9ZtRTjd>Vu89|B|o8??{S!Sac$Acw~-^abtvMrooB*YE?THEVXDG zUB23#>$FFDn=gITYBt*|=aOM9z{b_s7GEzT_to^~5;V4-S8F_RQTj^0vgnv~lc7!S z(YLERdYW%C?Q6}-!IxrEf{K{P9Gt%1nB&V$X0xxHMP5=3z3nqe##2VFeJ<{566x`1 zE2A3#?aCL;dg5jdE8FZkph=sU4&1@mhm17z<6ikC9(0~s$4pJZWZ`WQ9Td0SY?aVX z3EkY@=F<>9%VK|A@3qynHBfbRS?k^=N7d2e0R*IqrP>Vhazf8R72|{%-X)(N*%76w z$>4<`PlDow-!;Bd(qi`B?IH^@SUt?CQQnD7gY6q1JPREio0G0x1}56|KCr>YA!apB zSm()J0{^t@Q9Cm{Z+LpeZQNt|X(hn>+Et}=R&d93jn6OAV|-wJ%Umi+s% z15*3*8SU*4FqHW;?2&um$94BRf<>=L;@+xA?|sv9ptA$y4V*kMQ;HtuEWEJe<*@sB z(_^R4xunnc`!ftPE-V8Z87^&OD9QH?yO)+%bTm*!%7WXMUKvqb!XA|kc$Q4oj8w-5 zxy59tNp-*@n(YSmH^7JB2Rgg5t#*gPSIfv9c)ay7O%&r^P1@kp6ut`M?q{&!$=8(w zx`-tPF21r!Jr!8Rj%F*O%dXXC95-hZ6J$H?_1Yd1>HCB+|CAs}v`fw&y zjzTIOx4@xmPuW7xzqY(tJv;BV7!t(d`3O6#S~_Yx`&E}rZD`PZylT&A$Wkk&23I6? z)ev00KfDxmd%bs$4$=?IWrpsv(aj2@n6dRn^IF$1JJ(ckyM1Rh$%!b0$cQJ0gUeP! zJ+!XN&vvbbubwWA%P>SUM>YioIBo z7t$M>`Mq?hdN{;}ug_w|tmbqIly)}g&jCKLjm<-xTP;u7pltw6jXMU-A~}^X z?FK0Rr9epZZo2EZ)j?Q06L3~?ypfS(Tl!H}z<>ufBiV z&yVLGR7-pCT6J4l$_k9QOBh-`6BF9 zNB%eyj1(H!kQr;!aX<#CbOnsA-jKQbX#$9~-?6H*FJN1u&&Rqwc0OUu*t8Uy%5Cg(rtBE>AE6tR6<-^0ZfZMho_PSjq8%& z`Qtra(`yKU1&8=lbmabFbCR!w>*z^`n+1FCFR@@Z)9iNg@_5$kxRc1;nKt(?nV7dH zuL!p(1G_IzZ;xzCtUL!a>@#uxOy#VKZ7YsSuqMMtwZ{>+~{K`he|Hy=pP z>|Q+=kxD@sHHYrRx4;)4>^jGQA#6Ggw_oNs&EdY3Up^J;Bf9L|+HCCGd}NU_w}JzK zR~!M8E{*@uM>9naHn&Dlebo_}QR;R$_V6eO5a^h+k#|K#y)B?ye6vzNF0fx}a*Lj> zrqcv(&bC#~cXJ&*8Avm4Pb{&HVwOHitB$(8sP3SXw%yrj?Q0hf+hU1aa?`iA!mul* z-g5u)YF)ETI2!4>8PRBhg!ZFvIki$SFIO6r?Qt0HRa`Dp2=X=mytYEzbn-mEZ(Wjv z?|~veG8uMNEEjU@3pIDk>1-;3|q1uzO=&#_MI4)W^u%(myLVNZI`C` zZmdrso%n7O$arimR(}?jJ9P`O4E^$LJ*)%#0=Y6O=1e=#w}kWTb_5V|n))`?H4$Jv z%c;Tn)1mVA60q^AM(7r5GfLbZpkRyWKLksUc!3wL5fHpXF6`{^GC+u7G37np*OEvG z2#O|>h~hWt-mAU-=q~UA*i|)K7J@(j0r>Tb0NBm)`iVs#Mn~8SL{d&}4D@lr?ay;} zBp&6!luX~8pOhd)LrhZ$G2%7Rw6}}z)0;M?5yyPLD>QmfgM#xVN0WKu&XZd*-eOu+ zu2QtExN}WgPrVa!;Kg9$Nod~_8(kb(iL;HonR;Q{V>eq3ekWV8b#_h6fmN%RNS}2t z%{yvcaERQCiL!}0^mLtm9Y8y&?AI~i{(jl%S;%bOTs!d8vE&|EGPpA***=ZDG< zyJnh`-IeM&#;6ai?+Q1-VsF$S{AY@BD)NUrXK)F-t3623hCny!+MDZR9O&v1%ymbf zR_k7nw@)jtbv-_-or`(Cx`~50MWaZL6r`*{m3Ez;6p}Pwz1P8colJg_v&t!HiSx|) zJ$`;Q@1(Zt?+{aaWZ}`X$#c_MQ}4qD&SE$sB{$uZ)baH9@q%y!@kX zm0oqlH22?}ek4F+Ivl{>8bTBB&~}QAdria-3~t_GH_!9LFdrEf#Avd;`M=NtGoW#jw;Ej^l5~p2*R{1Vd$!ZPY(FGnvobKF2 z>wBj?&kW$V^RT0KqKgZ9By<~dp>5e?kyQ1u%isHGHhv2Zb^LDHmg-=>Dr~X=a1I3R zkb8#eVZb+}UWFoGg)IRAHzhSy%u@n_>RYbIujgE>t?=yiJ3$2O+n)DsB%d>t&PdmZ zkhT}Z@2(H%{YG$HvL7)NbatE;I_0q*%f|8O4unRoW#sWD43Rmwa#v*V$l(?gX1I!U zHaZ~nTK3SdSrOf{E3Nd|$=ar=Tit8r35nMNXA>;uTwHZHy;l>DoZLR#X|PE1aZM4f zJzsNe$%m#SWsST#0I=R1Dl#(aYdIBj*3y)n(D&XW#dm{MdJs&GZTX2G;FAOG%2kV< za@zFbF7t+7whk2)V6bR-xl>6h*Mp>e#37pKoYelu`g1CydY2Ya<0waO35i0K0XXkK zj#A7w!wttW#mt9JyVv{>{CcC@7Ona8^>9J<%I;DS7pKlSS|`b?A+Tp%H7U8!lD*li zhJ4T2*JO!#aCFB5pxEll%HCK}bL&CSchj|p-+K@%)-t1ng*sb@SG!9?aZ?eAmx)hlSlXm=i^-{iEyuefSa(a-Ij z@a!~2X+G8bKt2mJAeR&lXLR`N%3CV|RI>KP2ZX;ES6ZuFs~(tr`b>S{p?go#cWG~X zivA}KbN0Er{*HqMkwo??A9JBI5rBziD_HbIT&O(9ud6TY26Rh!psTOx8L#LOPQqaT z>dGszMrSB(SF(cm46Al@kR1C4RD~lih8s-mpLLMz+%7g9E=V~*g5cb)CKT2H{yVqZ zZfP`BU~aI8s*yFF@s{I?fg=n=mI@Ci+Qe7XBrWpb>}6Er>6r*8m(scKfqfU8H!UNLG!Qa2v$S_Qm;xZ2s~NG!#!FW za@K^lMaTo>4q-c&$6($H27lSZ*;OoZ`o5HB*eT0Mw`2SMu+i`I#T6)`{O%Rw-l z%Ucfm>@*PTIAX$rs99pF?L%meylH7s3s}XyXxyuyY(iMu zyEy(};7o0S9t7O+wT5p!r>zq6cJ8apA}OjR3PCwXRKMIbSS_;Q9`NdVxd{5{{u(I{ z14N8@n`Mn1_mDV<BExLMIT(>TyK{|dRd1dOEl#T;XsUC2z27;?%PYrX-7~wg&e?Q0yA$W7 zVm5r_kMz8ji716KK~lt?h`|hIHWk4@cPKPi(gX+Gmmsn-T|^}iB2m;}Fz*g%VxChn zVCL2*>kSo`Vqxumt52iPrtdc)s*uB_YAl$hwYh?2gQZ2pE97uJ)CClZIr|RLsTts7 z@#s?lB5_F8U8@b~Ltb*+-|YAuryG536!w{TEECz6IGbEIQb_30!B#VFrxX;xzE<=> zq^{%h3dJj2xF%@mLMh2ImG`5^rlgnAzgTl)^O)F@} z0l7Gv6=>huEU!KnX6f{qS2c)N>Ki+V^Pe}TxKti|@<(!>atIS&ui8bur23eS2>m?r z_JJf{P2snbKqT(*T4^>_M_4|$*a-GI*D{u(Jl{@@w1AV(nJu`&>i|!sq7`#OX%uRlV$ClLZSt=c%iL%N3mnPTG zgxBG~F~Hn9zS~0<&&Zz5G$ff;i>$Cuwo=91I%VISTCuk^ElPpYX^tc&y#smk>Ix<* z(jk6t5!Eov=KaRxrT0_8Jl){pC{9(st9>Qy8O&< z&6*tyd99-|bMdWi-RV~H(+bhT(-bJ*bHOT*Ar?9)@r_;@hvbv2H$or^=3DpjiqLvJ8 zsY7$4qeO~M?97~k^2ziGuIG7~3ysIvS9K0dPA4k`; z4nQg&m?z$cT?bC5-itrr?2YZ%P|YA;$|)-9F`A#B&+aHJV?7#d6nu`$vkRQKaUQ1H z@1eVh^M}z*1^1I(iciRA?zO`Q-jWj(&0 zh4zW`f))rZn^~D<3GpaI~W??9}s8G@&@`tV85Q>0%eI=()- z<(e7i4(zut5{?jh3&0%xk=?;ROIb%!rsdEANuRkBkkg+zzSb9Tl{5et(qdzm%nN`& zaiRCGQbGn|cORDElQs}pHp?7eFGfN>uo(idP4WybV7ozr;Pk&rxmSf~$jWI1lKvrv zC(Ft_>wvFfcM)QB7ji=8B=oORrl4$6ARfHL)(IE{&L3X`O~BS612hDd_49uT%}m zC&KX z;M1Kio*rLsGFED;Q~|p-UQ+n04SxzH+8q+21_}d`{?Xqi2V?c7fHoPv`MVAOSN0Ts zLykSNbq>I3#rO6=@V(Ez6nv-S0XN{h!ta(^m`3p(Z1xIwoIffnrT5R0!3yinnSH>K z9UTU0fCUnO15w<<5vDik&k(#;2MYlGqWL-UeNt<8(M?dO-kZAtwru@m)CkR%7 z(e<;t{-2ilw`2JHoLb;oos1nI=_*-L+(nObzqQdMfiIYNnD&0(gKUdmYT(9XY)mQA zUsf}M`1W0{5e?>};3 zyHNlS_y47fI&4}cO;{U1e-^lB^iI>le zyu1?7ko7@b^H}@mWRW}DhqxJ6ygq5r|DL!-jN%Wd&)=sup55##deKXOwytK$En6Gjrp1S6A*Um$em*0wSuqy&j*_~XlBV~rlJAI7?R2)bQ6nv&TZ4Z7uT)R}6MdegBj zkc$Y2F3h0d=MPe?fz!+mreMB96;%sdl6w+8mLW)42@SlKHG8!^bK$-19Q&>JQ`t1b z;Yd`t2^f0j#Z|fYm?;~1KkbhemU3gEn3F$rHK3zWZ$8mWA5;g|-g*I=a$A2L8Y$@n zTWaNJ+@h1!#?m#Hc2d1>QcM|>`!aw>QzXkyRG&hJkzULR zr@REuF(R3iLUJzZix4bwCJ_c{$E`fS#E<(QnAYBf6;<1+B>wE9( zd8Lsj66^ufcF(fpI+lv;TQzYk(|pXpyRr2XI}P{WG*8=zMw20?7GtKlRU%p|o>lV@{*8-3vc8%WZQs{?{E zk!J(c=3^Z>${j?Ul!mK=|N4HM2QbtSq}XznZvbK+>44EWd3eQh!+ zHxS#3H2CdZ3yXJe3SN*Lw>0mSwyvWt5EnCh1hE@nLj0WES+xRb`(oK-Mo0x#s2(;- zeO-%+<_W8%#2XZ>%%6T(2mY1X$;QU$^a-K#dnPBOj_1bxfVrvA+py|Ds96Hdb0WNn zq+A=vEMB;iwk-BE@4%McgnLi}JajG9r5#;j1ZB$-`3$fb~sY*O!j6l5lhUiY}q?3Y*w+|*gk z{cLnSGJ9lNUal8pF7E>mIOMg)n=I+Zfg%H-yAsk2+*^0Af8aXgYZO0;?>J9eWQw&O zoAk|?{GZk9v4}Aa8NooGHyR^P_P#JU4XTrj8tw zIg7XC3lE%rFHY+clRLcx>nBtX`MWzHoCrTc>EEp zMuCsfO2ko@0xI7eqUkSUIIp@5%PSd$(vSfvC00&#kyPyAM42y0ae6e$#Ohv{$Rn3n zawu_FAxn9;E_e#2Nw2I9el6c_Ha7@ri>-d!>oim#q@DL$oe(sg)^c;_b|GQ_C&=cg+^5b^iIw&b4nQPE^tQ< z==%u7i5v3kjdi_;o?A9wt+b^dDwbBm4qZS?bJJ}h-y#IAFJd48WmL5lyYt5eyG;FA zyMz-xwNzJZ6nHO4y1d#xxI02fts?njB4L}l3K+pTf&FdjH^lTZLQCZoiA88%JrYo7 zhW1_Q1tnS81ov0tO?6c6i&{6Dn#;gryKJu1_nH%XIj4ZZ|F$L?0NMc-q9_Zi00C+} z(5$61wM=^5;*MOPETPb*cL?SL-b@F&$c*{~%XyNh?kR9c?JZ7LU!g{7H*D>vyf=Lb zRe7fXeX+KKP|o?}KUtmc;*QFB3h2XHH(~{FX1$j7iQgmlzp`^V1rL;by)y&w_c4?pZ*EBawwu(g~25dm=|qG9KU!_L?)KOwaIoV1pbatXz~_dN8s2%cP6N+;JYS{~7(`DbEa<}FT|I!Ui4e#0UF2UF=L7W!n{mRIPZ0{*y zmDC-bM+BtOW(M^Zm-(Mf4uZ5N-wH5R<|G%JPi2U0eZHu|ajdiaozn6iq=85xGSB06 zBHMMl$DK#vYa~;PZwiXvAb?fbls1_NvP@gNWglNxZaHV8(v8FZX4zU9#z{XJmgWDTUoUU6R#U@nLW-j8- z4vg#GZxq47f4C1~ggR0)DHt^i8Xd2_SL?c#@~7$x;PfPPe_7k;PpbVhAu?2<$%1qi6uv%paIm0jC_0oIzjCzx97Pfo)$d zAPoN(d*p@w(&;oX!kMxfb57h+U6jr&*tLy z<++i3mipg?8`uCx&Mz?G>?t@EAT&4qGa&Gn zz5V~ahuz7#>!pH)_4*;Z{}I#x2J2$ZAA^Z*|87tLcbhwHUf0{xX{kC4Dgr#nh6tYw+_35 z)ju*JzWF8R;<4J2*_ym7wh=;#wHXa1V|VE9Pdv^I=fJqVj46NzF`5Yiqdp}Gb0`0M`?`6 zX9uD(z|XhEE-u8kfi5%YjJt39T;)e#>3>}eB|v-(P(!a@t=U;Q7HmZHjcoCwsVSU39 zqjemTY*{01F}eqbKN6eITXRnax`TPeM(g_3l-}5jB^m!VB1V~2ijRn~6R`nN&52;V z$A7{Pu=ZaL|B4X&O#^e`g9G?zC0hs(R#g0tMw?|(q%00;uZR-e$b_7GMR;sABX4{} zh`+4CNN$*kR3X(B@Hv6A#Oe)O&28Rz`;G};0+pAys`a&DLM<`^Qdw+x)c4d^P zIQtKC1|Ojm%ouiITMn$cY?ynJm4;pqdudqNs7-%EoBfwt9haR43yMZJy z^2#MFO!(MwHeB4YUf+&Qnu(G5fd;rl_IG?3m^H<6yPwd)_XvPRon5L66rHo1iocC9 zeC?_0HY#BULE3qh86wjzO~a4z;S&&f+-LIBh{T7JL4iWY0y29itS!8#yv8;D0nYG; zc!gF>wSd*HZuLc>#}=Qr--7cU&V$b#3mcVpOa{TPk z0sSAoUR1GGh{|SE(w7GuU??I)?n^t*V0ys~&97O{oz;*_hLB(=W%S zrz8Bm_?Aa}eR@F^cx}}i%bNef|B%`69B=d)VuBnEFyZJDr(+2a*z`(gr=L=D`{C$c zmwZOzXdqps_HJ9QEk5%|`hE2y>Kq5i8~ZB`r)jj)6hrmi{F{ZRr*GUIbCEL>78i%S%K#gs?oMqB#FRb1sDyki5+KXBKy^`MoT=3mnS^ZT$WSjT41Uu+2=}HmRZ#5N%9kCW1c1&#yIwZ zR29MO3o7L!$#+D6G`rPdwMMPuB`-hRTOT^70H%%2gSWjrk_wJ?x1UlP#`>S9IN!m_ zoSx!l_hvHhjvTm8@)UF?yAT?yQ15*8$iMSEt5e7>WAGVrwdcDbBF0kzJV)H>VA@_9 zXr|?Jji3Y7R@Nis7mf4EoPL32cNL-eTvuIQXl*|vBR^56^llMYdc2)>hE3x0y;{Lg zoLi@JPJr#j%Hci$HWd!Ug?~a)elI8aA!S!|9t5>|`X=TG`tTSpi-B&FvXVmsh6}tq z-?gZ=D3eW7YW5MG09?}Slm?2#YreN*LwroMrUE9nRBg*=os2)OH#i`Qavfxia%pNa z8WiKV9{~&Oz#5yY!6K*Q=Y|@WuA~061=-Cs2Q48L-@Lazhs8V`QaY{G@5UHAp8*vx z1sY6WOys!=ti0DW^2%3FH!IQ8-_sH55^eWSi5Q?QFi~q!ks0ExaUZyPPXcvw%;jnY ziG7iY^D1+=sYp_huLOB>H=C9!DSFGa%V$L{rlG<{ zRld~)%D*i2{l?DjYR(D`Kmmf_nDG&HQ!*S^4BG#3Czpj#C-0@1c-QMNzrB{}Yne^) z8+!KdW%z3)_6J6d97s+8`khkeEyB>_NMixm!}l5hg6rldAh4Xk5#_%q&ir?LJu%js ztUnK+(Yz%@dP@kn*W}X_7A6%I{_#^tgj7i6$4`DCVN&4l$Bp1EQo&olo(lrc1%KQK z2$Bl?{K+o_JpP$P0QfEN*Np&hBk=1#H-Q^GZ%|W83SUKhb@+wxNq<#LlvMPe|HfD1 z*T4CNf#QXa%ltD3{DYrK{vS{gMQ#a_^4&ADvaobv6&4X8<&(8?aaK2Tl5?ifR}SKo*~}t7 zn}!v3uu`LR9xn&n|3XbN)cR6`^VRZ~VAGIrAJw6kLd98{sQ#KgoXae1uDyCEc~v#Z zvnFjX!Fl{3b$Q#r-avFrp@)I_lA);v5q8 z2VUDfB{oq2s!QydJxRP*TbSxrJ zSU>$61MjbWIm{qPSW8Q!uFt2VqB_`ZDbg!3liGAI36*Bs#a3iz&kG)bb#!#pUx3xs zpW~*pL9Mj)K@_pk(b1hm_Xhh6pB_jG@&J_ON`YUn{_A=3r9 z#$9dSyoVnOVjEtgoOC{paSB`ZMHMoQJEi10*s~cRy&Kzo?H)g-tUED!G>hc}NA8vT zDCJU_T+21mNr+OR9kP?3g6IxReIFYU#c}$*8$9ECTN>vq7kKWl&$aPnkCMlp2aA-i z`@y!IvNbA8EiIj(u&{7Evoa^%^z(P~={I9j&TY91k zRquQtMy?k!z1b%GP#k6IzURXo)xrs$o>5LaQdlR+=QFyM2j6Vm)Z8^{r0W=Xf=!pW zvYs@cLD|p8+1$hyW}AY(Rz-;{HPa_Ah`+{hSJ|DX_Pu4uM9D3mwAB54!t=>0(zs2c zQ|CS!RhOncJ+W~#S~bdtqlt-$*<6^;diCnn;QV0YCbuke;LxGDmKlwVnd8crJo*0C ztOPYi>1{=*a32MW^mw_4MN$|%`pxIX*jms#4!d6H8fIyJEx!u*FsCch(zPlbzO+4G z<43sn7$myI4YZl4i?x`av9J7J)V*a~lwI2|Jj5Vf(j9_yNq3_nB^{CyBHcZtq=ZU$ zC@9_19TEc4-QC@=7hd;$Kkwe}v)}i(Kkn<>H4Za#uJee09OqgWUp5eQgUXUZj+VEB zHA|vQMYUHg>+9c5>l04GBu9>QDlKF6bOV1hxix+e!*r*@ecILZsl-Rc2#&3^%-Q4d z{mYFhjopfN{ZDx3uaDj*_DJSRg1gsNSM86wFkgub%@~)m{XER8uJCcH^8L82vVo#v zQAtVkCDp=go$HIx7wiW06&&f<1b00?9Y;+0kg2@wqsIFFv}d`V^_T@NGl3L5?+S$5 zEu!0i^@RruSlqjPM9OQ62E#eLd{(SfoaX40CTd{_`$CA1UsJm;;9p_wJ0sRbIWp6((+ z<9>RD==SQ7>UT&|K57M;`-`{Rr(28}iV{Xf1ENUpHusC5SMMz=2)TccK{3UG$QIJM z9(lFLA-{<%1aC;c4UTN|Ngb)z9wr{{BkW7<*uj%5{Nm3%ZlhS4;JMfrTJ%QH-u3f* zPpOz!gBNCl7k*GnMQK%%uzkI9>M@)j8o{KY&v?OAzws2_kZgxbqKU|tpK6GY`c1cG z)gmK9+qC*G-8%;eR1-BOB5umO=sYTH`cXU8&AuDr3)ni~kx*7OhP!+;k)2>d=56O) zo+&D8fJ-E(w$dx_wN`q4MEdb;tBF;Y>||jvz0qfLf9}2OV0+f?WVUB00>fg`TU{AR zZ@g6g7s3TB%f>i$L@!GVQ5wiEkl8+YUt_uN&8FYbe{HDUYIPT5zw6K_@n6|DW})Ca z_qKigdRafH%sKPNVHdTMwDB*o$Cr9)A@T)2)BbvT8&hLHrb6M*mu1idicBq0-!NM! z9O%puLZi<>4ya`-L#C#5rd?_+U3L;QqsL2(q}<&vvj${9O(Ra{`t#?{C;g`~jS<|* z2U2g}-Y|LAfk4U7J!E%ccB~y9HEHLd9d%*K{hd;--T3G2%>?;xQk6MX*kCdrW15W+ z`XdaltDTyBstn3~LKdlV z6(T_DYWzq+9OLspg1D>o)(9hZ7{wQTx#C1ozVdxJWF^R|OT=&~^+7CkP^jY=w^(pYgJv=-dUOSBB=ateTbv?}~u-8%v z!f%c*V4!Atl}E-YtDgVf#B?>6y4r54RDOS^zFrkZHZnS7R>kx|^ftI&@s)?$z7BW* zrsS>X7M9KQx6_7XKd;^v*CKIgLOi@Y=M4=qh4jo4O@lVor*Aw%@tKJ_0dW-wS2)O9n zSog!>pWkc3A@4bv|JGMl&fE6hm;g`#gM{1d;=*Y7n}RO4?IFvKwwL5hZdCeQ6D<8p z^vQAw+zZD2@!~359d&%)Fj@1P-U7prZPsZY7zIU4Vq$1R==o|crX?p|(%G(9#jkgs zpmRmM+EuI-Y?@>t9yFj_-6F5W$0MMT9V>cMS5or4P)bvqIB{d?g4IHML+wr7b?-WL zUTAMyI?}J+UQ_dRr;QtO{g08MJekl%TY)FCt*} za)kH<%^9(u%Xw>5wY#Th?)G|&QVwJNOrfHeY+IuBYb)8YcN^VLWep8p!6nXWoD!pB z-jz!J1Tph(vqxWzyMhbBnGtM65`kk#y3kS#6phCzJiMBd1Oi=5v6lb2ePsK{k;5-J z*$ApSlxwX&PQS>kN^oB+WuZXfV~%7~K&!VI34_x4wtZ9*E*==k_u$BU@?ESmbdXvVRnQ6?59mTq?6yaDDrb>9dj zViP&cm!9!8MulyBnGg>zF$SK~!gGpo3508WJUmP1tzVC|thFN9Y3>@m&+q7S$rVVL z#eD1@2Q^$1)6q3aG@G>_xq4$z$L-JkY+v>gJJ^SdAhQ;9U%CjTUye-Wud(d!%#XjZ zjw{}ot{y0sCw#Ft{W00~TVKL6qnQo3+bg!x(%HTGmbWuRrK$MSLAdjO`edVT=%F^p zT64Q}aa0H)QLx*MJLh+r{;{VHr0?bRoOiDZ5rQK{yl$iwDpMQ4qk@zQ0K}}U!$eo+ zc-9FRediqoOd(Ye|- z=k#-lJ9$S!9a`FF{n<>D!l7Ct(>d6kg+#n?qFk9-? zj7fD8Y*c*N>RF(eDwri=x(y$k?iRi@TWMa6hIm2J)h~C?{|ok_y3R*d7HQ6{uR)`f z&i`Be8Kq8xP5G~j(tJ&}t|S!q3%BC&76kn|8S-cXP?FJ+PNpm7B#vzM#N3=llQ3jI zASsfLjl_N5J*vA-Qm^uN-kWI8!kDT{M6sJKO~ya{vK ziE(r#@~Eqb*X?3WVjK%ze@9Yo<@r?=7I?)lRRlV2n0;vp>xVzq?`IUbtUr=)S}hBD z_FWfOVaBr=tZFiJ)FsrRsek+|cTSDlb#t2_pgunKSeI3B3CGcQBUGMXq5yU*_@l3Q zbsUcsr=B2}m~y_H$+zhq^ZqCw*3tAxPZ=4-x7pxe)zufR3Bnkkn8?b^O#9Se-o8>q zI^`rl0|%MyyKePUZ=J=G$a`?tiuUK0PgmY)73$Q3;>irV4!T^k zmXPopKATrc6-~Z6vkqVD@25}HVom7p)`~m_7_VXzFMK)p?A^P&YfeWOmq>qqFGeqf zyLEU1HvJC)1~Bcn03 zAH|r!z}QM!l4-*-J~4Icy?2xE(VOjkfEkzA8hq9=Dhz+Vg5w3l*;aJ7Mh}5;p5^ z!n!S69e0~(|4rG{6@2+3k-10nPnuNJ)f4$V>CYbL2oB*Wy}V^x+mKWb2yGu?r+BGl zP^I`rk89rSP0#j5&)+mPHn{U#r>3QKyxy-{Ucz;&bVEf&b#OS6k&%HK_z+z5Hu$E@ zkUfW=ix*>EP)Ox^7cBup_CgWKdrl>j>045k{e&W;jAr4F0YEapuiZQIaHOKIp4KZ0 zdaseWWX)IGG6mTN1<7=$a~!$a>RFAH7zteK2Thcno(IT9iq*mtG&HKpyuXL3ODlra;3?&z~vhsAUWF}M^4{S^qY^03g=MvUxy(%knw)=Hs zK=%1D4fD26ikYd`6=>{pg5q91;K{m|ikAn6%j-+*miRFHb%Tsqpn-hN$r<@!dhBt! z6}!hr(}VA{IF{-;Y|grq@s)VtUamvP_uTh7?Uv7W-t(GQp+==mw88Ut%AM-DP3qTE zjM!qmIswnSPsFPI8iiUK)Qy_>A0kQSYd-I}kas;#!fvk~tfSoyIkcOm1b}5F|ac^vi-*#^%r!FORE_Cs2NZ&d;yFs6C zu~<%n?e!(EUAIMjcCGX7&g!D1k|7fo2YFUd%m7{NsI*M$D}w$=D)qN;>1fC^yNkD6 zTrc(Yi$2?QB@Xum6OpKuV8wPPehx;$x|L|{(L@;N*R7@JJTqO@Pfq@PTMQqqC-8cm_ZL z{=VBbcB;}e0f7Lj{2bNy;guiMm8SgokmC``ckkwOMCdqc`@9N1v5s-~*aqg0%&0S( zgE#fy6DPtbhT5|rs5#1z{^`7D1H>zoYDDe8J;nR#mTLK5o`LUN4U1sO zg=b*sHm@s_Nj~$>wbhqH0Z8nM2f31F1Y0ir>v3kde)@tZ-^$7gBAS@j4Zq7w&TwNF z)55#@tlQO6ryBnl7h$^n=fp*ExczYx8Ug}R;7Xt|v4w49B@Dh^F5sEw+hoK;Pr5Go zKQx()LzZ8U7uRdhuFtoHOs4Q!T2qVmI5|tFQ+Qv#-+j-}#>w*d<*rgFVVtT`M^Yin z!zKNoDsz6R3~{&8tg^^Iq^Evug>s)!Qern8XB`}M3m`0ySHe&gE9v&Q=9eC^Aq}FV zqocUnsy_qw!sx%#kB_HLlM$0Un{JYf+0B>VSxlr{YPj0yt=)f=_VMxAZw$B-_IaM& zAn4k3bwcXZJgr(6K)`f!xc(iWC%XechBu$B&oz0g|Ij~vLL{Z8Ro?U4Buex3QS!=# zCjV@`QDOddT29W&*_LH8U(v@XSc6IKdp$3By{Xluf?<{9^Lc@(vLT$MHHD+(NOGZ_ znZ2C+VVu=c`$J}OGTZr@W zDsyR|SzK&CLxhh%n`IhKr-AlOF;TD92};eI#4=R z$D4}u9$O~uw&ErVn|9)rhi1dbI#TZJThEObR=v|~=+3sQ@iCFVKKrKVek*7{7#*WT zIj5?ud~hakao*egaa%)vTQ<}r1a-MHQom^|)852%?Ibv+ja+k@nVIisV*9i%zix3s z;{DF9UG22v{AyECnwaBj3ooA=qnzxvo(~wY%G3u(vA*TG$~K1F#sSM)X(F}jtLsA6 zvoT3mW3!{H?>j%ksDn*u+awIWeL8n9J>`1yCN;LIDNC<<+Etggh?KV-n}-uwx7v!~ zP2HbJCYV>dhYScw>pazJL}+xci>W-mLW^onCPPb8pL}17>lIQLrpG%=pI_ao^Nl=Y zS0)>@n`uHUBdEjJcca^*1Ly5H&OGX5axz^fg96f(z@c&5Oz7!dG2Uq`V`_I(#q5q}1GS9dc!k z*KV#Bl>%_~?Nd@y3+FP!7rw{YoCj_oXC49wg#G3G#%JO9DORJIaECs_+snQFriAYi z5n;TE!lx>O@p7tX8_x_E>nCYHV7wdt=DazDudBb5chn_Upb64?^n;-D{pBChWcY5Q zy0Wif8V)z|rF1s|Ra@j}sCTzAen9S|>$n9ZEUS>CLS>tXkeFWeraHm`9s`A^-zD?O z4aeAs%_aNol@ILns(=2Ch}S*;la+`GA5$|k3~mx)hyAMzYO#Wg{?2}r{qK*1Jx_?; zwzoPwPVsV1Gut`wwlV^9t(M!wFx)SQ;2BP|wE!QJbNsr29K1Tt$$p{w{o5!b^%XRd zQp~-!zk`Q=B?buZSCwb9!Sd(bFH14yMSoc7gQBQLx-}AOj@i!aTd$`99sH51@p|Ur zN)T4u*A>$(Cd*{L-#)euk|=hC&5L0^W7KhaWi{_76_{jJr;Hoje@!Oru+rT4Vr_W6 zKat06P@LL);)=)UkJ7Vm3Wqb>yRfaOMX`u-?b>dWsPXhJ%(&KI+-cl@|9F|T-I60d zry7adt3hs^+Sw)tVY*VU^-j~fU9z{+So`yM6?Usz&hJU5pHjQN950$^#g(g+E(R5= z(Rr&U7AW?UMOLFl0m_mC?2D8?cN}2YWMwuVy{CDt^&7*SE@%5^orBfxLaSO!Y_f-Y z<71{%`F!qfh!?33it{BETzCF#?`$q7kr?067fKrr+f8f)9m8DCPio2RWJidre0HaH zH!JU>NBwIEhI8F^4(GO=4LiAygO1JP|6T_PF^ZB5Rv^=c%XUNmyMVNf`IcSS&^m^+ibi-_=2U80=VDzvU*F)ic~sJMF8|NP z#r88lxKL7WYG8Xx%6e0GPA2TN)1S$iGH7AY_aI(9^Fl%RXUM%x5et*u*o+dQ<{X*#M&ue2{$z}G%?;C!~LGtm%`~|bo z2Umbh6cY5^URKBEcZ{*i$nmojSG++gjZKW@S?h{P9xpcXiE0@ifNh`6FE1_gOjR2+ z992soA^hvs{paf36`|3|pVi$PaiqTv>8J~FYFy;UJY*G$z@o~iM3{mLt15~g%LE4NGzW&CMyiQt$I4uUH+__iAYdKe zoLDS|+!vSj@kXJ4DxlP2Xfl-r7{!J09*O0$3f?Va{lYD;s=M8vx_m_8# zZcyyYCHvJ&@NE*<((ait$q*R(K3qch#X%>gBS#k*Xc@UCk;wUbM<`@7`$_{WrwosX|p zGif`kR8&lhXrST`-!{+t-Y4~Xcp!YLLYdySK?7sjIiZaAyTMrct^(Q{$?)d1U;VsneY-f_v z=RzV6gOD(uPCiZ#Y+N)Tc0U88V@;2O%*;~9_1}I7k9xYhg<*FyV`ID=9MSh%U?0RO zpbrcyiN#u&pKguL!|rcGaA==cx!&L1o^FrxadP4?VIdDtf&9e2GlH0xmse3yacpc%$i>SYy(l=i3v4wi8%6Q) za`mU4lG4D?&|w!P438xuG!*bon|zHzaKiW5+3qy1_fLQeGNpoNW@qW_6HFRjIMh7x zdAW)uf!)p*m=xe=Cn6MjJnX5_zaDZZROz6;RRT= zkTC$akaae?=NdfecEYtXQuOQH;L;5mJfKhx+c{xG$)9SuisWCI85y;;wCtFDB?6F) z!jgHdnbdxt6ba)&x;#FwIJ~%d0%A(qS>`$1TT`<;4l_Nw?zVl8vx8%iNDK`@XmfSA zvR_UQuu=@*q1bqMfylGqJaD-v3Sv^yCii2cRiKtm)H*Z&(H0O8klvdtH_y$@Ew7md zXQJzkeph|^_Fj^mnpa3jh#5G;*VkyX2t-0IEK3b>absOkl&<@8ABAI|WeBO{A1tenTIK){}!?q@s1#r)NKV};YcaQDI$cN3*1$eMzJf|;3_ zE-o(h_gxebuk7qN6c^uu6FIL=Hrv+F-M}%YAh6=u-Y}i1=fPc+zZ<4U>4ke6mX$^G z1R9wM;ot&+nk?vS*%e9t^i=|f)dYtH{HyH(?eYUl5cFl`<V_KYna|B<1_2l%AH9)WeC1p0$l3-!VKq zJUCdAkpa1iuuU&a=~v=~wNJG`jP>>O^n`^Qg~=SiR}VT8)q;4ytpk~@(t^z7dsDA> zoc=An3A?$T+o7FGr-9{_(=j1lYD=@V zkkCI1ywWDGOWYRxEI1DuR#t^P|BYNoNS#IR%nVs553V*XEp0{jbrZa}v|JTAF|mN_ zp5C7I)q6b1(ngwyCpMLP$2(?8WJGK{$QEtm(Oo_yTFRiw=e8%78JWrIHvwg+|pmv6+ zokJ#esFoxNPQdPQ*@)i*txz8Blh5yMJNF>DOPJw-jWdLVhva$!yWTeT3?J zi3}0Qf5N%;9 z3&ufD=0e3++M4+uget_ec~=1R98;CfdBl}z{Cvp8Jc3q@1KrU+CG4iud?2mcV|i(5 z5V!ck#Ahd2M@Q$=%!N!&FppIoHujCA3e=aCG@0M!ZDwyKgp7<#F@@jHNkK^oOVp0< zoCnk!suQkrNXGN%Q!az}@Q8@^O%PUz69F05He5}5kogRGhw zo+4*Qp09)n^ZJ2mfmp&zOd$sche4On(9o-^tG-rxFb(6cRt9e|`U9W$$VYPKe6H8?VUJIE}yCsqdR{tnq;Z*LE|x_ceyT>Mi^pZDRYTwlF-Vbsde zV`^&J*4ldTY49Avp#ka)SvtILFcu{ZpK0TD=c71M9?QT0FfL$tllU{p?Zb!mxb>Bl zgRmwS-;ItYxaP;okQ-cCII8T9R|=_u_^P2QZyLP>a9t67zD4@^`4tzlpL~qY@2loJ zU^keMSTCKFXm4;>?fIde?}qP#B|ZX5#m{{>LzzmOS(4mnOd>m*0Th2Krtp^<5Pn&L zMA}yJ~dHycQ=OteMwan8^eeD zY6xeisLMbx@9q(pjXecx!#5YIWDKKJz8S>`M8)U+_oe3T- zvYBEWH6XNv-H)EA{>hR-;}zoXM3-dET-g}PCRz!7{M4ZjEnve#2zDo2)ZsGq9^|f(JvW=lR}8;%6U3kpZ}~e0_-uF&h2#>(|7DmWm1v z@dUVXoMZuE*(bbQT#^@ZBY_H5b+77MIG2jb%D9#|dADa~^sKF|*KiT#SL~20qDh{^ zh_C%&7!#mxXJll&_)KqqQ%O37UmL^Wv@r<6+3}u29C!i8o{$JrB_$65g7ddwPPKp8AaHwPdYP7_~%# z*qC{FKnN)T!C0|@Sj6J^4J#yvT9%ZTy8Gtl<^Y!fT}~i5-Rdr+a=6CP{JCHrCo=p< zB9|%ZSXEk@{-%vRfU94aSHD6+Z2iH$!V>1lvycac%o1K1@=25aAJ939$lz;F|JZbU zr0|XI2Td>Cq{6jQsp}VTfAKGm-#=(}MEdzZFDL~5Z(r!qhqJJ-*a0_iq1lg%iwkHa z)s>YP=;$lDIJff_bL~&+{Vf@^5{Vmx4AkKf&s6Zf$Wj9kksS*1qPj9AV(&<3oRLXIHX7 z^iuTB_}xg}5ODsH(24A}$5>N-Cvdh+PA1+{K}1AEI&VrGaQB?X1gY7hRSN5K&h=xgU5_C3}9xPf$gTD{5|sD^X(?#LV* z>bZ)kgzWktzX1M90RZ>mH(O7;++5geiIWL>Uvc9>xcvefU%)$|?9hI@y1b-j$XXsG z{#tbgk`0VG?N64=<>?(A5~5YZ8+vkK>(-GCpyTPLw}}GYK+S4e07)>YW5cP0y~YdygE5bvD!w%}U1W-U+Frs4(aO^- zo*VhDD&(@mZ`2xS)b>H*F(MRNddY}#kPFnnqm^F(g^A?<_2IP&9J3%$Qc~tIN4mJPpo&|0^IlI)O@WR~9v9XD4Cqb!=iNQI3O9jd_1qaq_ zqL3@w`5RYEC~fO z5#a8ezS!7RRaH0n0JE1mtiF8PCpjkFbq|U;Xf+U;V;>^%1QZbsAgzL4huu} zcAl>t6i?)yb5X)ktv}=8VJ&@1h6?F_1C}|4RDz9{H_p8kqdJ|8DuuRJntN$J+Sf}P z_@ZqeFaXY=x}f5(a!^UoLQclU@LwfUDi4D9r7}!A3brC*P0nVqQ!N0D#$MAB;J6bw)_zi z5={!#Yt+g|P~T>krFN8@AuxV}tTrREs0@+%fL`Nu$>pE*^();yvFnUaS*iW9YzPvO zG}Q`W&#zw%;2$|TRSXOscKD}@3(v~Ph)zs=XJy6Wgav7ofPjFMmXTS+lY$#iN$k2S zkU>JhZ+4ycK3`}-xJZnT4_1BpG*_cg$DRR_mk25_8WTj%ANzN`4kM~KAff^SlY@gC z%*<%se)p83UWUi%pdv1)Ho`FYLEQ%|c(hPA-higIoD$%PA(b5w-@Dsu+OgWYI&g*f z?sgIqaB@n3S3f|GkW*C_kSwz3vZgHu1I#|nHrr!`nbeVF0l8BPLYfDT1!cmvs zL;^N`M_S*u2BCd^s&saKE{81VWOQVB#|M{aI|@Zaq)Kr-K|~dQ@#5FaOp1Yjz02mG zuU4qOpp*ffHO3;6ga`EnhhlhGSVFz~*2s5oUE6aFLNt@09s~T`HgjOkY;JOMaTttA zp2TZS(g`PF128p!5K@<5PIw6W3d-Z_SL?Wrd93MgngtP81~tU)AWJ5kn}-Kn0vcUA zxwOhXpp^%3#|{?n)2uLEf((kRUeV7=y-ZwyS0rl0-{7=pc$(lMU3(XB#_)pG=hP=?`wOlQLnE>2{ z%10w&k#OgMnCSkEQ;3tG!f)Dx_w?yg5s?P7{-jV=^TwiqP9PL$7HDOHEk183AX!|+ z7aBFWxlgB<7#I$YkIO460^5W)@gdU}CKKLXUbRk}{tG0;#G&|*-PXk?TXl7H=iB30 zcY5`1_IEdz{>1gc!NH-SD4jji)6;WvY1wa(7)YOU0-tu}P(F@@v9vMI`vWLlQq+{|E7@r4|SO`G|~!ooswa`HEmjo`z)o<+mwZAMUtOpT7JOGr=)33&pD{rmUt z*xeYXnFdcyIk^WNs1Hl*G5B~~$$tbVOPYUaZuI{*y&x_OmK1EsJPM+)sZ5Urw8ih= zzXM7N1RMWVuxOEykz#ij*~;EkM`iwPcmE}ZsoT~4p(#u^-j4sp-`?InQm9)EkV$_M zk0(d~%_~NHZkoO!1$uDJH0RmOn@{9 z2nlnuvmcX?Sely$f5Ide)T?!R0p>G}Xn_PnCn_pB(J|3u587z}Skp*SJ|OyG3hnPq zmIKWNpvKhH)Z^ph?a_SKg9QnBd3i(#Ue+BbN%~Db7?YV98Q7$xLO^>2#RT(u!qMoZ zwl*M01{~D^E#2ME6%_ixO`&`GwCw^EZRI(z1wBCVPWyAWqxqU3I}ZG4X;&<&-H+GO z($YSB_yC1M0n!7H69D+NMD*(2EuL-@-g5IR!3cA6^Xtn?lq*IJxROb2K+ye(9cO;p zn-~}vtf`kC>xLb+^8?I9O>nj~x($HsjeT^FC_Plu`7fpmT*m5*BoB8h{`&RwaJdTr zLLouHBSbt%eMd4h;6r|i&P0-#Dx}0$Mil%3STw~14x@<@BO=+8Fa1jXRMON?s#gPP zB0vJ0s&(E5TzzL*x5~;LfFj18$>z@Zq@=KqM5quPl54_yy6<~%RBC{X433Q8dFBNN zKXQ>GYb!`jPOhyL{FDj$qf#<22AlKdAE-Y9Dn!BLxc}F$!?Uxv*w~J}U$bmVGqZ1` z@erdx6I@?gquCO6J7^voi_e;ygvTtrVr_)H99mjgpCnWHW*2F_P*H{?m_;#IoTY3KKL;r zVvy!RQ^mOjVrsMn2uD^Xrlk$MV0d4sR_8Ucb4gAnV5J-`x$3?4WF9Xn6V?Z8ml0`d8pOHc(W1P*JJUp6i@ zhtfSKEDTi|>5JT}SLi(ef``Pap+bH61I2j&N^X}-X>I+0LCT>#`^Az6L^p((9f`9K#@SDAqsvyp{cGO)b97G z*$D(B!r~cNYO>p-!^4&)pu`ZCAwZkG5V0vK4YIy1+A~48T|xN+7`XW!(CD9tm)-wf zo&iA5OJ$HAJ%X9mFia4~@NgN7OJW8N1Mtno{-Oxtakdj$h3%Ax9r;cQdFaodEwE!V zuiTSHAh1eawAftlOg_ueM$S`)fZ=P9O?mSmoxvhY!2zMsuAm zQ&KY#n?WO)R2ZbMzQ@Zl5+;N2W5R{cW(N7xcMR~0MBJ*&RoQ}jn}jRKqXC1I?)P-`8Ub@Ycj9ooX8la^GQ4 z1!+d!Sz5}<$}XvaoyWPk@rXGb*;At?jsPtO#FAC-CkHDlMzSq{ZKcplSsPx$dz5 z*|^=0^)Zy{lE1=Y2wuA}GEz}mS~^?yBS$@vbtAlQNn1|eKY)+!O2B@p9Z<;gtx+^; z?UHX3m#Y+rrFZ2Y11ioIbAXeipEK3!m#MVvi!chTw+*n*&tF z*N@lm+CJWz0_qA%tI%I{7;-5!HTit>`hOs;fVd2u`7~vFZ*ET=1`fy|%<=00)s~ z38Z<|4|rufi*~EgBZ=Pb?vVK|AO-Y+MYr~m=S;I&rYiK7HogcgLDe*RJZtWR)a3>S z34BI>sA~~LlK`$9;oZ`Nv;zoT;BwB3&-^~m5q42$pEpnE0;LUbfqo?^)-d@`0&u!A84?e4 zG1jg(59nsy$5`RA^4j|FG+WJQIih+7;0N>mq){M076^KJUIXTiQaoGvUK3y~^S%UX zHGPda)XDp+)A>A=Y+zks5OFL3ZGk_?6g2uZ2_zB{5)ivUU(Se#=mVq_$cP9C2r74= z;DdU-v;ZnAI4nxH#85)AH6BAwLZYR=-x_cucX#&(LUfCp-lKpWh@AszH?*__PKFK; zWDyVoqNA~WYSfhWS*7@Qwzs!UqRh^E!mQ4xm$qq*FF%%ths%S%E-WZ8Ha7M+-}7GU zBbIJyy1%PyM;pop`qRIFizIt&C_HxM{pohP0-WJI3KmwA!)jPSfYgI_Db&cniqGsT z6HdSxH9P~*~{2-h;LV3}~90l8?`TU%9h2nqOH_A?kDU)AQVB4W-`d zE`0TRzo~2CWM}g6aLX5~$uj7zKiG?m^Ji@>NbIA>CuLj3TGxMyVAj^VB_$kvc*i9O z+=1=njYgdvOprD0mw?hsp0ST8{0yxA1ypmpdczj@dP-^qyNJ;;w?pG^WFFq2`~r~5 zXg`Sj500Ps{aRHO$FPLeczbiAlont%2Pyz1-#-2J?HjTi1qB82CI1KQw@kn^17xgi zj28%PIXO8%qZ7BIqRDy}7znzjt*tE}d3XC;^4BN&R#&&z=L7xy9eX#R{ORiI>f5&m zWwcO)&0YdeJnQfkUg<6{2CGU+2K)NZMNpBEf4U!ktE}V+#;Llpy2TgzyO{VCqFy1y z?FU&ZAz0s25z-Qm`?Opjw1mov7yJ#?chw}weK@^z)F0;10JlboN*~w~KN=(HxVU!mb#1aNjD&+5A-Oydm z=oOMU4Bm(R+Y*d_G7skota&oBh{CYRPaFjk9VOOasg+J9y#cb8@dZVmBH$zLX^f|c z&kYd{CoOG2_M5bJrH5XkP&YUli7Xt{3`?xA3r9Ql!OE*MJ;?2 z_XmpzI&#v4Y7o0hAc6W58mDmf+M%}wJ+;FE^4B|{dx0myhJoCnp<%WMXE=EfmR|De z9DH8wU5K9bZ7jeF+G7~_ZHtx8g}&9fjg6uNN;*1IK&8W^6z$92hr^bBM-4roEQvDQmcae+ z5h)jtJ(-O^BO@Tu+ZjJa4Gt==yz*BfGiR35585#YAaCMF34$@Ki|tn-q(pW3>&c1J zh}ZdEYGNXBus0BDA&~+8{?VAm!_uyMa}D7(ae0vTD$lzc_b1_NYil8UK)m`1LJSQ5 z2t<^Onr|0R*e`Dol2TJs1NJaqW{T#Z+RdM{^9nY(a~x*7*~W+bh0~<7S!vH+c0$UP zUMX#7e;;etKM$!Fte2nX^RAdjZJ5XQ;*yf^!s{3GRJ#898n>q94|V4_?A{k16`_#U zK6uOswG^{-ZHP@8X^F31a^AgTepikn>RYA`nCK|sO=v=1xM%eR1127R)#!K#Z!zv| z;Q*FAp#Rzgr3!g1j=CV`=Hc-pKc5zAq?j1>JO-E3zycl=ZhCrpQ2c=5;BPRF%i7f$ zm`YAfDMZM{kuy6{4@BfoV(s`=EdVYye+xw=JHx>##b;t>23RhG{xvgwqDlA{cToAN#&X*fG>{V6&D{b zR|f=c-y9Pfnq+TZ@krd9A!IWzA**Hd&M3+z%TXqD7Jsrr7j$G~P^}(y z&7&bN?(Ib?hSG1CjvDY@qkk%f{nZ>V7ezYm11Z{q=&w$b9oK-U+yf^_pLswf{0{ZY6C75mUhkbgAcyxMjU{{Lbk*K_O#;*4h zn~Y3vDV-M#jxYkflIe@9^vLkA)DIFIoFU-EWn@sHp`pDsTpfvf5)Hrb43P1hda#DT z>HQ6G-5WhUrs?dmOwD3_&;YZ!%V)`I5b`{;di5&e>sM2{zr)y^;OaCuP<`F8uR(Xyd-Fy?K>=sun9~z-j4pYXnBai4@8xP1FT{dz+GTw4Y+QPSp%7b-v-QKfa~u1ND9R3;1E$z z+fPnT!0IAFp_LXxOTeYb%g)X|{s$a2!tUpQs5vY`|AmQk|eVg;`n;8%ZK7IZS!f)7pE92UWc1d?#^>tf9Z)BMTeqiv0)?gJXr7phc(K1tGQhqP#X)& zqI{I}dU#MJ%M1`79qJrNbOEg*ZKBOcp33XjuYpb!y_8L6B+AWQ0qzi>0KIXnq@rFI z(bQ52T~yTQ&y@6yz*Hy5YH*8sP^zZOOyzm6feYiK`q2^AN2Ilcwoi$yaiaE>Ic_9 z3kWH-2Auu*!ygeyI#WUbH&v5PcTi zPpPgx3Q#|2{hZ!T4i1tqsAupuPLjTL5?~gLl0F1z6&S_&O-D~p^UO??mT(EQGvwwz zDO&(k*e^ci!SmZKKw5tcia>0xv+U*(#1#jGTU>y#6tdSnYn0gEs0I8PEIe_bpXnZh*QqVyk>2P@HPfMUbDI;)% zxGW+RYr#=D0OeE+s2~J@g8x-P3<}^E@+fg}9RTqI^F!R$Q`{^pEF2ulC9Xh6k*@Pk z4*)z@P4hXN8uLZdqv)8J7GN0NE5QNS40NxEj~@Xmj3K5Jc8mU14hJvrGMeDMg~fpa zby;f?;7DK`!C?uEu&mL;5di=I28w`@hGRTCGeaaqcGls~vA?+~0DNeFe|Rx5F?so3 zAPWO$+IM}B_&*5zNpn?*)v1uv#=`C{E07Rf#6W0%`XmWFq`wjEo2N6V8t^ca zg!CFBJ?j53>>=GDjtXA?`*c^(g>AtNVGq)ds) zsV`V4VZTcD#vitcEn|;O1yj3VAhUaR_RSA^0Mb|2)-*tgTUc1Yp_Tojr9X;Yr`Y4^ zgW{jJ1k~Gr@82JW*VNV2(9zK)B_%IbK|8zxjpOeaYkcKRsR|6@UJ092lCth#D146Z0GL)_5*4f>~u?A zS{l)7;iqHskPX;^0t~ZYU|^u3qJl@6LCFG|WCv#g7|Wal?P;MUKn!*V78xM(i-ZIs z%o7kQ%V;l$H)JgnK=X$kccgi`}RF%!59n=WC56wO6uyTpa>C} zufct=YGRA%@LdLcv)=O@Gfmjz1lh4ih0SGd@&*ijV{bp{5;P)(Rk;(^DZb=u`gE-X zW~$*BAx0&vG*1i>f`AMsnm-bumg%=-21_M$8062lrSIt#iwTXYax5q{U=db+FoJDCbkl6nlBZ7LC zir{~uwvv#4Gus$&6V5k>f#Aa#vH_Tb{Hs@BByh0=s~4LAIWHQs1a`R8fzPbL!A=dI zX+R_;ZC^15?5n^)#Jxit=s1mRE2bH-iZDAn)^RHs<3b1cN1U1oS^F_7q0s)!U3hD$ z;zVb<^&D}#4=UB}&C5M8Fwl<({4j|EL0~Gl@U@4=vm3bV%?PltM7Y0jfDVGnZ#606 zaU%YtjnSVi%NEE{a{miGrEvq}DgQASp1T967;@E}fRkC8`7EmXe^B<`;av9p|M+QT zWhP|4jY?E#7}=|&g_MRJr6D7s5^sBDwv@_9dm$lvWmTe-y@|+ zOxn?@7t(;BTfOHFj-qojpAD&3-TIqR5T_N3-#TzG2{MuMP>y^iRjd6>A6?(ErVVW{ zB2G=P-!AGbkP1$-sb_wg8eY(Fu21laA&t|A7d;Eh=*M9@D!879dj0x!@Z|#%rubgvc}T_G zwj5Pn28uvs{;y#b$pFYecS_;EVC~)a?=~468e04)I-1LPD_A;qiC}MVwGvw|QCXC| z7v^9Mh^lkB)R$si^8NdF%6>Ulejn(owK?SRY6JZJ3lD{OxeyFQK+w`SQ=vqzVjx?A zucekT6e^6oV`KveM9V;NyIopVmKLs&xyUU|49{F`@dl2`tWPr+1il353&nmpFK?F# z3|nj0E**LpwMcgIpaONYPX$m$&MrPX9FS1sZ_D4TIK ztB9UE!|fcm43X^2Bmy-E({5EHE(d2E4!uBlcC6+pgr3TYIqqWVj!O;Da@8{Y5I!dt zNb3`NZaEjz*jaqND`zWd0%sxM22s{E|5K!}_bsWEczLF8w?(S<$J*L80kl?e?xz>^ ztPii|5LNGi(C8U$l$+PepYfDnM_OZI(Hhkdc+$z%?9CGg&$j1ZOkIu=^q)Kc_irA+ z#s4z&@&T-T_wU`ao)~J)QFJ?ent@v3bN%C|Pev1{P{68%rdCLr5K8PUEX7lK_O;@! zeJHg3M?;|L$_ehm7(}jjq&DH7^$z3(5A(_;h6fL>$e)>>KGmEN{@x2Tc1%nR=S5(C zAldw_i=?hTB$Udw@ideM1C}MOVZI8@-+4=ktM~cy=KxL0Vr8VI0pRhoUm3nY*!10Q z_BK-b!rVN4U7JQFMX$;UN5R65Ca_sP|P}?>*_f7lhFP~ zMMcxYhvUjcm^r7pF6Kbzu}gG}|8HntY_FU_a1}mPRN!mZu&><^;!RKnxgTvW{+!}} z;NZa`fuM_}f_2+>@7_A!-)~>~fO|Pno*V3&$j-_Nv`uvDo>4~{lYRTFEuqQ)S3bco zZ?pwpY1@t;mP`?6ixn15O;l%~0)-#(Ql1M6EHn&W5cdUeuVo@hE?diIOw53IVbXy4 z$3*im1~T2x{ydud5_6YRAr{@gfBzro9{V}wmh~372X;GBq=irsrI`^&d| zlj)B$>0!u!`2*@e*{`1?f(oaC{m_YU7rR4|FGGxKp#$b;a1toe98j;!-R8|0e;nA* zo(tmtjH@fpoOOI?;?t&euY_xBmHyt6dQG!+;c@Zh(L77XVg>f;T{j!%GE4lW+r@uk ztpP}qckF`*^V=r^kda5N!NTMlV5}zpaOs*SZaW-;$mu3VlO-XWhJhNsP?M;mWRYU! zbNjZiFHPjU>5)ibmB7Ec-+CDtlF5I!*RHXOGzh~)C-k12iPwr?@R)0hc@uCxd zsV1TLg!<@BdHF=B=uCe{N1?T)^r9Ac^{L@j6}V%-x}Q0mej&IHo{katUM7wK{q7t)f)tC&zPdQVpM8d^E?1PkrRm12nuNoV7V; z2d~A(R;ca@eP*7{&&5R}#_)~m_LuWy*zHXdW{;&6c+2vW{99dFx&q0!*@BJv^e6zW zI~v~VEFCUdG)y5(ifHz3V*Qvpv`L$PtO{^)NJu{r*`;NTvQd z^K71Pub_T|;N^xC71%tucO7HTg}EE1xn>CpAW~w>2gPF0y_B|Wxz?ZDaI762R1r|H zy1Ipqj)b%{%V&UcQMn{2WH9;Ta4l2lmQz#r#ziT^NnhdFgGLDY2MuV|FR32Ru>$!6 zlLlTIfA$hK0o9AMt{_TVhC<1Q`tKHJ{0=DYO--jwxw*LsgyeSt=nd(y#<3NR&};&f z2ut6iDd=y&S$lqccjLB-`*^5?KR8`<>MjEt8}SWBUpIP)%8XC7n&}fDUv#T4LL^>AEB2^W56jYOQ zHU#1iX^LtKcg)Pp_mQ7+3ws`y8CjPVfR{irdkT7#aiE9WbalxV5yb^u zBjwh$Yk?j007-S%e7*O=l*l~Ys=Y~1{3Ha#_80%*s$)&184{j60hSzkNwhZFvf?O? zS`o^`UA%G$2@KwyagmW9068@@IiUO)8*`iR1?Cyu-P*tEym=BW=b%RObdbNlkcO8h zU;r%K5D%~}UCJXA4!_O)2M_LwZO`7ysmtbr3g)+{Mg@)z!Iz;KaTQd>)YToJ+>B{HxPzvtIa@ppsz-odlmClhx{SFRf{vjKPri z=DkGwtSYzes~{dK|NoGumCGzteuhv0VQq@|)c?|_0fxcuf<^m35H%*X--wzkEK|ph z_2Erm!Uf=7^YP<2mQ*R-c|Z<%B>ky_-mReEhE{R>_;H~r==}bw?v_p?f&WU><|Fgm zBcH4pTFm;nW6PR*E~{L5LvINNnM9mflw>=-xga*HH}*teb16mO$ksRgBDe4BmQ^_D zt~6lZSSzPLf8`s5@)iIv+o zxrL}$R~Gh?Xa6MT{-+}Em@c(Kt7)}MP8N^^Ncm;_raH~NVH+)T*uv?wIM;C~6US5T zFHUzy9%xOehV=0QG?tvqQ!!oa3HUmrra)EO*p==LUSDUrcke_Ahlbh9qiozY_z&zH z)_VDPP^;rT$D17sv=XDW9a^)OmrK0#*Vd_MR2XGDOB@I`iYTwhj_MI>|5#riR7st% zn)wNEPVQ5<6H%NqSjBKrld+|x^> zN%GUt)htSck5`p2pJmJRz&DT*M@#=0ZhINog{V1?>uGMmDm29HAEGG`ejW{dW#qxU z^RI5-ZcRV_X}au<+p^P!IWFC618j5HLh0h%eJO|dU5Jn0TXXmtm%hD>+?!EXOkm$v zz7a0Ol88!4$=+GawZBIVgbhT1(XGoI0S0iIC{ZybL6Y6=(Q^fD!->Ff#b<9?+D+J+ z&UKaqN%ZaAx6f|Jvw{MR^aot*gadX$0HwWsecg}p^5(I{)qVcVAYC*&+}EdgcEBVn zs=GWA;w)1WlhHRp<~67N=_=m6)0Ht}www>9+AemMfr^#vAn0e;xSM%8cRyh?XsJ2p zLr2wN!%!TuoV2`g@rhq#kDzIHHDjX^UA~(j52L~ey;izh z57DN1@Zjs@Wcn}_V{uizs@Thy>C}$CXliJ{a$78_pSL4JXz)1va~njagjItIpJzD{ z6|IfCUsNQexF!jnO6)mlnw&zXdDCm8O|74e*D|`ep0I6pDBVo3|5#?Q0v$OMzsL)7 zYg_mF-Y4;s@i|LUj+A3(Vf{(~om!5w!owrUEtB;6wQ|?0mOYKmW0UbOM6QK(f9~qC zQH5^PU%GyfsK(}MU9uz^fA1yM&0t?_2Ar!48#{PxayZ@!n@TiY6+G6jh>tlGAM*&k z3*jhdS9JwP7$-Yz#8qRugHHc;YN|7o#CO>F?ba3z9BS(*};+`8)G+|jI%WK!q8(22~(U53# zv);?O^65A{k6` zs5w))$Ux=L5smtER|9)=jrsjj&+ZfUIiAj6Pi7`MTNTQ*fVTi+WV}l;{T78ukHR>b zPcU+d-DhZGVPkvt{Q1=Q_z9nkwqqS-6p?q>c(l?tSJ33jZpx%fNlSbD^y$0z?}2T& z1IdkxI}E^SZzx+YMtHj@9&kF~I;Nr7ag#JMRh`PRrh9%PvEj*5Q+#eI6#r%a@lGFJH0ZTX%QK z>B_a4xpen2epDXjNtp96o&V#EJXK$(zpI#lLXVrcFOaMfEJ36%`aJ)?&g4QNAeX!nQ%<*=C5I2oIQ3dV)o3(zkr`H4CFC7uZj z@StS{Ve|zo7hGy^mQ;i$2TU0#0;uzJHGm>9Y)IU|QFe#fWe4oD2d-v{$!u_=T zJeS@08L}9!^}kdbovumz}Ad5l4;_yF{LBprOEd)Q) zmF_X%7STTdmo760^^ou5L-W>eu=NeUpPsM9;lp8%u@lucPft(7WA8ckhR@UShU&Qu z>7-kYsn~mALKFn(G_h>ivIC4uH8yPE=73t}R%~p;b8{7}0Iz#1MmhJi7nF-BjpY9PKt_|2wcHZa`QzqUhgh;yk3TM)r}i3j|dRsrVoXy zqEAA>q~(*~0J9&b`INcReapj#1zjrEo0ZTcC;-i=T$PXj)qj9~_qvCj*feT3P8sV6 zQ@@J@qIVRyev5hhSo$Re&f$t;1|j0oTQUNrjYDH@v^!E`YbC4&R#bW+s-zPE@=Sa2 zwV9~3)(o)ow)M&d$5rE&7a-`^^OF2gywpDIL8`N=O&JG~gGx;HK^hCdY^U>*7fDvd)jC`ni*sk9 z8)!7Yp(?V55w}58falv-6`hM(O=|Ux8M%BTy7ukA`jpP9T_83t4n7&uTzDer`?cQ( z9a?8(62#1}i}PhCB7tYtO6k@&G)!ZqiE^W1Oo1!!<40p}@5R?=`qEy|MO^`(JU-9O z$<92*luu(plc<@-Zq%N7BuKwYaS@>(*d5arSt$qCe+h$mLb(o*Jzn7t>)s}A^4Co6=*^MxGvguOkbU|ZAs`P~*@Xo5@YmqQYdO)SyD zP^(|9kI+1DfdAb#%o<2X__bc>@sd3MTv+K6^<2xqM3;^blsQAKV3~LHu3X0?f4#Y7 zHv4lVvh+N9Ov|Dy(_Pqz0F5avM{g}I)~09q;{U5)5dvulR!Y~2i_>OoPcR$sBAALv zt5zli+)BVoZh^Y*;D5Bp5GClnGb%Gv@hIDvZXwrU-95FHz=S+lD`?V}-@Nd%^D6~v zjO^^Dw{LfJ#De0R8?;>Xb<#c`9U<}7TccpxqDmP^kuPk@)QsYGJs+?gP+}#)r<|Q*{&SQ_B27QaMsVO#9 zEXR=6dep0(5Lj40hLo})&Hszx;GglKCm}J>2rt~&_#@EDN*8o3oO-uz0llg?7N1$W zkyrH_h8FS+RSn(?z!w($lf{K_i3J$(^?e+mOdKN=?bj~(w;k!-N{@5X4`gO!e5tDg z>v_D>ZP7yN`QU&2|AIq8UZWPietpi(Z3^F&kqA0 z5JxRhetxAhUw7h#OI1NHSoQWT#$h^IS}bD_7o<40=abKQZsLO!PspO>T%^VVb;!`v zv;c@a(q=G>(+|W$PyQH871?UD+r3~E!UPY~AigRi<>tw9*tEB7IbRVa=04m~`To70 zC_Rr+LMvoT@LM%EHh%v6Sy7Jf~5_~5;Vjm#8j(w8rP!Zi2(-8+nO zH6_67qCIka(DxD?rFsT6Fj59WAP^E#2|gZn_GE>1S70 zG8zv;-Vc9di$@m~qDI#djHe!w6NR&ze?If$~RSHwrZB2GffeMS`$Jh8X zzE$Hvtms0^4z}zia3=zd!}~eKWQ*e>DH>_yfT<0MU_eSuY>_SjkTg9dh1yA_)BFUl z#6Mt!n!Cna;BYppvw(`*sa?C+Oy+>ELqa5;T0%`c2!x?d@qdLOtnrcl4;VrR=q^M8 zVl$ZV#m7X>kByDNuu*aZJA@oo4#ENgvw+NH^QXJ; zEdzI`bS#)(5)cs<)|`FziN0stVX002Q4YI588Q;qTa`s5PHyAAq`J@2Qgjtvwck*a z>B#dO&u(9Ahf}AZ#~J1H2o=bm9gv|nNZ|fKBkXkMjNcWq^~!9kgpy_nyHIdBI5`x< z8l(J$uu?v;QTK(pnc|B_e+)JANo?MglTnEl`oyg!rW`k9Pt46R$=7r zx!B0TKdxe>%;>FsOmOtjL`vh6yS(V{($jMP@e!Wdc z=WbS316*{3%;<$$i&2dXY?=jxX%85sX^k}+Jm$X zesr3{Z{5D$Ms$D)XR8%$N&RzuYes?w3Ko$KM}n{Ecb+8Dh7`I42*z1vMiTkYOo<5& z4n~?@mQbbGs4^8KsqS5^dP0s>ZiNRh7iLAuH^SCk?P$gP`wl2Qty~-Kmtp)`KK8*e zZxSspS0jqf!w)mKH&L%e*^biRmDRC55zs|gYif>II^nF@x+SFY@s;rOCk(cN>O zK3$r$0X)*fM=5mFq>ld`H3(Y!%1I0SRe>BYI0KY&aLN8wpf}N+HsYv^f{g2MKGPfh1;^zCKkk?bRzie}*PK zUN0br7!ycegTnfiEAQ2^6B%?z{A-<^oC-Y-CbrBx%k;X$UK=&vQG*4Kv*AA)K<<9KCVJz(meKZAOpHlys-{R0aC>#9+{cyYe2 z&Lmizo%5k+Qw=&$#p9S5?ue(49$9afj`!7`PRz$@$$7S4{y$KGd(6vL0rSF^_3S_@ zWZZnTn+wl)T(~g!?OTzerU1m7hJruIOuY_C&NFVWbP^T|D=Uvf+sV(Atf-_EYcAVa z0;lrD{d@Q7XuxnnyJPitV!CS$w|BJ9inZ(42d?OfxK5VZjUD$8;I^bL2IzEuvk}fO-_GM>{^Tka-V(eSNyx}YY*Iti)+TWhDwe(9GTrmPwddz zdWk<8w2(>MybYNNV!!>b|3fSmM|2(hR!<&3_JzQXmiFc&F$TPCUtCD_;>Ad2yVtMN z7m&qJt02bsJIK?4%jGvYQp@|_{@__CD2dd?r(h2bLZGPF?s+*j_F;u!ZyW1~V|dT) zfSZx`!{bglVDikt=MuVH=4P@NFb4c!>C&-u{2Od5kPFw@(UF2J0LzJv-oVAXuU@@^ z#1?cBt81E_{R+mKbY}_tP`W#`u}T#QQ3C?r;Kh&e%qoH_#*&t5`k#Fcdvvx{kuUTu zK#pMI?(grHl$3O8@}q;+1B7hZ)F6}&aF`k3^M&$a3uwDPlRzEOdpOZH{V=liMflELSuA%~@FdLX2#2XOeq@C{pKz3Su z?Di$n6e%(|Fi-{wkLgTT;7v&W{N!z_IBC*%V*(4l<|Cx}M7xRxt}d^|`Ja%zeBUS4 z4z*~aHB@jT(9i#1o~^Qod9MyA9w{cIskM6y&as5|HL9wC$;VHggxOt?b_FkQ;Q7(4 zwplx^+wicuI5{D%$9I=c&&$@>(KfJm8C-r4IALF4UlwweUpy3d#hrjy_uL;E;Yvw+ z$0L-9LpXzJnVH8_esqv-CFHuz;B^|B36(_j4X#d~LZ7i`Unxfqwa&!U6tDetS@^Sl z{e+G%4mtx^uNb-lS!6Bqmxh-=O*D$-AV0qJr9H%<<;LtprF`9PbMw6H>_d|K)q8Hc zDBirhFYVvXb?Sm-g;*OFte>#Rfmq`?xH-aS9d;H>ieO;xInAe?YRTeaPDKjh(=zb$ zuU)P@MJ_fXzQo5Cyei%%UKda0)`_j%Gi4$9-a|!Xq&3G>vMqnlV=p0&Z+7)`P!IaM z#tX}4#?$7AOuTx_r?{k49kivA690Mw$+q3wPq%a!QAQEC@V#D;#P?aFpAI1?%Y&K5 zNHQ74jLrAY%hKE-E-o(lf<|-i4JiY$C$?x!+WQQ(AexZut&y&n`-9|T@B5H3Uh<9h z(MEasHS5+be{RX!FB)-c%h|{I`3q#;LM!><8X}X!$js~%Vkpd3%*Z#{wd;-!tq7hI zd8E3@;<1;H+7i28A*p=4yf(?BTRcuUIs#y?-kv4$+L;a%;|_g&koG=t)+;@o2b(ix z%kbK()?NV(P$qM*8JZ$_R+c~#S<@mht-4<-M85gSUg<{kC5r#4%PkO=cFF#D^zb3m zigiD4XG>yoq`GwyaC%0$z2wfiMv5su#P4tm*%Ja`zSt9&7c@*t#3L^jOFH|9bjW4J z9QiCf92gdxOlO#&P$9n0G3lKgchLWf+4R2zUMESBpCQo~*Y#Xzl5#nl=Gs={hLwbvRMB?K!OVvTtDvj&l05K5CL)=p3XG zPQ}0{ID2V71~YfEa8*1gM2kt>v^yP$+R_fKn6MwM8(QZFq7nBA4@*YB2u`v3C?oqp13(!L*N zq|Cgax?JU833As8gm60Qq_~6K_5yv+L=k0~k9+Yc40|B8(A(P^cr!GzxujG8R!X1Q z8RTf*10i?kj)*ItBfv|%u`UasR7=cY)PB)8cC47qXEg;hK_=L8&2AivQhQ&R4blk+`3ZSzla+Te_oq3)+ z>UX6f#?*b+3W`3?>pM#UF(Iw?CNiICriUg7$H@E#WfPSFTxeyz0uDmQR?^ zyYeRUcMPlj!hQ>qTGG+zr-;kXVRHoSq3FOjqF0pDtT31b840=^JVGy$lU;%4ii*Zx zxxzEN&nIso8OjY|jGNFTEfz6*hzAFTt1SJTqQAs&E~1`n8f*|LCNl|fzej@tBJ zf8PG_z@h@2fFFLW1Hs@SgYS_Q7+{y0Yd>d>yo1i$fb9kb=mZfxtLOUSy{q58-Kd~2 zjOFo9*J{>Va+8abGvV&t%TZB<&xGOJh2qx#MqwHfQ2;K-u)eZyi6Rw6YA8$RfPo?e zx;f-I8aK8MC~+{XkIMXE*!!1n*?ahKGZz;nLy$ui8*3*(bbd5#%)2uNSJ6yMh8bcJ0T+`c#9z&-3hJw<$TmTB)%j$JV_B$xIcDJfQY zI<%p&1!i8eXOv1_lHqE?4E{zg{>dKK9C9vS#vV4?050cTJ|$U>!T<$YL?U zWBJo^jKuA*$jG1`L|#neG0^T}RU+!BH{ZX1@4Qr-k!2$F6rR~yfbQu!&0qyLWcD`pv4QwraU0@W23V2IcR`sC%cPKv&TY8 zzJ+QPwMcalh8)$Pc0SzIz+6;wJl|`465MQE$hmSCF>ddm;LIa8C69sAs-=yhiz<8n zo{d+eX-NRmy~?D$QHHl(VU?(-N#K-OB_c7Xr%hG$yYOm8h=@5A?IEaHsh!{Ik}7~O z&a$SaEl3G@JI`n7=?ofukNQjxMqsRTLI@KG?T&U9pD59Ow?3#snqFqb7FVhLJ5}`z z{A;u*jeO#1-Q4Q=TI5>2W23Rd($$+cFLz-bEX*Ofi5!G8V=BZ| zA7h_CxLGS~+GP9lhB`b&W)b4-#EhD;_jBDMFPC{Pd%lgnjY#-Q(9hMd_3%)dqc<%9 z!7#=vlu$9soK%bF^8vu~n9+xd3Xiug>OEVifx|lOlI#>n-o8~J3QUrD%MTL}x zhUlK?Y3<9{4?2kyX)$?ijnoz$2GFPxKlprs?}7nYYpW#k`Y6)ugbML`^u~E?fB^)5 z#te5uukd(KZdGY%a(cSSaF&0hqY%HuR+@7qzSYaC$_}3P)U{zGe3Vgze2>`K1>`d; zuI?bb9M}Ktg)I++c zXAih0SRK=0!ppcIS)Go;Q{+DW8SWpao-XWzJ0HXHbm2#TVlW+5;ic?Fe%kpf&ERi= zeE^TM<^dq;ytE1nS@CB7NNypj?I-$LAuQC2n?mSPQd2{qv-$MtLfjqQZQG8#H=Yxq zKBc4DXi0Pua#9)H>(WFoF*KF%8cYqTEV!_4`H}-XPKxoTdDa7}whudwcWAFCAC>oO_l!aO%M>ii%QUk1hJ4`KLTS7uadZ0?dYoEcM~`qjH8k`Zo~|IWD4LQIUvwTUu9aoOGq9y3LfW^vvz* z4&a8wQD?urP$} zlis~mSLJR3tgAUI6&e)8m?Ui&*>aBWbDyDI-}M(7o|8-;UaVzeD)Vg-=!V3WYRTh9 zpvfy;2Zb#69K9ZX@J-b;qhwPn9)fX*Zg<#4cS<7*ra%&U;M_$gr0E|^4uI3mPGD|h zmu?@~&AE*0>V}344kKO6;S?ty{q+sEJ_E?nmMd2ErTqp7jk|zhA7E z%zdI1JS|*^#$SDDCa( zK~H(`@S(nBzA%|F67?X7yywJwZj908;6H<1{E#?DIP=n_pknWX!R0v*WiiT!**rW< z)gL}=>%1Vy=p*ck$I&q`&{W{P7^yyM50S+v{kL!5Jm*d5fAnF!2WX)e@4Yzh4#}%q zUn}rMoQp{0r>k&3i&t_^`u#iloQHf-egIQ38R|}oUDhoDa;Ul91JOf3x`L(Z0**hH zOfxNjdE6aq4R#>gDE*y@LZ`MZyYFeZA%nRFzrbMYZF9*HuMX_2+t~hQ6Cj0!5IUsP zy~F2FLI^fmK#rK*bcBr}z5t|xsDtepPBU%??(!n7C!q{loxZGPT$&@b!QiK^G~n zS{3-$Z$liPof^u)H<=t;k&7xKwlQkw@VEurQsj;BxRv6&2C*FV(67*@e$z3X7iR)^>AKpnt{Hz6xI`&~+Ht3R7FWs(Rxb^L<>pt#&WmL+Y;I!RVIx{bMJI;`!*u z$DnCO@sB!Rk7w3#PoRzyx)KQrBjr8WUk^*v>SpAjzdl^^OHWZ}{|rp@Dff@8*#r39 zwXvxQ?)NZBFPaAs*R%+qU|aDd^XzMOLRj-0M1_Ca;9HhXqDC?JB#H_ms!QKBHm>Nk z7v4rH1CFoEhVxT@>Y{2lxiWtEV3}f7gv0y0YvUw6@4@sQ?=`z7o{n?)!CD#`8Z3gi zq{$kZo;xHxby05vl;&id)up}ncWMPxRKPN|j@$bc2XoN1BTD?VX1f6aNp$UZRC8qm ztjQaQ{nd~n8GIlg{1HtaQXXszILf<$JU{>d#0slB)7wlKaxR4Zi*@8-5n3yIeNHwD z#SNx}#fkXED^&;Wq6djW0QIOdR#sMp>qo*$*(vydvY)(o5r6Y0%NeRgqR{v^?Dfy?};SZcNNa zJO=ESh<7-2|2TpvKjPY?m>4|O&Dk;dEMgcPPGLnecFA1owS%z+042&k zga$r2^xOcE4}t^Hf|PX;Og`EAeqFzK7Q#btlu%0JV`O7y9-ElZfn$c0=YK|rLdWV! z`vYW%kF}l=yM~hO@d$ilZEb2>>v=$&KxiFLpS}ZC8J3a#6{eBD?FXA&#z0p0eEkYN zq>I6tdKy>sVmUb{*ov^8KuQ8@sI;tXpM@H{N?u;-ECCmSQ_0|d?C?AHcA9=48p3em zR}Mow9G(z4(aFSbu&Y9%pa02aA+iK436z6<267+430s+gVcjMJ%;l7s=R9AqpMLH! zXCQXwOMtFL1qc-iQp!PAD{yZM-gW-`7L)J`$6-jokmu^`thMCny?YG3M^uJM1)T@- z!;&66xQ^-X)~#H0ndk$r#SZ=D77&y*&+fsvRg;c;(VzyP7h$(TP8YVmW4)e}h)3kw zYK<0#i4Qm+Gc$8BJCUd7hIp1!{8yme1sLBU|MRi$F9yv!T%yxN#WVffAdxLppP%^H z03A0fB+M8HF@;KJVmBZAOcT0uU`MTRay9U4kZ zWwc_;hnZ0Z1^rPkFgyqNL+^=Oqo54MC`AbucUA}~NXuzA@HP8XU40tXeDPG55>C(g z$$F1ms3avHRai2#4R&;pN-}izB=d*gLF_|mF+EUQUyqSQ{d(9)b0)_|EUO19VVLSP z8RfBI{_L;)(qW8;@mYc+sTlqK@&g%c2+=Mkv7(%mlXMRul=@pv$E31yZZ8#Lz+-lH zI6S7NrZ2haMJ2QkeHixk1p9zOVU4#p^5t2arVw$e6wTJD2Pl!iCSwv~h2y~@!3oy_ z2>;+O_IrR22-8VB2<|%TQ5I~!b~#gG2ZP!gnwmmOtLD*S5|^lM71#nQy>kAmollA8 zhW8P${*-*eMZ49D% zb7B?NUjGD6{&EOSqeLH_Bx({h7UuxYEf)_rg*sv*f<-c#PXVb+OLM_DE4gfq>>cvT zl+~*lrQe!zcrw$+E>n2aa((_LjkmJTF&4ICh9iz#0{-#wq9*a-Pe5p&wt|CGJiwc= z(Dn8w$J#}6I!#ApUyNePa#awXj*a*UyJ4B6}dE10;~yvVMm@`u#CuJXA8a zz^lAaQwGLAj~#hqE096?66F(;VRZ>ZWB{N5@ot}!rCz(nyX8g2A}y|TNK8s1S1Wuj zy)4kM{!!j%V1m@iMJ!1}*7U3_C!-u#amcwdXGRS0@qA%{bOUhT5l2Uk8N@;`xYmC9 zborO%2HY$GKdk0)ie8i=nhQ@C0ik=(Q+-=F@X(+HItk2;xbOx{f9V|?frN6n&^Wd8 zu}J{II&|Ow5~WI{I@UqgV-|qxoT6;eOrZ6J_U4LaEIur;1}WWD;jT9(;}bh%X=r{R zWSAr#?jM7z7CK&=UL3Z5Ic*b+lUwmsoY5O*BrkLUU5icU%u3X8Sdg)Gqq6C@Sck+W zO-x!UvG;Q?K*E*YcIPkAd-@V>9Ua)4ZhTzKa{>c|mJApnE?MD`QsEUSy)YFP3vJp? ziaee%yAa-{e*|&S!KgIwI=8-mzfM_s#@zj}Jkp#{e#_px**rW%>wEx=9F>O7@T2SP zmFQk-Xwf+vusves5_|vbKjmxC)`XZ?MvRL*4$kvWiC_wL<;g=rqe2K~6re;0X+fu0`u zXT}$nuvp>i>g!wmbL&>XH5lFVR*vM?w>*6EgprX^MOm4=j0C4*Lfo@ltkmhZiq z$$6xN>zkRiKwo5QdH$`DBVt1LY93yWP>eg8>>X@!3;&W4oK|icR;mueZa3)o!Loqo zN2N@#fb0q?O~;7+P(uC7X{`OlEq?dWqej}cV85I}T-G&(VR$faP|k*l?&oJy%hU(Z z)f@JR1i<&3!iU!ll=0fd$#ue-SSc{BbUew**@?cLtAoBx)4cZ>>Le#eqiOVB2s*{% zAh;)ahw&pkfE1h%sDYOQ#$S85zq8Zm;K4QA?aP(^DBflNDBfAVSCyon!|8!uNqj8t z6u!YKw=W1OJz`}=URw#qAu;PuW8U@}DFV8>{>aMmXUq2OiT%bB$SERn`q(j4?jYA| zgOS1IG!^(&Bu7Cn;2TxSN=Y%4Y|G|+uK&Z^y{Z0>5U@@=-z}gUBJpo?bDm2dw>`qO zLlZxK%)uz38#<&)&q%1OJlA(bPxFI3gZ`J-+&?@~QphW1a1ny|rP@@ZiT7cD=81>` zjP)?4J2*VEy~0@rG%tIpCS+Lz7F_%K=dCy~Vh<0rK##l9aqmV5hl7(q#V6|_I|;j@DTws#0nPbs{sf9@p2(-KK-zR3TQ5cK(!-qso! z-Va^E@7`}D?mQJ(V4Op@!>5IP`zZW$x;DLjoZ4%~_!~FIX!nG9I@&fZEg6G}FS%Yn zP4QF%^+)to4(JBh>4LOO64o2$BjqM(w@E)#&427oU7sd%K+OZR>+bDk5T&%R zT!PNy8uGc_1+_8`%YQr{i;IXzc%OZ1xuPs6k(@tr{u~jBoWt_}F%t;T<5#{PAVkO- zD)o!oE@f4_1I61d4R0@0R^uS8;|LoJ(-S@6Z_78RBDt-uFpuU&5@mTl1Twy$qh&2l zVM4ntqHyW}0%~*vwhP~9Jh!?hB|V)-x~s1*D6@ZX5Q{SI0}!5(nKi>D2)NT0Qm^iz zp`qxTIv*tuA7^Kz)SUL~Dr9tLBUr*8fC+!}Q{XT0z0HI;(IP1R=>Gk(t4l@INpUAe zjTAGF0mQ)Fv8wZ&pe?6>&(q$?+ZIqVn&~4?vcNVKG)(fxKT7u8gyY!*kx${h76Ssr zmy41&(O@{0bF+~X0V-s(jl0#OcAAd7iZzg5#g2FG^J(YQyqI_xqIdnAfEP3=mdYKn zOX+`3K_`e@2}TBnkkU}Q)2FK^KViF2P}mRkT1GA0v>q22Dcpv>D$fTG{JbqmfwwR7XT zor$Cpo%Qdr;w{Ds>#Oar&#c~mZc3CUs^pKTKv7JLrg1g50n;&ndkHOu?~#JGc94Xc z&d*P=6Ptk(h&|A?3EvNj0-qi`vwuJKs+jo&Vwj%U-NNEdLz z4>xR?gLfHdZ`yuf@sS2FDmzV&T0j4WR)q`Zwy3C(YPgaz%`7kN=T^E=jc*s+%%|K5 z&mop_nin=a{W0Pb#S46zh}Bis8Sth_9zad(1~!Uw{|gu&fKp7_k#cMgwX&Fht9n1HB$S1xh?61GG7*?=&1 zUD5=jc@tX;s0f_}a<4b{x#T>HYbn!VnSA>Fz^s_YclWPKMCBG2-G0Qw(EJ!55+*SB zw_tRI+C|Jm|2@Rni8U2U(fiZf66HykUQO*VJRG$_Sl9ON1MWWikHCSY^2M#h8cuDK z5yy}c{BAH4Q}&T31`l7XPe=O)6&IyACmu;z8#<>*X=509lgmSD z{*J(TT#^-)g=I=kuP=`8mWb042n^-+j2@fTeVv`{^2(ZN8p%2z&;QoiwE&k5UKGVu zeK3}x!li9L!TQ_icXam-Nd@^731D_|jJu3UE$;8#zl{Q4A<`$-uYd0BnEAhX{x)1V zj{7j+&C=Zd>FhN?SYzbBL$SXh^)9H3o@W$+QoLMbiU+tB;KAYETndGH;SqLxWcRfc z2#}rkFsUQJTRZGeq8C`9_5RBr6beF0RrMQg{{_9r@{p0B?%`oF9TY2MUUNiVZ}kt) z++L5kyQa`bVVHzD88;T~gChVnqVai7=xD2ZJMeU`@ygY-lmBCE`B+}QEn0dIM<%&G{d13K()n&3PJhxJO@s!YeTGd9^%7h8V*lMp%JLfhwH9O??mqzh z{!!%Tr`~b_$l+lMT?OV8qE>t4YRcL-9>etq7+ct{9feKmIaziGc zvHzL9(2`XnPESn2&?ziY{N$+@1O`x2h9@Sbw5^enmd0Hk<}lufc%!*;uI?G*7xty5 zCOiR%e;AjN21aUEDrz5%s!L-fJST%oRhFJRe|`aCd+`wAK%PgIupijSJ;3mO9uaKf zZa}v)1UIy+vXt(6UOe_De#CRx@BkhUs6yO|1~5p*Q%;B|F7CpYu|bGqqR3tD3>iz_ zpRDica1=U%Q^!{2e_&N-RT^t(w%!0MS7X+6)l8R!rwA@ofsIkoDipbKktX~y64wst zGwsz~t5zWpU1e3o0y@B?L%yx+`}d`ZZ?q#<^84Ptb!%y-)(oVVly&;ll#kXkeiRT{ z!2@Rq9Fc%gilW~9fsriMXK9Th14TAL-56w|x-GI@E78b$q17t&jo94uC#J!`kw;Y4 zV{%~m)}T99W`D$#Wru4xxy^!UzPR%g3#H7?bd?y+Ei3|w@@Jey1ve^zVz4$IiNdAy zH?sdYHInV&)HpC(OLIEXoSyL|Rp}-9SeV#XxIc2{z4;*}EIkvFTNp2P2vUU5` zt3=W|Uw-1`Io7ArK5e*nugto2Zwlo{9Kx3zQT_m@l&sl}o+eX*r*ymD->yt!N#(K6DL@up+1|I_=|kmA((e#I~6hiM5*GFG8raX}@U4>5s^(3uAI zWS*=)jdiMcQpStTFEN3RGa~LOJ~qoz@BA^E7lrG;9XUj@et^G`gW=Qtx}Am!aWU-;hUWr=3|?=cZR~}(6F9tt{LYqt_`vZ>>uR)L zc23R_w&kDu2>7VR);C5}o+Z*IF`x-4i)WVPfqhPEI}g95$IG-de7ey(I#W)ue_|g} zd?!9@;O6=K=}l4#5M%2*p+DjRz#1XfY;1LRBh`KBG)=*SgpJv}{)u~p(xDTIUBRQv zfBSkafz%I7iFBpb`ckh?610W8hpb^F5Kt`a<-lLTm1 za0%bQO5pn2LieB}YZ$2_TXl6)AdraXBV?9*+HY(uKKYg--=%SS)8}*goDO7=Lg5;5 z(_$X3;-$TXp(Xhz`wC}$xv{Z5ojl-*bdE&p9J(`BZ^}c3V8PfVuqW{q7FR7TE%7lH ztX6O!rg&YP>AjvNytjsi60gG@xih-=7>fm6l<YP)_wqK99DXGSo`ZrSz`3FUr*N4r>Fj!FY{(p2%lL&A76G& zrPG+q^pqD|Xv_G#E8Vx>c68B_qCAvi1HfJU`?3YY6hm5xm^ooWm(LMCw|tMWq!zy! zFGkATxyJ0XGA-2Ka@lZO2hZNLvEz>?q9{#F=m69`T+uW-89=;$&yGdnDlR=0z);~W z5M%WT{maYgOEYgJ(?qIaH6?OjS@St0QErn{Jpv`LscAi;vUPOmZb-E?`2R6@8Zqlu z|1o&t{&EDM@XMOehup`7F4&)O>(tnv*|Up?O+;sfXZ#t++Nf}dEcX|*OzTha)<*qe z2$BqD-VZ=ie_5ijp%R+2zo}-Toh-prClNDkN%W+RDt`B-88}NONmuA1!%)1%oBfS9 z$y_sSWZ~M>z&GrXKRtm5eEDGA+ulRMELbzmP9FUo?b9zf+?+~ z`}HD2;kQjk%9aj$)6lESVm&FUgP+#-$>k!`YCh3UJTKCBkn2Mg*OrS)(~(Z06)({| zAFjvAsL6-5BI>f1Z0Z2&Q0j8Fw|@z3tHg$sz+f9l?(S}IPlBxLA>&{|3SHreh)JHe z*;vT0?MT)F`YjG~@L8cJ8XsRErEYD1tWmOAIKM3SBS`!&-FyBVKpFc?JCI!`>OUG= zQi(*%Y|T>2CmPsQkgW6gCx()Q#fti98}Unuj%_@K{kWUJb?Z1SRZ|V&0R$p3uy{b@ zW6h-w;7s!F2u0BlS|(Gv5GB3{yClqK_UJh9I}Z|U>>0*t96g>4GfIb<5qi| zV+z$MYvp)7yL-JD4b9Ej`g~sUJac+sApD_~qXQt#cQ2x)fOh<%g%dR|Pfew~5cKS| z_2$xsYTpe0as-l^F1Rp6@Ux>|Kzp*C@NGar5Z@Jv!yhU%GTSpF#Ne zj7>)736yUr*-+-=N~#=48dk3^7~DOdcLU=gsaIqdZW40m@Z>n&@6mk7lPT%5CVRpw zpI#3%XrP2ZW^hbFDUM`s!#G;{>;FnS{I|N;!|xwOFDiMa2at@ff9BFv?M=CfxxKqb zJ#j(xH#A4ImLr+@Gd-90z!w8qZcEkz)E2;JofVZ%xE!s%^%_7q4c!uqlcxYXe-{Y| z*G!1t#ohNc!cPu(ZU{Vm_&D#LY)G?1XnYlj@wn%EF-S*}C0vP$u@bq%_8{2sJg@;` z(#Ms#7y8%>o0?!)-Uv6;@h1-HFkQvNdNlXr)1J`WJg&kZ1aNVx`RBr{ZU=$^*3j@L z2EYHkN5lOfI#K`$2mCDb6h{SPHInLSr};BVBmsEB|Ls^f90U0+BaSu%C*D75w_#j8 z>RvhY8~37oH2e>t?btQ2_Fd+GfHYsFbHAM^NoKgBhTHDs$zS!B-qvboU0iGiAC0zA z@l+ttho;Tm4iZ=>tB}p?D?RwzW1~OB8imW!aDNgCMHu$A#?w-m`TxXC09^kI%F^5_ z(}6&h>&>G2)u8g=noM|)lO;a(05#>`i9rPH25$}W-;5;`XqeOGKeIz2mk^KU&%>4y({ ztjw0W<|HTkuc!M>Q(y#P#3h1}b?q%JB>o1_`5g@sg>by^zXWMTVT-x9EOLw&id&{3 znDJ9=k90!sg^-Ec`krgfBI*-4YEDZ~{nkrM+vKD$sZg;p+lU2<-1Pz{%*e4&&`{O7 zf+@+DoaYj@aOy)KafS3m;zHVgC^O@HEf#A=N~Tx-La>L6W&Z!i+?$7E*{|#44-t_u zQz2tz2q~h$JSLS$hRj2uM94fPO3748gOaHdWrz@&$`EBJ5z3gztdJr6&YRwMzkBVq zj=lf*{_$JKTE|lI;C}A=b6wYYorCN)md_H{DKFr8j5?$p-n8HMCx1i0IWAKNlbd1x z*7mChZ?NykkB<`0MPPeH+yOXuq+uT?C+FH5qOZSN&EV{@qdbv|N7|czoA~roOcxwm zwzTiRw7euhCreKvcm78!)q7zF?O?~s+zF)Bp$iECWH+$8;QB~mn z1yS|!*G)z+_!`X+ZCTC?sP^Ga3DSzQ%nx+ zq71b%+N9Ulzsz!3D$Ad+veGp+-n}xjDZ5QDUp<(92V*w>gu5_grjO_z`z~`&Jp_*> z&T%OM4(Qm_E=lP@g&--}9}0MEHjAz3Rl)A%p!DAKoivU^@&)xTz0(1zduwXgFRmuj zKhL6+2M-Exzppr%QOtFMt5JBO3p69XEZ>nDT#k7DdtOeepS$GGBxCVuV~OC$%^tw< zu7>#bVvMz>+9rymBlFS67{H%E4CPdscTAjZ0Gv}Bm*GNZ`t)9*GiT3MT#l^Z_WFqa z_|xf!Tskc2wZOy7{iay&l^;{AgaSg3{9b`8xwK!stfEo?SQgl)!u;@#H_9`d1wT=v&-sh= zkeua_r#6u*n&*Gc|1w3tX;W0bWPI7If;!^;>a<(ITq)#ZfR7dSO?WS`oMk#4!y8&6 zK{PD&WN>m>n{5hXFT8wq_V%qcgsqhb5wVHZTDbzmhb$8-vI_4Su2QrtNJije1+Pda z38Mnyp1J$rPw@WZ$FuJ4%?%CJH8tg&cN)mL&S23kf-KvVtgHzfX@ovvDUYtodg|BY zr0PAwq5aBfoGIi}Kc_SVZ-k>#1K)eonLbf*j+4^t`h3Mj7ChnDyT3vQ%FN8n`_$PO zXRJ`{9*OdW*!DvOz05jV#qP6%?6PK~MYL51#KHLhC5%JT>NV(U1}LflcPOZSy(K-oS-Ld z01bfdiSn)+o?LKd3vm$~@T4g~?1!q{I33pOX$ovs)q&_d*iI%7FLxdx=f_p>`K`Rl z4GeDq9Hf;-o$M@fR3 zfz3dfQ`S7${o^b@-i2kJj~;pW`OF%jP3DEZQ?y(X9vvaQl~p*cuU);GTtxns5E*T2 z%;W{{#xBo{ijkQ)s6=)>%Pn@8AU%L!?44p8evp?%MIC1~LfOip3^-U0k*=eN<#bbX zGu!6u)ZOZguYIU@1vX!}ew|hKCSkaX%m41MoD_NBkdI zr+=^K{(tc$(VN{#xc9}kZpARzghxVWJCa2KNr8^oo3$J{KX8%9A0Ahn>(=#t|Bh_m z+P{dg4)(wa&<|qU`Yb%0&R_l`>MomW2cXI64TZ=bP51SlJhu|gLq$PIU+8^NKBS_F~`o_k_Mn;HGr5<}j!<&VL1oV8ypXS$3u`=O>@ots9 zGnh1RBBD0Tfp{nvuxKI}@$BB*_)Imq_{)h@1Cqj4==Rkr>#&>N77KZ-R#zO_GSa=NdcKzuzsr9jO>_j{S_JCM)OG+Njk9S&g>`a5*%IY?==XF&Tw6=e) za0~xN@ zo!4a53q{m~(+>nStK+$gE=L9c@OQrV(@*^CAbaPF#%69(GRrwLv^@PJ=NlFww_y^2 zcKeKAc2vO9d?(P)uMQg32vIAvs-SsFu_M@b1K;Tg%kyBN0YV)Gq2;~5;9|*{OP9(fiICk@ucHl~n%vsuy1C}eQw!GSm5uE0 zE9*CG06xjEemlhpUm_A|laKz7b@VEicNYkfw(#F@60}513sjVrZL8vu*+EE_%?n*5 zrKKy3=qCbY%7d4kV+K2)M}vW`UXP9a`7x5W*Ax~T zsyl_Jm^<@Hbvy$vSNvJJ^P;v~667Lzhed9BKpHC_n7RGUmGlS`)<1w-Ksi_HcdFO4 z)Nei~EXjXKkNc1$@lO!et@YY<@uyz|*u|^1to?R(-d8%u^xUiiGtRd>#QmVcp4mjb zh-VnvIyJgoOO$o(9#dZ3#|~{UK6K4@l%#$+l2mziVeahKf&o^}*w5aK&Qfitwzyxr zI8be+!mm9{OiWCO*X#DL*-e7Bc_0*P@b?oKE1+qeJZfR$>z$yvYjtR96<67}ngx?_ zztNfI@aLl>#8UG`umymJi@SSeQQ}YMHCW`NE682~jC4#-@BAU*wZV~*48O$l6{>d%nmpcV6zc~U zQ$%3c))J8eAVQpp=K=EPK5?sRF2W3pt`*l==)`hGN#^43VUQj-fDZoEmh}fR=ip@q zo_3al^*Pviswhm{%=iXa8m1MTJg2tO7+PT-gOS5mI!8$DcsFcoYgnBlG^aonI7O{@ zDTS+e-Kd_04mlQd_m6LNmE8=3@^~BHu8{fJ8=4}LJ-@*|n`o!iBpzc zhtl1!{wDKI@nY{NMWnU4f=l9AWLwLos`BGm(oFx6{CHyZY^wO}-Szuoni&YjT`|DH ztO;C>qVl61RiG<;dq3LMm6np^4~_N*9fGx8M!*|WnYI_J6oqi&L~dGj#)h8sPz`Rx z+Uw?TQ2q?>8XOvOjkhVFw?H~ooH?@ z1l}`(ROt#Fv~`|)FNj{ebi6=bMTshq4-?AyM;RpBg!=`1Pq>_5zEY z0jc;pwQHHL9GjiZnn&>!>n<<|lh!^;|CmepTZ7XbVGTV>na}3*E$v^ zQ54G^{t-E6(y%Bg&a?a^k4h=o{Q{H@>?@L%sQZb{XPIiXw={s!-dQ?aZo68!A$m)GES{D!x_{4C1&> zt~%>?XUEcfM#89EZnduQ*cLC}#|Q8F)cJJyjCz%fJ?Xip5jk`IO-+qe9$kXunGLei zginP+Kty_Cs~qWgiNzM<^Oldc_Nv?6YNH{Xej2(k@}C;SL9Eh}mPG23bD#Lx9_w)N zg9O#}P7Rt7f;!>A5Vra1VWSUHK^>5&FF_PNV_JRNH=;RntJPKK%8(+e?(j_^mleq@ zvS#3=bS9hkqvfiSJrU%k+b;?S>s|7qc5EBgV$0QInd;|5shUD@W9(+6&dPq~CBAz} zEkoezYr{-uVPO$cTn{mCabFT4P0j1)6iEN>0?oyjMa=qc1q;Z|d*42TOCD{W`cLx* z1>|-wheDp+vulcoxqI8pL$|jl2d-2M)s%6kuaKv08Wg?YD4n4v)=XuREZciCkva$C zhq@3`P>7K3&l`FXZDOS?$AkARr6X&!f^GdnODcRPq7e4u7 zJN7~>tRxe@xgG1J4Wtg1aKUC1*#Pi7W1&@RuX+L1$c3Sceln@TSeZgT8HH$u6DB$X zhVrUoWbg~=;=h8j*LT?!(X^%C!!k(0%#ET(t#vKQt-mJ5#asmHzRbXezh}4dXpnkT zfCV31O00h6fKibPD^WamG*mwVsP1QX9?!|=*~ZDVmT{-WO_+SEpVNy>t&sm{w^%Fq z?a7gaqc6>J3aJ{rTeu6U0+V2qHsOx#zs{=6%boN$Hk(juI#0}nNfhh+)_gZKdA6A< zC$hB|N{9Riy^*s3uX)d!YF0={x6qkBU}Yu!hH7Tx)^)=zi`pNp`YJ?jV8FV1^#{+= z1dsAiA`RS14^0%hSLd;D6+lrB&l)(^f(#uIMrTj;lq#l|OXcfo3W~15kOl-zZk-n` zV>?X3j7jz3BzBw79-!5IrBx%30Y`az|Jaz*@#F63h0&F=9U;Z}@8aF@ijvfqHp9u4 zI?ZPul|_iqv$L5u7Zesg8(T{LguxFTb+=49J%le1${+DMj z<@%!%02e9O*dR=5^b*xC$<1I-ol^baZanxxMZ6Fw7^s{U($HD#)^*=0esB+Uf9Cpf zg8wr8b3yp*T?dCPM>aE`);3OVVfn|b}HqY*h7;Pa-AY^)!tYw%0RPiG>sCO zZox;7kcL}Sbna@C@z$UxEi)e;yLrZ*?nAG} zH2NSIcvtq9p%7vTE#6}fVtZSZ)TF_D;d|KBFOV}hwytY5)Y*0i9vaTk*8Z=00dZWD ze&d?%#v#B(odQPE8v~N=$o^L0j}q~pJ{f9z7nl^oaX0yT+%(fs*jB(TAi=^y;r-^< z#}C$qzJ{Tky6ich#?3c4o_FjE-`_0Qb~M8*{G5gGrHF{*BchAaU0`o!IxkH`27I-1 zo^0Q$RAx+sr>2S;)zq;iv|e6Cxc5NujloCrU4V&(tT1DGs1RBU!6Z-&sTUwAwtY8w7cLB*}(dF>Q`?mfG673>_#1fnZPx6IDRHMl{PN8&qDjNmsd)W5Xa5+;3TNEh+`#ArP^d58QVy&J z4g;4Nw3s~??pEh2Hf>y-b!6WoohbcHr9JXRig(QI_}kAVjN^C2=R%*p31nVAzV5Rd z8V9_aSj3*jPN%dQfm?MKPs6y-K4tF7BV-($oX@tf5*#HwCDw(jnq(4A?kM(SErpW; zMEr9I0C=Q#>zP0;tXeWpfew+LLf7=^&-d*a(IJWTok*QcwVzL%+V#^&4~K7_WBa$R zuKRU6J-DP^Y?M|D8%puB-|2*(1#otPweht5btf6`$0Q2Xc=fnz*Uqz+VY&hlqNOEv zPrdO$%*nMK!%ohog+_vF9?Ea78HSuYpz$*kIc3=pQ9J|G|r(Y6Qf1QWxW z1TkqO08$km&8%CW(UcF#SWj;+;F=AboM-ONWApLUH9}6e-=OK>fq7eGl}SQI+tIOz zT|kBRyPdg6n>z{??&k9*;u_*YGe!>gG!rU(87bxXd9bt?hmK(zf1KY=htyeK+lLPp zp2x(ee0z9gUUxdIx&JNCfvVcTEz!9G`&hM-zny>3%bNQT^s5nwB-UK42kjVUFQ?Mf zZFBO?WPhqoey_mK@nJ~Wp<}y+J7i^FR_h?oi=T!FeZa(xu2uM{kO{{rgG(T|5<|a8 zIR%1w)dqUT)Fa)U&v<)!!q*@n8p_H{_hc4D+?NCFByMFuOrHxq7)0ft zlI5Ha*_fv2=O;H5Yt6ty8caIC73OmCBeAn)6(Y2H0QB~5=6q5Ye?H=d0wdYim?oXu}ybX@R3OkxQqr=8d zOnIztwkkradh;tvN2nA;4uBMh4E;rSCjeM$5rO?Wj;j7-bXU1q66Av+GKvIaKI zew=&}bvy4$z5M*zySsPoN}UueeT#&Cj1d zp{Y;K*LUC1K)+e)C|l8m+ZXI?Z<}h7ZH1ev@}A9`zu|}%DuKr?5T(UmB}?3*i;x?C z8s&wNSh-rL|CwCpVWnZEjrZ#=91-!5aFnCu-EH<&T(>ufp&Q6vDYlo7P}UsO^yEu) z-D_^w-Bn+(O1&=a_^>kdJQwAg50HG@zW=F8Blhk5_EWK+u;~!seAQ0KpQNiE%@$gV zwx?E{E%WqK*de7$;!;RUB|%$9-T{HyF3vl`byVS%qP7g5Lk;KOY>Bt1mbJkwxinLy zfZbzNr?T?GkXo2&)5l#UA{n%)UZOc9BZA@Rsd#rJmU_J~=`iK}z2~u`yp1@SwYgbY zhnv4{9ykq$Aoo>ASyDxnw8(;kgB8aUxtQ>D45PH8->;y&z#4$_sQRYu0R!2m{peJ? zw7Nd6qI90Ttyl8ZD5RcKgnZ zLpmL0U~kC~5UJ6pdEdT-`i-n@%^SAtNBHHCamt{g;&T2hnz8*Uay7VTV%G0G#o;0h zK%4Ca1RT-*mQ8W94Z1CA`)6+@M3XlR6xF`|7U|xrcH~tk+@V-$Q@)*7@4cQ)rAIz1 zsg6acuy629ngk0}jd+5U6O+c=`Hvo z+l5XqdgNTzG+l#}1p3s_D_3Hq-&p`I5T+!(yZ416W*$YzmSz{vQ{4!;xP_)WjoH6Q zD@|^6q)0$AntxBs<@$5$M=U5?L2uRmSiVt=|D5^)Q2KQzjh^|C3}Yn|!T(J-=}Va0 zZ>=$O)^AI?!uC^X{f+&WN8wA?JA&w{%*T(5s2ccND0`^b648Zau9KSWn&;*W)D_1c(#S1I^57Acj| z$KP@Yaz#-CN*Q-tY1wizH9in`fT4PKCDcriw+ieONGJ<^adzl};Mz34gEBX^tX-GX zY)odin@1I_`5yH4J5PNgO$Dm0(+UbVc973$I@_r0e>~?gIpbXg<16g|K#y;eAU(}TPF*P zK*9}k*Y4dem7>y5vDiVboPbi-i26Oza?`n*xJ6? zr0<^V(GWsiqu(Tj!}r64R_imHH&^lCfj7%K!SPc2w$vJ9CENKya|zv_s&0PQ_QkK< zKeh0+6J1;YXnZ@IHf*m+OV1%4Pud0#N^BDv+hE797|p;XoB5K?>yBmitJ+$aVVAsg z^s?q%{s)6__;Vn5Zn5p{QF%AO{(u1ij>+krUk|LLSf^QovSeomc0y~%g`(Udh(~d0 zbOT)Wh5p^0=`Jrh5+YXuEUEp1iA+HXr2&Dz8oWk5N@q|U;dzv7)D2c5qygzOf;4{j zQz}tXO;uE00af%^amY_R+vd+Rhm|oR`(B_efm`V1`c?Km``cn$crteP$AVi-i+&Ki zZ**9%!_fFmfbIdeva+GM&6;F(bnU6y4_W@vlSzs4NLo?Ylwn!k_V(&@idtpbkKfD` z6UP%C(kLoUrj{Z!*-#SL3L=hRq1pPBQ}@4Ij^Xe7E^gOP z=w4wC0iJ`ZxscLpB6nL~|2kWL9~{N8PFebpW*`AKWk|C@VaQb21cPy+(ONAUTZ<8k zLP4`tK-x^WWZ$gP zlT@Q8Dc3bTd^jOw(R3s86XQf`BG>=Pp+W1#18OG`=Yb)J7%Q?-%8lz|}|K<49(DAdZF2)ev9W`sOqFx9qq8> z&YkKWz-;lWfV19<)wT{j1MfDK2F2Z_4Ct(p)YJ9puWK;)TkGAiAYQlSey|Hevz1rB zfw^CZ+vUCp-DrYX@Q9Iv!xLOQNGI(b*BC3Fma!-$8GTqZsP-`W-C&n@^x(X%`{f9O zLjUUm6z%WU*>B1|R`dlyZi%wyWMGK*bRI7p`Z1!!s~T)=tx8@~$F6dKvh+FY81igu zOYlB9Z+etOis}?SEnB&Fn@u&Ns-2PEmkDpg!_Vs zMkv@zmRrl~ppfh4U^idhz1wff3AIXS_SexPa~}RGN_xF_^F5AJTRbTavpqhu3ntC2 z5Rf@`K5X&0~{5BmD!H>b)gO8b#8!5Fw$ffb)wT*1@OsT9;Fi)gW zbnDQfgY@8T5KG_-8u%>?VRQk^ll|a&05E!gveO=m1vlE@ablcHAyG7;-^=PsB`yLyAjE!D2hULzYpC+w^&gQ zx(Q#wVUgNaR%5)O6X&&ue{YZJ7lZFK^3I#|N#Fy4lme!Qrgu~nR`Z!Zu)N}x#GW1E zfbuMmA}<#PN*sHhjtvfijr6K+G6|@cZv3i?2TiyP;J zT1T?zx@(0Sg!$w8;SdK1@fJ&0+68{mFL_R#*u-}DjJp4|1c&F> zdj<1PnY#-67^{*&eZ&=9k22WS+Dfd+AWa|EtMgP75KpgI4>_2;$vJVTxLU_Jq~s)Y zNIJ}LGQhslt{bbj%mfV4pb;xuT!6&`%wOJ502kv@s1~ft(6;KJd1>L6Xs(S~HM(5c zc_qtfYM>#80y24liFnS9*jPdtsos>+57}y{^YBIqQ6&zd zu#0rA6m~thG}L8j&5mJe-TjI6Be@TaU-Kuktf5EEtF+XMam zd2ql}<)yd|d-NMr`&*Mz$rTsScJP1Rz`?=m+cS((RC9arI9X#$Ma3pq*G+I3kk9vV zpD0RXVz6&n&-2LKJxeD@Iueq@ZP30g4Z~xU9kkNQ}X*Qn7F{)Qs_i$)Umkn;t79lq<5%NBGO&sh z(F|c}d2&-)a^OwC;dcO>*9nN;+GbgfdzIklR+CeV;q(R?`z%sQE;8x@Wczk8sNcfd=nYRSTr&`3~LEfGc&lR&4URM zd;=*oSZD^HL)6ZZ{o2|@yrmf&HJ#vX{ry37G}F=dxGV=5WZ zUa(R*oP?>K@O0dW?2_^4I0+Cm4sWq-G@vhRU}x_i8Tr!C5GW;sZb_K6f*LV`HIQBD zXtp(t#Y%#1g7i@zpLs%Lj%!xEWH^sjEtC-*DM_Wf7l2O)%{=F{0AEc5qa%Tvk=lH!f^!#81X~+YbH%Y?!N2M6|2)9S6{U~km?I!BjMLIG-P{# ziPDQhci&lcSl(0b+Ky(Z2r>iy9}3SS1V}`>Apl09DlNk38Et&+5n=4u)Q(;ZfbDN% zI@idnEn5Q?2GcU4*j_Pk`Eb-Qspa?;cS_kJi51!d^`?v`PxMdm^wX9dDv;M83!OV4 zK*`&8h`wg}(d4s7A-apfTxIKnAtIMiW^ z8_N7OySjvEi#`_oqb+*FC$0LZw>|Z6N%dIt4}N7SQFh08YX+5FiJ{Nyf8BWi3sVLj zaH`p~ESQy9vb_$B5kI~bVcuA_%9HHLPN$B&b)K_A?Md(J-*wG@sIDHsq6qRO@PI5> zDWvpCgqOPn@Wir`zkZPqPGrgaX%8QsaB;~7BB`_f%m!Lfev0{sqV=Id1Imo+MKIJ{ zWW+6TD^tkTMJbpkI1dW)B6NAZ8cagQ4jz6d08nz-`?U|C2{fv9dEA)X=?xhPP}Capbg)4CEX8k zG6+vL)P^26WXw-mpQPCsHJFeKJ3s;NEM=QK>QmtAhthx$zl&JSrJ)}cf=?3wQ@lA4 zK(e#2*gYg=eoi7hS%6}A3^u`?CamwBu76ZEn8t^b+xln1ry?c|-brk?*oUVEbra0% zU}a3nfHupn4X~FHSvWXut$8lp(}?JV1p&2yH9%! z3XF4UHes))S%&=+)1~Nh7$Lz>&#JjCLL$N;(`S%kxo)(XKMRY2`FBqKAC|kF=N4t; z)2yekU}}&*B`zkWR-##(qeseqU{SDa>boa63O&v7k{F)kVI@C`)llpp#TnJ;54?e2 z|GtsX1Dg3EnR{5JZm*f~Mu;VP(sOgU$lTqz~GWt~$AO-kppX@#) zUo)*aYeaK6z<<1q3J3nVxpRS0(hCs`XAvQP_?&BT^6yoIwQ)enOb_jK0e(=Wg(v%N z1y)Zp2D7x7D04@(@w@zuO}Kpc3!C7hR*r0-rR@6l?ZOqhR73c}`n3P}b_RL`Ea>@7 zPh-DijN*Cs?p>HPwzo3|@lJ;2nUfKI5O3ZH0~ZA|@TAkR4oxUSQGxL*FJl|1_B!WkanLPoWzuhAsOK=-C5f(O94p+WBpM`h}w>4 z@Hj*N3k#c$fF-}{;q7g0pf7+!MKgs;nRTi)`*`7V(ca|-!?=Qq?d6$J`D;(PnR5HZ z#&qRAE~icb>Z%SJkWVGob~eBb;YLei{kMSFp>ZltsonvhBF@Y$-~hO z=1m(T;!}PTEZLl`P6gyRpkKj`gh`X}3ThM!&&g|XarnZ1gcb3Uswyk_gL|dtH5Wd! zoDtu>d&3PLyjd?^c%w^0SLA%=Oo7MPy(9A&x2SW_Oi-Vt{aUG8S@hpZ1 zi`dW`eRwFyLlr}hHIPxiRk`C{tTAqVj55*h>(KP{^r1k=} zK(xNq$D11&U9x~FL4@6F`ZMnCaIwtG&DEdf zloFj1!s0-91H-?WB`J<{a#FSzN8emj8f3Uz+J_(Jvuo*EfR!+`6UO#M>84(c>v+a|v zI}EbKt3c#71001N5}xYU3J*w(=kcFt#w4x;?z0Vr>EAupde%OV(%92L=SvwVi8h73 z`vZu9o0WC~M6XE}kRn$|OovfWkYtbe@lrr+vWqd<7k`cfK9U0x{$D?ISJIa}5=H#Y zn>V3T>rT+dZSeZom4iYgn>Q$kz!cEs1L-|%#8dDfElt$wBTluPp=idyEx7I=`-UI*FTBCmnU*#Oj7=rS=K3xxa*$>{wrGjA1BSkbu@u;4EK|h1*N6+ zXRIgj93G03%>vQ~Ckse?p@X@ec}QDJ>oVG8gkA2gUzM4g3yM0Iv;)gvXZ{&$sIcC- zry5lLAtyxU`1CURtu`-Ax^omi>%f-X$)wwIOm=wdac3bpimgX7hKz+Ib#6TM_92RL zPlASxb_6EvPzGL+W8iR_)krPb5mgryU7jYAdysRvnkjoUm{Q)a28KQZ$PBFy%_awt zKrox|FgnALy?XJEpUpqX1AMx$U@1fzPgxn?jvXMB63#F1HD=Mujr@VgtB~N}$W9QBlFg-X=bIGb$=@Is+k>Ox=3T#W4ZPZ)`W64r#1- zUi`;Q$?rY@XQ!BGJ{}<+=6r0F$VGw3s7+ z{HB=Rs(G2NM|;zR435z@JUsNLxcvIB;u5lo>BWV$>w`3}?56e)4ceAeTx|9rf!q*_ zPB2#BXF>RZQ`2Srz`hcGGR|%6)O2)e@Avxu_AD~P=+E4Z~(osQ1l67X{$^<~o>D?SVm=Y9Df)>u>F# z+V@=hIyq24{s`Tj+V8%cyGX}*f$K|kb!bS(`1m;9*PpC`1D*+V^~XovW*0HSi!HP};*Bi+S3bQ36&_H2u`ZKHId55VoPv9k-6h0)f9SFIl1@5U!5 zwGSQyc6qqjm;p*h9a!D|%N`vz#_# zlbkLb1ir+C2i5UMsigZC8H=J*1vqMn+O)d^59XOsveI^Vn+tV5cjRm$$@k4KC-1Ft zGayq{RfU%~HeyvNJ29pwDHbr>kbV zd3b0vowz8wXAg3Z1(Ng&j%6KD1#rRUSOUxj{gNV!gpd%7yHusQDp*KOYnbgcsnA%f z4uQP}BjPu=iz%}H_d4}nnaqM$M@*JbSVKmItR&%mj!ObxfDy15x zw!;^_NcK`4Q1QmxxRJ;`u)3JMlmjO*?RrZK3(_@UKG^@+zNaCb<8gR}u-8PYxm7zX z@SbA9-Omrjy|ula9XvXZWm=GNMW`T{y-OudCq`j~oF_~wUVdDg)iqcHwQ}a!0=uv` zL28lc-k3{hHax=`*8qsfM5hg(Bsn?1H&-`_3<<=-mr^Z#!#0aRcR6PAahrdGx-0!Bb58(qVOZkkwduUq$le?+t;Ha99jiaYjcF5dNt2T3Y4 z_gmMUV|h%qxedv_Z}V!qC!2jl~7xkET2sMc}>4wtlQ ztn5nTr0lQa+VOvezy)GIypwP<0iwdR6UW10Lg18TZVO&BD>L)^LJy|`6Z%`sEG$PL ztw)l0TwENA0nFMc&f-HfP8N=U7VP|*ZteAQQB|c_eFw#EYd>4KjqV8O>6u86I*bt> z25-{vl6c;I@4-k|bL@{u3=nYdw$wH1|n~Yy>Wk>>Oz$D1141!olB*bOd;q0}oVWBvfRtR5u#`6*JvUFz%c^b%rS8@qewQAwyr5nStGK|Ya)CD}k-mH% z9IW43v@R{k3&*Va$AA9Q)ybAN2ylKzXU@cRwLf z+>n5@qaR+4+Y(g6P_f?>FD?2EkSMM|ABCF)9Dodhp(S-nla63$y)qG?Bsr4(wAg!l zJHkF8RgaBjuR%Bv0u!%{0vM0x!ezP}vMF_L?UX>ykv%#jj3wwXZb+-CR&!UZI(CRm z@hLQ2DxtjWC72~EYezr1>Ws#^nyD_lQHWgTQpgsqU!DfB@-z5MrCIor4EEiw0}XuB z>n1=*;93M~-{$~|-kUdX04<7esun5HqMKAvRb>pitNA*_^a^NH^c(k9@9ZZyBS)HJ z_o0O$w(M=%ZpuT9!s`^o8;@!i6F2Jgu1CNT8;b<>&>mbHs6b_~= z;3Z5SKk*?(i$MIO^+%6>264dV7J4$YkN^ooi#26JLgi6qF{|)7PEAYz<4doZ+kPpu zJ}AjYp5C8i`?w&AZo=KbEvqZs%xYUlVB=Nu)b#k06#*1%%p560b~xV zY#6xXwoMPiR-*e6>~8SM+GX@EbF3*v@jNgPROQfI#Q27WDXUiHH*A+zPNnSwjG?(j&z!ETjoGXGDNNI}frby5^@Z9g(8Q zd*pwI$Nnbytf4HuN2P zh3B$~;2^_q_4bH+#+9_RA#h^|q2@`MxMs!4R$s0?YD0Mz^MeqmnND+jJL)YTa59gm z4$l)+XcQ+eDPrXMNbKqGOp1t*ZngcVA<6!wjKvUHZFkD?wh-%wb_;B$%ms{nE^cfi z3&nj*>t;;0mP>XU2;eXjJfNlZ{vcWAOG}89|4m8g{AWpMWG^QeXO9t`qb%qAf(Z5c z@2nx~Bt}Q`=Er@9t<;0y6(}q!$#t0J3B#dpU%$EyHHVM1 zU>A!-PpUC}1A~)I#ea%{myyw}bbFtmzpDZJC3U;QOU}bFKR|aT?hYOy(v)akDmg)B z!R!=-LH#_+uE8Ek?CmciZ(QI$zb9`FT2&ez*yEssCKxg31~I9jEAxCO|6b^qDF6yM ziNk#BtII6Bml-#}Yg%?hg^c$m+*-hH=BqKwcRn}bDfp3IWx>=tWf0E~6q90j{S$tC zHw30nHu}R#7c?aB0t1P&7bwQXR$t=B6<*S8eY4Aa`Nqj1(OC559hTrUlUnE;AJkXr z6%|a#Fq7W7@au6xcSYC*_9;5LsXciWIatb@s3z_`*}T=}4WJ@SIPs`a#Fp;X5N2F7 zxgO|n*>(^U4$Hc;jK`rVwp91?d#SBL8TgjtlD&lmuW}3EDMP-8enNqG#QA%&t)mrt zom1T@%*@GxFI-q0^(Z;t+2PfH7bGgpG+@1AZ5Km;a}ImG1$+JqVr}+*E7aVj?D|{4 zVat+lG&#y|133;82rtt#i|Gr zK6r(azL01OPGGrwqFe97H1?Jt?LZbVRdiLd7Cf0D6 zavShPP?)9CcEYC%qv*8pKPtzE<;qc4eBSB8--{#laDgCx7nO9(ZTCJD$B;8RY6!7} zHxQ2_IP)OfM>+nOuV6QSlrHhnA0Z!bD8+ib>9^~u>62?wOLlh6o3|eH_v@R+d`f+N z;1RjbSLv~TLS`(0LRPB6Z)T(6KULukQ58o1t_n&YTc2<|PK4h@W@ZBci^;9PVsX zO^9;DlG@1ECM@Id=5_s?77YZc8p{uX--!3%ie^m+nX9-SJc#VLoU zCJ9B8^ebQI+1_x;iR{x)5`H9b0Ya(@x~5)VS{Je#&@qk}%M8Q@tn5gdyfy|tdE#he z^A+fT&Jt)mI5xmex;eZgf9qi`lV8uh?JHA*<8+k8fn!L65%(F+Vyk~+@S%?FE5b9- zG*wc7xxg)R+GLM0fA3t0=`a!btMArxjMTV=T#1a=g0{XA^}C>_x4+4kzhTc>HYyVXsn8(GUA5?>9!MuDwFtVSQU&apTkj#L{VF6o|=Y`1d0~kxpNHW$)E$ZpIv?N zbw!1jkB^L$6ec?8Wq^xeqI!E<8V%5XSzkbTaEc(jUyrnaKZ33U2vae55tSj$hBneN zG5`#F;k$ueobmAS`g^AO`h8tpQAmP=-BqTkvGHXGFmrUoJkR;7C@X`wA-2reyeTJy zRW!zom9paf?55ab5;}-aZ!EF8m6gEzQL;EE+9UJhxNwQ20>Ziz+1Dl%6`73xL~$al zXn+C%^5Kv^L-R@ejc)H?XUP(nL6-fXegR^Ixk8zI-*8T_FkGK(PM+L@gxo9M@P@!v zk#%ZI)spVC-EK2H^`N~2mY!xx;p+gyorcFU z1*Q!1nA01j`T5C9(GlqQV+Dj2|J?lio!hthE#i=kjP!Fqj08hi)icp+1S`7Df*Fwf zq8QyW^Ji?QpsKmgM6rfVVP(cyI~5qn1VGPh{5CiL?epc#6niN&G2eW;79E`h1Bh-72 z+QW3OGBPq^Qzyg}VLE!X4hs@m;KB$gYH~MS0o?U2VrTXi&6h~kl z;@)d;i`Wazf}duU0GbU~7TX!C6)Fbx@nIP{YU}D+7*4cSPA4)^x7k7;d5T?LFcuKJ z{^a@FIDE~8SP$>nb$YM+Fo*8oaT$f=-<$hRbSt7L$0*FAe?fpy^rgLLf2S6cH+UD} zv3_xW)Svb~5l)LbjVw{&7`r@~E;t#jV0uE=3{z8F_5^EF*ayo^4j{b;nO(gCT>KxI zpiLIiH#3XK13N%vvYbx{9w;gTiJf#l-rk$xclPNM^`_7dk9NVq?B?YU+2DVMGEj&l z1U(|RDDf{X(Kf`TPZ|C?;|%aQQ#Hwllz}_w2-0cNLqek$I(PcVKq&9RG47mia5@tynr5a*HMsHHCMlZWOu@j$@Z zGc8xS)DS$;v&Sb^bt8%L_zF3LT4Z!|blArYiugEq_rKL0S3&C-^-kb1D6EFY#{9GD z#u>UqE)`RFJrqWOag-B|KzpTiZrhqXZ9pD!a@{*LnDD(b+aaq8xs#t{l+Zbj~Ov{xsWPP zD2g@L?qlNSe%BWLt%pAY#(V-*)l1%tH&H8U^Dns(Im*Wc1 znl-Q4I8wQvks@Ia(PCY4?<8k*qQaIE7p(kM5;5qCH2_mg&-n{e<$T4!}10)eXm&QCwb;MDW(!e7fXEaY{5 zPu%ApEBbkm^BB=lFz&8s&mhH|e`yCNEZnH9e+`O%qm3+qbJsuWk^qaqN_`lnJZ$qH zM2YY|oVfuDEdkf1+1`tL%+T7`*%$IT2J6iKrzLT{{r3vR`G!wEcRqS`lE9R zeeX`g3$Y4L=D)W^yG2$Mo=zxND1aK360x;ZbQ>^q9fcgit_PzzI4neyA+#!IEz>xR zrqHBH^6^>XFaSxie{JN-l_g%B*#B#Gf>ouHkIg<{PyfZ)equ}}lCA9DC$DT}iU2v? z@>`mATABtC7?2d<$CTv@H;sU~5AhGQZ(WU#FR>^K0{9n7|BqMa6%>5^>Q(RjSc!(E zp&=2!36psr6m;N`Pe6kDZvsIG0x0Lj&5H67DnBqVaNHfyC`;W80XQ!&KrxIX2$m13 z7d2K$HL8b?kiyugs+`&rX1>3zf9O{@DjLqJ_!rSWV78C_DF5;XKNeeYw`N$H3I(Fh zJT)&d6Vl$dZx#VII&~cY5(*n=suzKE5tSPf-1PLVeS4_L|J+e5YLw%N#o}FucF^5Q6@r6$o{&QtLEOv1Lhp(xA9*eQUKhWwfL(%)bGM+FS3I8oot@;Q z*WYo{-nn%P#9Jf{-Ap2}iJNe6ahf;6$7Qxus5O-wwEx~aYJCn>jXlWlk zSRDWB)oV&t&Gf};xR%6~NQ=C$Y}2akBpaar^ZUgdo!xYQRPoO>Jx6Xh_fg#_=}HF4 ztf^)5Z^i>FpXgw|PgxBMcF3-LxP1rB_8osdl%(1I=gTCeXe6bGzm=E&`&;bXhQIjxThPe- z>!*n?{p-{J__qJ|?v?{;(Z?*#58IhWKs%`ZhBE^QZXdb@;#kZp)YJ zKfkIB@l*WuX-S!FH2B}Y{9Ma_@#mlDowaiFa<-M&=V*DtmPSIw>6DX;p0lO3t%Rzr zyS=rohKr>ajf8={jhh{>)OKka2~Au36LxOA+hy^wvb~$Dj;)J|lcTfKY1`9oys|VB z>h`DHY+WSOPg%Ozs@hsR+2B=I{$Iz^#nBb-xsHpijlH#-lMAmTUIX9ptmA1{;>G3V zCA4i%pTKvLm6eu}m;ZC$c*c#~^-yG~YOkWACsR^8!os3dA@0tUMN!B>yEE~y%J2r( z@C~##K24pF!d^!(5~B^_0Yl=E9&(wKD56|>M9OrJjCG3NfOV}6k@Q)b7W z(f;G^-)^0_C#f8$bR{bK9E*w#Zw1SGO-Z%Yy4v`o-v5g~dLPm{ZlijZwL01?`l`Mr zC&@B8+E$KDk)opV=#BfynfJnlKTh$hd8>(Z59{v9Y^l#~Tphc*;6$X<=^q&>=Bq5f zcpYg8WBJaM%D|o>HUCBUM0UxSsYEil^YlEqyKTA`6ZB3s*B@!QLj04H%tk#$-)vur z=Mjwjbu;t;j|BNQ40b421j{>JcaJAiAv~yV!QRm znvc=~YTl|efia>xjCCC#9|fd*^US0d2b1@eXi{qDMb3E~di8bP(^nh& z#8>qxY&@xc_O9kN|L7NcKTh}$i|pudhcLoUfY`bbe;WsQQh@{r-4CeaoHim(Gz7tWQ1EW0?6k;D*fo zeEwuDo_*gRu1&tlze@OlW~8QVEc-)}z1!4S>L$N5|D3$-*-my}ZoGGh-XzDnN&KxJ zoQ`gNf@-a!{E_X;$0r|J2V~4e^X||R7WZ~)&-HSBxbxkh&ap#5Ry$KK%j}yqa(ZGc zZJB#qI{k!$*{*?S=^KBI(7)81I)9$@RP#v9y1rQU%-X_FGABEWnR2BoCB9u%rg81j z4S%O?Q&jox&h6Z7PBtb(uf&v;%$K5E3e;>VcU9b|+-~o6;^Omn>vz4e5)$5LWOUg3 zjP{HDPE^N^x%SofY5HA-AJHE9w+Z?~%{#*fTO^OxsX9qUADOMn4hk-pO7$6|r_;H8 zQAGD6bH(Ohmb1^D8sAp7T~5i};Gl9vU{l`@tB%(;y9*eco@{0nNflvL{Sx3X)b^qE z`NnHUpK_>c@mCjbu;^_}`v0hV%dohXrEPeC5E2NGAR)LzfB?Z=5`z1{FbOb7(4avE zcMa~41c$+42rh#}aCd@Ef=h52eBRl6pYxo3&fd?t-s`*GKi?0246D0VRdscBb*;Or zD_SpHZInT!qMPa~a(lfygC7Lw%pY=m8DHjQ^G1!#lL;o2CJXKy%kYeM>&I*JLf$=t zg+ypx4W`AE#j$eV2Bs|C+Pfc}wQQnLZX`}(rsPC_yV_gbsp~t$lo_`p=q$j*YWTs) zy9qVL*LOH}GnWY=k~G{^;+V5ZAhCxlouTcIA!ppzulRzJ1+U)8BX_y&Ke_9?SH}9x z+Z!FTG)Sj`a$>+yiXheSJFC~+zWsEZ{tht3IOH&TqX@cwQrG|%+)-AJVh-wrNa}x8 z*U41^EwXSu9x6^Zh-%gn8LimRP>Fv)ktN_FX(y}%OuvxO!XWoXcd zP~Sj_HA|gGoO>)y>A7ax;MVFY@leLaPSWA$3`9VHIkIWa&eFX(7JE~zl*uD%t`Vzo zt)Ni}YyWU8G)CabM$_ZxX26V-2XlC@tCb!TuybfVs2Tk_9GhBft*S!Bhdcp$x8PW{ zzybu(`;$AQn`hN|92{?MO8O;kFWYGa05||1ygs)t>T{5@px#bC>Fwo$-7p=tp%i&7nfIk5DhZG&PaZZi(n`z<&6sM7U|fMt=>@F`Zl3;oLPN<+?DC%=Zh=)ik@@)q!;+fyM2qYNhZ>QOypk7R(Q%eO3b*`dg2~LOhu1_ z@`yQ34?-!wO6X5?{>>j`1mSW5Gd=q{U%-6_34w*P%@NP zba z4jc$a|8mOr(U&I%VpqmSDGP-ss^G6=v_nfcB36HrNGaJzOR73BNINSB#?3`(B)y`e z8x2f8o7yr-MAamz;rF8GYQvW7^#mDM)#-h$Z}l$9vLswo70Ah` zzMZ+`q(1S?w(zS@ZTbwIuk59Y2tzA5OO>7SVlNt#jLRP?1u9-XB(!_(Rq|e*kK@${ z^9;IH3ofjLW&E?}!GsWJq%!%hh-(AtFq?{aPQy_i&@EiOFAWi-8y6QhVe(G}v@5)#hdT<9Lt zBxUaV&yy3E;5MQSQg1?8Enp$+fw4dWMbi7Hrp@I!@hNv^-5tlLKGarOEDoJT>3*=` zV1@1;yenCG@nV3m$$uJdX5ejL`|v40KQ_DZbtuD~c)x-E0Zq-_Wj+`!N5ivSY3r(w z$%#MYSvlZE(>=l+Q3-xNZo+j%W|v`WP&GB_KpDCn@U;$Gf)Xq1n+QrvnOM6Q&oy5j zo2=_ZQjw>?;F*wxsJDjXHsr{bdGX0_O}jr(VRPD$q14szDK=_$OHP}xF7l%8H4x-^dkP|8| z$P&HkP5mietE-S5e0pi}b4;(P`21h#fDZ+0#qA;NOFTo1hQK}%;S_z*m?b|fF`#?>lq~n?ClvJ1=F~ac3(_X zYxi6!&r)OdOtx<_Z@;t=qV;VgPGH5NY%1S5oSU2gl$=0yVITR<%_!Xj68R^@ooEM&wuLOj&@=TQPGE6yq~AJxC(i#mXz!Yq{6TIB z6X>vPnSb6_>0mXzf=yU=IvAAnTrTuZFpkvP&n$*_m9)7_?@c0=dS7?7cU&7;Iu2}$ zYx{P5q5>9IsNARI&=-ERzJujIv8CPYucQ4Uay#1xAX0ozUF59T zBP-m`RV~@nOM_7cWC@%v`F)v&%0IN}1?$^5Z=lui$x}W(6}KFe%>XIAbZbc&8lKG! zOMdLPaMwq*Rq5boNR`G0XT;OAJGa- z+9PuRY~elsLsV<}3-Mz{C~vt)RswyZ8;faLSRlaUMQl49^)O-J#_doTFhe^Ez6}XfoXM&41W8I>fNikpWdMj zx~Hx@Q}Y`+0L-l>DyuB&twBtgg`d}%81R)ceP!Kru7v)d|lBZuEoI1 zdF;%*fzNuYM_A5^i3wk6$6ETn-<<5$fae0)y&5j&PcavOr>EC?nG(Rm2-c(=E?sBA zoe+)IURO>0gOB25vu3wudT0xN+)#a@-?k2#%ys>uB$QNG-P577e}uq!=D&F?dv_tJ zFME$bMqzjdq4PyHZHKkveVS17E2B@{Dz3U?1NLb@Q9*`Yrwf1$wOcT6VAYKaLe}bV zFtgykp?NPs3>%E9N?{H}R7!vHDvT~U);$=veMXeO`o`{$_C+;?4M9UISE>}}Y0uAW zj@yRchbpySHIzQX`s}~x!nU=PE$C-YRjX?7wZ;{+_PRnD1v`D|@x`GrzH@MvRc7!- z*GfLjf>E6&UC@W(@_cwSo2E^)s!<-DlkARv+$5qk> z?z4_^P1-tnOuB5eQyS(uT4{50gN@J7L^*CaB3$BBNwpUQ)uX_z^uqZN8taR|Zmf?&bYTebcEhs|U7lZ_GWS|?&S2I68$5Jbxk1 z-g&x+N9{+Wyz4HvXlwe-mwZw|nw}_>=!0LFl>XObf?Z) zKF{hl=HCKD?IONZxU9vj)%N+#=S@(BY$?-)&nhqpcvlbWc`rZ)qU?;~l2^Vlp+T^^3x_OQtW=aSua9hU^WFo;t-JUOuM3 z(em5?TQz>Yu@M9=Mf13TkgVbxfR$5HmIB8&gN{KBZ?ekgUM-$H^E^}~4)3VwF8{VC zhEl6l&L#rG#NR|DGdwnzDD$X^da$p6UnGU~09#`2V@1_ItnZXMCJFHazLIFZRB%5L zFD5y}9-(pqA;Bj878Y#gj((xiMK1EtFx6u+sVz!4lZTMtm01^RXO+@yshEcZ2Uhz+ zg{;-3a`I>#`Tb=Ko*`;OKifln1B~E?5t7$5+qH)5H-$VAM^MY^{&vVhcFzzi3$)n zmaibT<22#Uz0<8G9fi*;(^(R)8}>Rfh4FEElLh&SY0T!kQ3~MFakfv_6xL7Pm^AF( z&g4t3Dw5q=)LDvlsL@4+-r?A+$;6Y;yFP^QX7_EnG`V<05qQF{f9I&K zB$B&^`Z5Bzpe0#BpW%f~nXO1BBUQE5aD{WZMTLXx zY!SjKwepjI>#MjmCDIru+qN20Hhk@Cj*agook){Vp~EY2Lsldsp0djE-Ca9RW-#T8 zj5wX0#EaMCaY#mneni4Ds{8z@h2v8`f*N+5iICNNGX@XqtWk2&Ht4e_$Wt>0#c#jr z=?qqR?tjvLD>szuqY2OOxjS=NQgg|;(k(mE6ndJ|`$CD`)Gb|Fah2!FSFP~aQEpCw$*$q`Y2`Th+z) zBjZ$dI_$&)A>~r*Mc8N)liR#oTEtuMQ+2~vKS(>9ElMCjqLzJ^Y$Z&gFsJUka?f{r zEQXqaEGgt#6!s;?)MHX5neBOEnK|zk&Oa~eIFBpcJS9gwh_P_7Ilsh&uOAH^i6bX9 z&kP!nB#g?ev~;0gAzWjv4K+t^l!kTckL*!ghrFfPav+$Q5Z%#axE?Ntvd8wQwKo5` zOZ|X9p7PcXy{gw64f&6*?ZG*FmCQdg0=^HS+zEGiMU3$mVVsG^_U*3ZuraaxcKNDh z)iHl5F*c0cJ>^<2dAXP{>@}GweC5`v%A{XV%jRuJQryzc)YSE z*SY?@qXcZh;~H~qVl_a)Zl+C0<~2m>kH(|zFIUoraEPqG%M`qbq!3)J;hRn3UKB2y z(^3MSo2K!~S};6bND@!u!x?Id+@X15BwUs@zXBG-=Cm;PRLaR zt+6EzP~~L#ZbPYiI|w7rif@#+wFXEP1Y?4q3#M&1vt)U0xlFQ!?&BXmY|e=_i~rhw zn=qIS$_1;`_;#?7Mdo;Q+r3!CiM%9|+{kw|jmwA!OfR~^#qpxcih^e+&QJ3T0^%2A zqRi+YUNQRSu|9s@LHVZioxY~hNHPyHsYz|WK`Zs*Srf@@WyZ0{mOM9^k|@q3m$}!s z16V;-0$W&WUSIP9CJum&veA<;PRl2*NhpOib=}2u9aSNiIsda~S)J}S-wg20h`^yS z!7M4z!biq${aP@=&K zVLS|*q-}K7&rU^&(Fl_E^%ip(BQ9NsJNP(i!JF1s*K~CxC&E^wOq?oihQJ3|d!YnX z0$%p}ja_aOnuOais2Q$k!fpkgeiUB8O_c6ra+RG@^e| zY@L33$*HsuTN5Pq;EI$Z-dU&F&`G0~3BLj)pKl0`-*8MYsI)Nq)- zShI$uuoA8WI2H%b4kG#V&C`RliH<)jZJpFPdQG@?zJ=9OtMA@Q$hf8bEYe@}>VAmh zf)$WKYHJY4N?d!L1|sJAl)!n>Z~CiRyinI>Wm=88nH1m9)nvvSq!c zuOQ?9HKU)KcuD_RN#$xI%N?a@tEUCaizT{w;B5nZaku21Nq*gT9e+mL#>&`BH*G2w z^U49eQJmL|p)mW?8~*Gtrn(}Zv-`hFlpnCdq{CTpU_XsF^KGm11-7DOYxC za3C3QzkQLkJw!Nwk(E*c+6a$B=C5URfVX|CG^uS9u)pF2Wm7*UZjCy{RV9Ds5syhR_vSho_%$?Pb4u9!WDcwFL2w%W_I@#AvdMW%J(wN;KK-)66KUktHOy zo)FnZIElQ+#^et@^=F-fyfkZb3#blECPZWM>BuZmtiBt*mg#QjHZzYB(6Y4Hw2hq{a)^e|EAtMlt9(r$y2 zzK|5%8Fy*APgtQn_bp(6M{QlSNe7xjC4EGK{W8npaKe|RsYam0MCCJ%G!N;=+bWNg z?*>n|bS1{RYAbC`nfj|`-LZyok~^tPnVD#k(-*U(oJp4c=yvLxwhc+p%^fy@>{4EH z;wwjlb3cmdJd!8mh&WTX&R8gRQ0aV}w4}Juzw^D)0B52KAPk)UWc>U`Tsw;#St9oO z&0Juo9E6Yq@PfP`qRR9e5=p)P^RWaw@C@qk!4l@F{4 z>DORlAM}BsOVL~MCB#5Hx1IUpZNvJ99KGFOr-Q=XA@1#uC7I+VOeyG%9?*A}AtjO& z*ylllV5>J-AFLTb9CsTS(!UMy*=$&^1N1?V62=ocpB{_#C<&2z+X+~1AqN&45Va>_ zRAjJT#haI`dviP8^CLAm;`+&;Jc!JqlLqi|UZ<*Uz+$$y4@-fywxm_zP#Ph`~^$CDN z(9L%22bcPkX#kvDTeb9;_0YWvAH{}SxNmYNl3myqSrlx;Nb6v-1GvlTv-|1e_#8j8 z5|xqh#!nQq)$p%;ZTs$Vla-MJ<4y@tj1nYlZrbXc>o=q9`k&lwg2}AjqaN|c=?0Qb z!enO?#JziXLDVoGPQ7pT7wq8VBocP+%igGCV4Wx*NMf!t4WkrCw*^R-=lGM=CT-ak^J|bZu_Q8lEx{!mxno>$8DM^IWDF-L9`U zW?ti1WHCxuy_YrGc(X}54`0Ff!S$I_8r_V~wO%j-1L*y~`Z(bM+di+vKaY&-;2FP; zHJZ#L08#u4nYc zd``f6H9xkgqx2LjQ5OGanEj%3bmX;2sk{IX0P`HAc2qozQp-p#XR+QkdM9eAPqCvE zSUUq@BWAk*v8kz$PbRJ#2wcoQzPpSA|#dS6$Hi zf*1yl-Sc-ESv%HzKd+gn60v)_Kj(O*Gir{dQt$zB4Q7~&48|=dz|7)_*h=z;o5d9` zo~VW>Ng40(=LfS2UCxZis{#Rc1cEBnuISp=v9W+l)c$e%)^cg*yWr7evUtm^{*C2` zIY$DSk~sHo<(6WjR#YeQuB^DSy?)Z&XB^|j-wxM6G&3#J1i6qL#@?It6!Z* zwW9=s>3NqKSVwFYi?fv$xN!+gq&#Q?qJS#s56fMW^MQv!7 za>^R&f36E9)tB{IHdTtKcD#M>{f4;ak8`Yt|0B} z3;bU7JE@W4q7pOK8mg`DLWQyp79~oVL#PGQEYbCh|b6yx$r2Jf2jR~|$ zLhGY9<{jNy&=h)+n{yioOvsTG*h)PQaZDfgp*a8zFo6o9Kg)j5(QJ4K9h{8jok&RB z=fp?0d8G(Ib!851i=_DCbPJ5yqkJv5#5*RFL3jo9FIZUJNPvE>)OoHx90DCCKtO_0=q9~0e-e@`+HoY;LI6={9OhJ~v}#FiX>QfpRGRpbi99NFwJEf7b3XalOM^S06~Y?%xuY({o`=A^=-^|6-R$Dm z(dL8#OciWeP8|9NWaG+{N_`Y}n@H%44PygZO7pq*3NLhr-e&~lL^OFqYA)EIgO5x? zwRo=?PG0fn-r8qPX;0SGr5%|D00@tGZeu>~Z`K^gCzI(mFh{&&v}B4NlL5}#X$^Og z-EkHpx|bo8tGcJ8Ol(vMUSF4nF7qH>>=ZWho2wv|7(WMC4Zra4`^#LBD|1R{u5rHM>dj!KmK*(Ki~uZkACK%aVqSHI{pURB=Q?R z>7VGEzeg7R9bQS~H-yqZyZsd@B=Q>o>YtB=1@MLcfr9$e3;vF(=%1lLf2At=zwr9E zr2adDqJL)aPh9;8)%15%#r`{kVt;1v@5TNTQ0!0d;{WgHFtPtGjM)Do%-^HK_yqXy zF@L{7tS~sRe`3*ogM?wASNy+2uXur?!uX=U0 zKS5?f7|7Z`L1scv1^?fI%zh{SJI2k0LEv9-Gd_M%KH)#(%@*)l$W~j?2kQWQ>u9FP zyZ}0a$AynN4H4gy=2z$|54_Y{__`Kfli0??Uy>@n#(VO;s&L-l*-Y)pcXA=VyTTve z#yjwaxb40TyEpv769Y4|w6gN6SwHeSKdh6GSVh#-94&m9sSzwWJ)Jp1k^uk~-b&5lvL!)vhBXT zQul{-$uxujE&qlX#F*27nT9mt_zgwvfcSZ|OG}r&0a*3nz$yKl`B4SU`i6ldxfw-kTY3N2{-v0GZWV2)}~s3p(mOHLB$PxNJGg&A8kD$~yv3CIg*5>V0+ZLjilK%C}XJvXkD7N#TBUMq0 zS=v*ziwmp->lGDc=Prx)y0#Z8+np{3hY(8!B5{u{_4hUvg?Em7qD{_PW*kM?WFxN9 z>b@8~Nn@Xk*QDvO9IKeFkT&=9PF+6Z0%NF(9R+c<%6+UZJlSnSczl^{{)n2|{^DU^ z*DB|_6o}_zk&k68d8kP`2y>3$6Mnodf1HWz&wPJc?cC*%0eLV9=EN|hS49Qj=F?eLC> zM_rZ4ZuE-wT)BSLeEP}&qm01_Keyn{ns2?327kLn^K$K%_oIv#7*(MbU)9#bk9R!! z*Jw{HP>XPMivR|3t;p_h+Km=_Z4&25JZCbKJk>6BI4qU*aW(F#`&wD-FwMzYyBoG~ zLgh_6bFAo9`sGdyxV_EyA+P6ppRu99<|1C(k+I^{adi|)(e4(Ui}(*SiBH z{}8MT%yK-UPP+HVf4SqF;Gx5K%j9NJ#{RdO@LO?VT@!m34c*anUJHaG+%FrgPix!j z>gzQcH>V=p=XYp@Pi9?{%;L_6-mueWdptV8R77!TABSVk;-(9quzK5R9tC8kaT}Z- zy2PQj>PoJa)tgaY(j8kd@tc5`!~AjvJ^Dv6Gcj?@(WQ)}&+LbFOwmu9<9FFU==b@w z(?+gm1>mczkK61SPFoRjLzhm1pZd>89op3Fu)D^hC8{T{j?(^By2} zt6c=SRh;%{ms@Aw%7`pB+Z2fO68kxax+jxYeD-rLn60Y8M@ z#1%P89pbxCZgCsR8j7B!G=6Z+xcBX5Uz>v7Yaa`2=#}e^$~X#_xms5YR&3>K&78>C zM8DJ6K;E1tAgP32_grjOtS_|rT@6wgp9(nkgffR4$=noHwYRvP;jU--d`0bu(Pv++ zjCN<$svk`yp|8BX?S|8C?2(vy5vX~Ozau8YUVc+<-dM%^2l{3x;Tx~$ zUekIJjmtd8;zEAA@5;N}b*amF0;I&v#9Bpz*HQvHrcj<^7vTc6AArhm&(ChDJ9nL@ z@mhbN`&h4e6w95keBy?)TtuiqehTIVJqef5h#3n*ru%vcs}$f9u% z=?@+E#Lh-$Y7Dace&u4yk9xQxKT26uelZ^H{)O>l299lc!#df$s>9L`ef*GSNV&Dz zffK6}OlfSQc~6v|@1^ARnOti8;u-R0_ioL4?Yze~P&iGk|5B3IRYZ|uT+^=@k?D+y z-LZoH0y6~<@5%k7**z`CEKR9XJjXOD2z#2LpwGrTKHp0RF{iK4>jsf*m+5s&`nK1d zkrkKzqpJMdG40I*-TXJ0GBgddHw4tEjf1`@O@01HibPI^+Fm{PcnkRUjf*6IPQuWF ztq5Kj8P9QbFE7Qa>-tNdImPUD>TIG&cVs4M%dEANH0#uaa4+S$@sys}PT>w>P{W0Z zx>S0E-~OrdTM0ofU;Vmf_~I)A@P*sF``oZ68o9klfp~Ih-m1BnE^@NUt9h|mPwh%M z;(g7#^SyPNXuB9XS>4X-f1N^pb1qviFLpIObQZZmEQCTYMW%3BwH~No4)e4i7I)U_ zTcgp%B84LJ-h$$$t~WR3$GDg&%~9N3tc;Qt^%_{s=D9wOR8^q&?C@`tsl%L9mli(n zZuyc7wV4wxPbhw0_TGAnR0Qxi&SSrlPnpJ~eGj>eDrkiaQ!2 z;#K$aCenkqR-|`x9kMm4fbp?4O0E(Uc>0AW-S^bXhSjsD5SKqM_hz^HTz;f940--S z6Z`!nHmF2;_Qy;ktB}oeLY3pb{X7Wd{ug6oM@oc&%QR1>hQFowTpmp*}Av;R3xyVR@H=Y~|I6C03=XDQ!a*pG|@`J_!m=n;aY+^g}s+d6LL8h=* zy)3#A~ zU!6sp#fgc#0?Z?J#118pGHdN|v)BE>!t?tz#OU)XogvZf9Gu%o$s3#HB=P-#Yd^2v z4UJ5R>%%Q-g}6s~aYx4j!?c+A6LUDS-EN>5eWCd+5Mmf@(kQZ1-e8GzLiv(9B5aYZ zsAE0t1_ucDQ3N$|?hR!-M?Q zmywY}!jr0RdhdUX!w`Sgm;4on-LI=b%8cc!n@y6_l1bywIO zzip-vzA^6QE_3lis;K$!%4ICJOs}MnI6Z8kX3Hurq;j;1yYJ^qaH%~~@Mr2A#engr zNj+apv4cjJ@aTO`^R?|VnOVu}Uq{~*j4*{n3=Hf>FY$^pSEOJV>vNfgU9vCwO&?R% zv=tuT*NAOBpyG@oOOnEhxT>*8X&VqDBA(lOgqZfLPlF>WIyY1ey% z>oz()(CT{QIREBoe?(MM`s9}rdv=xUrVOtrx?D%&o^j(!V=?z$1n-h2v%9wiN7B6H=_mx!sf8g%M}P3$Ctk6?Z1i7mzs%NiC9z113^==}x_86UeJ7ZANH z7yE`PcWRy|c%c!IAH}vSu8Ggrga-{|4o52chp=;E{h-4yDuoN%#XFs@cpy^;7=pi| z)*94!Z87l{JH2lsCXx)Uws-s9=@i>WITU(VOauMXvnboy2ffpfDdPWSUpr0B@9;x5 z#O>$LaNpKnhJdXN5!AxkWLK@fkBCH~X*WfyrzyDwru~dDmz}0z3V_zb z7tiKuVqLHRy87+*cx-VKmZ!)2^kixLJALF_Q&W>=ywo>JbO6BJsfkJVIMK#mEC4`9 z^Yu;mGz|n7&E`~g(KwIU=M+!2(=@jEn|+yoWvh7`2nGPOi@5-@xLRO90DcY}03erz zU;#J-ny~@8vZu|n<~6iIb5Rs6Ys7aKdP3V6e4TQgoDE%F*`QuFCH%=;7o3mB2@*t; zTC#K>Ylh9FwuPMlM(0YF$j=R*>=AVz1lrk@mNiy9MK!Br7|b?kCAjo+1;=}?AzmLv zCYTO&Dfi9pbuSD(E%VBUYo$tV_j%kQ@xdSRr7s#5tKIOSuxYB`W$kW_i!4|3f0avH z+jiW@crklN>ZAI+k+k?xqhzYGO+z_QP%7o1?NJ+;6%ORe~hqb9y!! z*ww08Uob~uPJ`s9f|AoBt0VDW7Q{kV>GBuT3nE+SeJPDxxA3(`^+zYKH&o~uD>Yq4 z0}Ccnq@BM&$#30R5L$~Es(IKn0TT3&9ad9R$c zb)Y#?6{H4fT8}`as~bTpM*onQRu&(F(F|>XHIRDEw5-2H7M z*s0Wn4C_0P3-Qs;Q0-7V>ZT`O56O~Y(^9ZhAx%iG0?q$eBmjyFCPQ1|Au<51bE=eHwZH+G#N@merMv@(kFx#4whx^KPm(ZI5}M3^ zZj)#F=PyAIK&rc|GG z(vPMG?Qgekny)UtFz+zaxSh4mtQjv?&d^=d9l@aAFYx$ZR3)c4bCk`S)Lg&O5N(E>g^*#g-lO%uP-f3G&oID(S~#vg z_RFMwQvff!xRxWKlpaO2%grxaT(Xk@Cqbo>JVy<>CZ%ozw$e9eUh=pN!PJyS50=}% zSZ8a_HqY8O9OVH$I1krcdE@IgPP3cd)-O&pK-_R8; z7|yyWi`|eGd?|W!DcSm9NL)3BmKtH*eZH}*n4LM?7OoBgFERmlDoNMrQJT42GtgE3 z;ST?cereKvuQ{vF0qjP`5-n|t;JD6-NfXRM7z-Ds@i)+!voUNXO7TL&%$#MK54)-) zy}C*iU(tc=HC+bY^PM_je+whbhsWzVKvPU9?A8xwW(wd})FoS-qE@Reo;Gi`RSG1( zej1ROJ?6Zjmu|pQHJtlE&E+L0R{pXZ2lE}i7P?9cA*2#is>>uIr0e^+v6b?^`66h0 zbh0SF5_oetWB{$GSWvtk*)Ebg6%+N?9`ramr;3BOI4z0y9%?aoH1W2bEn$j~QFY&? z>vJ~_Bw`xQ=gMBr8kMd#8*H3N@eLX2nIWpsEo^rFP|<%CoC%$mImoDo+hoK^%c(*v zHtdFRzjepb%NU8Fs*>}|8qBtA2-fq8(1;c1!%whfb=I5J- zC1rIrF5mIz)<%RK$;G2zF;DiE&0}1ob;^5g0|>`D%D!%k^MW->bQe)!l4WEDaUOjY zyDqs?8MXKlirH?hC(d+*$L`MXo{XmGw@x+3NeZBB!Hc4p>kI^?1)*EITlfWBWpF+B z6y(cXbW!V_Y%qkCPJf0s*aFVAT0h3=%0J>U$*ED=e0bVW2)u zO*PhS)SR4lE)rH&t-^w_}?p$<``#pIn6enzERDW7XTXinslFC}f(&KJdiLa=#$=2LSk5oA_ z{dyL^>~-Yb-&z11^oK&E9_WBC8|ff~^mT3ihO0+$aOZY63(tuHxU<;Ky$+5dcyeEE znXVsnwYr=p4t}ijG8XTp(9OHp+AbAus;5U^oJwuMMvxr=lK^)x+WU#bbn^vN4MMx- z?!B2f?Cht;Sl?ncA@yUpO>4wzvG@i6(e9Hpl z;3^lVTSV)sC>qc2x^Y$88^Wrw%ipl&AS0V|2xSe4_us>3{NKE}TNM96^I2&k>8Bj{ z;TH#OHX{mSkTdqf36S)6?!J!gr7{(b&q2QhKffyO>vp~g1{ZIctEmi+(l=Yu$+Fu&x`e5!N z#dpyBz|Z>V(Y&xm;;FVT$3@UDm#3C4R>L1`He<1Zl!L^~3F6(FWLvetk6&5)Z#8-k z>Vabk#^#vhgi#q0It7F|arZ@%?p4)D5il4}kgGgw;JUZtc}*RA`MNtWBB~y&{}||+ zbM5fdU-cW_nz~mSl3*UxH8Vc*G!m0~VaB zEq22b(sdwm)AN+V=d-;Z`_G?seN*@SstYaP4Q+nT ziQzfbW3jgyU4iPAO>=o2>%vtC2UgsVs%6I!xOZzT53W_M3r#5*{k7h<#MHSOeOqbX0+AtA zlffJli*baZS@Oq^M8qv!LpEHn47I?rFN1yed9OE<=>Rc-&DdY5>`?lB<3C&IofRQi zw+U;)xep@VE)t*T{d*Aor{Rs!0mu5+-vt!s-7eumA;U1Syms(JN^CQBK-ahyRH)}C zJuAlYwB;sKh7UG4kIixbfL{7-%#{L|RBmc~Wouy}+g(1_F{Xs>Sjh;OJV|;t;u&NT z5>~0N1$KhTGsV$*k|;;92opm=x3)MH|I{$NnNw-D9gzoLQi^&(CvnJ<_)yu7Zc7Do z919olTnqgCZVA_$?3&~jrIjjXO{O;q9c#Jp5E9J(fZ-ODl?>BJ9Mc#Rc)3obXkkLH zjbg6ckcpJqD7cCd%i;F~_Jmrc*GGTQ0o)I2CW*w%0ouRxe7>bJD-UMnCGq^#lcc22 zQswzO9df{(XOO${5UhaMzw~5;vhL)SB~nC4x~(X)a3_A3#BlH&!%0XEJOra_S;hbC znH=Ao=r#)K{d+;R!GN6n|Lm!v1W`t8l&<_)g{&Al*Z@WhgP0jPq78oj?>$*za2UiD zboj5q2yZ6A(7_70|1TB&TTlF@$vA&GW_M-9O;N+?%RMq zc}T%S8WLP!#WRe!{5f#oepH{w(vax9D4v--h8q(_NK>S+N(?j06v*1Swe>lBT2nt{ z*SXTLw5 zIhKsv_a(tR$DRP$2>B%}_;O%|{Z?_AYjx(mfqI6!e;pQ(O{ZY$A37^@&9lNLXUDsM@G}IDkPGQlNF|c)L(PHRP{D#VOR*Lj>sj%NYH`qW*727dVcdjJvq@ zWBA=}IWu#z^F*AD?_+*pZEVe02nmIiaddw8FUW_qC49YrZU+?VFfsAgEwDDlxP?~fcO=s)e_I1l&+4#AjTJS7yAQ41x9yE(PD9MwV^YTUlXOr}JSW{>rj#O>BczSb^xVjJekG-h>o-5)Om0Jwa`Pz};{peY zxxlAx$`auw@BHO{A^(_2mV5tl?YU@Ue?dWhzzUZ`gHA)IHkgT!s1N0W0tehP-`Rbs)U@Wqb9&~M*N$!#=(;V8%0P&k~g@dtF){(8*lrdDN&w6OhZvi zrH-ukW(?sNsZ-eUaxqD1Mp+ejP8tH@onz}4_ zDy8o-Juu}gM}?8Gl$pkE5}M9yS3rI`Q~>Yjt%4s9D#;i*r3*LqP)aECu=@ij>Kf8& zEA{V4QUK#X$;;ju%_QuVⅅqv8^OvkIw1nj0Qpc_{PA{`nf*HB!Lvg_X7|??v|@7 zE4`!sMrqy2R1mk!11PKRZo3U5+J1PBJYvPM>rK@R0^>VMQE^WTyyoz%o<51g?z9a! zUD{d3EG{ZNj<;11JQe@u=|OCjNmtaP(*ezq%-nxkn##sJLdnX#uHBx#`1+99{@cGh zdrm@VN=)sa*Gm;Sh{b;pz<6fLT!1XkRw>QtZ&BeLj9>Xj0wcx{+;`#rTWaFXKIW0& zZHxo@M_Qw}ERT}6NV&1=;f1hDL;|dWNzC(!zw}EL;WwVq3DMsqesLzIvXgI>YIX5) zshr);Z--Kuk6bQ&{5QvF_uMA-2s@2gEuU@jaVbn#(( zBM);m64I!k)&Iq6LVab`N>%t1w#1M@#B)rmbay6<*d&X?PNL0;*^0Am3LcQAjt%P* z25wEx2~h5HdQ=`gj_N#rH2Vyw`$mEtqp_k{m4Sy1gCVI#E6vU&WlYR>{d-l0lYaB@ ze@-T0yv4urpf%5S`~yDITcgXqH&%AZE51d4O<5(5AX%3wzK**Fq$ohJEKg+Kb!Mv231U9!B^dfApB8GFFc?_hitPmY$JFou$9 z>2NL|lVzfY;=WIL3Fgt!25(pwbA28-qs6-fb4Q!84Rv34n1r3{fUO@*keldzk8Oh! zu3<4EFSmg9eBeE$@z{+?g^HZWzI3{Lxi7QeSrlg=)NTD!~n`MGc{MILl*&Z=Su#So2#u{dN&*KG&A~0c;^J_hM%=> zpLGaGzS_da#P3=(m$Az9>f|rMqjnc>wV|sw^K$3QT_Raa8?VW~v%6 z+dF9TZ+nvTvj5nV*l9{4PnJCt5}Jczo1fDbl$IHuMyEP0J)~$jwi6SW2Gz@PrQO|G zUUx3!ncUu>3;4aAFQuj$TjHT>VGr<{`?}~hgm$0Gy=cpJ`3Iys0+hpWQM%OL;j8b{6}!^-}uk}5f<~GXzSmZ)BgzU{;vZtkeKnryj_3Q(u6wKS%o_Q z%zj##cMKE!ToM5WJCDfRPd@;36M*>P0i^m;-O_(Uxu}v4e&9?{2g^uP4f2+2|A_GB zdT`a~jHo9k9_eXRss^1ADEx3*4S>5x)WF_hJS+xDp@1=X_JV4zH+21z0TaIh(Dg>- z@3iMXKpTs?FbT$Mw!g9M8KF%?DdUwruK@5S;rWd39P!bapAT|#)9>-MU;|*B0Q@_7 zK1%Df>c3$D7J6&Myv`3Q4%Zm&i~i00|6lHszjx+;p6}k;>SmTK`-H<1GuLlU-oBCCf~Plc8e{xUjOxoJ1Eri2*d%q%F>ySD-FJ1)r`=C>wk59>Hv!n~UEnFW9j%q@rE8N|< zV&NZkqd7cAQ3p4o0AnrM^V+xoFI;!k-;D;oX|i~b(-5Zr(3**3%PrD(a=zo5BMU{Q zp{?QW6>JyFxRUoeOI>}$W2Y}@_N?2XBg0GUU6~D0V$beBZfx%>$}e^OfV`uDL_G9G z3{On=w>K$dUsJ^iULnm{G+(p=N1o$ot-4U*w;Ho`_uH>^zC*AyEiJJJ;Qjo)py8GC zs|0P4G1j&rm&egknY&Nhb`P98r#dg`&|7Jn8Bx~Zbh|L3Z*r;S(IwIJPgk5aOe+Or z>Mepq<+C3OrgjG~Ma22wn&Mb}y2xh*VZ1$QWq0D@^W(rh;!gr?5|BmJLj=m27BsXN zL5n@n$|F+nb^Pp5OT(ANCFGXuY0BMd81n7FA#awf!A#;a_jbK0J{JWz=a9{PaMAKP z^4;+1rNmXh)seS)8D{c*TjV&PQAIpl-13e_8HSk63zx37m@)d1Ou%vH%Ri20uHiu=8*d6Gk`Zsb}lqv;r#l^oGrtaQ3n`2xvN%&lgf|a z0N6}w1#(;FV6IQV7s*Ctk9_}7>!?bWmiyq8<^67nQC<&IC$t#pxO>5X*NhD*T&uxw z=Lr3_8D(ODpsF1TxX?0$-w9NkoMQqUa3-Z8f8iv5th4`@`P=@Bh5Z)`177L>g>w8C z3uF6xll%jh|LGmmp1=0b@jO6E9aJsVe8`)D;i{1y*rJhv;rti+KJgAyn}5o@ekx!7 zf1+)X5SNnqtF{Hr4XPon%icYI`qZuSCl5dCd_Gwd=Dha2JKU>grzzanxL5d0=HZaA z!+a-M4ns}f3&wQbKGjNDWYeweJ+E(j?sDcu?tAk1>3a#q9Wj!2JMaR+u7bi7{E&nl z&39{=IAUkHrNnLQSC(z|Ca{QH}nM>9Y5N_2Z!1 z8~J@OHuJs@-V$}>AbTmkg3$LPj>_Is@ReO_l%L`D#_>A9CPXU9N$K0y)>>}$nAr&H zUtvD8F7ctjq6QTBK{mj&AQJJ?HRmP4LEL_%M1YBg)zPV?;mda$yTz1crBl$4J0AWl zWTsMc_c)+#iJPPfgRc@^BC1s1ziKwRlkD1uyUa(s?c&W}<*BP~n*iZzz^ zp}OAA;T|rWs_Cg)AXwHsezec3!2`YkU)xZ-^$`>4lMY=Hfh1bIc@ zen;VWF#@~nWG}C1f`nwza&}$WU5Gg?#U`jV$h9FSw{^$U#NR?!2lA1!K6_E=9nyEc zYy>MmDac#l)GdIaVA44y=LtEeayN~EiPhbKRd@zwJ?1jvE7CmbgxOn~Bx<;i}2U%7%RENf=UrU>db2)pK_v7G5joLUF*#`)-QL<4>c` z6rgvrj|A8!@N(h}E54dcCr@BHd1vm#joG(GiwOtM;8-PF54x(xfsFLxiTdCA-lU-) zD0`e3@#&*U+hTO8>4Ss;ASg2lt4LdoWk;3z4e=zO7BsG0+{`121)Jqt19L z6faf}r7YCPp8jGNza5s#Oy=Ffo^=I6OjkW8y{*WeI&w3wd}+=m+qud)6L;IwwxYJ5 ze_6ru?hIYa(1CiUx>HBM_t0A@1o*s;>{43~GQqihJ00TDz+CIOIe z;egwtdNSzHDhAuZOY01vESD~1Ctp(dxa6c{wk&&Sxg4u9mp+CvY24;D@#rwH$|X>j z=P+{X(>?tLzAM6F+!&IvZ-P_J_NJ_>$+!ddK#)W2kQwvtcxLK0Rk>z4Psh)XE)wjt zPB7Ws$<))Pk6uV8uQOvc5f>b0O*u7EO=%AnkJ0dATs{rV+5yzi%faxKv-DMVW%&Gj zk9NTFx**1{URu?@bmlgRrc-TLf{RQBe`|mc>b^puG`_}kmoLv{d-z(JIM<)a7OwlC zLKj+tB!bH`v@W;qkc{D_Us|~z46xWf4;gjK!vD#6-mo957WxvEd#Tv*C>^hI$?eb?zlC zilRlz2K~D0TgxXz$qBxOPuBM$-Y0A+%;eZMzezEH73*0OAYWMAh`)2)%|O~tZ(Y(k z7OTjsqxWs28I4=&pVP%>E+`8G<}6J3?}Q$b9=HCa9L8O{f^mm$l6`SKHwmj~?+?73 zuCJIw-QC1osF&wF)wEF-<%2$rLxtR+)La9p6xnKS8x3f`5gQn_Ssz=;>r~iI-=Oaf zuIQY2w6i7WgptE1<|vDkKREPrUUiwT!eFqt*-j=PDjP@ z_^){itlXI;sa;@?#7rkzrNfsB$}1}?t5=uAEwy%ya79Up;SRYae3D{W-d}dAtjAKz zAuEkRWMLep6R@vTzcgOXXp3De-}>(Ty>>{DD9RsBs?3LzA_iz5!-Xek>?X<-8oeC* z7Bgl$MoV@=uO13QRjhvoRvfeYA1p|O@e8I{Z9 z|9$mIofN534NN!D46YuG@k=WYZ z&N;-yB|}Wi;nN}?xC3`1uKCkhIiQS$Q4d0?33;bbSUoT* zD&XC5)jHVZlczvpN=i5vrN)&VkjR=y1(e)K%{9@7>h7&5Vl3dK&Jnx%Y(a;Lh9;3i zj@2;CvnA%U9$#L;YsuPcor2}OTgmLR)=Km5pZqqZX;rTGcbQ>#rv;S)#?cZ~=2pRU zpILkW9GKL2p#d1>^|18iipEtlZ0+~{5%?LU(@yl^yV4OHo?qse$ZZKdIt$A0=z8!S zLf^o+S6wN1TIhjZ8NO4@kGMuxvM-NvLt2J!l%SlU)#|PwXbH*n82wKW+!A{q%SZhfXlY_#f zlb5o3dr#V^!PyHaLj?odh1Uo#l@EEUy`nnf>?P9Ra_BA$odF(grXy$dWpp7{jI)Cy z{e$Szgg=1@j=;5$P|duLD!P}vGNv|1^l5A3^RjYVDze9?T9#Im1&lqXo&#&ws7tt6 zBz2gi%{_*JV>qy=9cx09nNCW;tgM7pZOM@3ZH)J_F739l4}|QP=r@69qtpG`Li z7=U`n;SeSpRhC-bLR!Tal+BF2V2dAAG^yio04r^c`C@x?c2|P}4}N1$@oR(zT>S-n zFl~Efiiv^(mSqKMV`Hty<~oo~8O598g1e@siaHb;&wl0XJ^cLqBiDAxLk^#49wQE} zO;$=-WFF8gHGm@nD~Fxd2t&kWt><_Q+(-hl!wNN&!T*%Qiooi72?`(kY`cUy|4`lJQ1FK)}c)WvOgM`ESm&eFys2*vSn* zHbP}9Ln8pwO#~1kfMxrTg%SQ!@ssdp3k}bX$VO87n;W@Z>$gT6B%El^B^pvF-|M1i zYt&*U*=;?C0mgT#nChv6K%um$BXwj7^P@VG=>%46lC-bwk3#(^1!?Fc+OpoH-^i=Q z>-N{Ku5k2xe!+#Ittf&a?qlIS*{IU~&)jM&Yo&D<=g$GY<B^1F< z+e&yM%)o#+F=6>|>)x29R(QaBbgTvVipe-D7^{@J#t(4DOOLq0COf0g9Kib-Zsc*| ztF4IhLe%7X=(y2J|1S(r%NOGh44iNTKymThMfZ{QeA?jATF*!{s@)(7q+|{`-6l4Gw49>6TGs^)HYA|4 z$q@Kv_Apx9+rvi1=dz7%0y$5TwH0hiv$^aV&Jl3^quJYY4Y4_6`&g_(t|Q?djJDb- zZ^$2fLHG#g+tiGEL>Sw+wyzk7xOE>du%$$F4@ndb)48|oA65Xxe5fZ&7M}vIlO>aL zpJ~~i1kku0LWL95{mc#~$)A0c?UM+L)dxwyER1!A$4v9W5O4Tr z#!e>Z24q){;h6MZ*mkgoF_3dkfZqw#0nO$NO1BX9PP1O6H?sw zR``66fRDFme(ohx)*SPO*v1Osn9kAIXU3s{&!R6cj^p{E90~eQo`IICX4UVqoq0WE zq|%@KNayAHJExl_QBQWgTkqo=(k-ViXkA+$#)-kqKW-2k2a-LEByK+nthLm-$bYQ= z;Y^m_^L*!?_ozv*$WyMftfw2YZ{KB{5^|{5tJn@(G>Q+%I*~7J{4}N9b7|yGtp2Nk zrdr)*q3b$d-fmW^#SCrKvuT*RF*1B&08I7oha0MpT{5puDHw?KMXZ!eiGGQgMh`nT zecG}Gq$H(R6J*ZrNl9D*!PK#n;6C(bShH1{_w1XOSfk-ugco#wS?>{R;KI8-@d*E8 z&D5s{VW1P0Dv5twI@v7}M|TzJD`U0!L^hF;ghK;h1Mhb@n3SfsOjqKmk|TjiWR>0H zc~x*%SDYK}DARdl-ji|e(-i1p+g6|w3`liuWi#=2hTttS}|i?U8fWt zz7rzq@Fz;Y5k^MJ%&OT$8N1GSw$%64BiIF%+@=SlD;M(+O1^93N#AzSm9(T*DelTI zRBzNGeRtzjBe#36ZfJqzN$}3Y$f<#$Xz(gJ56^t}^!6Pm8q+l~)L^=L6C1c<@tTbZ z>$8gP!aR@Xvx=}+r1#pvWyO1xW_(! z=44?c6*Rqwk{HpU=*_1sqs46`2s-cu&My0MMYTx3d2-qUF%r3|6N>PEg=^u37AQ{! zMXt7^Z8?3$?bNu9$@4AgYJ~aq37LC@+=1QejS-wVz{?XLLnte_2~mU=>SSC>1d?)u zBEG94(MO{U81JPSj-xkRBClRwX?#1bNw1sR`6^!SFjXjxIG1%E6d>Sm!o>ao? z(QgCC$vQz|?bRIavw|7LM@WGZ4LS)|zeseLUCuzn>)~uArn>q-1E_K9F&J^U%LHlW zCTZUEx;_|4<);pL@7`Ar(s4cL`^59un1gThlQ!E5CSwo}IP^B6Z8+>(tQEDkR2Ye4 zH^{t(FZ(LBTQ5giW<3$*y=cNNS!k>1=}vfK5X$TiTU#5=5O(U*H=?w$3MqTeU?psO zbL)eFLBN4KT3{!P)VBb=eiRKSq`g21A;p9BcX}SboNAF6u|C6n{GNhctN<87_J>_9 z*>L(L6a<2tSQ@v+yX{_ZSmB>qT;`ptx(QpwWy1Je)=b;wQh zmKr#;@c?MYbvfW1nR-Lxw36ZSof^5@S{cH1JpmrjrZn&4SI=KSe*HFJC`mXZNr(wW zaA>{}tK_`4eYLKu&jReQN`&-GbNlu}RKfFh!^)m)mo)g^>PB0_>O3}YBVN;}T7|*~ z+Qo9NQgR-hOUGvbUdIf&X)X-4o6XToe zK=Jd1_+w1@9ws)Esfx1&-&;OAmvQK&o4YZVm&#TOC4$nv%(pD@JdWjpdenvyIV( zkTVdig7!S-pc}LEVR-0!{elQ&i&bn+1j701!z;*x%m!o8A_jv?rWG1E4H2yKQ_w8< zNEp99*`oz7WSqv#8p_P!Sbn~|O-~3+LEskO$DoIM+}zw765In}pz~*;pnz2kLhfA% z$Yqd2y+<43ZOmve17ZgYEad?j7@n`NK>D%Sz$5k z1m%aZNo9=}OtY}nw2g|})2%RGHwd{(NO5*)oA&YDLx&A`!M6^ReZe8$-H!}D5PWwN z0t(zyh{Qh?ao>Ng9wa$`#sc>rxU`Sq$_)r`czp^Cr#0%W^c`gQY%9Nl)^xro3y9ss z^J|6y@rcOr>}hn;HQ$@QrTZ8@4Tp$G9dSGftS%KH!VFIt|92fqP{qX()ruA^G0vu5 z^04UYs60DeaHi9RLMhiBIoE=*PfwkrKfN?%oQ8_s2XK=}_-0Pfm|Y=S91@*$hS636 zCE@z9nlV=*Q}V&PWmD|_+%vG3aary!qtm3(PX^gJwc8-2O5J??-vk%&K`VAgB~Y?7 zYb{uo_Zj2v{t$&P^(zMx&LcZ(y>#ZXHp`+z1$1)~tz{1P^jbd3neFnLveC3qiYbdL zNtEoy2@wn~DXnj3Fly`%5mrC7P$faJ5Zh(-c?ooDd#3i=s}cqpdd9d6{wa+bJ7e=_ zp-(U1juy=~@-NyO2g2A;TB(j^5O-U#3td+@O|F6=AMGw6UmpYNYr*5$U4LWj&;hN; zP>wPI5#;6u&+#i)Pc?<3Z?(F710k;Dm~+*w2DfQ>t#Mgb0_2t$%)) zY1gBiC)+*qO|&iiI-8g(d|9|4vqWx+(cEK5Kn;7nH3^%d%KFxpvVP6cuVef8`UV4Q zJ=@8d!9(=^bnPX^&nNc2Jt7SQY7sQAkQ!v)k(7leMt*!;q}!$c-Hsj&6|O@$>}Rl_ zR)-|grH(UvR*kHW4Fj+>NrnxadJrCSnBnoo9GuW&naVJ#*RKpWHX3)7xWP~;RHPUD zP)#iu%IMoWdYaR2Yx&B^O46=uC}Nlm-TNGE%OELT*N~(r-|A6iiOV}uAA7HN^!UH- z3q=G??~b#<`WS2-gCZn-J>ph8+UsNQ_kUw!=nX@&v{a&9C}yc#y`yJ2e-xnc>k{rL zgRKhWhzexiQ{axhIm(FSipwz9_?1DVQ_1}N=yG{LOG5vr4&szrUKOR8i*B^I)92ZS?bMd4Dp+78! z{DOQMqe~9^t==cWHh(pomSFV$r}`(s68kbO5o{#D=K{#q!#9wWf@ojGI> z^hvEs4?NvD2`1M|e9YGT<+pzZ+O6{_PN=;8*pM)N zi|v0lG-8dYh8_Vgjxa2$LT2gC1cuRHjb-C5^^`yd z5PdcV45Oce#A1DpW8b@dfYDIBRT->#V6i$>_WkVuFv3Wm9Stde42Ar~5`gQ4XpL9= zyS%)GKSv!%i7gTd6n0e&GLwBUHhyk&ul6rbf!muo!O`FPHp949fM_|u#7L_<XxBTN-6dk2}&2^oklL)QU6F6BesQ|bQJs(ghX7}!^FEip>ajk1&4M;v9= zYJN-&7I}V4qrqNYQAG<&5M7URU?V=tS4l5OEVtbEx;ok-BE{o4d_`rZ-;r=F_B;;9DPI7K4RJ z68Hy1tJYp;A&JL%FDB=Esxr)GF77=xw`;_M&wytUIU69`n>d}0()9hWA_|U z$gjVG$)qvfeOdD&z-M1{H-e1znen;wYxGt@^*}EVNl0pe+$}q7f&F)=a!KOC4+b9H zmA7Vr@jral1rmn%2qrVP9wh~KtAY#E<&Wj+K#7GOV)VDA<5qS*is;0i6Mi44#A(<}!a>odI32o!XR~ssL4|4jHVL+8 zbg{lNcBYqiFN}UQ$qD~n+HvQ{`p5E+#u*z+SJ#>VY|P^K!F8`O@9{MudHh?1lbgj< z_UwaWOTbLkowy|;qs2Ff~{xS=Rtk6Ua|eJkXL>m)>1}h z*p+&_&h~T7qDI353tWSWIJlB3*^(#TFvJ`R*>~$m_ z+?Vqink5vy|ES$I)uK6FN|dfy|BZIV;MrwjfjTfBN1*q&e43$Vy)bEy|M_+2FpKal z0w=jX_6{&DADHthxX~UFecxjSPB*+#oRM7*@}=H8>R4}b0GGG#FL#4@6qYU2<{&58`wWfiuy>_a6dM`TtinUTj^Jwbr8|4*b zfmprb_=m@nE19Gm=ODoFW)ZW9@h&hM_LVWtOWBdI(@q)mX%9+%sNHV!?bAnLt0|8T zz$jZPcdsZth^CHf=YRR&;Hb%a?unVS?NoLdOg2P=s#U6YH!V$ z6#$TvL3#R6A5pOXe6=MfWw&Jii+BgK0VlI|?^9qG_ZHe4wL3Ui-uIxvot3-_39P5} zi{9lS6Aw#o02ThJ&3gU#Wd|7DZC2d2Xm@!&+t#za&Toqc zyZD##yUvOWmo9}%0v1|a*adbX6CkbTWU$`LW1(Dj9SwjFWYQT6^u5F5+$NMP**3Y%%Uu?slX{5gOx znhKs-^zqnczR-(OM8{c`l?r_g$QO>iibO`%lGn~7zaIyFukWokq2Y28?7UYS*YE7F zxV(-6u;9Pr=l+N9`&JDOez^tEpuF54mA$*1R{OGkxQ&hSC8WNT^UO)|-OpbcrwyHO zQM~7nO_|yO5$r)B!oBJQl2}{3xOcCgicPB7v)UqHH57W6#|y!hjvoa-Bva?@fV-Ne zb=v*@8uHpizrnE*J?pk4UnUN4!Ar8y-3lM8F*@n!{MpOa{VG8hZb04} zhbkLc4Z=BSY`OKJL4jAb9D>|!c_O6K${x<%wz0dLY;aKoc|6@LaYfHk>M8mbE1$oo zC1yD*{qo1F$j#EkUYo%{E77dWV(VRRU|HjmemKUoE3lWgr@+>cwPp{j2Q3O4w@|LKfJ3aea=wbr-|x*&YJi zKSmfSw7?-r$Se?bSoyYig$tYrb$ts1%|3oSyJT$)IBwZsFMarV5;PPJg1)QAvsW>R zbU&<4P*+Ptt5^RdW!WLLT*KL-S&5vk7s0az^H!Qh{o&AsoXhVdb}#XLKLt2)xR!q5 z_LUO~PCplR0ohqD(|<&6%k36YNi60jj5_3VMO(+Pe~~F#3NT03gAU|Ya7gtp4;lPG%K)1> z@ov^~@KLdq)sW-By}i{$@@Z1?pWsA{`%mn&$A?B~j|Bg>GagXQniD+NsNc_Y8yGDB zF3&R!XnVnVz1l%Z*P#&!@V-BRI^g2^_w^lB03;WLAi@~GuyW04-n$5l^rPpILfHpF z&4BMe4uFTp(|?H42WqNl4k&3{o`(O{=pL2q0)5-D{~P)Q6)JK50PuM}e!w&gaOJ;| zN}vt+NnB29!SN3gMw5DU|3WI?f5kg|y0)+N2lHdQk1=a%_~puvB0zy%Y~POpQyx&g zJ*xRXBM!flQQ*n4;09-(vi&5cU2|S~qE_rs*Q5WUPB8wxDzTfKIhb-|ud<*}v113e zE+Sw2pC_H~=e$bcvl`azhJWGa8himE+|Gyhung!7eDG?a4S$hH!PNjIP78AA|!`bKbYRyQ%N*o$uo>@q?6uzKQoVDIobo z5DRQ%g|EQw1MyX>V=MQ?5&-G~5|H?ypbB*8;S7Y(x8OTT=0K}_=7NFZYo-255pa2; zKRWy;iu#Xu5x9w8H-n_#{x&A=sRWdkJ?jG)>mEJrgm@Y^R{o@U9Js~<$sCqHods?< zWvQ;S|L{np24TS}`VM1`hZu+#{@!)Jxif%np7|>a0j%h!OXP13kN>od{d8vlfY330 zDmE~Q)6DGW3;^KAy}|V_F842o$8VPPCv+KM;pyf@EV2I`Su(uZHemaHB8?RWQdG8i z&bb&TnSNI34rCwlNO8+Wq{~I5&}`#9^v$}FS=K&}5aG`^Um?TzkhZ`bH$WkX%FL{2 z#NQqlB*M3@cLmAkkcYCKW}N+v@p{OltvuU>R%mEsy`@*VVw(vtyfRF3U#}!T8 zUqjJ(XJL$w^53*>@jYWNX&$Mlj*QF+K^#@-kp1}VbmAMSYkunN;4hT-gN>hkloSk| zBc-?MMRH{uc9M)Zs?Hu%#fz!1jrK-=w%ZEV@5l2Dlb_Q898AIG2~}<1joV^T)mEMz zmZvOxD(x(@MjfL#O3L!_KE*MAbIQ?bhLpw=g&uO+RP4`~4q&Oe{*FBe^71lg9Qut# zymQEziDcFZW?QE>=*NQ`-`FoVWZv$=W_XuuFn`yl$2=ulzJf>UP6?(wc-34qsj%1< zI9{%2%C|U0xY~Vo0scO|I7pZ#N11Tn~e;(;%^oK z-#d@5x|Ze-aj+oT6@)DVhVwHGqxul0Iw@!tA@`>iMS8P}hSs$qmHEIPaY_b8ck{*V z+PGeW5RWDtWZod|;;g(0IrlA{dZkSRHm<-nom?`@-@xt_;6s`o>2r5wE1ExgGFxQ? z)lJ0aj}6$efLVx;CdUA4V?vNLoYVK9zXfjlveS9C?a#^j3ANwzc5b$x>e$}gNC!l7 zS7jF;6?{$q*zWo24UAJ(DVz7;x4C=aBim2zy*1si{oZ3#hz-#SDC)h4tOt^!JM%le zhj1eW?htqo`K7^<)blAzQ}AcZUEh>m=k;7%vCi(zX{+pZ>9`6z0Zs+>AQp(TEVc?T zMcgk{yJN4AX}=~Lgl5Sbm~UB&NFs@tyCf)S)353A9(0G_DM(SeC1lesAyYJr6cu6DuOj1?>Ni?z6FF|H@zQE8o%&9LH# z3olAIT+YM{-C7h)?QK2@W+@0m)E^Rp`}PjFEY&>^$qRa~#p7pZ=}x?RJP2a-B)p*G zQ)=X+(20J zV3)gJRobaS@^b*6ZQeDc!nh6prP`DJTdYsBgt#uaoBM;0SX`|vy7l$tauMZDJl*A{ zePP;2go*xmaG7htaV5G%{229a`xO>x_cMe&H}W>&)rV^e?zfxqZ&f}?^uF42)d_`9 zN#rJ1cg2qEO`C`ZXLsN2D~iHa1^>7hsr^gDWT0-~&&Awe&Z}MSl!0XO``>+*d;Y_w zhK1|ze%ZqcEs|W4`&)i22q|BIlh=Qqe1&}K^0NfM{ib?miD-7FU1>?FBz45{kBOVe z76dy{ zTP;gSsqSfpCKX8OZC>Ct)1D`HFOmT`pt-1 zn(1PzEgYl;mE|mVHQobWD^}~#VbdfJ(-UVLT#a@*4+G4UQ@S)_1YoNCF>+x#qve?^ zR*v-`FQW}99pSsn9!z)gj^>1q_1=v3a9H$epS*2aUM!1i*>5_*DRc-Yw0>by(x@<% zXrV4TQtamzE2C@KE)XJo>``I*&|rk&KybscPyX`0&s&*Jf&m(L%V2Z-u*^yDS34tdtY!B!n-8o zy)$>Y3O{;Eh}mLGAK;F50Q}h8-EFfy_z;ZI>Ll>{7Wp0hH-SG%cH#ldWJ&)w9` z+u1_wuEP^6i=$#cvft=AKQXfqyJO*DV`lOHb?zOh>({UUS)Y`8Xq3yMqCDMS&*s7N z-uryF&bz6LoxK0TjDAuvccQTS=EEDm*u0kxJ=)FUqx;LqdXMY<7^VxSZ)(inefr|` zVeTU~cw%(cYzv! zYu1OaOjT9wW$P&fO##h;hW~;WK?bSEpR^w)t<3jO3`99sK^dRSKD?;{h?(TcUW$52qe z+9)+5Z=m$hC}6G9di~7f!1$14WR1CZ^TuM^s~$0EI7lf8gBUmUF5Umu{ zY#ACkmCn?fP*X_h(%Hiwl&EWUcfrP#9A!FwlSAT+h+*|=<$)l3#q9<=!GX3;=j{*d zEGF-=Jn_byj-S4;E7KD*;Ldj@YW<6WEY|yuU@B}h?QlX7DMnc>f8)yIj3 zRJ+eeO5dx*B~=h+;r5-D!MrY?Nl{8le$wJuly0VU*y53Rh{sGd8C665$~rbS_7+vW zmBbmK=)09dRH|GpuU#*#W1=}~3`L(6=Pzq~_eEaBuw=gLqh~?+xLOapdrvzCvp5WF z82e=Bse8ZDZ1BVgU6`VpO-?s*l3#8zixV;OSZr?er*N8J(L~%7Rtax~sdn2q70lyB zEmVGWD9w3C_AROs*cc~DcJm$nQUD(w>Xd{;ii*t%Dqo|;utq}7A|&tG6GWkvy{WAS z)rY?8Wh=S$SFolB%nq$ON|+8J4{@()VLz@@7wqUmWGiE@^-Qp3J5LEY+bTU^BR9Hk zihS{yA7#ZeX!*KJL?0MF8+zy>-Y0nn*NQ|>f~B#k@<3Xke)!HAs*&Z2%%UsQLE_0XoWNYYi$W|5va zQgVAzM>LRN)gZL$vwy2FlXjBx?6~iW4Tg!AF!k1v(#SnoH6Am*fRANQ55rmqV|HT2 zv}DNJefrQo&RVx_kX0H%&#BEOC&hUoQ&^CO!@UjI$OvTK_JCf{Gxc3oFfAW2_VxcP zx3o+QU9VcMo=ThYBxw5`;RSk5M~>L0vnorYx@zMW^X^f}-vB+@8~Ju1kw8vHq~eo4 zkbcE-JgX-OJH=6M>_^QXLPc_snxAnxZGKjSM~PW&Cn%bvN|1mACx=~C(QCL?61i7U zYQ*iWGIc?$k-A;KyS4ij3->9zJ6ydE%CTRAszszrJJB*V16CbAG^VF`3}p(VlH6c^ z7Z&U$=&h7ApB9}}U;#P6q}ZK2TPsgDbiG|e>>n9f5pU_~>xoi6>pdX+61%&AW!_mW z2h@5^1W~keckBQcDT9{_Hh=T75vO6Zh_vWH!}79L(b(Ad6*cPisCTjPt2TM(PN`zk zQkSUczPS^EOu-r9F2ES8A?Pzh3lxI36n9D_YZaeNzTvm*I%HQ%-w|@cdM{<)t!ne$ zn6g7D*^cy;a}8l1RH~<|^jEC8ng+G0L)p_EyJ07oaQ!{y==GR^ExIU9{ep>JIG0 zp5oUakZkYQKCM|cEM5^^WB6%%n_n}|zP2yY_)Q{qSGbl7FXHq(5vx321*oK=X8UxK z9V+VN>`=Sg7fDH(?VKj=Ee9ujD3iRRhMU33DBhy>$0HFjv1?FGG(sA zSu74NXM@LG4DgFYrSK3OHwqn0LRYjrfiW~$Kk00)yIO5ofgIl(LuZH0!&j=|jiXd` zyb9fzIN{WuxHZ3)+%aJqF&-!lahP+^H*i`~%0?M%PUEb2O-x4)utqsqpYX8aU)@hC zxH(RCTj);2Dvl$-@uY6ft%etPA3dL`8qX<-hIl9T8DuU3A^Z?pb3xB*CU(ek+#m1F zDz;hMijsevs>WL_zk6FnzZ?iwrcx$&AwFG<>ARcb#Dn2c>5_I^xnrcQj%vMCnvtLE zxa=?j$+OWxSwgYHJr@I+)1}ux0BZ>akoI_bdUDeFBI8ZG_+TpT4r{`wib+86Smrz# zJbq@-qe-ffn-B;yQ&Tzf#(zaJia)#@c|v;d`>}M&rtXAto1A#9UbUBTQdAF z@Tat2hkE}}PiDXIX+*C^?N z0rM>GNcCFCL@+5&Kb;EL4BU1RNC}9vie!zFpZ$IS!v^<^kDfB|U2&(kL|@a4y8`Hp zp<2XtBm6-UgxFS$9h0_Ll%1pdeU`IR-s)70erayv+hBHicWly3>6+DQwOaP*69nRY z2I)9=6!QAx(o+GL(NX&FIYE1s`94Ivbn6pkIXl|&!n*fV#EI3WP46)_6=2PkJO#~C zcPhWh$yIES{w0}6nOCdYDH!toULi5=hd)5+&nZ8*t&D9CJ9ftKw@G^`X$kJX@zKiP zCtWAizv1pUc-bsUdBzEjx#%~b7w?UXp^fCDK+Iu@BIeLT!o4cUKMQm1VG?85R zP|r*ZRrFK_^5azbxbNaVv}!Aoy*!gBIrnz^p9KS%gtk*81gLZIbe*jN_DIrfD!IE= znz|Ebhotm5nyL9F=fdd$>oe7ajw%z{aCtV?YoYgTB!y~4S{SRsPU$GPli3C!-sG1J z>y3>FqDU^tH~w+TxYh1?fp! zZF7KvJVJW7Gwci0eyh|vLC@TlAffUw&5~ zb+BO06I0vW)6h1@Q!IAq#JDW1hy$x+d&q~lxYF)2c+ILKSy7SXU3YoPY}C6Z9uLgj z0)Ul!^+>hGCAL(>vcij(bIR2y^PREhhjgxu8#rzB4PcYyor>F~WT!vlsq@=!eTj=n z>&qK>agy@d_t2aaAY+&&r$fnmPs{aj@jh%052kXVd;mg6u;*Ym!_uBqt!|Dv(c?XZ zbVBFe6b+ulUc)NVzuKWh*6a(nhV51gDQMOxWuMg2fk>=Zj|hfz#}sv3VewEf0Q~$f z_Kf;Y9GH;ZK8*T>+#D4pH~o2@cz)f>Lsh=^!N<*&5zm#<{!y1!5n!3L>VbO#DdLWy z&^whFDt;mxo3QZB7?9Kl*-HRmT43n7V7fIZ04P}#PDZ7~MJ3|Ps1w7~EeuUp?ifQ!q%w8(oDL@-g?DaP z@FlHIwY$uB zy*`;=g-_k+an&9ng{Q}M0O4m-7^jMko`z#OiV3hC;~I)rF_%lPjjOTuO8S?*IW}xN z3f&zD@VzUz56FhpLd4WKsJOE!y+w~yizNe0^79pp>vvm^$K%V1!kh=X*npe%1N&p% zIC2BC|cMB%$_LF2x?@1(5Z$H z4!p8n^Z1R&o%Wa0#P@vO=N{#6pYb?QAG{Pc(1LxlF%S*&dD>vD0q%?ZI_eH`wIR}u zl)Bh>Tih>d^OLqWzIN`B3+~E;xn0}36Ib%AJK5BubC4{Wuh)#6SLb9ro1;NTFmt7mE`fL1#yEtM7m4A!&Qf znBqpE?Q$AKoU0g*4{6I)9DT)p{iPUD>3;w0zzb0=ijkFN+}YNOSrtdS1%=PURW-*l zM39>MRT|*;o}JyTB0Et2mmJ8TrCx67icG{9=}Yi+-cj!NGFUrb%+lm!+l7AW$r{dw zo91g}!q=S&>diyyU?_tuX91}$13r?NGGODjNEUrVG`XJL94c7F$6Ib-0Mgr@tk|2p zLoKt&g{&uvx-^^K|Dq%OZk5=eA|fXRkJU!meD+HMl4lhKkE!qmnD*%X!+Jn6w+X_Iw(6OX_I?D`_k>`zK&vfEc!z|f3b7wk z`L2Ek&H1vfttwEif-8riLz)9FbAl~B;2z%hBlb18?}^&KAE6@ZcH?^ z60hXSNz~mZYo^Hum|eh$NoX39OpFxhz+mUx|1;!Iw!7slpD#qKlK$|h%<8rTk8sA8 z&EJu^1zAAPl}awrV}pLj`FtDMg{2Vu{C%TFSLA(K3|I`ItU_>)ID%n%;T7q~sc@3v zG^fY;1^Cy~|ap`96j znkm;P)Fk%-g0*;|n%5Z}aFD00vQ+W zUDv*$57nRVb~o;~O{y9m!R$6-$Sg}{v}~8^VlKA?8eNVhv8bY}%So46CcCVwg@p&@ zCXpaGu2q&edV(~H(B-ZaYiG7LafXHC zfM46=uv4CToUrFzZ<93aP~>rQ3N%-+*nM7e2y$0ldH4jVJ6sfZa(M_83mtOZ2cN!B zsT{9v^4@Z?UpW2%hYQ1(OhY})+hYW7B{>bB3$eisiTpQHcM&_{ zi{wU05n}S4flpHc5NWzL10eL=->@=Qho2d&!b)+7W`0(=*l_h?#M@*N>8{ftbz zv$m-VZ9Wne52dIAALj~OoM0suBI-;EgqRnKK3h4Y0tbaZO|p71`)o%0B!xBYW#?C9 znSlszj$)EBuO=);OwwSsU6ys=Gop-*zk9bO%C6$I$S@qv7&phkB?TrB9G`poR6gmM zN#yr+eRdQI4uVxEFRrfcnt{!q>47b2&U+pgzz>GBId_Uq_LeeP?>z;U0_y1aW%lWL zHJaaN)>l^o&w)0PvTQ}BhGuWUjC<1-H87IK&J2oCMeP|LQGLLFQzjo588`|yD|~T= z_^7jOGpnsfQ(`iSiqUL9sS7Q1PMiT%^1~;OJRT}H8R#PkpwEUcAj;Z<&b2L{y6Pee zG_|rFy!i@QqbxFG^0>K5hYKj|R=R}A#(#BDmb7=tfzdBQ4<(Pp3ySLBKrZZ>G6O9) zMBf>Sf-y5#mBOs-NUny3+bVRyd>-U;x-!YNh_?fwp#>Zj0p<4mPUY3X2S3}UJdFw+ zD~7j+vCRrI><;?88lN`snSXnFphF&jkPzBMfj+pT$vM;18qpIf$^`ms@ee6)DJUt~ z#gvX0>yVWVo1>Q-_kjdmt`_cZeddwpMJANeo@CTYq968ZKp?Is?S>0{@{1+jhN=+B zT)JroXlSHNYylJWFr@npXVHsaXOPe|Ne#Sv=SJC(7^5^ln9bZup!q4DW46yWt$3%aPCHUuR&@@CcJpcsmsqM;IWnuH9 z7(jU*s3&!j{@AiE)!{(e%t6^o5^7i__1jI|g?eaMa#A?&2UdkLN)SLq4+rUOfRmBX)Jp~`YsWqrK#IOjNz?$R^P#a~ zw?!Ai$%}tP{bhP26ALY|uEEqY#{U(%`Y%A&-;c|2Ui#l9@TYM<23QQiBtg0QEu@(> zI9gOi{+BABxSOl}5tJkGZW?wUNjZANSEKeQ6MbY?bw>MR6d#mBtve7QK?#_iPo_qS z4z3!~t#|=!h6VgQXLXykfp2C}8m?Vd1|P_y8|D)dJJm)RBia~qZZlE9Ff3lolGluV zAEt_zvSX%SLxC!uv`0wx{8&Nfi%TNrJNsZwQvMJ~CRNczpH0uAZ>C!jL7)cS`EJTW zx8R+HC8Hx_AbSLD;YJI>gh*0G>OQWHBFBL+@SlQMLmsQP>p!g=%jOi4Q-fiQNr3zA z4x%zh;@`f}e^)PSoQAp!k<6C_o<1ABHL#scN?s8y`UX9|p9F>t)Wye9_)GpTCH0L- z$IVn`L zZ-}BvjGACUK()&9kY0J9i+l7o$0fnB(JtXbgCGZoDylp+mSo;_f&dTu9sJEkszka8 zjM)x@r-X7B>>~%rJU;c;Yb+DCkE{I^j4=B?ONw~<;orHr;tcvCaIqjU9Ke&=Th9z= zZ?5=AQ}X2k81VZZVHzF!&GlU$s9OS@jh9B}?TAJ|j(v0WMrcW|01!QmpjTtLz-skk zk_6bXIlvR~%nLZ1>2VrsXuz6mUB1?JhX44y8`zX+m;}v}Kkq*i0^{2gds&u#7D;Sb zKni60k8EB}$7rCV-6-uA7KFS^zWX-+tNHmJ*`T00%DetkHi_Zm?jx0|4vv^d(_uaLHgE6f zmqqz!Uy`mnL;7OS)WPa<&oFPJ4f?FgVuICfZtp<8OH7lXNkD+_M6b!78yL$vH892B3IA7Bq1n+e=)aV~M~ZTcCRl%$?ZXJN zK+6vBQl@Mge{=odYQe9%C@IR*0pw`~nE^DZRXQ?~t~^@d-wQM@So!&%p1L)GV3sqW z`J>Vv763YsEsga(Z1w*%rCGqABJx;2Xv*NEnrFE z{UspZgOi}icirTY*F)wrz5a!Iv`cO6hC~|;Ikj%gZ@nYW;5vMq*HhX{J3?cYUHNz9 z5O?O{F!YgLzW&|yoOUGo=e@J?r6V3IJyUSm!B;ukN1zvdAdBVN)o*CNhS-V~v1jl? z=v%8GOAX?72hcL6uCJoNd2>8RrYUXbDQlzW$)cCDdAIhPl zK&=`(vfbHQwK~U}Whu7MLWFs|@zagfnpH>rcQW!2^4xE@b_*6i`XxnI2*P*$bMK(% zP)YIe92*msPreTJM3}0+(ochbtG?S0dd)o{KKUx)Yu(pX(k2sQc71A-eaDAHY*`LP zQ)v^UEqVu3kG^Bft(XRi_YGfFX^q=Z0`K>EwSRjB@oh=3npm8xq^aB(q>7|d23Imz zrSrD)s@HeZfb$&}f<@y*NBWGcuZkR|L~pB3^|u~!ORhUFRV)m<5%j=K1y#t}b4!tB zh%!r&&qvm*2S>}WIs_U7m8PW6z>&0CFn~>o&OQX{K95C|tgO#GCk(W{oId^a8yc1k ziY+rCTzaMY^;=nwrc(uU)T_*4yR3~5+7M#HuP@8H*e9E9*~>UlY5p(^Ss+=*&^K>% zZ2I^Wm?~IQ)EB8mdfZNVrgY)odMwMZK32n8JFF-Xhy`yt-Fwfb3+JDE>FML3sa*gjzw1I`^3?C_YW zpgcRKw=D7?p+8TsiRWdkEv?)EpTf93oNLeU8sWbi&CJ*o!RTJx8!!_bWPxnDLxoH# z7|_AuU$0gC%XYNXonCK`HwiX%`d;m@m@jno=BLqDo6|hS90<6Z7kAa+I)8VkOk)R! zj{X&Z7xZ1QXnhqBYZUk zD-&L-wZdBrayW9nK>3iDS22O`RR+PkE{GfqM~zrrzLeEi2C zbwNAhLUn*;vx^~e`08V3S%@RRIR;=y0Hqa#l2azVDm!01+G}b>!JsNYR|}D9yi7I| zD1hW^Sn8+kR0Rs#?G5ibH7_p_)|vfax%`&cq|MBN8;a660?F#9J+Lrj`%i1f#MGj( zw6ClR*7XDqgl0w-yvc(Tu8C_)@i&LX$T~vLqiQ}TSxai`w1Pr6d?(Mt&k^ED5b!t# zW!HrR!Odrx4#T$S-`-z_ zOT08)W%-r9uv&0ZnMT*toVz0Ss;G1m@pL{+VPo9Aor2UA8HwylV@*zj+h-%%zkOb` zBhlR(Iwx4D+zU1H=$tTI+CLluT?^r7$Cu(M4yeOhxLsWBH8@(a4Xl*!bh691jPcjI z`hp&=c1=yvmUl;sU>W>+N;nuf}(F))cX{^QsE?67xz|eCRqpQk%NUWnAKP5^!g_+NgzN&94 zKK?dlwCgsI`C6zi;`wJb=nH*D3nkLYO~sanroh{`^y|>x+d-c+-~|KSR!zQ(EP7LqR4F6EcLU=B-r|F< zk4@j3d50W5j(@&$7`Ggd^J1>ONSyK015S3KCCfwDybeY@-ws<>VoFCKlOhhMD!Lzm z$zd36p1{9+5!G$%^9nj(Iq#0$L+cQ}>{^#BaVX6d1Hy}Ko%|7`Y8VMFlLVinzX0dZ zTUxVTgVQuV@^%by+KtT<+LN=31N%;CT8TaKcC6EyueC0UOFe1lYbk zL^Sv>M339`drG}y)ztI=6kvIW02SjGns%;)4~J*}?A(5yjJ1nhY(W1I#^7ZG$h{8= zg_Ujb`BsJbQfl9@l@9cK8=%9ul`vtb_;vMsHeA2)#V5Cg%G}c8ooV>WlILk<4wO-joTacmR8Czwnp8ucYK> z-P8hq>*qgOwFb2F<8i?S<*gKCLF{{0kJu&W22d-;+N?`cpF@oAEH!QO7UKCmmqsm@ z9cOun1d4MihC{&ht+z2KFC&~#+Mt=?L%N90R7@pAg_{JGdhmIzT_I|gXp z#LTt4lD&g0AOQYfhb@dif-X58?tWN$_gZ{xQk3OkN~BYGxShEV;>CYDDrwdDn|tr2 zZV&o8`jy>zxN&}LV(Q?Kfq46}efQcR7aQq8C2yqX+UH>kC{@s>MS+APq`;#Pj6fv_ zit&P_!D}c0F-8nSAwm#^j?1=fjp+?2ROb4ujwF~*rmibVjy;WgB9SW{ZvO#h)fkBj zQhT2Ur-0@B#c(``PDiX3Km=ZBV?JC_1J_K;WUx`DFXLaU>gTFprF(N;Q3?4rZDi5W zL`_lraTUXE;c5VUq~tL0uiI|$KEm-c!8d;@Ev)y-7@rLrFqA+^%=PkJpFG?=Yz!Qq zoOsGq*-UA&M^LZx%)a9JAO^A^QNbAh!5=NV;hig@b{?Ga65_T@xR1-|lGashp%rr7 z9@usyn@x`>UAoJNf_?(VvH&Oa(`Wj*BrMzxJE+$l6$-Rc($4Y%{O-C}j_`dZMkmFK z*>PZ~j^c9CQ_BN_6r5m0SLa>H&1^8P{<{ zM3(r|$4~0e9hN5CYhm~V?&u9Z`V= zWa*b?dgcufK6JB4uc4AeTXs!{B6nu(AYXOLjX~{tuXc&3torw18%{#A)6h=Hg?uV0+BwqvTkFbKz3YKqTI|@a?K8 z9aH5y%LV)ssN1{Hx4j>8trUxA-VO|t|IC2Hn%gD9k3vt#UW0F~ue-8yJ%pq6fe4=O z-FkdO2;lbI>jyc89||LDk9MYm)WG&$(|lBhuRT85)fBV|&u09l_u$mXKaTj!?P&)R zoYdckkbJ%tS_Pw3+#vcXVq>gLnXx%Nn}!mBV%CKTYS$4^sL;fh*IkEB4h3qbXXxD_ zP9^3ua)9e&p(9@L4TK4);M)w(18||hGj%)|RQMax2k~Hp`#5WjVox173~V^&ll=!o zXC595#<^)bRDJL5vLG$pCa|Mh-dfT8I@ z<8;L3w+Heap3O6|y}|4R03c1Ts+M2Jzh8_<8z@1R4SyY7qAF$_X39BO*jCeBm}&5ELyLq$bowlY{5MUp$QG zERR7WkCFjBzWr>Gh5AGg*N!21k>t5dCv{r2_C%~P{ey(2zK0t3s|dJ?f3dg;0Yh#! z@94$h(0vLss;gjbuTV1-n~sFzMRrzUoK#&M3X&_w;G@Jd2>w#OIVZh zteSSG3=8|{{nFNf1a1Y`U|4x5K|^Bz9Z*3O)crTwRx;HkugGA|d zantsPE4>2vqx5T{)~iqB;=FsW55yd>wrYK-+DqF&1c;)ml`R+{uFg6v&BOu7VgUtn zRg&?U9J>V047%w_fiA8Hg#7^PG~lul2?2B&E^u@pa-_`(?HRI*3I-wpSTVa&IVDKE zjaZqS5K#5x!he#@={mP?otq76_+MC)1F!}q;}m8!4iH`x^gDD>pYi@;y)0Uc_1+!r zkxf3k_KI-RL?3QEBm7Xv2!Q1Oo@G-yM5|dYSf`{b26P;&?=?HM3%KERe^J=RywZ1| zq>UY>53dzHMxR26Rl=PjL^GC95R`@Pe<0e&7{7IX(>U~)A^!RhZo&T|>bii}xC?E* zTLz#HLZ$3LWH$xuqg$U(ZQY<}BC9%x!f(MMa5zII{Ax%o7rY@H%NY*C20*hAU| zb9b*{;?<`?D-WE?%rN+^#9NU6U^Rm}OU$giemY7@YJc=e_6ptBAm@MKc;M6$Mo!H} zSBLOvfcxqsWx^+YKrZK)bK-;}p zzfao_^8cI%FS>|049&G2TdBohMQTqgt6AE`kfBzyX2L$twwpE}d45WfVuJawki;!R zAXLE(k$(;C+GqM>y8JJ@UnlK&_u#TzdbnNeIYzBf7^&M-h4oI&ZyPTORH{;piM4o# zic~C34{{l4i+-_)|M;CGCkVgVK`SUueRljSTT9GHjx?AjYpvi0_dkee67I1(0ko>- z?8VFp-t<^aj7}b$5gmYbl(J%^Y#zhd&Cg-E3`vODNN!`#7P&jtX;omwmuNL+vF2unm?6QUV<&{G^}F6>bX z$K;GVG3w>Gs?%)8;zUKuwtUS!f-pn^Uu%M%&iJnTv7#q>wtrLq&A%zd!U97nuWzQV zOdY~~j`r3HgSc9SQW2Y1l%%MX!& z1;NSu`UiFz`-Olz`0jtBFw+`1X>;%);QF!C^KukcVc5G`kg#FOq3MeEcSz}0GV-={ z<<6Dh8cXBhu2D@9Rd~`mlH$?ZlR{q2uJzG4{Mj3(+fH!&&Qjkxa;#fuqcXLWqA$ie zq$1eXEYK9$3_87WcBy{y{}d9)EY*S3uUws3QBu8VNgAp%ge~kS!a!R85EK5E!=~Pl zUyurKj{-N5FYOd-@mY z0Ft=o_a!SG6nYfZ#PRK|7+ogf+0NqY-?R&{vJ7hE{3L{i9Pf4df3#5zeI`U%A(1J3!`{_U94XzlUryJd-g z7WriZ;h3>BSU>4WOv+Jf@VjX((us2}U}pT4y5&`FEu`s~@ch$dQ+I1Bm(eud%$Ak- zcAVxLilz3GecY;ZRYsm^j4SLL|>}!Nv`g`~0EM z*$$epEYS7q;c{3=ElVLH=U9MIQAdu05TGTT(`sE_ZMVwlpbY=Fj$;CA#|^M%g|FvO z0+AXX#}~L&wZf0WR<{355EO?PtTsPsB`6|0LGSk`xX4=Cp_s{f3m|=Bjq&fGpe`1cVDFQz|XUW4m!w;f=0e>(s-qyK{~``{TaK-u)Kf?SwQaod|%w9!p^abd_k7w`4(U!dscYvVr4PExHfpxa)_@aS-y97Bv z5dZ;j32@Q3jo`9GN?^PI9$=(o&EHVzzl*Ok1lRxxuH)*^ zNbmpqIRe-7Ar8s@WqN~t8ldw3C3p%$$%>#$@s|s<-)(h3LlXb@uK*J-US`DVxMY99 z2Tncg1F;4OGS>q8(3zdRuf=#S;(cb>VTkSU>6m-;dy9$(UIgc+DFpgl6X;;2$2U_^ zJXKa%N~wCUN6uk(G_n8_h@lyS|N58xP>gi~fi)02&NpENdRe0OdMZTP9Uw6<1&Jz` zl>s=iDcN-P*2I(KI-*wI04!|%60%pfnS>Y&)4gFa)r7AQ)DIdBltnxfTd^-d#v|CX zKwQ`d&Yw}R{G&c?Df&yq-Cr?MEp3~#SU!=NT<*mpqfg4#NT%pb6e(SiztG*KYR?c#3BC^V3T?sHS?+TWk*Szd=px#aE{-pDT9RrC(3o|!; zGJ=(U@H?|hzONtJM`C734X3c}Yo<|b>C+!fmrH3&DtMz@E3l;Nh70+t;cn(`p#kme zN$mNjJ(mSlIQ-#9r_Vs((;S~Sz4@!EXlm#X$&QHKmr;yl48Xi&%@+lyv}l28tjmJL z9>$T5E-d$J^;KtO9Gvg74wr@ClchK=A){A9ZS{+egNVf;6@M3)`zWAM|aud8OTG7(*8 z8O@50afSfQgbdboB}VE<8)Bv&ewljlkb`R~noLv9z(77iEm4doI1mENrA)H`%tAcV z)~JZw?ymdu1qZ=+9rQm7jSX$YPJ1^th80RQ(hr~XxeBgTT#0%SHR=oK_V9Zd?Iw z;I|5=3LhUXAKzcM+|T%Mfxo|g@CxGc3jTG=!;8zq`{$M$m*>xm+|Pi-e_rI_!sX`S z`s;@f7p~CFt(e$#F|M=Z;r_=a3@QS+*S}Q$`S0tD{w^C2H$U(K|Gy@=e()#B|ATED z`1u8JIc1NzV`-?pCi4SJ-onESg{a+m#YOtel#K|(<#Af+hjmC(kg|ki>s`|) zk3sipxij)cT*yd5^JE^pLei=`?_C+}TJqPraMrT+^f;x8EKb$f8vRVF5uO&R?N(rD zYCLJsCc7nh?~dd>k`&fq%fJ+MVrp*oM%N8PP3>3LkA2Sf*DsSLUJYNV!#afqcB@R@ zEI`R`-YDAxCHr|jh8SgBzUhxoYE%g2G#bG6qQ%a*UDD#>9m3Zkucxtj)DRLL|Iq?Z z`RaB5fNp!&$i3^AnOKG01bVcQZ`!*W5lP`)FK)5Nxu_EB1Gz9R<-g%>cIM{h+`Kv| zQGv#U%gh8%#atbimXvJMUxJmCKBuN8rs@S;&E>uKJ_Sze11T#<^xp;#-<1^&Ks@1T)Hlz~oGgY#HMX8Q7Cs?kL?Uu8it^72hD-Sml5 zO^uL{5V=%VZf@rJP_j!U-lFMHA#)}M&;)msBS!C+VDOxiM&+apRdkscJ>eV!GHA3YH?jC1_aM5C~!YN<`#Y`%*u-QA|){~F)q%3&cSlZ zLZ|k8HYTxg5B)NdAOL z^JurK-4--MDd#<4)H}|p9r5LhPYg}+C06P;w@=#Q3=M(YJVTsJoh|IP>jJdg9K|ly zr;Dg=j|ZYFQduRs+x?%#+|DjPENu^LN7OjgYyq`DSOv+NcKH+1q%FtC$6M+)2D%U# zHTIp3^#I4}vge&u>@qoLE*5QDe)thpw)LEj`+N8B)p|{^BRdGLyD@&ZUG-_`)`?pc zPo;dR?vt&^?5zDSqQm^>GjrWbVYZ;pZ4aFYIPz}=RjSG=unvjq>AVh7e!NK%7SYJ} z9gaJ#Q2<+cPfC_*b=dlzzC|56?IQK=N`aGUt=q?#e2r{zX(m?4{v+pHYT)E}S|DOj zJ8~}5pbo5|TJ~yRH>trb`7}HuSV3dEe{TBd+hykE=XnElqqRp{oO(44)?fYO^S|$A z%XR&VY=7=|EHLBLYBa?l_l7wlE^atS|0r;-kaYa#S(5!cUv(BH)0l#ZpuFzY12c56 zZ)8HiuerTR*5}ffL#+rFSACO#EMKCsz2oJM7#0vqLnY7d8HXj4nau<*P&Lx|IZ{gD z;W+Ew)=i5MHN92#H>HZu#yAkEFi9<0?$%TtF=*d|nv4l)jWt(+piEp@QAg<1NcT{f znwnx@V62B830O`&VPF(>+l6JI6vH2;>aS-?>Spr0y=WXhY!Tu}e6o|7CYKvFkQ1_n`ij+shleLxcW%FNA}VwO^~OBt z2%&y2YK!}ktg`OAT}-V%;fr_4i}J(Og7y~(UR=G__KSByzow1kmMnz>D56p#xNUx9 zrM?b-D7yPp(_GFi#_-ot$11A8cM_>qlz_Q9Pxb(|{vq=4w5N^t^#M#ffd41o9ctk= z{Cg>7=yWP_tsgrgXKLB4&JguDIByPC-9_Igp$b=`MsXhx1>a6;bcC+At~?EUWIUe3 zcg5vfzkVj#DQ-19VAOAwv*DVkOz#(j5^~@DQ7BaTMbD^%;eJPG#Jbw*XQveZ4>Tmo zxfW9;m@%mxtCR2UMUsrBYov$2{`XR2PANPo&H^d5b zZzI60{X~Aj`BoYAaIy7N8A^cpB>N*?GDGm9-_+eRdZy!p#41eogY7>1^}YrTtghp? zHlk7=^dETme#G0y8;L*X$@W$FI?9{#17iHt8IauU$9BXd8ey%}`g9rfmg5cG9hS8^ zi*B0d4c%B>EN55*Gqom6^zmI{4n?yZ5FSGi2O0X$5UdgHXtk-$*+57HHKSDeEvPPSQ)985HzV(XW zT&3#HpQYBBetYJIVu9yoKfT%qKy3`=-@^xx{ zwd;wh7ilnRE&WcX$8)#N%SoT9fM$NbinDq1gnh}0I>=4!6_s#_$Fv$mmq(i7J4MtYCX=>r>MJ$Unh|;}qxpv$PD(fD> z#(W)4iJ`e(b^6%RD;w7RyVN#Gv+)kF+j^e+H4y=tGZIz z_gF*^nkrF7SJd+u5W9Hpu$lBF`XLcHUEY(g!mxxXCs`O5?Qy$|)y zcBOY<>tnTV=A;FRlZYx^mrkATbf27@^k`SIs&x1>tq=C>_kDuo3BB9qGI&bwPEodX z&GQd=@kZtP=* zEn+`Q?6cQ4fEC#gSsvP$W!CH7iI30|L6w_C9c_s}thhqt+efX%DUb+D#vybZG&d;r z9#?u>kC&>`yBwX02?@2Cw5?8lYAC$D8+jM&$H{ z^?ltM!F`sh_52xx?BVE8SH_x@$EDntYw4>f8n?iM?uAFAmeII>4GYos54j$R;CTkg z{m1PvL zx6JyHn@ZO>s5{QB=v5G+=#1bJs>uK0>VVS2Ft%`J=QicJhBJ%TjfJ` zs`mC_L9z=&(tdL0OK#JdtX+0mmED|7o{J#Bn5CtaICWPRu(0$7?`xDpOI4}74;5*q zrQ|25cWBjs(}Y-AYZnBjXIJ;WkhMrFR=do3tyhLV;$1oIQ8ExJ!ru=SJ~B@qcqEs# zZI4MYLvcGiSx|c6OCz;R{S#+!DZ>xtj1>P4pVHfe8bhTNK_o#_c)j2Bv5qk8HwPn( za-M`XRV%$N*Hq8d;tT!pgROU(|6DLnywM`^<)Ra{fveg`X&?WD7bOS;N_{=GWO=7h zw~EN=>0LvGM1w}hPij|Ip^)t@Ea?ZOM&59*!LV2Gz@HRx`8tF`y{as6|IvNBB5H+t z97~<-5d~f!c;wWtd$o_MBdFhpj=6wK{D%;mr2M z#%38uv->Tz0!cvtawMrfJDO;IA#y6y&4R;1@_=-HX@TDBC;KTJ_GFC|-6gyJyGDKU z8%>h>7KeHjRXvPj=l#`DQSnBJM!VOaI=zGAj-omn5tG#wLkGjpD=Idp8@!r-PWD7b z>b>yPR64g1P`%S8z>!M2-Jswjbo#BS<#p)8=O0EsyJ6jZ{=B%x>NF296_ZH26KK<; zQHxsFh0`xM1MU<&$7h?9i=$%}Hrk@*0X2h7vQ#fhIqfPXo;1GwGD9KAxe$U~|x@Wg{zIda)GcgNb6$ z+rJ`Cg4a`}M7PX_&W^ti*sZx=>@5@78Y&vil!R1%`m{)&A{K0FF~UN}j8k0C0xFOR zi@wpQ*}=Xo!?wJ{4~*jMTs*{?>I?=O%$%K{4?Q?kPah=i&pEH!(rU1oEJ-Krj^k+8 zw-;D%NWJ<=b(s>0*(o=ia`CodtHC}dYQ1Hm!L~Sa&y-j7{xIri42Z?@vZs5rU!nZx z0c92A+vHGxkBzPcdVj*1RV|xNkzVhRa9m;Pk;dMHm@w?`ae{)Wf_6jDnu}xLFwJL? z@i7P93!Pc5^O^pKk87z!V6aSSf|qx~$3Y6Es9nl5X=Bv`I8T;TaJ%xSNX+pBw{Mt@IPC=GpS z-2AFag|45EN_jn{kEQf-f~VUa)$OxP-1xTxlGEtXoxkjHL9(*~o(Xcl;%h{Uyi3=6 zwO?C|kt(4Bs6^j&h}=3TOikSab|iV}AD-Rd3~JP^@2B@4{gKesY?U(nMs09! zMxSwWxdBYYgrlJvq6#)f=2{GLN1$+9|2e`?BGYf%ImIcoLxMP4_Ph8P5#i+ zhAip)sqFZD-15v)+ij}x>YM80q1_ZW5A*4or!3E<<>iZ1I}W3shHZ>yCK~Y7INrO& z9;H@)KLd_{K3Z%*mmGIkf3HWP%Vl|(H}jH#O3Vbw2P`~n!!vxF%v9mF%zegtYNCY+yu0p+J$I8^|o5|cW-|(RLAZDEu z^97Jqj-cB?97065!^oF-?4s6KQv7vvrIu{cLVB|Xb7gEoJ`_nx5;4#UeH?o0au~vl zJuwRMwVdA-zcGtDXX;81PLDCyUE|M*7kj=u$5}&D30sPojbDz#Qyp4TY&Iw?*2-r2 z7;jR`!!YCIG|75Tb)QV}Dn5LFKSaLKslB}&j|B(VLvwI&5b%ih#4qsIb9F?8pHdQY z9`B=^nnt+kUE=p8p0Q_QkUa89!uHy3ecio25IH-)V%wcG{NoGH`#w)GnVz}(k#}iu zn!0w!b1HC0)RmM1&M~9x=63UoO;Ie+an^fl0_T;sy_YUk90dghu~qCO5j=Z}ZSet% z?BW9z9L>iv8y0c^0>OXB#^XT% zzqo5nH_0%^Yjt&X6`L-=uN5bC!^>aRX1?;2s8Gq4O-M)}pd18HYl6-B zy<5_509@XQGO8LJ7IxY{Dic5}Cg7aj03#+{4_M^a;98L94oS~0mku`?B8K_Z#5{Jo z2IKb_L#Q^EOY+{D7c=csJ=;$ll1|hC$5zpiME_L<(ju{o_LnBD%edjCvx2X=4SO$u zwcOv?5A32M^*FQ}PIpn1AI-q{73ZaO8!X&jgzKJVVlEF@^xa5MEY;9*?k93+GxZp=D3bXu9<<^_6ccpM{X_<*kMESUrQf38HME;&&VF{9i%oC7tjH*} z$uYaa>@2kL$Z+gc?z3+&8B%G{SiUmGE@FPoE^c9x`6fIer}hEi-zIA1NTilorg~Jn z<^eY!vp%J4B0ZMF!RDEFNDOBZPJHP%p`EsY-Fkti!fP~AaiSamxkQW2kQ1oDS{$mt zqwZJOE`GIS^uB9ts%~P!TXipjaP z9{wl6E2%k4DH`EIODFA{7kp;d&*y$j3!Sb-JE}i9aIw1PoFvtr`FNNe^3W}&I!wOl z#{qJm?amOCiW|Z7zAj4uu1xmT6+sP5DsEyV=+Bdd*$4HWXS&x+7%dBK3@f|@{jL-z zt<=-&7dSn;Sn7g)+P{y8a}I^65U0j{2_-4(xT45jn!)9BAnAGtyjP>7eB#nbb62W2 z?q&ZP-_ZNBY8=9@kg^rzdIxBhNyO(DrHk*bsV|QoE%plzH8m#^QE~C`wV$V<+5stL zkRji=SBm0TrMdvnT~X$y9DC?cW4l)dj6CBRU_i3_g@`;VFUGHY9P_ByQ@;}$Qg<2c zM$2$q{$Sj^)Ga2G8>l+ev%r+Z{#*L8(?rlzR$I5@iWyBWgHuE)^LNvrQ7-7|I`w3& z{6hih^1jIyR>s9P>0!Rz%0r>(G(x#Mz8lPk?J5-cgNEJRKz#yuBr0UNgHpQfj4l|F zoWb_$aco4?4<0-ygfvvs7AY3{BY}+MS6=kf@9KU3wxW}I6oY> z@ygn`wS-O(AX8rsr3$*Nw=Xui#n#4M{oZr9|yL&E@PuPsv!G}5e#r;Oddp(RfFFb#ttZ* zoK7Z@_9q+QVQ0Iw-M2pL=rblx`4^nJV&hyAa(guIfQdCAW%tcy2BSE>{{G%IfjseE z!=VxG%m-^=-D2DedKAm`SPC|cX^dlD2}+3rtQtYNUDRAgRxCCl|HmntwV@3?fkL?E z*BtN6uYSnWF%;|kbwl}eui8a;h)&kMzvu|3S>iZfm^cak0I{9aV9RWO`;gbU^*0Sx z>A*DMo#f}X_KCeiA37>pn{a*!zF+_1$uo-@})RE>UOP(7cmx8ofg>>i%} z{{DNw%*))L<>X>8nZ|~k-2~-ALgks>+F`(?J}so#`F(evvO`l-^Evx?K*}m*MYsnw z^CC??$ty{xjxA@g%e}*;W7XBr5A4&`HevEmwf(*Kne9_}7v%?f{v6Z2Dcp7vjbfpc z0xE@i`3r5%pk+0-WH{svj?2)TKJ^x+OY7eiPPDig5hOIaqH0PV5p3PUJYtRG{D7C9{TwyD2`Axo- zxPQ5=Y-mWT=zxpwle^&a@1b_soKgjY^(sD$e!JYYz+pnY z8?Enxl1Scr<(n-Fva_d!^xN7BlGMLfy~rB5sYz$ci@P+&eQ6ENhi?v>xi%;0myagd ze4VNHZVMqbhIItGZkKI*OLjS2AL0LHdLCjD<#M#jY=}Qx4IJpb=VPt!dVV{M`n3Lv z@TED~kDbGVEB$E&40EPR&eB_5j$I2hGt4~tx!H1D^9g*Ww9=BBm+_a;*$ZoNy|~jK zCHWuOuLT+7Eph53SehLzO|Aj3w4y|#nAGgL%u<;JT7b4{vomVRVQ(Y;_&#v^-5zQ2 zxWgu}Fk&dndM>v&ga4`$)jbEUS&v%xEwu?<8^~2ooEUOFKPKwFh_@wcMSeu(43xH< z9l)}I10PD$_P4Fj`zz(()u)Qt#DH8c2O zV&1i{WJ(n^n(?X`l27EXfh~+pURUb9A`y5&V;v7GRA`?GleUvv1|~IiiX=a3Uu=E z9Yyl^_(k!%I#pfq7t|6;+x-NI?!lqK0~Y-sPJS`ezij{mg5%rf9MgTHK;=Mox>CL0 zf3k^>V`oel1N`ld?=ctyFxxCVrmLutTmBhFZ@~M~Jp`??DL&Kv0N-K|3iM#aLscy~ zc5paARc>q_abzph;4e?)&&{B_bfpdKKA!!qXNZm|7fV@b>a;oE-)js|>+ z`Mo=Itg9%~5_CZ0O9d%hqZYl}6m3k-?f$!8LvNstW`Ex0(a}IQtMg#g*@6+}H6*!L zmN8x+D*PF-Y`1C_muhkSp`BF54d}#PUT&48&KswArV1}vXv}lFHHX#H`Y=R8$>#^j zH)w>Ea8pOrW6|-7#@%$HT$AC`Z~gZ(9g63BmLEUb>%85Mkuy5GTVh-|88Z2&L?n1i zdO24jPz8V+#>L$Q;%*GrV568;oRf}Y@i>BZ%~x&|lC^wY3guGI3{Lwg+GD2Q;QhLZ z^^FGYzc5pV*KMgPy_%Z;#@k!QRoQO)!isbWNJ@u-fPe_noeI(lD%}cF(k1}eKiTYJeo$q*AGG1Gjrzgju z1@>j1Uy1~r9EoYj`2Kc+UvgU+4h;#xU(qWymJ${gzH|v^$lzu$E=f{S61I}h``Iru zAH!+*44-Ei_fGAdrxR>Pp-@O9e&gz7qtDN8wSsY>M7^Y)qGoN_4<0U*q> zFDxuvif)zcf5}_jV_smm3(q#0Jt-G zEeX16m69V6`fv2Eu(8b^?Qd&nXpl9)x**63+6cLxUXFYuNptBH+8!BB$`}->+WPI=w~rq!es9dki?we?QSp4Jth}wR{&TXC=XW#WBNOseWXkuPl8nnd za&_#z*Xq-zpHt1u%k&Hk#N=(VM@L7N4AFXI1X5mG*f(T+c8Q~;Ejo$u>DAxpydwMr z%gL#cfh3j9qP8;B z>id*NqkO6U98$x>!)+8?-nO<}l-0Tg8gTdW`wt&{_qQ&6vKub0HT#I0{}TK+t=S^o zf+qjt^qy~UJ?Tuz@Vf`>5;XPL@7$g|`TFIHxc5$>L7an`+1caak&%GYlg5Gq&Mnoa z5eSQff#BX=^=~O@XE4uW!Eu7nU%}Wy*bR-0$>w>ZSYoMD_VC z3tL-SCME|*NB-ZXna%I^!58-rRYc?SD{Y((FIrslGDb{mi-Y;n&xI9q=#P+uKjq z!G-Nv(ta1SLKr$bI&wo>T4WWCimi%nU8!W0OAIo1srOi)gnHGJ#vjitBP}eP(siD= zdx<1IDn35GsOX`;zx3=?vqQrLLwA=k_DV)kvh515ZEMGM&6n%P2P>r!{nK@AZEfb^ zvQRBvL~wf>JH!q3&&6kpcJq-i4Db(3EzNbcQRwc3k2ew|5|K z`ZS6(RQU!26_v2xf$NFY-V;j3I`qm4QR@ZDS1AeD*g{&agW<-6C-2ZmXLz%M>&cN< z1a{iBix)5c`0)cj*tB7g5Ol%}YC5{evUB=4r~0l!r17m9F;XlnfmaUDs66cp*Y0JC zy9q4AMiCPgEmNNVgsL5X8YI8yvx7d%&$=U5^?6$oKhbwmOGis9(0D^J*H2Mqd#Qiv z%2LI%9;Ooan3xy=KhIuQS64C)RzbC!H?Iu)Lp|?T(L*iuykE}eWWaC)NUXZMGU0MZom6w-HQ#S1V`}dzef8JXi)2(-ZJQ|P27WX z#b%Si)MyF!)rexD8#kz>2%@AfcZnC4mh$(|zteK~5N1Vr_Gy`x4yqj6Lc5cY$6bQ* zdw2JbmZ#@b3u0np&CUgQWapvF@N_=8xGK^jZ;g#~ArJ_sI`a;~*O$mpz+p7gg&rR4 z{D|=Mly*~gf|;VHiYB}&U9q5;w4GH~!hMmFa*2zAc0O9CM>AVG_T1ygj}?{Lu#GkX zl-9o%^pCx_aVD69LtzsYXYgrql8MCp6J$vCr(1)egukz!*KsXz7q}PUNoIy0#U{DK z*MqlV-cO%(7W+|MT^&?=(GJQytc=dTiz1LBxmH+I#ClgvU43=DlEgV4rJOk7bmg)+H$AGj5=b6b{K4x_0dv0U@D$1DiGX z;qJK;D%?jA6E$!ovfxD*D3rF=qF7yirs3|!6511SQTS1aZU~l>X!8Oz?@LNzJmPVQ zR@T-N^Cm|5{teRjtl!S-e$@b>mrtpVF&9M@;(*RQea-h4q<^ng*lJMbjZ zxu6Jn^6JMEmm9bb>whK@)CE33&2WuAgenbng6!<0@G{v#w6d}?zG6bH`LdFPlH}9w zOreKgT7&WK-8??{RXg5#&6*5#{?_i#??jyOwAX@cjA@hlCpPE0ocR}txa07q4}Ptz zmLAr8dNtl{ab8~nUl)QOkwq$&PTPyO;Y@nZ0ko^gJ)&Y1{IR_J=;1>+MQ)a=5*|N8 zhPMoet%R>%56)1)L0wMOe$6Zz76(5eXHx!qaekhbmbUBxi$AiQB?F%^A**6n>D2oj zAd=kNTy~YX`TZ5%9iCM5-r5Azg!e}Q@mX0}eJ4zrm8)}ed3kxk^!FCvxGSlsuq#cL zTZ9)P&LL$L72DxjN>9VH51pNy0{JSMRkE+!#BJz+kv!St7cCe0o$X#+h>nqwk&qmX z6J%q~hEI%+a&U4g^b07XtF=%#N&&Uf_M>IR#l?YvXLiS~pZgT9MXVc>5OiEFsxP56 zpc2pIwm!)yeU!0Y$37Tbjk=6gJUwk{*mmxtZl4urnv~AO{^CnVG6ZW~P)lCl^J^9x z_Vo1hJiFACkXtiMPDNZW!3Jcc^o=Do2Lpml*tA^7c>V%nMI4+cY0FXkA?`ao`gh4G z8%cWaJeew4`v;zsWBntV;adg%#jnX{bzCvBnij6=A1zLv?ystbZ?=Pmh{QH`L6$~GzN7WCzm1KH}c)Dc8FayT=loTs;8o+wgL^( zTr4{@6ldpwiODJC^9E$9=H6(bhK7dDGl(XApIx?b^+#>nZ7SxVr{zo!6jD zwwOU-dvo)eu<+;pei>JELToIFItAtNfxVs{d<)~RuWvtl_6+hZW19Xy0U_;*IDDi1 z5}giEO<}ozE*#!Mv^rXTuC?pEO+Onu`!$^`;w&{3pn9)^orj*pTfP1lqy+@XP*lyQ z&{YNx4A(3PR`r*x+H)oAHX&N-E9%{{BZ|-k{OFdiBa6 zj`StD0Z&)dfnRmk}5?QJh*9i8mF@X%1B8Yi=vwopXqk=Vf!k9fNG z=B(0t>(2($I`(nKuWqGeWMp7E{~pC<&8!CdF+t)~BXIwqO}^1Bh?|eqp-T5VJbQZU z=L7CaY5l{9)Qb1-zkdBHvt)M!`!B>ixdGug{-JwniuqO;?_+3y$kS1gNxCG$vtFXk zv+af2d2viqgg3)(l^+@W{w$i`hTPZ4l6+`q*K?hMtM2vd*C{C}W!U?C$w_`AQqt0s zZEfviWD#a%~AjOIFHgQdvcJw1o#Fi}Oa0Psg8*p_*jG`Q5Hx$or7J4H&ykg%}7 zabYoNjBwUuIokQ73gZQEZnVe%C(uw+3qC(~iJd)fW5Wr`{4SGpK(p+fJ5<#Gq<#SE zsTf>(#C(BdicKYakBn-QRue-rMK6`2weDWOejVwhtc*KIn)GqlkAXdM@XHq+ZEde# z%Tzk*=gysTXIC6Vp~!FHUK_1*<>Mco00 z<+a=3wH@`2e@uD~`gepU0C{QuBZJ~>Kxq*aA^z7(*szNF`ueOt9azD$ii92=@kkO= zGjAjy^eF+5!V*9Wcq#Od;^IYd=UGL|$%V(szOKuIKgKKVR2Rk$*)YZYo_v(CHm#&* zS$KGOSeWwNyQ%f{^)FvO@Or?(439)WNXW3scOPOq_b01hd5>uRkNejDwz2)c{ed67 zFGbb?LU+Y69`?Ev{Yxcz<+Z(tSojZB!@#d(D=Dbp80hYehhOHGvIF?${1=prC0-5l zlgqTXw*wfiH2W9^;KuLQ@{rB=6&jtjX3x!8=76JetDe+;d&B>=TT47yjM;dzI(Hw| z(qqa`#I)rM-Qo8pKcCo(!ca{v-;bc_1NP>;0aX%S3Rn7|nva7+F$+Z&;vyf#*9Qz9 zUR4%yiCtX04qlgMkOrmZovhgTkKyM{%FRQeB1T4b!_Ep_zz7txhrdQlqKB5a`LB46 zuLHCn)dZO3@x(3bJP6j z_a<<2$u$cSCEfe??*opb`rJ5R`k%Wv>Nm&<+LH*SXhsQl(?q}B)q9qf9QM=Qqn-!v z^h>k;DJ`7jDujbbA$a||SH_jnOq~^;X}lXhY$bv3i;5ZyY7|BF4fR2fwCR1`8VA&p zk&?2#9|9b};gvF#Am)gl}WUAFEk!|%k! z#Q_Y0gu^J}z@XmN7JddRDz2pbxwVZA9yT@%55zG_q&Ay8{otXSOGXw9O=y08URDXD z#>X}`oLo_~WI4U*!aXf5(@-svR_Zx)4wYWt(b5v|-m#5A1FX<5F?=BtARQp#GS+>^ z#8{?99-D6fDeku1()SP1LQPUkyubddC&hF%IlFR(goj4UwdNy@=}#z73`a{%WE3;B z9BP90@k$^&E~JAUmyArRL+N=D5J z;O9(^{-K8qGZRz6tP;5P}O1-|KKXLNj5L%N;|nRd8nY zTwTNVqGH4fb75d7Qq+l)JYOUegsVsaV3}*G_6cVe2M)+VSTjGy-gAB+DX=wzD&a&K zAW<>VtqbcEQDKW>)7AY7jj=)(esY%Zm7-7;=vim?jusaew?v<+p~%_FjsT$50wCB3 z##$4x8zyEYVmqha1r`Qu#LfBc3t7%MxVW=Z&>N!vDllCg9aQvr_?Eh^u=CnUKx>M) z8~r%p&w2ep%p^&xHkm2mA^qNvqSzI=JUWt=kT>nx5k-Yr3E*5RJ2>Q4Nih$DIY7t) zJ?{JPFm>b)Q0`bb4W!EFSxJIq3_+>geI%JF$6eat&Z{J>UmM_oFBRbA8I3ym8AI@39$M@`X zTkL%S#Dy)4te&x-1FIOIovBOgUlpc;OZ?#1_I4gaCW|VnCmHf*rZb&{uy+G>|40)9 z`tC#R?HpWO_}={PX_jI;g4eE*e`=M!KxO{$;guq^YC&0*JSy=$0(&Uows}f8oxR-B zvOddu9do~c%~_l;qE)gz&-2uFA5@6dHAL~%Gv@?s9F3M+pm2O^pg7e~27M~2(9GN{ z&6mBk=J7dQI0ARTM?-^@XC~dmKYyHm=zLTqe?A;dIG}Kb7wAUdEKbuEiHT?ROZy#o zdU;hoo}hk`nVsGLmBuelgRDX!%J}sTXbEa&dCIXlE23+|@96W@G&Rq6i)+Nj#I$|< zn3!9!R}!jv74&UYYwJZI*&r5|JqO%O_g1VKVS&^2YNXU8ZxK+way--LuhI(cuZT%V zl*UDD`WT3pI%DZ+t;?hMDyIOGvZJaiDuU{=0Rw_w@MNj)>Tvlb1iIod7kUq}jf8{* za7FXMGEWW7BsI4=hGkb!jA^wM6!0{-y6u2oqy>JTNjiT<>W}t)B+O> z&b*w3XGXwu9@}fR{^#cACTJ^3Q*K>_ARJu7F@M+nK!ePLIv;I?k&ENvNOc(82|X+r zH+Od6&2dsZo4dQp;z=nfRAgjj0Fh^6lNJmX4ULRgXTYjZc^&$J*6va>VyZcSd8N3j zY8OseS1di}K~|aNp}|}N0rZ)o!or-(UsM1!o~@RbMZ&)mZ^-G9<(S&GIZke}jPd7V z83&28xe<|)LMQG+BBvk98B5eI_pIQx)7`jnqr1DCj27-p(kn!tA;czV9|Zmj-c5V~ zBO18s3#S;+HJ^(;xjb^jJ*~+ngPf2~rgE3>Gvgj_-?;a!Wv(Au6qNJXR#|kJ+sfVH zCbUUurNj4&Pp6?AdYx<#A4gp}@Z6XDgH-`Zivu_U^Tfo&+v!4bv%-KU;R&Ybm|$1}M?U(L z>ed4k9MIL78PIbQQ&JXw{`|SPc=r|~<`2>Nzd(dWgs|wEaHwzId^p)qYg-FgAv!u5 ztr@?WmPRSLw!O}x<9+OpLQ0fSYz9LGsjv6x&yu>Mr^h7YZx4;B?q$vDwn5Ng^xQOn zpH-Us^78V(CtAMiV_s-?GB}FJsIgacsR{R?k3g*Naz9DO{3+gX8(jmue?bZ#Xbi zo@;z`6u_$M&u{y%OCmH*4p#U}4g@HEK_~kG?wsLWZv7H)FmTH6eX!LAvc_-H6l01d zAF4(Vu)jIr^cklnnM^KLGVb_Ci}=CaR-hw`AaJ^`j+T{`0U!l6wPLEO9^Q)y>j6Lo zrwD4-PB7m2ki%J3oJNa4&;#Dyc{>ab9H2t?YVrt^S67E@CH$0Z!3)Ip@7T8{ddkx^ z-oGBXr$aQE?M%liYZIj^>Qxz(#?es&1%;2m`+R(Sl35HoxdZj}As{|CJBzLKpwP^1 zk-O`xu?64=T0zT*^z@5&AI*y(33#tw{r>IS*47p{QdLiuH0SAP636I0XBP@c0FA#GUoSRH+;#E|R# z7c}B~{R1?f7Yv3y0#Dm4vJ26@t~rlAz-mbVZ+=tBYIonAe-z&1U*b~azqp)cWB6(r zugXIWHe5L}%4jxSg|C@_it#SI{qjuaEMMlaL4XXuA zmm)84hV&422C>N2tnkfR1CN{kZ0=!Zh|JGzI*L`RI=}HL6rpy4@HaPS+ZqRHlR;sL ztXOTAhtSv$s`d9uJDT_J!5RePNxOyV#2MN?A9UaI?`(zh=bl#z+YOsWnnoEHPjMWE z-iN}MeVXQHwRe56^>p7+`rh{Eq1k8bynOBV1}&8-$ZwK#s=lEvu+#qsS{NicE=E!*3fR zO*=MR&^hk?%HJ%b)_opX4yGa@c_=oJ4f(6>+^T)-X~*iQ+yP_~`K)@jbmpm%E(Rf{ z148U~$WQQu1=NThCpox@QOhBsMlS z|HCzrsyhvaYwwW{0c#LZ^UA*Ww6+Eo;NGHO2Y!l0XH2Uvql`ZT|223sYl-#Pq$|?= z8WBD-s;RkI<{MY3R7afJ*53SPTeI^VZq_A9M^$(o9Oa4#Fba7xQEb%nd3s`({TIJ= zSd?hGzJ2qBItQFnnJ+>g1y*%%O0-du5o(Nd4CIs=k98&uR)hgrIUDgsAzRqPfWUrj zZGl5P1O;vrkuG4?2BKI_O>1i_ey?^jlpQTYd|ID8bz`OQmK=sIeHylRjps+^bTu3)gEQMe92R3QsSKQlo{w*7(+Q&x`iO=S#go1 zy3E|^_L{F?j_Si^;p2&Hx}#e5OPHv{lt0F~@>%V+ZW(i<{UXc;^KI z*3EAPpKEx{Qb_qduni zha2hU>k5G0nM)SOI#McwyB>luDJm<0-%6gk8Ia8PFdl18z6JX@OVUfQmzvwV-2d4s zjpoG<44PM{FCa0>NzMx4sDkgk1VnUj3S}$*;YCUpmW&dE@*vEjLPPLe>SK)HdVn>3 zmzT@na-GLIU#-Z+FTD8YC>g!Z_zb~=_<3@CsI>!pILjYLaGmX7t$K>B=#H*#@L=w@ zp&_b!5x}RKSU8Ywh`c=KsCM!q?&QFNL`ZTNHhK?@jotf@P{5ca^_8Qi_9*6q`lDvU zIqq{Z5tGr{vLoaXAWkkN_V`O)$G0VA5DnBwRIDKR;gz6-LX~D`Gi%1h1rl6sS;D`W zxQM_OGY8NIxHypPMPv8rYzI+{d0&RuuayxRV-8mght>3{Hpv&1@7Ox!pu2*Kzmb6q9P+3@OvD#?Ho$&6>I zsh8iNgJzF9PaR|^8LJh>7b?Sl&$1|;(%gBYck|}WR<-J!99gX$Qd$bvhN#gy7cM-@ z$zdrMA$XPgp6VKP{;5NOYT)RSF~ISVkQU<0dWOe@mUmszc+^<=k?LnGdr_AT z@34q`FSo!`X4Q}5t4BQ9fARM3j#K1{G>5Jh2ZqZCzff05{Wei}rP3zyYR zv$b-pBA7Wc7QVIZO>78;%+Gc7Z9l~kqIy&7v**xi6A;IDSOZNgluWUhY&+m^4d!{4~r`W(hA0d$kO|F@c(caD!M=!sUv1TDI50 z!k*2KeKRmFklSz=g19U}#eHsvu`%Z*UB>v2tQkUsCLV$r<~_t)x4VM^lM$LLUR z=b05~H#X4OT^$R~3Gpk)oMM_)3#U9b`ThGh8jYS_Xw{e@ZJ3mlk}5}(Q#d+0=1V~E z$>uL~4txi~6n{QU+a>m6d>YBptqq>P2&=w7l~r+k$`RTaj^MbJ3=6y!4P%-6gsblm_)SllUMaVP=6uV(beQbpLG#c7nr#CA7ZWLRMWtX$%wG^C z4LP&(=g*Un#6p{f&I)p%&T<6CMWOlsJEQ-DfUGYMFE*S-qiroMcK~$5hTc9+y+>zi zZ@)S_%XW~LBFMI{_UO_?6Bo2{U^7xayLw;`9Q`f_kb-tt5WLUEg*xtW4y3beK68PB zg6;kcFno}BAjKuPD-SXq__bCR8`G_z?_~>^$vZhY0X}8DYPJ1VSQ1%(J&KIZO>bs5 zbh>6f-k3C`NyQ=h*0|rL{F-lz*rYH}@?~%~FV30mDp9OkQ4SAmy0J8ix>l9#d^Oi zRR!fWzI3rvZ?tI~poOwKpF6?*mBq!^uU=iM&1;zV!~s3??Vs-DOw%8h61A2u4@pl9 zU%V9>7KW>%j?8z`r(hij{IA@|Wct~0Kwude42A4iSP~KvS^o@US%uv7^6|+Nu2K`( z!5sqco|IX-7*b%?)}8L^v0Sr{ze+wNy);IF6}4Yk86T8_Qy2^&lyplnFPUAR)Q;aI;g*TIM=s7 zUgW+9f9SMaxl_z4b@w$atP+=De~26Y{9YgK0-zNr3BC^a+DR74s^1&+bewC)AC8u> zhP+XVre4*ZZ}i!dPXW;j$6ey_aPf=aUYH?l zkB+vuMkrIkRR>n~EN+P1*w|Qc8>Bh3p9YKw2eF*kB_MdH40d3K1c*(Ci)$e{w(>uf zG_J(?+zQ#g#y*gW0nB6qVX8V$#Y8hdc5rY25FT?0kN2-P5X8#AlN8l6L~2PTRtH3B zVg_t-s*9z8i0zna11ElE5+jusR^DVi*OEaYO zAW^Es#l3}nDvIIAgN+7CY4#>h8H|$uJz!)w7mC<}E(h@^@XA2`3?+fteo4P85GFEA zPD|sgo8kkH3qHcNe+6fL!q1b{f}AQ(qYXFWICC_Ca;#NOcR){ogSPDx#u9N#31)hU!F?jm;u#6d56UJh~4%IXRi~-U*>$ zgSRCrl4SzXHt?;k5Hm~rg62IwJ`TGRND@`5+V{$5 z1r7Pr51WCGCOiZDp6uLA^~SGuTw5LWv8@e&g`c0F6>q7ns-MO!AAf=%E{p#{qmV;s zJ_9;>-^i#D90M@Af)JmDGBYx2J~?ZFV^2bVgP2ZG@%C*Jo*#onxCh)I8>@tcHY z>+0&_d~5cO4nGS5s)+ygA_;FT@YadPsc#LJ8=i~>Y|Y;+Qr?o}G(1^K_bBR*G~ec_ zKL*F1C?7p*`r;!+JPvtOT*`-k+FDRNAYUwB7mtIQn4nj?9*0_mhwJ9*3X&fLFC-kk z)xZTzHy)3(1O_7V>>?E1-Q8tn1K+$^hEBbINTuo{Ld7GY_zK)XxOvN<5>%!C!rC%- z4%Exv^?^9X-!^5TXfOa0gkZplZ0snI|(j>{F)IEo7wbaiw*$5ndpMOhN? zaRyExs|{y%^b!|gCl0fG3d(0~ymD@CZvU8_;AiM!E@Q8to|uS8+M0RaD|8GLg&Z=f z_WRFx)5O=0cGcRpGo1Fb?I!7Trrgpz{H?09St4AXQW`PX0#EiSyKnYA0MeqM1#F{H z?Cv++l^h3h&ZbTSGL(Jc1j0x9aG|yZc)1{P{T#1+3*&;|h_K+2lamAGsc~DOrlh&@ z19-d^Gu>568X}GMru__It2?vYc=(IEvM8$2SClte0s*I; z>@PvQD)eYAx*W_Zj%c8BmIYdr^YyAE(Us5e3Q?DlXuFnp*-SJ( z8RI9=(_MZNH0j0qaVg=+mc9k)&gfn5d{izf$qsEmN!D z@diI0YS=k2pNOm39KVi?z?Q0i_wFhMBNyJ?Wsu`B;|;J52C}(ma1f-Wr3>Q?cmESP zXNck}Qvc&S-N5)xS3xy~|Wx%8Z zn_PHP#oND)alog%o}(u>Eiy6^IXY_dLO#D_5HLbuuPiFjqMT7IF~z(nlun(t=70)W zj8=Wmf(uSk@F>1z-yaUGLW3odi-u_1$E${G3a8WM5HT^wrFGI3GLR_5iBr`7?a4yKf0CN^LGpPEJAz?)lSFO|v^(QZNzVp^smP zLuEU|KG3cR0>xKNxB=-XlO|s;_-chMU!{lJA-JG$8T<>a>ztfj7;@QIp@7VN{doLC zD;ud_$3Vzb!<<}&NeJTxh29Mr8JT~P%L1HsGI($*Z1|ah9HXP7Il{o)m2K)m({i6?J%FS`Om~MPzU?3to`lByvmKJcjKA-a4=+=Lfnp*hY z&6~aOr6UNY3A>w-X!S1hl}r3 z*e3|XP$e)CsCsjKnG%TR!`3^-sDy);wtvGr2pLM<8_9ajgw^anVlBGjI@;R}9y|zm zeG`UGEmct|BwPm>VoyeQo#79M3SYr{i-DSY5e70=R(LGDl=7he<4b_D#(tk`gp}`+ z>djwoog@IPY))Y)Ss=nVuf|U8d5R=;mvHR6U@E89L2eg?!50^K5^S>rk z1|;6g{Aa>f*z2x92mVL;moHx^zHc^y=~bYaeOF%}!b1*F_;PI3q&PV_vvwCMnBhTn z_4k)Tw`K-7adNZ|Lq4o8B#$A@HwHd`r;U{r4j$h2UbJqBd(F}LewIKxfDr&s%?OlL z0Kc6IW7aPh!CoEAZBc6@k(i8h$YtT;Duf0JKNZdbj7=fQxtCAw1?c@}-vQ>}{sim! z`B#|CvitH3}hF~rT*3M=efriPWT8^k1wNw2MKB>Q74uOxk^RKMu>eR zO#bPq*h+`dkb)a2)DC`JPiiH9hP5Z`zE){RG!0C&4fXV_fR%*?Yrq`B(zdZS)mr$h z$@EGu8M;37lda7Av$*PTIQnHyd3kx~*Y#rnn7v3(H-Gf|FvUK+=MU#>U=$2P(6 zk*zI0<@i-S9dhmPw|=#&cmvvl3@}{?mN#TbV7?Ex|H&^RASKWSOY`#1jSLmv+XgNQ zgm!UVzk-qP6q7>vLm`RYfqkC4iJ08j+Y3kZhzbR#p+^q zql5haG&coZ!((}mnZM1AYz`g;yBuUT47xGf^xr9^(I9=zABHHy4_9R10YzjzDuGK# zhu~w7ltXS=%(CU<$2?HaKzC5y2SE~23{-~dH(LvfU}Mh%rEh`a$XxAH*rx+O%&CkXNf@3uj#XS*E`0me!Vq8@%=_dzc9ORT zko+w{Yg|1y$^km+qR`9u1CRe$-EGsRCd)~NU9MDI+|u4*O?%49kb z2cp3q9(w?p-xL-~`X7z<^=Y_zc#R#G!Eohz)1gC4;90@ldH@qJ7DP;cL;V98zfe_I zFNEuX;5P$ZOGqH2qvybv$G=iX8Frqz2`0864FLWIXaIygwY!7d?xpYgLkf;z6xH01 z(kQwI9C@O#UqyPyMQ3!@62;NP9mGPLkJcHjb~LfKFV4+1^YpBNG20w8=M9iP-j$RX!@N*Ujc779 zF0Q%oJa?BIfIkuYQ2`k30FYZ81NjWU+#o7V=P zUFc+FvbJUD`Pyj!GfL?e4dO-jV~-b6_@Ubh+-cXIpap4#@pSzi^70kzkb0|P}8bI6ae%s6_qX^n&!jq z9v;o$CWnT0KtU!qyLmHGb?f~SG&d!CuK8%@nwpvxW=JPMm5+;wp`5%)EG)}ZxD5)S zEjh~N_&cn*nHg)69!&ClV{~*}|L{Smb}sS)90{^XC=DBw{E<*>p`z;Fz5A)L8S7UM z35AF^c)$P^47*`+jP*K96x43wf1`<^mk*7EK1G(lQ_~&vG9nMuVPqdYN(^nQK7kyW3u~ST?uD-qoDg6&KL~S% z$!d$A2|8ll=H})Aq_0U>#6`!&g|%(c4k;@t?f_qhm%o*$8t+EFV632%_Vs-H_^S0OKuJ7Y+$atnTwblFlLNca9rzO}wkvsE zCX^Nj2L`5RW}Y(1=|LU|NETK~F&NAc%~fpx6-MB;!i<%b6_*S^nSWHTF0gYILq%`1 z`1h`RF8}yJU;Cdd?FTSsp-ClhQC~8^GhG`+V~@G-cV^QuS_IWcz8VF9cX5q+3STKEPX9zx<~Zb( z0ehJhU!Gdf+hRHklLV$#j*GZg3TIN4VT`pSHcp824F(HTT#^jMHPuzOghA#XV2dQE zDk&*R0rP};78qtYTz*@MNd(Y}h>3ZD&Myj-I)K}W)#Hmedlo`{a)miPNhX|JBiJsUj9~rWO_-J8zptK&=m>I^$ph zGZ7b+&S1^8h@1$B`}8!{)I5Li6+b5eg%Q|Fa43 z05k{^iToNAIDM`&Z8)mQSLi-Q`S$hpt~Q^nG+XX5eEdKv*M?TbX1$RSZ+L@~6HmGH z%^M0^{dNo2F{w{5{}q#QM?oR@3a6+j?Y`mln7Aqd=jaae8WPRKLRPD;ULGxi*N(Qh z&!q2Cfp`r9R!MO&<;^C4gZuZF=jTHhXv$fccKdEjG1(y{61QBs-wL!Hhh8lUOE`Sp zxatX)ErchKdNyUnkHqrybi(uJ_){Wvx2hPn{cqkR5Uf?swjx|*Bg|vhwvezex9(bv z5qK`}dz|Wuy=(6XY%0~B(U7;MaeNaF*Iism+X?a@p-+@nM$tR2+E(@`@h4XH3knJf zfs3~m&^1H`LerQGuBpevyzMn(?vWg*K?XHtx9=}~e#tr8+169Xftx)XTJzAe%#$15hMgl+&@+3wNY6nyjTo8kPU)kZtg+6ClN!b89b%?%9< z&+@>3m*0B!n9 zaW{~I36rPM=m>IZTbg@YP@yqE%8NKCczkB*D{BY5M`+pSmsTbN^)qOk(xRTkf)rx zgU2w(h!$oqX-b((u=zP-t{#>gf|Cd*#j<%NZgS=h$Dv$U#R7Kjcmm3V_44J{(1Q}l zd_GBwLnznMWEu-*u2uP=f`Y|%x7eW7i0eVzLl`TdB^((ZR=ynmf%Zvu847No5pYa@ z{@l{iQr1OOF2}$39@0MNCbapCdk-G;B&jyNU~CJ#oro)kyTMb}>9?(MX3YKCFNJ?d&la@u{O^ENCKXPVAp!6 zsEF+&6MR0uA>y8{?geLQ7*SLcGRxbJEl}NRJ^Pd8i=S$;gvrlis>1AeU@upV>IQ-M zx3rwOT~k|oO_#8peb!5g%gXgR1YPLFyVgEd8dQ}1dMaD*(q(c`I#T@ZUAfcIY&1VM zgj3gU+}hd9o`CW-D#8RB*yvQA$eXj}W}B>sA}*g&FN8c&Pnxyz~KnB*6UA3_AczV?04`yP4bcen8b=5CvvLU^#(pKw!{Qf#eDjq8VWM2L}bg1uaJo?5r?% zOM?7!(Mv92!r%E@DwaIVlx7IGtnweIdM7aE&pkG8&d?bRkwtgFp9Utro~~|BPY)3> zvHjThrj+sU`Z2DiJg@CX5-<@192U~@_wzCLE)2u(dew3aBJw!UEztZSiQeHq@@xY6 zR>@OBS!Et>dw5h-iBAUu*j1RH6%Z7x3pj16tQ4+z^23FQC>lhpT~K=R^RYEShjRy& z>+Ct)9I~(`ukF{6ZjA#27_4lU`gp)U*f==Q$ff*`L@TlP&>gXgvWNyMBrt~}9M+4KpawaCtDAJ!W zP=nFseC$n4q3R*yU^LVITMg>-XOgStI0BF>g(8qRukQ!~II0W8N7+f+Ojt9_1J=I+ zQzRbXrNN<-bJ=k4@)GkvgDL^$xs8lgv(t?H`SbDMSx0bKhf)GCH-7NI2fU`gpatRE z9zp&GWoWJ}FN;e^yw6m1YAP?^1f4%y(hDnimchMA)!cRPoJig~V90It1|lt)kV>;9 zy+r0~ZT-5rxmmWJ_^HQtz*cimR5V`*F2L{gj4Fg%$|YfriI);WTqwecSM*fIb*=<` zKSxTLFLsy*{qxfcd+)B+LU^2(rq&S}=+^krk#8~tlQ8olKk8L0`02K+e`|7F<546E zp5255Q^FwI6xGe$NSd2fjCOi5ec`w6H8nxfHGgi^H?bX!jDIE4Kr!lojbe2y z)&p5VUO_=A>9GZrH4)f6@T3yw-$lT!HX51YW}nZR?fv)~e%!PQ%2)ZDgp$WVzeG72 z)M(-6r9&J#Bde$6(EL@<7ur7RK7PCg!;YZ+%vT^yW*Wf%i2S{`Dt{8IN8jh5_pXJ> zL_mC)P<_{sxTB-Pyu7BYj7&2T%`P?!LQ;uJyTuM{(pUNU$tfvjZf&=4|Fry22wRoC zo7mV2-2y4StXPg&SV#!2UWnU*f%zT%I?PCJ8~RHw1-4wndIIXsi)$90plLww$&>>3 z4l{mr=T6E8-u>S6goHD#gkaaUy|=rhAVjl-UBzVQJ*%GNemIn#A7k1a~enYbe3sXf_z~wosafJODVslGNoQCnL zS*QZ_7eOUp#Fz8$IkRx@*n(IFbf%_#ax%+r62?C|paDQ!s!1)44>Ruz*YUVM25A`5 zL-;jTxNsE}f=X6dUwC$I4uT}P+aSrcr4Mjc-1%v1Y|PXfbh2mBN0fw zsIC8fef)DFm)=>yI$vr&Lr;hZgMZXuUCRqvC;Z1;76f)@$1j&A9lkAufe9!ai6=#s zcacypA%X_G1*+tm>C%!Wlz(K$ETqj7*;U>Y6~SYGk*8bhZG2@*57=SF!blkpx;eAC zMjgQ5gp?i#(;P;lZ}s_i(?Vd-1i}XUCx`3jnIsEUA4heK>EKUwRWrx4HM}jPbWHRA z5n+1|iH;>8AQ1D~;&?p{_6JA-W+w+f>(|q@`@&zpwgxfv+7F?Gear{)<1%FeHWg@&&Y{^lKKl)e`lF7a)H3xBlN&P&jw_xv|!(r@fGDWjdov(G2U3T3NJNW3c|t-!N8-XZW>M#NtcPrvND)D;MTByNp9K^ zu=mp_BUpY|h%WQbexQR40bB$We_s0cG}Msi&5+E;gg~s5iP%Tb&lN!*g62f@HWOwa z1q2c#xIKoZ*lKx?o-RUC;94nMoAReYX$Xu!YxVT>l%0&YasB#Nn6clsR#a4kvJD#& zc!?O?9OX(UU-x8*G={WV&IMo(48mY!cewP#;DXETz`M|#Vv;E@n1g?Lzt!TYKS2h6 zQUhm3cJ`EI=eH6giEoVf=byRVy-QuaIGw;~)3j-(9NxdXK6SnlHqa7irC7Il%w1zf zF+A9e@@MEbQDCwXpdfJ^2#}=WXsO=2_d=G$WxZ5&!;LE;ucz~)e*A`CG7dR4C8Z_g z_`8Ed!L-2KEAaGSa~g8yzxj#sqBP9P5fLcu^Trc!$BG?ba>|znVnRo zGEj-wb5qLouea8MqV73%CtZRK9UT?b_5o(5x4=w*8%y+?k9X-~;+!!V-#(Ss5iuke z_-gp|9m&$r*3j@xmN^-AvV@mY z(3Fvt*O%g*VCptX=3_q8`qQ9z4a>^rs&;`Np+Eib;gK+53P=(lH1c_U=P)Bms8<58 zFz9okEvT+9F)*LH?s222r}^T|_7OrN`~2#euR}~&-wt9AyJGAd{i*4Z3V(bkY3V)? z%%%HYK&B)b?F{r=DE5GNA@aPJ)TPzNP~;h7Y19QhXi|vZP5E_Uyx8b@)#(*Lr^1d} znVWNd1=12yEyvL5X~c!7GBRHk8)3XrODn6$hzRk;s;~B>)xfJNM_*Ynp1=#WiAId} z`NBA|BNul2O4}T(ZkKl3ZKeS10JSa-HqGp|O2B-=k3uOFxm{^_d1MrP3XQhvc5ZFu)2EX=G1%?#vQ>k&F%Vh; zCT7-7JxHD%-tQZ2;&k-rBk-t=&t!Lai=UM#PVA8B-7>#sqX56;9vv&4?~cAqJaSS< zQ+vJ4-vz@NDwULBD@lAMz|feOyz8|*)YVlQ4P>7SU`k(VhA2`K#~HCkgtkH_-UL~- z%>(Z|mdN?_9xOxsE+(#O@N|uVQRE-hjA@^%xMl0{)V6~8vDBE)hro&R$(#l0=^Pa| zj+Rb{$3v1O__5CR_NNvL$Fl7WoiFVw36Rs%V@$|e_0PAzXPQ~|->P@bVVp%z*yAhc zRV*NSqd@8fCj=%CgB(P+TU}}g^_{|cZ;$?JFq!iN*6v9@4t=2;|LS@FPms>-*3_;7`ttE*nVLlU?_2W|t!Il@fB8K}BZX_=ie3JTvQC!s#i1DvDXDGI25U?9m! z-G*BPuQ%U>-pHb7u;kNz>GI`M%tT=`)*VH+AJ;U&P@x=0z5YBhLUKDnh+4}$FpYL= zh343-%*xm3$B#kiHtx~$U}iGPZ8=nb?Xqp_(^8RhQh1fi49{h6e|ed&Uy8>@20E4G!H3qiR0+XIDg9b7qr-uQf z0l4)Ik02se37;VI`rV{BpP^eoId4i=pB-B77qJ-|a&sbm3$w3!B~Z{a%|mq^DavEO zL(L^IcDfWAaQk)}C@(0+_i=%1>tsK;vg}*HwKN7OCKZ^2N=kKLHg-6(UHL5Wn|Hfz zz2V~ZDR^)`aKM%Ds|GVlJjVrr4);2W%MI#K4npo6P#ueJHv*p?!I_{@!1$7?ee(FR zPL65N^v;WR&+>1_y)?Af(D(?f6R=-_U4XY`OU(15dB+!#3Q=Tx_Uxgcpa}E=UN)e< zF|FfQz=Bp2!+PPHP6JyNTvqUVi%b&0o|}uYE%H_cx)qd!``9~&C-fMCIjIl`dE>&) z=ypLHtVS?wpq3th42H#b{gdB3N|SPlwm1wFvE1`BklX2z$^$n{knm!1T<{P))qbXg zVmux}W!_#h$Ntx0drbyRx4P0+teX8zac76rwzt z;0JmHlnwp?<>N_R1aL#-^eQx*YXiymA#9g z1MRk7I`tU~nc>M0Z~FZHft(KTJ0@+Iacw|84RQPz$H7pyZWx3>7KD8PLuDG_hn!Bh zMMzx9c=a4@;@ysrqln_PQb|O>U{e<{EGMjb`|cfu$UCqZU0nKI^2n;}O*)*5J?0$D z%?E+7Hwo3G9z&j(H6!Qy#(c*CuzV$A!Q0b_CLHw3knfIwj(%=Flw~V z$}JTgOMt8(1hwzF#>lDduZKKm?do%qJcr<3$}p&0`Mnpu+ZgV%6U^1jmmyaB`ALVT zN}dJ31-$)CRdAf@oIu8c|8?X#YsTzp7mQ-qb?i<;LTX5o1&v}K5|$@^gN(Ihaxd|o z#1Vdi=(lg)jJ|(B(bBKU0eV$C&$=0qhFxY@Yz0J);!b+Ihx_a4M=By9zyj^r%&V{4 zA#WHEq!STTbG<^s!X6N<^o6L`*jFn6vfQiyS@h-+%$8*h08qT5xC|TF7GMo5m6I}Z zo4?TP-J6}^*Y@ljg<|nsKdmqTd54r6ASza)8y{XTx;P=x+nAZ4!PZ{vRh*T@oLfJ3!u9S^R-#H7B@50S_ty$t3r<7SXd@F#-c36neA;bcZ zjNXBvG=RI)?;`;^Mi0ORP~$};A*W61rX@^2Lkce~R0ToaiCW$KySW zsdTopgSu(ug2%swwvHDh5JNMMIDqRjyGIvw_^{a33&810!ZQto+??1D}+%f&%vqV8TMI7RPrG z`r1p#gEFv3FlgxhjOw1ti}^Tcf_T?KL(^-$d+G5i2#xLm2Eg?R=tC_)KzCIwog@G_ z)6T(Re)^rFrazJy=pDiU4*eNsh*yO22`*4+fLC#=esU8QJh!s#Rg!?c@8&AF)bSdk ztYQfxA)Qj!TQ=>4NeUp(j6o5qQbVTp_EL#kAOOsL3ONM@-5U}SAR740)-xvjsepLY z#ei5Af0&kLBAYKWwGF)w#m?>{nZFn0CRE0%-<7Ir=LDWt!`B*eMn@|?V#D2PlKD1ZbsX~2-P zI<#KCqq6m#6vS5gejR!T#KnWa5}P;KO-_EPuL@)j0CyfB?QM&fs4m%N^TD$ZcC@y} zo=t8PPJo>Et|O^WjJ@_p0_5`*clBj}RGh&3|CDP16|E*Arb9|uI>}jp!wN{a>*wd) z6GK*^0;O6&W&pwh&3i^$o9()F+_r^o@76DxM>9_$A$D6Z|G@}ai?L7MyAE(Kl#F5# zvUM5+X}GdHQw$}#L$~gsq(jFXZo(mrD-K+6z@zS09o;NEpw49A|1EY#{WL+}talAygApF9z}m)Q`u`&1>rC zQE&es-oOhiC`ngmXQ^8Mgo!#(L46f3Jhd3OF9!m?9+d-dr8;?4AaHE2GR0w1#g#~t zm}!v|WhyezcPWe^_|?!qyoMU~Lq69mxtMrT16FmywO(K^&F#@wSJ}=1%nf+Xp$^Cp zM3PRAo&qvoYN}*(@J9{5eFB2&`hX_hfpC^Ovvyacp6B+y9`z&Cz^yJ{AO@ipRUelN zWF^2lOQFQ#5GoK!hVj-BF$rq#O}|$aLfK4qlC_!Hv^m=ZVMq3XM@+cQpHepPPHgNm zn>ImV7bmBava(`S?ch>^&fh`D&nYBC+vh8a!R*=gGG5F^AduJ$U}%CO$vMQ~C9-HQ z91Fx^F+4mAJt3lXtq`f4&SfJ(HQnLw&G#}{gHMg)Z$SRYA`#YD{!e$c$m|t#v zmPV=nK|sBM7FKYC4bO9B$#pusWy}Zqp&CwABW19mSRu25aeCDq=2L|CpFY)KquN77 z)y)g^i^NVP(n7h$LF=8EqAv#1K!JyGi+%7>X&^*&nJ`1*HF&mR;}zxQzRL;6sp-d_ z*>#mcmIX}CD-wjd!@tXbD5B*)*`?Q5xHPnu>?l}K|s%0>->8Mq3}E?Ik4ok zxAO>&oe&fAmf^mmvCj@$NxqplIy;*ih04IH-HM93*ED!w`K(Jah~0K##6+gKebfNE zr?#G+jt4LX$^CRJa^~>H)$LyE#oDmSdo_cplW* z5b-TdlbSfe-a&qlDgMcItRwB0uzO@hq(MZMqKX&yDbG4i17*>`;pXNBpL2PlOCnq%_6KZUg}~-hZbe9O@^Z*H^y3e!inw_bJsxAvCNyw| zkC&ITr)&&TZ$Zujwg3#)mBj&3%DMB?5C=?5N&+v#?-(Vgpv{hoYqTw3{6WFNkVgda zJ$ggr;B2V*1TGihB~;3}HF-bVbwDB3mog+M=*_U|rI(WS_E`xDMo@tF1U?oZc1sul z87X=7Vqi6b0RlB?V{{}SwFOMBk)}TAYO3Vi^9%mfv^pT}!Bd%6oVb~^>PWQSErFUm zDSSV?w!dk@byeCOf!&0S&5X2n*~tPpE7s>;}>k=t3y>mEMkd8l?^suX{JEBnKfA_h{Ozo>Eg29cc<=>QuBCP_fU*YB+UijV!*ou z1Jfr6;7(DP1Orp=-;IqdJi)ewhzR{5-_zONG+$DjJd9AgkG3wa~%P< zSdnrrO%U`T+a9P42i7g~`Dt`edUCSsa3g!_jYKc@C@?mXVAxy=3#$jskd~Ilyrnsz zY7Sx!p`+_j)jNFPGeW;d(iQLD-GwlGoVg|-#+ zaA3}a^*%X)l(Bc=g+2?_1rlOnVn7Iy2(E@t!)f>Kg+>K;P+WCl>-E$9+ns<{Q1R;3 zgQ6map#ytDd@BciDLx^E>L-!cqM^og_*z3Soj^SF*BbyJ+na-ZsL|)U{N=>Z8vD+s z$Lh2j9mGY|0Y_9opR=m2saaZF^jw}Z3o{fdDjC#Z$kHoNqmvBQx@a7IRIInEiGYOK zuCJOhkkh@={f(<0WZ&Ef4ZZjUjQLYaN=m0sA3P>UT>(;1?%noFZWQ36#6dRzGR8F~ zE=}N)%dR|o1=);D0)Stoh(i-JH{Tj{>IR0HA7uK{`pcg=VTk!?~VNq)ni0TRp* zjv5D)q43bxXVNQdz)CB4Kxtyg&yn!wzoH&`6Nu_GmjZ)>$3AAUFa)sLc8ObnswPHd}OAC20+;Q5}ED01G8Xwd3g<~@8%K|Vg+2=^pVFXQOM;>#k6lntNjZvnrzm+ zFF#i8-%=hPg1@uR!8@>uR`#4BmA0b+S%Ha~7 zXL@yIlp$pfbv=s2@bcUQbu;^QzFtREN3zdX@g0lf}q0 z@lSqRoO68dNA&#JGY-9?*UzQco&^lY@Dv;`lndH|upAM}S3xo0k-{HgyaHi6YmwZI zh2E8nLs~UBI2e4u7vStR>rUZip6!2}oBQ0=bAe|B z1TSaiM4oL&@Jc*T_e@H`a|-53dNK#bsrjy|!Dl5J6Lh&({Ad-yGj<275?oD;;EsNc z0;j_V>_6haI@E7a5M_sydPYFR}!i%T-UXebO?;mU^ z8HCYqG9$GqwSp4~|7gELVCMu!p~o<;S;(iO$BXpwnPxoF#ar35ecnxETsMNrLF%^} zJ23+~d|4af()1ya*3WqXQ(ey$!m=xt@9f@0pM(<;Y+{#4cliTKJLc%59T5ArsVVXn zi8Q{*d=QezJ7}MYXlH59nB6)9xfDrjR8uwy=2ha%dg9KGc$;3==NW z>afnyT`0YTU%WUKAd~gBKB*a;w+a_9^~#dD6dgsVmJUi+>Kuan?st%)+j$6i8+Cp0 z@%t1$LV3ZPH$OlVgWCqpooLqtwSRYC3T%%8;H=jR9D}IG;5Twv<=8%xumxKu=8EgDmcteamv`A^|DFT4(MG0FZCo z{rgwdC@Cl|Q-2;F289g7o=;XMNQEeTcK469RCBl34}^ z1ZZU$;t%h+a>e8d_{|Y0fJy-i!^6p=jz9|8Wrkzi+~iO0rKgjYu6((>6246K{M0e9 zR7D(m3DsFs^$1B$kV!4O?>KG1{<0BE0=CJt4sf=X#0_=S)hkG#O(v#FK0gFzu?C63 zbDx!XD9u*!;VMUG2ZZd=G(a%E0*LYU?v*Hh`+eD7w6rl)57>_!`3zpKbsy_>Ho44a zc1})LMzj!`5}^fQRtO+t@o)j;QqJ_TbUYwi*X24f) zhmJUZSXq3#;xSz>?X|Md(V?V@#|juFvuZx)1r z4GJk-P@^6)dXf479g@A{6VCf*JSSh~fR{}ob^LgV7D*@*A!Tn6^%6k5Q10Hy2lB*I zfGAID_&()Ss5bDgb&EyQ?)KAMfC9@vEJMJ0T7UnYY_$MK8rs+dFI34LI2n}*CL@xb z5`8UDbguUXFzj7qniqVN;62T>$JTdr4a%Sf<#_`WAV1&w@I043JSdj#!bTD20`}gI!y4u=-?+{ie%u6g>hckFs8pJ?P zzYc^PIY`&gR|BImBQsM87pCt_dGf>+ra)-D2U->q`~9h)w%kN6ASd8l&_l{D5%4O3 zAOmIZVHAd41p_Dh=CxdV$O;f~8dTzVp!`hdYCymVB_*h<*$mbLWcY;L&6)@AoU^B; zx!J_bEXV%1fS&M;1M;6T4K5cIc|zncAy(0539n}xSV&hn?kO=@TaaxZJ8)ely%%O6 z0~+1RY^7+TBE?gvId(s_zVF*<4!p^UARb1CN);_F+8#29szF4`5txLn@b&@a79NFr}U0zZfc6;cfc8DgqW~$6}%YpuW7pP4S%-el_%%KOFKd2;LgTxjMT}a~W znFK={-sCwNae4uVUa;X$1>c&1`SB!5gt0BEE@6C@Kg%@gA8N?4^(l%x(CFmP;_Z1R%8tO7U&hMO2(gBPTI{t+UR9 zNp%jUbc5Nw??V>^uSt?zqT~&pZGl`uTAI!(nO$m|gM4o#445)&Er89a0-!pNJt;SP zqK#6dU98;WfJNHFhfNo;eGbEWe6KNE5$1m-4vERuuTxf00Wdb7{L0oorWSQR=|~|P z4=lXxO2W>~jk@6MP!48r;vOW3j6o49C_!i?GCUl@WP!I!;!^9u_pOtI=by~zre`I* z6xyFwG+b*YM?i25P%*G1#*E$eQ0zDL_(tQ%qEEH_I>Y?jJ;?z6o%n}~4o2cRnnjC8g$xia58 znir}%X)!P!%l*74HSH#FEq*8_fjGoWRrNiv&M($L#m!QY#;#B+r=rPSvh6R5p?nQg zSBr@8cLjMT9t~0lNReYa4q>eFd$#YTf2Rp$c(@M^jn9ies(J{SS9-d-!LRCpsJGCn zs+qvzBYxy65?m&w%@Q}hOLh|gb<;TjRBsD7UR|P8hm0#o*8`OA`U1!kaP9hO=-*); zB0O9W3g9+Ewyvgb4TjVM=|rW-h{{3kZmN?7b#ysGz@Tn zLrWEf+Rz6>21Pr(M!?)#A37`NA%32AMn{xkHD8AOVQJBm6Y@3A*B;=U}a}N3s2GDqjLYG zW}fveC`t{ zHN!dtP_k}woHA1}A4W@yo3$sTiLJAx_X6xHPegOe?CzkP5xVnHs z4kAS)cR^7cc?SpX02Te%x$aYW#b9`z-9d?Q2ha%uVx9m8RiTd_Juz>lysD^4V#G;|YSeodGu2j&({pwd6Lf~u>%*GJDJTl#hVCuNu04h%J)9RRrPiD5s66cj;ruY| zedMX^c7!&UXQ5d?(pEVLAo1>YtgNu*Ar20zfR|O{le_(dlr=y(6}denrsSPRV1W?_ zp#*>ha9lJbQjon9pFcC=3}6;5UrAq01I95nI9Nq`*k;;v2I64xqjgsUNq>;YW*kp-+%s_$#Y&=Y`Z?8{=r_LHYY%mzqBb>MnbI{<_FPc&1FIPnl|5HR=>G7d9+y{lsA%#s|O5Rd3e z3Yzvgzzs?$Iub7?S_viSXRW7R1~HJ6XG0D6D3S;mgD>|(5&aaZTa#d@LKX`1PAHcB zZH^bpCRe|CBZWOwSQhH@_K?R{iSr;OL0H4YXFd@?&D}*t#-t>gdky^tSn3ye_+k6f%r zl2QOI)?iEqPz1E-XE1kT>+vfz`R??8U2RtPpxSK5F$=IXAVQp<>`#kK8iiyKAu(c8 zFY}9!;~zZ=*bP(?N>gzLKVIHLhkOfYye6+ZkzJ$7fR#7)VM}hsY=?~ zF2HnZoJS)FAsCy=Fn#R6fo(3S-y_Wg_+b0)r5~92{NaS2o*oqED0rFu3PNRl<}gFm zSun6KJAnrBqoaS22kL2SRLt3-AkWfwcvu2zJNUu$ZjmA=sYg&U)28jomYsw!Fyp>ikwX!0v1dA4v zAr&vnS@s9ly2Dusaez^2WrLDOjsK9p)U*q!x-b4W8vgN5gVNvjSKZMUHKbehvCjxK zV4Fr#Sk8-EOzv29w{u<2yeu3W8LtO|Excnqs-EEuY#q~NkP zx3oM$g0M4#hFSbTtY=}y=oTm|{w$wSzw43SJ)P!`t4J1B zwDcplCY>?VYikH5Ly!vzWp6&Y6ZluHr|`WD`cYnUH30bsGl~|$bU$EZep|?}PRQXi zcS>@(XHhzj|LG-tX`7i98z2+i&gPWk1(>-Qdtk&vA*U!o=Od@%@704x2)?-O8pWI% z>8seRoSd54S{G+$lfs9c*MH+oeTHdSZ}FJjPfm7>ges)2;DJLmRlKyqUlXU~4m@+! zG%$$MV9U$Of^k3b?HiPd=sDW74&Bqr>6b(KGbrzqIS*aO!qO5cE&-#v5#{Lk1;Rq+ zmX@Hh9z*DowK2okS zAY_Arxo8KO6JVqk6bQOd>ct|ODoA}gUFdGTkkjBr;RR5MggbWh5mEB4X|G^E2J%bA zAQkc@IIpedO4ake-Z}{d1>zTh>!5KAusewJ@9G8y+ceC9ss(SSp;&{Ir!+f=PvE90 zAe1Q}v?xRxKYZ|6XjWh^!y=X7=)g%koNJ@6ZwJKrA_s)hWtMs*v(q;?7%RY#GtaCO ztEZ(EunFddd^^8inOhnO;e;|vfT61aHB6zL6wF5sp@Z-*kB=%9cNg9#D)$0H5^(Au zTnI@R-H^G{DtHm40Cq?ocKAZmZ5Cl+x?41<7jpxTsxG>=!Rtp-v7%@NkX&X5tEZZ* zT$SK;YqXPau`Efozj|Ud0BPWzfp0|?NP;W-)-;(C<@qgo95_`*{1BXFmJTVR_CfMy z2d71_$H0kwU0YkBB14+@f>Xq6neHo#OcZ%v)m11nxu;O>a6-=+?ZLi2XNXab(UJgs z_dWykQV)iU3v77O8KSWEHZ>dETM2DkPG10Hl*woo@gc)GY%3JlISGV`j!DSuW60@_ z1=~AIBXE(nPbM`i8?tL)xG`&1o=V-0q{e$Ly7_|tzVqA>J;$nrFy)#9lVw<>nv0gP z42zZs6hMN2YzT5u_0Ag!t0Pk$n3j4Pr2?C==9*hnJUTI$k`0g7y}Pj;9=FbS2c_ ztf~;Go{YMTlD<~J#6C#F9vu?{$#&$|?EH>vfzwAV(@Y1fF5qA-K_=urzgr-OeOy^? zYLVW(86M6={f#Dv7Y_?FYygD|G9gqg>-4pw96*ax6M4Jff8Jw$S}dW5YBwe2S8z!J zw%0!rC}`!s`I!k+pJknUP!Y_B4rDAyT?kLo26#(h;o6leP)!IeD$2-5w5I+% z`Y%(~g(74rPY4TwWeG(M{aDXD#wGsxgV>6Nz7Y&)rMF8Qm$nF$FaSf*39zWJ(aTUD z3_3DYK8Q<8yA8RIK#L_w*zz8st?oY$$Zkjf6Yl}0G7Vf3N$$NW^fhVHvJM}}^iE#X? z?8tUggR5?w!@0dN4b~x&hEOG`Z*=nwLF~A4m#mj!=8_ zN>&gKnD#k7VV8{XuB=jR$u2_9XCVtj%9>DG!TeA-2Y&}heJFvDnU~iHGdnVQlCW5} zK}?K|w9~eC5DXUz-y2{prPa#?wX?oC-*j7P2MAWkNUK<)-US+r*>XQtIuFc4D6AZY z)C79^>Py%QU|1O{Jju(m(G4g+PcY^NHz_7oD$RHS(hY$C>I^2eD?LoFD|s|tjrulI z^j|e#F2{PpZi;Vx^IhqhsmS8RK6YtwC|U+2#1C8rsn7bTKt+>XkrV%wI2M>b`-+HW zX=4=o!t6v`tAC=`;Z%qz!Z7iIBzURo9V{`>r=TQe_~q4X;91uvf+q261K@K)u4*OHb2(58Ad5Ubd-bZH~wsY0?fWlacAsZ z@>`(zOgKTr57bcuc4d5Jc^oE2gE;eHQBgg?A_yb) zPQEk(1qg9w7aEGy0c!kd5VF-;vrSGwepA9MGEwEq;un|%*7v31o;{J^qkaE1okhX| z`*cVf`N0eC7amy*H>Rt9LT0oE%eb-_a#Zy9vq@ij3H;E>-BVZFl7jAphXc1!H0l2R z>}04IFxz`W(XK3t%LqzB)4{3l+*yXWX^{=i6!PT@&aEH5)8xK<0sA?Q*TsDCpwW}F zL1OpQbCKzY0UR0|9eoZ{_oVMP?t)M$lw7(1NIAgFfR3NCNPvp)bhY4t(VhPcs3?>) z34_86k09XmYW@5Q39fCA?usl~$G7+dL~h%;H!Ak2mWoP_z<9xyS$>$W5eTGwd=aBY zXKidqB~DnTdclby$11lTs4)vLe*{)aDk~Xi6C+FK@R@PhbChei*!q)tEBu-{I)O~mMtUBWUH_6u8&M@KjeOxoX@@Oi`k^8)T#v-e-kfZWvO_N z$LuLZgM^jBS(nettQIVRG%O$MhsI{NOwy6B}bkCkGRQ zv&fRIp(PPFmjDwd6S5>Mj8f*~A>!kKb!C(?8cl>ouP*ZP5%Kb^F7ogb@$j!Ma`EyI z!Dn@an}>*dZIO!?HX~a_M801Hw{QI-7$VHCyOHD9ck}ZS@#B8~x7*?7g1cV5?DuP- zl==CH_;EM6@v_LRuAlc0m)-d28=m)17uaxC9^^s)epa515A){+{SOyFBhRsR0j!0! zlZgWgYi;0UB57h|Yixo#X<}pMWX{Be;T92Ddzo&rIw4}DWlUsJGqIOw>&RQo8!{in zaPVTEZ}L%mA_y9SAxop z57Xp2(pA4+_s(42_u>ov@zYygH|q5fkJQHG1%75vd{#l1C?0NuH}p`>se%wMc}3lW zIMCEpeD~zGG$x%3Qv1>+af;oBc$kgUSTJ_%F z`ylRhuRX80fujl5*2W2?sU{(FLg}c4yox423fUrQ;%MYxVdrG)z{J1WF;#8VY%Gu_ zVdBO$nKDZCoSg~oU?LRO!okr=!rZ`tiHjF?(qL_w8;v?`VeDk?sKtclflfrk2~GX; zA3ryr4iQSq22N~YV+N&LBsBX=)F=0TG^I;HSh`}JY&V!Sb zoJ@S&7$$xJ&wXfA={93WO;oZ z8JzrF{J68iJ|bj4{F0lSiI-CV*dN^R-d2Cf2Mx=MeBl0&eQ@N4_X$IBRrUPkJ+AKl zUxy+$%G830i<<`p3ev#Qe8cd=sl(s;iI}RaiWqMA{oYUhNh7ku8(*HFdJ?UIy+*WDF0pW zY%pH_YrO-PUsXCAx;Ymw(&c`AVzE!RyoY7Q1xRKA3~reSIRf_bgY1UqL4Joj z2OPbA-qmZYU5NcVl;)Y%S*r_(yRR8rb;zF64g4#ftS`+aIpzNJ(!DP2E zGj}2q;9Fg@HZgVjvr<|0pnmOlSShTg+!>tp@mt5^;{CVQ2iFhb!pFJ#4*z@WW9_{{ zZ~4c+{|EcgyvWev72st;mXPn&we{8DWZ)AP--uMs`6rM={tVY~X7&L$zxUK~qh!?~r(gMg9>u!= zaH_=-Ur4*T9S)K%rM8YfpJ4)?De0(>u|H~-mq`HKU~hjT@sg`su-@$WDD z`C)V-zvBVr4RQvC`@i{YxDuR~ALJNLK)^Zpal#t|;}tmuF$<7yJ`5j77qAK7KwdQN zR``)24mXcjEBt&LEFatta2J5%(1vJ1M z2o8{5Ys>E==>lSt^XnGJfQTD57^bPhT8&XTRV~nIr`sxkmJ|SirfhXh7N|4ACxj;=kqf0@q@wx zs|f?T7TL#x*wD~U$Tg83Ex-jfJ@Ok2KM`^)vK<3T9C{5XF`^d#zVHleuzQ9H*DttgMkMbe9$oK+mPEp z_8}kKxqp?(t8VyTWiqn+e;r^yOn>kJEQkQr!O3W2L+e!!;1_>@`}=O3OYkrJ1DtXA zYu7!El~j~p^$!GomF)l~!E^mhxbtlEOu05Fd&GeGH$C=ypZd|e)|Pm<;KGO`g&ROV zt4r(ue|)c<;jg0u61|xOz*GKlKWGf}MIPjgfB0LwBH~TrJWIGT&a;HOSzpK98E%am zlmJ7>WYFh_HXgAo-Bp|7)k>0V{B$ z^g_h$uU!DEh!t0r2k8X>^>6weQL%sP0=ygXCoatQF2I9`p})SAwT34`M*2Vg{l_z` z{+buggN%RVd-XrEhPwycHg4Q@H1Z#JM#SYuj)a%CL8HLU|0{@}3uo~B+JvW7#T8}6 z5e2~a`yl$K78Lj~h|oWj9UtP3{P_Ggw~0LAuXiaaCZ;5VjCJKdyysPLTCOGIunP661IbR0Ji`%+sA((Q88!2Z^cF>cgAR34~ve`!0YWjv~}R1+5HIB&xiT@Va3~N_tC9MRLN8~ zlkQ(kbE$pHeu!O`U3ub-qAYv$3ARIrsxxHR+2mipLdm>2apcV_S$3E!O#gbXk^YF` zh^fA*vGJM3>*Jz1YI|Swznf98-C|f_^vH`S!)#lDpo){`yWWV3yodc9`Bct9+2La) zV^udjW0o-2tnG&TmF#mH*rOVRE!2b6)U&uXgJLcEh^Xggyhm)g6f%`zx z;ANi>&Ua;8^hV~E7kRfkGDeMs^S&(Hy!~1u%43O{!mdUfMOE%qu02X@Ni zWq{Wwl>P!c@2v|5n<&O^=eW61Q*ZJOD@^}gEaEJrf75w?Bj4aUFFTrvog48>c@W*m z`+En5jT<{KZgsr_BftDhAI1m}q2w(b5&RD)S&&%Q#!ihgL>Zw>P^Ks|l=(S3a}yhs z1J%>c;al zmHw#%Uo3A4qZIR;=eH+VAGPh>;p5SN($YsE0mV7FO*5P02F85zrW3hx^mk3F_@W(% z-=7PFeujp^hrCJl4Ofjz+WOV{QIxA6iFz28dXw(DcIcwda;ewlGClk_p1XCI)7^c& z+)nvNPVbNBd7VIi*E)RVj73)F*b?dfqsem9N=cuu$hXQ0$99F(xj%eB@$K7ZgYA*t zx=9Br=daZY5-Dp~tIEnbm!)wGb}AW{uv_w(+$0Ec_ifQljNW(Q$kr&9m)D4Ds_#9x zgdSHOdvn$4WEmr)?#LXek1K{Tv(fH@dJLud$H!-1(ucYTg*XMLT`Vq*QQ=&0WV;=B z{6t;I`2#We$ET0#zCS?L5GTCN2YVsF;-s`xrxG1sKKUu%=vYYuw%Rf)YN@HT;$w6) z`Oa3oUk4w*irMWMK5>fmD_P`N!iyOhJvupqSPuS+iGE&{B)W8S*Edm34dUmLu#57v zbG^Cu(U3jUuF&C)c%)Ni_zPyU2Vq~nCV#a2TAxiN^MwBF=Q)opY<@wqA>9q?a&nIy({7i&2vfa< z^=+MCA$_dEn2%4mgRN)ZgNu?|{ipZ6Y+^kkDNC|%tS!cH^p?&|`OqkM?>h_m>oKBt0Unu5IHj*QoDyN+1SeH#r84zEf0 zutVVNoOa(Ghhy)>&L*U1@wTPNU$&T5+~r2$LyVeeo_+Dupjk}a=mujQL!xV`V_wDQ zoula1a#_>LbQPFVN&wC4F~4+n{Qmf-isngEQ#!v+6!-2Sl$5pLF}L`Y-u*2qa``=C zI~W=wJ8y82eoW$4yE)$S)-?A}-1Y|kJbj7U&t8#%k@k^CE2@12v(L#pWoM7(i03^V zdJ=R-=1ZM^f8zZ)EK(qaxW4DoPmRcn6h>L}-GdRE-X@CEJH%)2(u zUqzx*)ML)3>a=a9WjeM=N5M<%^syDo{dGq&IC;q_2xgy@OIl1Y{t95)Y&niW6+9?#2WEh z@^U1!j5_3N#s3(aKxKJ0R?l?TpyK;LQ@n?IcH|v9Z{5mCUStWFH}N>k zNL*N`=_EO|1Qo7KB^N#O4kFp0g zF1SscNAzn@EqBH67N!?>sO>e5dvx3tpS|Gyw)$-`Rcb{5kx%1cCB`rMH9F50pYPF6 zZP)B{apC*cqN!n)L!U={Vk<54Qr}Rjs>0O{bmz+{TGS-sC?0zIs75tc8t;*82>hRLZE7Z+$~E&bRarCw|C*O8q;pUE6QjLpM7+ zQbrvYEkX3^@;ftvme2Ann%Znxug7cBR)(uDJ&TPLsWl#9U;Kq(J!B3A{4ER*3#?uTZ@2*g+i1|^LRWs6PozN2e z98GKaQR&32Uw}>h)>ML$%zEvIe#}kVB<#P1GoCa_&|34*?>m&{A7Iq*J6Y9A%>DbNus1s z(kNNfNt8TF5v7Czw*#e$QbQTwEE62#3S|ry$||)I3>DzafUN>%iseQ_1+~#eadNc< zJH-X%igH7pL%IKKui$*KjrIz%;s0!}pm_w)8|;-dO#%&7*SzAMLARi*l5bLO^tL_n z(N_zSSVR7yl+kPa{&(2{=+;RJH5iVgt(T6kKCP&aTG&xVMj#b@$jy{Yz zoXm9Ce%dzUO>OVM!2Z71?XkC`!f!~Cm6yp|`R9=HMH(MW?>p!tT8uK(QE;%SZv1-g zLD-x{i!Pf?hi=ra)8RD5)?FF*2?-5%O>WvHe}&>LMSx$MByZ-UGHH$7Q14}R=@d;^h~{t=*zC=$e$ko3Et)=d*Wz_6QGNSo1c{ebx~?3F-1?sDJnsY%{Z9Le ztxPxf9U^bJcSLFD{=Ib%eRv%^?5+u`9oE|^?7elRjwko37v#bb|b`ld_qTS|9)NPQ>anqAMw>rK00 zohm4Gw0=nLxU}UocXDw(p|k3yXtezC=r*Ok@XOkYN58(>MtHGpB>VJxr@2DQLK)R^ zdu~PfL$4_-<;tIO@1brH46IY2zj!%Xor#?z#i>RtQ^n}fyM`jw`}*7Hp2_XOi}!bE01;c>}(#FV@BU%vTNNH-o!4W_de`7z;(1~BnZ#p zNoHGW({P%*puWoo34tL>{(zT$)m67|KgjT$o805|O~s2y**&0?1bati?C@(<<5!R0 zJH8Iv{%$2SNro`wDGJ-z=8)INvch!sOLWaWf8je+zB;jGuTRU->$?o^FgZ|7m9pZo zNhVn(NAz^{o&yaFO{02SgkDt=WGj5zX4z&#81-(ZOSIiX2p{aJ99k4bpEm2Z6aP_zqH&>Y6fZ9$_AwxemfuQjZS9OJ*_!3 zwoT}%h}%Jo-1f;?1H9yW_lp{vJlXO__xIaetr0GH9pg3svLo)i$ZS9*n``w4!P}|| zX_~nwb?|z>#oqB=p3nFk+(3Y05UtyyFj(*2{VG$-T2`NAqIm8b&9^5im&MZ4noWgv zCN_y&x=J3Mf9=N3y`j5#?vmb(p`@X!o6ij;7QR|Zvw1e8-s^4V3F=#{!Sz$U5oJ)pY%DH>$dbAT$Q#r?xaLvbjk?oz_ z@A&i*ig!GWQy#mK7cOZ3GHE}z-|>=E{fM{zt$F8n$jCmRXH$4yY8hYs?CY`7&Mh&C z+{w@CRIcdFh8(O9JX3k7Ny@T--_q5RZTF>;Gv;rd0_1(};R&QTsmC;R)Lq2daL^SEv!bUt^8 zEVOd(H*9(TTlt;IIeDZ0epeYqs7HqlnGHkfg#~iMA7S=d>obkYC1|sJ7~*~Jk*{&E zUTl|Q_r>glZ9b|AyS#%xmHEnTS)Awh7_sgrHD%@*f7R|hPB-$6Vffzd`m^{1_jWw< zRJ@nnhQ4@rPdw3>UD0)NEY(>#d&{{c- zh?U#&UG&EjTGa`5_LCl;wttA zT0Wye;h|G~oeOpEsHI|0$b6{9IJN&p zoNNAg=vL|OU8&Yia19DW{*@?-20Ij98Af|Z<* zj)LvIg|=6DW<(-hPq?tfVYo+3c0J;5*XJVYwa!jsg0yJ-0f&wORsISmd&=aIvqnh+*=cW@y~vE39yt?ptCeXV zV*PS7sn65vtM`jZ^dzxE6wL#ohZkuuT`!ePe4;cM=II9VyJWlHG`N{;R=jiM(=8I^ zL)>!0^8MLoQVv{rNh+qGU?BIp>rx&{sJ`fOW2n!Ekgb=#2|6)gj4Q@J4mvye1$e#` zdslbCOX@~?MsZ1|`TdmvPH;{V6m zI|g^Q?Q7fVPRF)wb!^+VZFTIVJGO1xwr$(C%{Qyp-fORO_BqeHpQ`8EoFhqPR*ipB zHSgbbUnAun@8CMOJm)PXyxkpe4%Pt% z$vg+9{I!7!dtq$YsQzPqB@V+gyjkLp7L75MLk zY*#-Nk)5?hKvpE>zd_cYSZ`{j7V#H4r*i;Y6q-f%fB;$aK zfy?OU$+7^Pdxlcs$q++IWjFzBlb{ig<&vA68uv&{sS@PFW|HR+tjvi@eMZ7ctjr7S5d!H(3b*FzL1%fjG*if~!bIJ0y zA1S^^F$P6ISPri6a@b>5E+*{-w_qkxhTUF1GAkDR0~6SoS4$iI{wkS>r^dGCm#IYml6OSZ1ts zzGOj8?kkwAUEoV{!DrT_I?&gTRS`3zIMxVo+kt5tlnC~+Kd7Jv$B0#Es1*iZ8M1$$ zvAbzVlm;zCFgoncmnE`A*)>e)ZRLo31$NEF^1EBtP(-sXsHPfXVv(441*w>85JgCv z-AGvqi{f!Q&Zwj}dcTxRL*^G8iCGjcX*~xoh@x{zo`N**F(IwRnZ+PaDM^9J=y=Tl z^}~>pqoe1;^h}W6eW5XZ_9&#Lp;8G|DZ?2{O%GUM8m(hmf>d&6!NbAZzIzP+w!RsNV!CIxmyw+RR}J6^fQ3jbAO)v5WEj5bpMLaGUL|#{LS1C zJ&7hd{!|tsD^SCZ>FxC{zrs?fOptK8s29DMkdB@ca8N?h!!E6AUPTzgd~|KoPo7M( zg`7Xg)*Ix75gynZCQS7nIJUQL78P@ir#Vf=R6fNJtq5JDKp(Fk6(U!|R}fB^V!7Xj z-*3F^#>|2Z)*HR{`t;RMP1MNIVw=eZJ`zIt9ry~^Y)bzE@1FZJLlNOjhI9TPCE&Q) z!@TVzvA(NkoW9r4u0|-;sYFe~o3}Bj#!EBWB&UywbXJB~_NE0`J8uEuMBtw&ow)TOQO~X|CLhGX~ zgWjofR0Z+V1C^K|a$$Q$#3_|SM);_3ajS-Ce0E^Gfk^ePOEv>-yRWF3g_wb!rTd04 z)gc@L;~Rw{O~eUxEf~b3-xBNGb@j1-aeoyYI7t-|6lJX&>=~8;%-YosP5$)Jj~sn` z1Z^)Z?LZ6UKB+8voaiB<5^Sw{*Sjui^U*sY z5+LBVFEa~dJx>}Ku5)P;(Mnk}I*JO(bI2v@o0YOs%9=GjYxQq@rZ|y{&x?mz3}v!Y zO&v+&V1Z!}7{Q}xj&YwJ)M?1H-ItEHx3CHH`HH0q`NA8rv>)9tJ!_4szgBc#l$~7- zL9n`B8i7NwBXV|O2BxqTX-y3AwPYQY_O)<7){<&F>WYfui&s5WRPRFcZXPx}9d$a8 z?ZY<-_SnQ&YYu#pW&);&Zi(Z$}$2Yn-N>RyxZugLfz1nv$t>QK!wKe&SW=%=sQiagbsrou#eV7A-nfJgEJh;ppq0+ zArg3*LTz>TD{&^trcL0ixKETsQz7B>Eszv4o6& zfmEq0Ub;Ax{>+7W7pUV8Voxyjnm$i3>5lLy*b1q@86FNSn5uqfTv{99ZGLltc(pQ- zf~=&M0QNmox+maGq`^!Ty*V}Z=Fmw|r*2(Ikoe_EO5A|%F&&5FtHKksv3-I-b=&$= z#N=ByM;Y|gZcbcigT1}oy`WO?5bxqOYl#8kn6>~~T7(Ai@CHbRjZ&`|x&(EO4p>Vx zX=MK%Y}+Bf(wV~~ty^vf{S)7=ht-^Pm)-6ojE{I@CRL16;Nx%0EBVbb0P4<}0Chrv z1;9X#?{&hq%gr8Cic-T1T8_vyM{Wioj!0z#nA_&&#pb0@uJo4o-q@=&jpd#(ZTX`o zWiYpCT(fSNZkdYN3w>k?WVkp%%I*Hc_s!e$iC9%OU`4a@C_vt^@V55S{)VQ+jwy*w zi~KHK4~=^$QfL@=xl?%+piPoS$-s1n_9FCpJKdlZ(Tfg_&C=!+y-hOtiY9v_iJPVN z{_Ms>__$71=5LF}R!lF49p4VZzVkb083xMh$`JOM<3>sSbk^UVID5y&O2?B9aF4uB zBwJYU^3T_|N&eM87XZ4mzY(9DXS`Nml`3d{HMJ3zzC~W`0EA0Oght_5>eH}Ba>F+HqT$llY>`eTg?0ua>Zqx|UP)(}-o$ifwCYp^F>JIJ2bYC@jB=--PxyhC6^> zM8qqTkju;1^_7B02#l@e^jXcAdCf1q>JbwwF&~d?RPM40(SHr!3hmMj(xycvBkhUg zirxWr;0D_5tFoq1{fv|UIAS!O1`?B^gD+0hBc&TEg~4zcW|GW zrks6o|50YmsN!i^!GM{OnXAw%>rxUvHjJ&k;TdM`JG&FG>Xi<9sSRtWj{TZpp}Qu1ODOnAFAX;pKQ_O~SnE34s;cpYG1=^z;|?EGb9N zFfY)$Stg~!;)6)SBllC$&S`4b!8-a~Gg~T1c3HWlLq-oi0i_g`fws2b)9@|Vt`YUM z%!)E|>Jg&HKVP@MH8;4P#(g7C{t!^m!;JKESJp1OsVs|gbaWYCQX76g*5>q%n}FHt zmXT0rqnV%1$~fhZ_|>&%$>He?0HI5LO1?)?T}#Ii)8bW~bIKDDvEK7CB>Ca0)!v@x zI?-I%=0;EUl$WMR3kyAET2%2GfLz>Q>>pHt_kQw$`SSo~hAoT%JKA}qWxm6&KS%Ts z?)HaCTuiK5WV)ECe@`Q;>AF+%83;ODK>fUTm;Bn|)cW$f-AS^n!hv?Ze|+pAtpEKm zF+*Pfw!2Rla{CzP`<8mzFR|Lk{ec4j8&L+Exgo{T*EosMem-%FiMj6#d2MozJh=)* zv5Pc!YQy+UK|B&hXDK(;DrQ!VkI=z9x@p3X6o~=Y+Fab;!CM1+{bw2t8r9G_^s}r9 zT|Wb`)%o|jh$&H_{NAIRw|Thw@sk%r((TrPW0R5lNvswDmLg3M5~D4H?ja*}=4Ouv zt0bz|LX^D5_z+-I!m>G6r?rLKYDsuQFMt?}Xvs_C4!_%zB(LI^ic1fQ4vAGnxt5Hi z5#OAhB~QIr8ZefyJ(96M-c4G4zn7R10j(9^6O$|oML&OEQ42-83%nY{WD1$m#|g7Nh0VOzfO0llSmwf|ya6$Ahcqc&j8rMQ248P(qkhq|6;(_Kb7d6MoN$Ug_+|6@q~$*NQH zI{tGy{>k@JOX@oRV^;qA?!QdW|5*783E`#Y`$vK;^qFCce5Tl9)Z)LBY^mQ_w(MVN zwi2~6wFzf9QU?M}9xU z@2fwb;2+KC9~KUFe_`r>X7PrWpPrRJ9?s6t@e?bsGj;xpA+R^GH8iCDGo^R1GWh&G z`qs9F{|fA>T@7um|7&Xho1p%CYX3K?@joYPm}wYU|CZW^eWvz^$_wcZx{jwn!n|Xl zRmAlwdSSHp-w<=Wb^3zsBMpyQZtL9=s&A_+#Vhdp%TtF?G*M(*xXR*3iByj+%{lbj&txF@M&au!P;W8X zkcT7QQm0zTa?>6g%X6ExItJ1h(h$P<9{G?~iPYNO#T)Xz;OB8^tyfQ3Q@YvRhJMP5 z!?oZy$?lfg=zrASNF_BGcS@n5Jw`Z!EuZa>g`_gM26cQK-sO|<2~|8mUd8&moYPjc zQIhIt7mmuaEwh?L6fi_)lP1iG;{!Tb+iRgC)f&$v8@_OGYqUF^ffp?_$KkD?Y$QB2 zy2Boy9HZ_xbdjxk6|58o{?t6DH*UMSPpKgpOX6@EZY|Q^m&Rz>EVH?g&}Px^ZV47t zueVykmXwt*qMbE5<~L(y%t#gr%d3|$FG8CAdQ4@8Sr@J*Dp}Ake<4p_2o?)*_k}Sg zS)@rWe3tSU$_#K%piQz(v`Mz4aA}rsI89A*EQ?qkgUr~Bj4>gZ&oX;nW~9(17K<_V zSh7k1#|(8Y0bS}Y=d|cO7Lf5LygWhSuUII?Xmo)kxtzkTS@T&~F+Q7EkUn{cBBvt3 zSv@m~J+W@Se9KHoe3Yp=tsJ+xKyKKK2A4IXh%u~{zIqVT@bNsaPeww4wk@em!p*vX z3*lMgoW0@V&U57XZI-+6g9LCL^M~DL|1T7fF^pLD!>&y~A8JT6dcxlFhBfk*&y#DQ zIeW?tywLW!AYnGxU$yT?PBG53S$xAILkBUh_6Cm#-h@2ahaG40Wnr`tIvii?xEn<^ z*tt`rH?2cGJ#J?f3fkANpF0LdaS%B2O-GIOnZfq}eQgb35rN?XLnAE^d&IT~SA+1S24fhc6@wde6yEzrR~Pf0E{g}Ju~1l)41lX8Tr2gMMj0e>+3ylO8L zxnnvUn6@}|4;QUl3_;8*mV&*QsyA1W1v=r9avMXNaR3xU zXcslzP856*W~3Y&w-EZ_ab9dmBpU??5}jgH-n55oR2Tchg_VaR=IIT6)A(8sl23{5 zpgch%dccau7YN@h3j*@>F{-?ryk2`o^6iKniWMq?L_w4&C?=612#Wxu+O;cVC+Kum zWyD*&fKMQV?O-l(U$QQpq`+&%*?tQIn+pyu-ysI-(vR1E1r+a0PnSAyahWF;6RQGJ zdOKPlzy3S#XsRKzCyOEkJZjMgDAA?a1)U&~9{JsJ^NM~Hh}J6}HY3Etiwy_l7tarB zwRR8;5Fi*@Odo31N}wc5R!xmHzwj!f4W&$QPuBEGP~yd7avA=%S$B%W)na1L(#$Lz z=ssu_a}2Yq^9&<;Jdu8G;0EoglrqZOJ@tGfgW9D${V*A8*fkTMVkTNlB#R}L3g6CM z9wEVjj8q^XF-iA4L^9YNJx>Bovt4#X_>Ri&AuywG(EOgQu%+?4)-C>;^!m02e(9>B z$-UmWUljs_ZEb_;7&g4~H!*Y0LG!hrD*2`hFP5_)+92}C;l0srF#ORvduVn+2nNH{ zMOJ~FQw-oC^E;@V?$`DXSb}hbd;D?l)t;(q4#Dl*#sDezf1sApxD*BdtjXu+UE$m? z_5(+Ps!v$CKx=TX&J1f2&&lIj`A3TCHaE1qLX53z1g*RUO+Yp;rez<54m+I#gU@9?fx(X zli_ZAGtXFXG?R)#y~Qrsh`vb=xQOnLN#pJRC|T!UkuO6`4X>^{TV-F8Q< zB!t2kuNL&W-&_>(HvaUy+nlv{cVLsHFA0c-TI)ha)vC*aS@F=+8Bn{ruOv4*-F$LE zPZYf5Fg-85mKXKcp6eDe#tPxYVnE^pReUiUqTI+KH3b4+WU~JpmZ{%5QL)*sjCQ0= zBnpFKbUIpvdUakgfrz0R%{cBZsz5;K<&t3)EZ(ZVxQrr?ftb4-c!7lAFlv$Y8Pl3j zcLXKaH0Y_X@|P#5o}W+UZ!h_ zkEZSdY4Q3HSt%Ji)$_n^n;}LaziwY!f_tY(kcdm~VmxIBj7%B1a$VOAn;; z!b}0#19`-IWnaqicLCa?Fp?m)AX^Yol<|(6xUBlKBy3hD1s-+v020Ka_ay-7v^c7c zCODDu9i_vaX6rr@phDGboh{LTv0ti8+e9NFa*KD?htUxExK$9eAU@=>KoSRPS-L;V zK%&cS>ikq3LjMun{yKR(_=bV*FNELvZ%;Kxyhr4}V z%1U@#44Cg&KR;Au8-hSj*g%*%Sme8>nNFDnsCz^5p>AfJ3Q5(;PZ`wjOMclY4>{L# z=b{T|hnkq!&?~%0LJu-4mZBsc_P6z}(#yrTJqiS+?kub4EF!v4FFSb|S=zf{JMuX6dUyd>FX*zeFhhl8NU*d?D2zngN|%tL-j(ogB93f z!|7&1=x$ICLn^8fP;fYvl2;ZBcS^);r!0GGeW;S#Jg&ln(l|O#J`B^?FLctW=CkP} zAAdF4a#hjTddY27O;7Kyz9ioq%G-NC8S5c2;X7~@1hF#Hax#)I;l#lPql2HQaJvG7 zSA=nA`~ddwAJ1XB6zzq>eH)TN^A@b`t`v0$^MR0yBjTv0Vuu!)S=fskwz5 zy2c+85L(aRKF)(tY(&pQ5l89zU z)p9imtjTrOxu(g_!C^@)0RAp9AEPpCm}hANmpHBr|M9_!_AAl%WAPBeguHO zd6~%A2`z2U)xZJMl_&PLsa`yb`ru4m)msJ9r_3^X6T(xGd-EuK&r0^27(owtEB z!UQO*EHKLvxd~A#t7$Kv-*PrX&gJxHUeh23JK~cd%Ip_F6^5-xB$mW2z%WG*BUAH# zA?K29VkQSoV{t;-BUJcN%R9N{*mY?wHGeI%Q_cwDaXbpvg*GL{90^+29Vu?YjpyNVRvAQ;a<^C(1!fr&R}8`-@d-MKx);C=^IBz86lkWS7l$g(xicY71|D}cJCK; z-IrLuq5et74luEl<;m;J%*n~j%kA!mx&%DN%#fSd-j z2P|_GV9W8+rLnV8QO;~~MN`E*PtC%<`?N}`1w_Vu+kmf-QwyLLN$L^H6)spoRJ%@C z%L#8*Wcm*)-qUG7>0^hvJxTNO%vsV`3SLkNaLE~^C-?PjtPXP7U*VfH$1uP-0vkS0 z_ZolN^xav&bI(66DkU9L3km^6Z4*t!0)s4jVJ{I;)`dBR!lvGM^TMNpY_&;@D|S2j zzENLli-620bk{nc6^j>NMo{QYkn-?79-xjCGdZt>~^XGJzt)0 zf5yyA2L|($+sxs2-Iehtm+?fH$r*W$Rz4H#{lJs^qJt}9ky56mpFFn(7Iv^nR)4vA zib^s9QR_&`q|Q53Ja5r1?d1?Kd(bc{jF*OYs!w~dF$W7f=ePiBLo7$|UVPDyqMA_` z&G#tmTAS0-k}|X8WpkU6)?ID%2oTv~vR}-2(TI}v zM!mexXAQ_Hvk8$Y+ScUYd zpMAS`xMYTq@0_c*i}UcEHA+fnGzU8M8?neL)sR~)LnTgzN*QNoW6w^XqHi{qB4wGB z&SVblN2}*7AaELc05iNA9#se|~KpF_GbPJ3gGUz=eOB)}W+2IdFA>WYl z;2QHam&Dt9f{&@?9Z9AJq7N2`Ljhdaq`G0;VH5>DyuhC{9V@yJW#p7?SY8Q@#6y}$ z0y>HAmJ}9Brtstjq`wSYS%OKD+L5d!ZHSY?s}&4I57zvq=8fwh#ht{K2ZyECcj%9%n)<`1EYS zFK<Q#FTbE%9buhOulPkh9f`?}Y~}2`emR5G4>UDi1fh+kG}?(@ zG%Mievxz6n5V4c_Or|Wh%n);dnp*Hd%4PrPXJ#(?-UZGyMsQzqMWv=4K8uG{Ys@B^t-IEhr@FAHO^%rf@Eo)k<$lj=?w$9lc z++-AC0WK;Ep~f-Ly4zZ#J5e)xS3zVVScv zvsA8|xJ{SK0MGMB?_okG%(RPwd2)P@5x`f~H#Jhyf>xe!ZoI|UJ5A?iX`ekx+rt@$ zQj4?03v}itNpbFwQi3Oj5m}_aNI}v8^znMb?(Lv@_G92QIJ>y(2CYVTGOVhU$XxV3 z?Y2Y!^EzoY*X{Vnu9}RetO2=@a3t~cclp^Dhbvg661s3qK&!^eBJFP#1=58 ztz%*$BS!OM&&}@S$AoOogH&S8<_Y+=yE5yWYkXkZIy{!O@QWjk{9t@;L$qJL|2G@H>UytGG~bnjIz#leibq6!iuVccyXOj@J3PYzqeq-%fxkNo@h+YUXSq z!!F5;R$9rhl9_CMPuxfWcZb)x4^a))0yVwMemnMh+n10)yKd`9KFB!A&@6~#S-TqM z;JqtURB@C{BWvqjtdXrM=TO4<*Q2#iaA#DXf$6HjmL!Sqhme(8CbWU!XxzlO7t)}h z)LkVWmt4MXwBWldrE~iWHmZ|f<#mg;qRSaLv5;uwVT>zn56Y&himptf$i7`&Z+-Y8kDXch_U1nZYk8$SHjKl z?tGUV7ykW5VhAjbS-`T}zKSN}ae8|$3A|`N!vG;)A)Ace2^{bz`MZai9Dk^^c z*B!cgl2ugz z<6AaKr(YYSFF0D498XNjC|i9i?x_|7qod^V1jtB<=+TL2$}#3APEHjhrk25d`hHx1 zufWTk9gy8UY^dX`I#(8FW!ZUS_pkm0W7Y|knx(WrhG^6I{>chCgxixzRB{?NZHl7& zA}k>yln%#yl{L#GR|bwjD3095;>P z*Oz*))@?Ryq3Wv$DTp1DoAS=7YWlAI4E3G_3$3~}muD2Zw8Lx~K}zRV)IptuwwRsl;P8H#waLeqZ68RprV9|{u-_I#c%38%x5L#4%k-d zKiTeGM`dAZ;Vf?#o5{mf0jDVA#W@&ShWCsal3Z8|y^Elx{7IbitWun8;Am`CwPvz- z_&JNox1hyzc$ShbCZT50Zz-^~dlq%U??sa3q$$Lh;E%%vX(3G|%x~j>sI(i`yFIQO zbgIfxpSM~fdO;Ssa(Ca7+Wtrkls?AU*fXUZ2qYYypCvc7D**46j;hb?WQ z;YmwK$rENBj@y6#c;Z;pfHAqf1&6){n|5uuPxT9w!q_6{ruvnC0XH8Su+@lCpS1WC zHRb%beenR zGU=&^T$-EOd{=-`jbP`{87((ze|e;+B#OJ%1CO*eG^Z$2byzoDoO)Q%K5HuXOnls9 zYT`#R`+Bsy&j3dRu~%!}mNfPDI+Vl~2S%D$*M_-V>{d@qU|Vr4cE$-{u8Ei(-8D~0 zF#-`7R?@NfNv~nUA%xxIPauE+JsYhBwUPr@_=}dlmL6mBp7tFdU%wsU5PlPKwY1&p zu7XOz(%e@kq}Ygw%Y<4w*^kTS2^Icq$H_kdkxV#Fr@n-NFbjYHDOYVmPAqy8M^Ctk z_VB4`^=U=NNaoXBV@m6Ws10IiBS^nX4m?M*QwhMO$aMk~NM@WfMFmEx*{`-)iQgSd zSoaFRU14g(i@AbG1+_*}`xuK)p6hkw(4lbeDa8(N#=#>7wq80D#bBmm^5y2=Z%H@5 z^tGz_Nad*QyMeL&42FrtB<0E@{wkg`qc9&(xbp_;M9cZgRXO9##Nm~8Z$tkIv7{P z`x z{zD7E!0;(%V)!4l0H2G0FE;(Y{b#Z1e`_@{G5z;a(|@T{|0&1*uhYxlN|nD)FaM9C zkpImKK+8=3x8dbKy#TwAju6+343!K(HoKo{fVW89&(n>!9ta}qQUaP%0t}a(D6(L@ zt)H~PXlQ8Zf{WM=4v=HxbCJm&_X~27_sG8O9T4wlfzi>>&^Xf2#QwCeTzNIVJ=foS znRt|q*%DfU3AzT_cWDC3ecRu_CFjU^QZp%KiSuRlZgLgQ>kb_twMC4!miIFXaBvh z_PO}?ef@p=&wc&lC;t}~fS&H(w)XQ||C;yz*+%z#eVY;)j*#fS4M!H3pWf5ARvH~lZENO|L6Fv?fp+aVgFs&{?8BCAC*YfPc!rX z(?;ayVMzbI5&3t?$lr;QKX{TqT9NmQz`!7K>jq2oBlzA zSo{+R`5OrGPw~TV0^~o(KK=whev={p@|gbv0{K6oAAc1z|DE^vl;sZq{qmwlA=^+g2Dm&C<*h6IwdVQJ;Dy%;Yz%tRE^5 zO_ju7UrU+5Dfr5mngf~x1R5{kq_mJf&$7eb$JVR+{v*Oo1VB)B{ILu! z{e9>eJgKS{VEI`EGt4~^4-u+@d|7K*_QJbaa5Ij&U!Pn@CX-xAVbZLC8G@m(s(eb( z+${SnvKiFfcg7^!Oe1-wS*79hWPZz>d0FwIhr+X2kXbsjZ+$Wq@)fd_hJ0sS8_h&QLw@$Is+3jkEC?Xfd8^y;^rchOcqBEJD z6++}}puVjin(KcZIP9MdcX>2gqsC{(Fgv6cYC;ExeBFS=XV{8L`~cdk@`PVfce|o# zMNTw@Cowe2iLJ;@!Tq3J(1~QBi0_uF1SA@rqT|}Tg_86RsBK8Rmm#Ly?)G>jh|cN= z6xJqj%eDmebSVndp41;0zCl!_g@p<>aKVH=Ycq~QMXWN%rs1;pxhF*A2b}Ga1=7#d zobAe!fk?`n+H=IUgHRx1^&vSjhy)fB|0shUe42EsLuY|99;}WSj7D9?hOaSzg0$MQ zQ)PhMVCv@yrAfYm^K&|Snt;r%cGG+3za>(4sApZtBrb3!i`^8fxBm%X3)ZZZgae@) zSu7ScQd+tCmA()+4}c-kN>#Pu`vGKajUI|G|F=^BZQU-gL1pBo9Mwl-h=Zzk3MBvp z_!Nj~2}wcdS-R&y@5{kTXYK?7>;i22_t>;?ICHK_1RbWCkV*4}s1FBP9G~$@FGp@h ztLU3*8MK0DC2tZ!)R)PG`#csg8@w}0pSs<0;o348egM;71YbGK4JSWeCyx#qBGTEF zD@W3Mro0&J4ym&-?239_?KgEr+X|1qT)R^4gIwt^b>`O6MAGsSMLi!^Z#UnR9OvsD zDNy$NTm|BgWNn#PAkYnsg@FhLYs3|9%He-SQ3I^8QX)zA?bl{^U_2odV2*n0Ta(tF z8px00b`cJxb0e-A$|JYLrE$)ZZpzKT9kQo6O%xfmm~rG`M8ldSPGp5+E6Hn3S1O4r zM=|a#AldaX#6GljXfn}`SmZ0CJLmie)`(W`y*U`1?4+t@N!7|7HI2XSv#%jO09Ll@ zyb$;1DG~|lcXQ*e!p-#JmfPH7V zSSd@qgm)@DKx-=u$D!EY*eY8br3?eUr}d)?+`C+WN7K^LpdNaxY6XM(3M@+aC{iIS z7A*%R8c)kA)0>4u)MpY>l|cwcFDvDY+GSVSc>)&_B>YrmZ~#(x_A5~t*BUt~LKv~W z6M2W$Z>;J`I%eu5(Bld*$xg+exkkOSj;)n!w{n{l(+BX<<}K!D-3S1k*!|AGkt}MWEo0itd}?Ag zb4q)VB;&>`pLZs~(y|=X{d&A?^6?=#=YeGxBHWE~8jZ~--0NYhcjOg{9|^5i;3s@a zBHE$i7s04|YlfVRYXK&NzMJ6D@x_~%Fd6g_lkNtQo6@EGkHv=p89}c*f1S&*HF&sU zj)2n-Kv5Q-8#<14*9pe05m@%pKh@!}K6#?O!zXMHKgJ1^#Y-Q%4_M=9)?c~W1>P=& z8$2ZYvgp3;k9{IqZUn)qJv5oC&MP47kTHvXefm-S;bh;VKz(k- zT#D))gjlj7v7&-83qb}JANeG&7B6=9uMVNj$zyyfQUsn-DtuY@9A zp}w+JZ!uQF3Gt=m_(_%}3n=Q5^~%O1vwc-QF@zO%-y5{QD1saL1T$~47_B>et8*u> zZTpu53qXZHp*~Jb)~}WhBYL1=V_8$~T5hpODxIhr2ps~8mlGRfs6wj_nTjakw#I?- z3Ih=Rlt977aNnKX_vA3}jLC`Xw~e^@969cx7Mu4N7K~WjqlYCHuw)oR9ONBYi8ew2 zLG*`p9GXg<&X0{4djfJ=gveYqQ63FJJ$TrA-|$Np&g}NN+ z!=q+ktfUp+_Lt^Hm|=Pue3is+?4S&V=S;zyF!hoSTOYSyvrB`sAB7SUu}sUQG(@h_ zv(q{y)S9o~(&n@bqoyw-4YWal8ss{z6U%I@+&Y6)?|X<1evL*=U8xtitGfp`-ra@M zpe2rGESg?gy3~|6XDX;EWKEQP**AA)U**ScO|U>bOo4}z0MQzq&y1?n8Nn|Qov%MD z7zS@S2SqW1li@D|w$I&={eCB)en)BGR`E(P?jg`9Lbo;7o_r`S?e|Jd7VRa;J$9F} zcG1B~w=uNJkn3{9Ee_@iBX$~cDYDJIojWYcS6*KZ&zQzXR?r)GaB!a|-t<*ZpEZx1 zO!NzR_LAI;zTH>bR50<F>jA(N?`(}xcBDEq4~YhQG@Xo_6=mj<5%hZ%Q7#78k{@0M;txm zFPzzcPzf4f`g!?+#mE~Tz+rr;BA2nl zgmP0QTSLRp(Iil!;e+W2Wy;2jW{rw4G7%F42ESG^B2!;tk{Hx&JNZs?_x{|E500F2 zV93`B<$|4FHULZyJ$)lAMzfO7Crj)MXiV;};0(3ua6a6bXrlL2KaBIlK6m_45osbD zb@%ulDU>flX&_9yJp52yr_0ForAxP6s}62X(y(q0v%U)_()L4Ci5zSzTbut85|Iac zNL})4wfVF?NFIma1AF|eMGBkj0?_TPH)`Kit}XH@2lPQ=2##iBM7+W#>p7cLOs3S3 znx-X`wSkOtB6%=neq1*W-0g}f*|NI;R|JjtRk7Oca_qr(fLxou=x#v_uh>S zEKWG0HOR6*d?BxMl2A{iI*16#+5`Q;2dTs-re~w;419tk-CsSu@oy3K7j4*UO`l@vq zq~?Ha;#D!RRN3-QA-PeE&$_ieTZ;Vp4+#^!vSGvb~riux8V}@!>Z}HaB@3UHP=x z^8Cyyx=Ba81G@*i2VV!Pbrwf@1;`9Mz{8ecAjv-p$w%fYl}U8r!c=JepPs1XCt#&boffE%VHX-r+Y|I?2Lt z%!=;2zWW?Bdl8T>np;MU)KDjW=>xN*gYp7Q z{scwAdlv=u3l%4L5iLjYe2Cgb=FbylQQC}<@EYj?%oJLupbN8)>O(URQB%pi_3R&5 z3mOjKB2DaeMiU%GIBmST1uAft;clbAm%2t?IPOnoD_i_~spD;Pr=5jT}fF{SzcLFeJAIk?1~JE08#SSZfv6r(hLq7k-@r6 zA%aqwkAUWnHdwT+_m9h6cwF}&x8b14$LiH|ptd#A!?TUcyAoH|k0-GU=m&9~r(y&wu6H!-=1Ci6`%s0J zc%mOB;KAl8?8D2xh&#&1+K90iK;n3i@owk0_UmXD{3ewxmGfcHoKQT7g&X=0&U34lhb)2TH7e4-u2BCo046Q5Jg!jA@|c z7ypJ&uoDJHF{JzrsVVB50&vaP8f%3HI)(b-$6{;aZEk|Sm!e-5UTHToDUH!XY)3gi zyus65&PBV1hX-HNZG8I){Hl@F1jkGK+$&T)wqn)XUEW^ZSo_nKS^4Mtwk0ji+(OJi z1?Z2kkhtd;KQeBS5ILd}kqOiUK{L?~@}A}D4Cc6C&qL%KH2=ZA!E^Tl`S1TwL4j5fuNb zTfOzfGsga;TW-}5#NO2#k&$lZDv@gFBo?mZDya1z)&) zL3U_YQn!bWaE*7DV^6#F2WswZOc1N53D|k^M=26Gy!@4p;oO)T6mAiYIz_J)axqKQfpIRZ|JE$3-fXD=}>~QPrnN2z9-J4aV=&X!9{qvksky@eUr;a zNXpf>Z^V(6)!!ztFQW!}bEZ`pXFk968%UyYLHQbs63VG!cbrQkVsjW|g2;ppNyR$~ z^OZZyaT%R`7M6z``L=LfhzmR7P&TxvC#!;jFMlecQ>K(CS8RYEuQO%{PF10A8ud)J<%X`To=}yZzEOjPSL|<#XSC`QqtYa)ai#+^S&turJd3(k9?8vJa zXMO4HuZ%#f2{#XWhg>A!8N6E2SBX9F97Ko{-hS~xo3m42ESoe)piJC}=vbHEsvGqJ z5@=uXg0^5FROEE`m%b~Lie!nLL2R{BTjS5nM3Fc?`htLf;%TI3l*~c<{)hmx=~lg+ zqNQyPdGAjzYO;s4qT5(ZO=fbupDx07Sy%j`AuG^){fcc-&uT(up;rk9zd`_qet$ZG zg3_w47t)x>7w39U1}yD03XJGC&xc^Qb)7X~<+)v{=To!u3^4A9l~OJcjU))>CraYJ z#cwqAigjbOl-_dllvF+f#fRFmBx7RPK#IZ`BnzT8;<%H~cuRqBlCe5KyZLrsKoYs!kL4>q7C7>ON_j}s1ehslf5GdJ&}2?)(s zNZO03|BtnIin457(6lpbWFW)Jux;DSux;D6BQk8;wr$(C&5pfKpVL`&s%upLs*;lZw8*vhF!hgCZ_6HhjRM_OOU1Yi0mkJ)L&TZ*tJ*9?rNiP zr8>B*)NY-o)ce5rfbWxt6FquzEmXakwo-}j_lAzh3_bfvGic4JI<&{-i@g%d1;IAt zyYAY!ziwax6?^QLDQR1l^d=Ta=6TarErX^=dkQ5O1?D{Dd+!W?>yxJTxIBx%nqBf@ zpgnHWh$d*>AqiGYx!q5ztbWugw1OwshshESADkn4HN13SseO7-b6&aQ(Pd>z2V*0J z+S7cG-@GPY29C#!BctE`?poXQEv6g!yb~S$aihA_n z=fxn{mj(KD=l{h5rKSI? z0sUv^nV#iOhf3#*7ycKI^KT62KRMxl!8h&yqa*tF?AxD?=pTbb|8oO}_G@nJ56`Gr%$y?1>k?rpUqL8(=kdGg9&2DVf84~7Ogc)0A*2~;XWk`^?>2SxS z(=hVgZ1zX8ccsEp4bZ;Qv8|8oiTM?b#wBF?s>2CoMuf@ij^>GN#jz$OBl(Q6n8k`z zzeMZT!sKjuG&Bik(HlfJ6oxYeLrh0CeGGMKB3$gVXyw`2@@M#c<_9O80)$Bsaz%?pJO{ z6_|@cKwy9O_y3qnVb5cXS9S|hDkDz8halo3%J|HCMaO~3i5^1sa~usow-QZc*}OhKm5DjK6?ta&R7-ECXIE7j-;c)bz+$r`f=e8}QQV)1;> zSsy)B>MDd(b#bGK_F3PRKFT@9aip8y27KLPTH(S5-luIqD;wK;zkt6$F|*9Mh3Ag7 zZbZ=-DDqaG1m{3Z%=FgWer$;O8+}`b+N60$!y$X!@qv@Mk=~_E>*~CDF5HEORp>}R9I7Tjg)~U3*)FoIJfS^MZkrzw!5x#DBYi*H@LWg^)`waH z`qpx$iO|8SqzTB;-rb4r&X*JpdTx5)m6q1@4H|mh)?yk_1-H9Hb(=o52~zQ5w%E9B z?Dj!q)r4E&*s><~8d@@II4!raF>S(dmRPG+F{MgZrBJlnFC-*IAa&CM7q=*%ipz1% zTdS>2Tv__;75d`rXaIV*eT^e#S~?FN^@d2Cx7W1;l*@~a5Wl8Ef-_2TI;;X>zeokkh~sk^W} zUT&oE$@Bs+>U`Q3=YC6~t{rh|Ja(ez?||xb(3|2b?tR$kCc(&@JSiSYBqN)vv#4QH zee>=JwTHWRntCMbGx%Od9t%&1G0vDve;r*ketHZ*J->Ox%!E1)1G|DQAB6%CKnnXR z^tMOeIj+U!=7`HQeAJ+p|ImUSpscD22};vTTXc@8yDH53!3(8UIek7I3!hj#>2r60^nF`+!U1 zk(~{3m!Ns1X9-bjGdBIr(fG%qq>|RlD@SaVCsbX^`h*aeMoV)ZFGO4cBjy7yvyp_9 z)4HdW6QM`o8+qaLuyi=+#FNoz$=HX=zB$QBDn>RC;u(j%OzG^%oS0f@xEuN9WOtM< z)zjpK+KGiJm-ncy9dV&<^|d8}R@AlER_s(LkKrV~h z2A6L92eobqy-b=biz6$KL>bUv>0ZIZq72*7@p+gsLJl?ruG+R~J7=&Tbz6%_;oGd; zRN1s92Hbb_;ys+s`J{s;4EteGW@7=iStsM3+Mw*Ofba!U^DgC#_YNbEhxUgZQMpRd zxB`{)0g4;o+tZeL7Kl4F7jw!h_d&;Xap&E4K|eR_FStLb-=M$={{7MY=epv53o`ll z0q=iBOTI?RX=%T}-Txo5C1301|24>jmig;B{hyxPf2NoI%$EFvR`MsSX&U)rL7XJWo8~*&E#-yD_MHEJoL}Hu(D)Po98G!~Q z%jI#(yfDnr7m^3gMuxBMqn#k?_(Fc8Xd&c^O5{)vpxA|~-`raH5WVcYdcAj=ii$6m zw>)OFPjbDg%S#+eg^T6y7>?Pg&@QMvU&=IBid`&+jJ-A2j%LFFu{~E|P0d;c?1EY^> z*s^+e)a7uiuIuZ5FbV#kL1XvsR*~&l+w+Dp4!c?PlpaiYDFjNfUNdaAyjC>6F{AFa|)p>0T4N#}>^big?fkJbxq_=Bz%)yNQ> zJ{4`0g*GhNDJgpl;XvcS!4S1JF1a^cFOYupi%JP@$htew)?KE3Kua|SY=~4Fn>;zD zy`j$_L0tfaPot5%5ssxdzC@pn3N{dU+-q<2LdS`wW=M}X1WZfC&;va% zzPmwO26s&UpfUd_z+Itb`Kj|x{85Bms?Z9Y?m zdV`(}^QQfb{Sd!Y&z9q>Q1v6NYjMmCch)hA2Kz=~;=rliipB$sP4p&BPC@S!yB>3i zO)7X33yc;XxLA}uC#3p3^I>?^Ui6nw)SWgQdQ?hDHugpk5S!-C-7fB?@dPb;{a{rp zazgcC$nSX)wy`%(240}G05&#rVBwD6K*0K<^~fQ*$1{r@y1_w$T;#hPgBdEy)h=Dir8!Y5?9l)VGKhho3FIPFt(4N^SoyPR7<}iEN(>bTuZqS5T5HD zWZg>4MqtKK|RbvQFjio>j9l}KrmhRJi0bW z=8%u=pH)*g*(aa;pn9c7I;TnZi0V*=U|pQt4LAh6fglvTxhMJjyW#VoW{*v-o@79Z z>Fue5wtyMr^7xvKgK33Q0mnh{<8Ev8_o`~nbsiGh;?%840?N`&mX+}l-SpUll*696 z7-mk{tELJe_#p;G2>ipmorB@_NxL;`6@RXqcmEttxS4~M-sb7qmSK+wpT8jo{IQLB zA$y%S|7-0qV(KRb{+C?P?b0;t#eP9gr)i!#FQu$_Tic_8^JDX6=b{&9Knt%@-)!*r zD4nUgYfQJU@Lo3Wg}Lnf5S6J*F^9m=2xBsCD)lPtv~Frj z1U`Kk0n@Hc{XXrLR!v?(glISzCjpzl9)AeQqjs20L_ApPQJn)V;MVK!P_rH!L_mgS1Ps`7*_@DHIilMd=h_x*?2Tcsh}gCke!@BTu{HM>2ke zmz+6kp-Hh;Gl!m@)(*p!1D*Gh7dvE-21`q6jcRLXZ!?;rJ{8yZ;N-A~2Ti`&q@{0; zt*%H?=M{^JSh2Px+t3WaabP!0oh#gkaldU(L>V(ov8ekF(ZXZyvX4IDyu?^p^UrV7 zSaP%BF&}sw0~9;Dd7G!37TZS6ecQW~#L6lyzdw1SP=HyHNyn?xBB6!eE3oAP{CsNI z4waCkrMr%OE6r;O&o$5pYhkQ)D3bwPo(^$+k0iKWe>}i)D|BWuXbuS{>J34;=6eYt zQukI|!fKwu8c13a2&Of5iss5&btg`OMs%d?+_E9M0Ck7COpR&2+Xln&jCb<|1lg3P zBu2N3lhp!vv&=PVYyd*5k>~;Vq2l1G;dhRxPeMTvP?(s001CRx4NO9d4h4yhF0CI2 z6LR@YC-?ex-(U8e<^qmy#BDOhD9OqqDkrY3nAgKE8}GElsw90Q7r*^GAAnn zgE{Grz{3;MXZO0kfLO3!HX0#UdO4*m!d?rBCMXhBn@h5Who0T$7#DBi+2>dhXr+|r`U3S>w#i!GM72}Dn(5ATSu z!GQ?H|FO%U^05$unn=Ts-Fo?Lf4h@Wvq{bcma12n7v>T>EtLtx(9i6|OtW^OsY!?e z#GoTu*y~5VXAKst!tRt}#FT7}p>-32unZ5gE)ALwph~`l-L}U#s&ra&Z<00349Y?;Tl!5Rn)_3D-G9^rgY;4 zL3Nf)-TW*|6@~Vmp;lo$FWOKK1~$MF>9mLi(J_#Op9YFVCBJD7^@BiAr769&T0w$w zb*IeqvHP8n7Sav9hOW~p;;RE6BQ|) zG#Y0p)#n&;k%c#0E1>0mbi!+uI)2}IYDt3}=VjALh!58Rhs8fIeXe)>hnQs{@D+LRj&1{h=3nhtC2{=}pE`# z9%;j^|LOA!q2GisAvf3eSASf39#nrwk8MM=B6zb^#CbQr<|0kxhm7`DiB~z3l^BKK zW5G4GZ1L!*tUj=i22q_3@71k4t2<##PG73mYe=^aM3Xz=4rU?@k1PefZ zm(p&jx0IyX$=jo;M+qPu(c$f+#KNqcP<{B;E0Qp`B{=6f+;gmd8VLNrB6h z;~AmmsTY$T!}CHP{dIy2L@A~6dW>gMFg~Wu9rNHBgW9xjCxmi@1}mmj3WpbMn<$Z~ zjeef@TgNU=SI`^&%rVqW#?r!WRCwJ~cwT>sp?*+rx2crf7u|$sx^zQk7fyBy@UrL2 z9)}fHm&lL(5dT;V*q^HvL`TqtSwV{G3LdZehESQ0Ide$lp)a!O=^$EflwG5^PNO>a zHZmm~+bY%&+7a31Q>uE#u&N4{hE(D=8Ke)W_3fFxzUhTNvkSeZ zHVIrR$eY8DsZdkBuw(c$zg<_Teh=(ImpFW_@361)t}ZXHZmtW@%vd#Z*q$dzMf6XV zM6091irigM*b*iUv+9ZIdyBwyd9E4{JE~1vQ+1C!QJI`8JTD5tCOTPO35YC>oZzCM z{CsUqhUY!_b~WoJ@IvFLtkx4B^9J8n5)|s$WsnEVE;b{`X5xh}))Yney`A8a8I8%% z6heD{3-HtC33H4_v7SH2SkM_5h6qQxH=TIe;uP4k3H!;jEYY|P*KQ)w_K@w(X;ZbsfRLa7cm!4 z@owuOxr46255yFv-c>Vnn}av;hnfgcZYJl0r+jp3x(f&<0hKa}SeOjW7;ON#S=qN* zD)JBtg5LA}`N>BBi$UWA84SBFl4J_&Z;=g!6BPY1{>-GTH+sV02Irynta?@}3K@% zED=<6x#8{Nbv9hB{Fu#s>kDAcd#&x&7RQq6{Kc$`{Oi)ja)^_RKK=LFudqHP68GE+ z6^8J02d)-ad!TIcUFG#SOyzElgF7BfzFv&0O|9mwySXqes>{2nepL}i{wh(+Te~l) zf>8Vv=NL&i=&lG=4xXQ2mg|wfl6SrwfAfac5-^w3@>+Pg%stUXcr=_tz4h*tJ!Dj9 z^)Y>wz#5hy;C~74!=A?RAY#NOL(#J?qY1@eC1SGgZ)xcr+A;$f9Mc`7m6B5-7iZmY z6Tpo>+s((wO$14WeY8hQh~VM#G_J3 zt6-#XBa1GdhH)aP+)Qs+(5>ym3%>S#Eh;mYc{x4<+SRUx-+t!D6`1Dmb!9dh`d01( zei4u5UmS>@!{0IrRGCV<+|xW3=noUrLql)s!vtRMw)~Le5Ag-K0cIf4g_El>Vw)K$ zY&v!C)_Y~>1WbKf1#sTqQodyQEHljVUzUB5&=DawK&n_p5sc|sCTd?S{roscb$fZ& z!0+M7Dl1?`JyLm%@ljx{tIpkZIHp-Dotcrz#d}-V`P3OKE)H+CvvqHSzX~f=sTLBf zl5cK)6@LEp-_BWZSNm|ETq!76?IMcywTDHyj;JeQam{lWZGQH55M8rZtA<;4dqj7{ z4Lm?pTNV=>K}A(wQB#%wA_Jj8Jw^K>N)Wf@rGc=Qa9~pz^cq6JIBwml=L7yF3r`twZbk%0m60`bcP!^9ORj(2&UZ zzMEeyR%XwoEb^9%u|O(Z>#MHny6uovR=@COUmZC@N}Cp5VO7|CI~Ml*kan^ev?>WN z_afmH!fP2CJ)6$ASccjpi-4T!yaG%6yK0>7Pw#VSKI&%|lJTEaJ;dbmPwN^_}u0PeT0C{2;Hk3}? zXJ2(FNGK!HthSM#YhV!=on>V+a7VO2oi6#%JM*gAcp!-+S~oTpJd@@&!56K5M)Uf? zMb_#GdU3^EsF`=$M(1*|nlaxEmP&30o2HSHYKnCFfIU$H`eApw7EukV%S@tjTE2)O z2Mq!00eBwAU~xUoDno&7XaYy)9smZ7hE&60k=g3#}oIBH6AR$}QlH^Fpl&s_BL$vR|rbqj}cY z-=2%PI}K^Ko{LD8U_xJl#l{bS$Mu3ZJ&&22V2$}Q?ptQO-h||0zK?8apE_SWL2JT_ z-0+bo6o6!$@C~2+4{QfxXlRyTi(i40f}N zS)+6iKng(38dsbBVYs;`m=uuEOQEy9>*v-XR;>^~E>d2UOu(0%a@9J*cGD2@=xQFt z3S2!=;+&0!h!!6tE-v9j1^Xi&+3Mg4mIA=_Er?CnHINls=mz%)PV-6aOlIjFAxser z)sdumK-=FJzjb^@?E$cVuGqQ#vc0copib)$EFF>XuuO~mQSW@76KpV?L4%wS@2^js z0waWVwTkCin!sQ;#}ap#I#WZ}|AJp=Yg}ssr|G3u`aBO3h;T~Nct@|9(=T5i=IbSt;v+=BvGk7J3HbI7=#M=CR~c9{s3Z2by0cq-GSpF5={LE;k2 zQd=c@$<1n`5|NSiBuD7E+&*}lN(c4co-f3S^UiP}5L!wHCneo@bot~qr?OY9D5c3n z;q$Xe!CLsLj6fqzaztcsXm}*5DBC2ihY$3w#%54BAL%>)H8_~?xG;VG8M(pX3Azi0 zJM@uzy~K0xFp#~Xo@=Stx8I}~67KC<5ru_X-f)zZ1;Ez=7<#buGZnqrz+*&qq+YQS z-&5XBIWp_%Bpn{dG;KYhXqozd7dr|7qrL`R_`Xz9o_K6M;XmKN31M@?VSa~ z@{;vtQ2ubwfiKL&SLg#-(%N>w;lLNL-im$NXn>*R$}ltJWq3+vN<2u0L*k*=!su8W zB&O(ddbk!W8rWcYfEp|4YX(dbMi}bSv5Mgmcspb`(q(i?;}tSB*nMHK!lOF$}s@TP6!a(3T`cty{Yy64|_sw14k zVlb^84D1;uOsWQ67;z}})Bu=szXh9`$ph7%VW0Mc)z<6n`)TzZgsB*X*ziEJF|&vX zrzhvs>n0{S*ML)#2HI97q1S6^X1uViz9HQ_BhV3+G2Uz)=U&ItYPVJCh@38YU(((d zs`B8ge1I~nyaH2(vRm?rHXPkjkp1@{soN%A>`7NoR#bCY(l8b2@j7+Ear+z{QB$(B zENW>c5dENU@yau)caKDA568P+D)1T?FNq$LF{wA-w(%Y-!TJ+N9*^$q`(4|U;1k=@ z6SkV_hI*FnoCXn6BsJ&90y?w=b-RFEByhZX!82z5Tn5MN7}{e@v49*2hv&kWdkjAeS<+&~>nr zw6c_-lru1L_#4>&PeY5Ag$bAOtB}vc#PZKF{#T6TpJ0BbuhKKWj!vi}70|KsY#HICpGRi@N2O>z1511Ae`Dg?nOGW`8~kT1{+~en|2gUtv4 z>AOg1{F7-Za%jxOs_Ah_pmPKSKzP+aB8WtMg$OHnbk%jk2b`NBQu5gDojQP8iF+AWV%y}v*=NRm=c9gwEkC5GMJqyrlY z@_IOwfS|7Z=^f8nRl~w!b7s2Ay({!#!s&Zicic*_dKSGbTB~&iv{2@h#N{zS=U}fM zPDY_lo>^}^{nN!dt<6jLqF}D5Cui?+OUsc2e{MQvgrq!oO{+N0tT+BfM!{dM!@T}d zh#Cj3xjjhQdyOA0KO7=7`t`&YUmov9p#5?km})ebSLZy4W^ZU=H8@;`AbfqBQ&_7PB!ch1o( z6$QxG`8@P`7`Cxh<2x-=7bDLBzVlYcbl09^9eg#uch3XDFi|=i^$+G$KD8lsG;|TF zLzE?(zDM@y>(XzFQxLy_JL!^b^N#&|gOJvx+!kCy1n7g*rK*lp7L~wXKr9V@_GjJ} zGbeBlHUO4{CJg+Z8$#=kOq+(v7mh!Gh#w5$4?`P+DjMxiiHF}4@|=|657N=rZ=RuY z8{Nz=m9m;@MbB+`oe(g+!yJ;C7oR5fLu@m4Bd@I(C#VIE67zty%n`NDzJWnGqE@WR z6!U`PEwX;#rSLldKAG^_D$&$IzsO)rsc^!Q>gtcxjOzCQ&#(;vEwp+A`TZi{+>fBk znuFGFgQqO?N4?!qtaeY|t@J+x6EGmf#P2|CD8vYM?}}RyV2bz8I$iB&CAHpMn*u1L z8PCKd<_CwT)bFb69_fq+yNM>kodP=~plW_oFk<=8OQHnD8sl5VWtHbxkR!O<9T9xb z$v-YYl+vfK``x7;$=fO_(nU1viC`wcrA~9VUCyGmg0>J*0N0XTj35wpA;Pd;?duQP zp)N;eYaJ|FlPqvMrB?^fmEcYm8=XP`8|}fxwV%Vfic#sys@xxuZPiWq#xbx=AhcN| zC=E2c)M14WHJDTZ<^Q~AQ&HsXMJt%eBJWXGq|-yHEy4aKJ0BT~3NMP66`NwtOphhs z4R~V~wXjULvWVf||5Bb;MG1jvHBd}uj$?PVxfEOZY|(~{=uX#l1VqB%`2x-GBjV+l zlck`%Jm&&I&0?V;|UIQ!nac#(#@VKCy71y?7%^xfSMhFHOG!rZ94g@bl80P>agu-ll)HGz=VKj1#bI*>&nc(=%n2Z1NIVWS@%7 z*JJC7Z@FzOUZ&3XlbK=%5<&XvX{>KjB#+GypCwQ@R@wECU2;FEEF`L2al(4yTel;q z>ebvP=~8bYopp#1zw_HkyL=Pvq{)WY?n(8$_+~duRGBbT2>>G8_9k0p$WiD1$XcV) zLc8LT9=-v*PEEhA)hc19zH_F1Id^?i_=?5-_zbPV$^wJ(o31GtK+-Kdgt!NrvY7$P zjd^6^JB)DdXA&SWN08#-X((;sEd4`4VGZ7@hQr3U@7lxVeVZf`Id6llTJ}CvQx|U9 zM2th5TC7i;MjzyZ!7eD0d<7V)U83e;NFDF6bv)tFf~ml!q7}k}S8OaQE6^uS3jvw1 z6{;``vK2Fphb$5}1d#4vc7)iw?x@80cZl%_ouyyp#g>MVUv3YWF&ZL3xEM08&;hTZ zGmwslRjaq_P;uTV^|tBcr}TsJAQ?G@us_MIej5k^p|m`rtqQRU6b0(G%@^=PftU`WNj^$XYtir>{tBcaPP zG+bJ0xxJJmKm43Wx-hk4i_%1Btk;p=i-#xjTL#3NsYZlM1wrKHPe@s6Lmmk6 z%~q(CD8>fa;22lnvioSARf&z5JwX{QMI|k}wmsA>5?4s8O^SSCn4ffhd7Hvg(_^D< zNuCoEk&zQgp66KH_l4>p(vb7_jE}PT99`$enEW`~>&}4?+&`MUV6rgPnJa@yqRJxm zN_R_tt^T4a#1egHiODgGJfjGkj?_BLPom#!?-2c(2N$J1yC{c%%CB40UMESIVazt7 z8rV$wMi`~acB*TJ4_mVe7x?29X^b|{;8cwCWhl}^)BtQC(}Hzl2!zR(}p&F`!1ZE9ySHO2$_$-ZCP4h1eQI$A;~h= zFclyZJ%G~7iaDi0tE*iwc0)ax0QoUlMp^?{#)Tn`e|V6oKN+aGSeSJhuxwh8k8R0g zBH>7A8C;hE*QG>d3v1W@H{UUv|6Q?yBnU?_q5RN2u$ z`t_uPMx-gBqI+L`ZK1^N@-#l*HQ!uQ=I_gkq^Y+9)6nd5afg%$KGuq_epO0a=c~oq z!aoP9tI&p=ktbk7MR+_gZ|3onlh_=b)gvY#(MUwlqb$z;#r(aIZlxSXy}V;>O$+VG z7So6xT+PlJBO|EPEUJA@Ze#q(^7_eWH4m0egTxVFERM-b03xhmcZ6iGBrI}kaV z(0H;H_-2g8|M@M{XOS$r;!1x1pdFobVQks~-FCJhCRc7;GAL?uxDieo}8 zbVs7IixA-P!g6|Klt2K9p=v~UR&4Y6;nsPxKrp@#**M}12RCB_rRYDMn=)E zAM)xtV{N$&@z(GW&@K>Uqi{=ww(?8$dO?2rXIS_^#Ts)IR_;88gyvb@SH?lWMRaHT zeuxDC2`_qVShtl}@|{;(gM?XzL?b(5bQH0M>nS;zry>-NVWc|fpT1^3fmp3p%i_&y zEO{D}XBlte!Xp>1NVKyKr38-DI~O6bA-8wy@2+r}TB57FJjdltQgeF=I>0HFS6H$j ztc)G;El_wYfIL}k9trV2QYUM5sBkRnT<4fjtQ%k6RjDNzyn63QTQ|JfQX!eW!bWZ- zVICi%RMdNZ0<#wNltsL<1#XGt-!#@W@UH5O0d#C z6UAaeG7_Kwlr#;=q@^aeGe!r6+_>)h~NSawla#!c+mHII!Zq&X~MweN8v zBs~31SMy+4Slc)~gwC$h5icy^D7@e{OaJH#?X%D?2m&HJqVKd7{mYu<38Zb~Ar-7{ zifL;Y6+C8hxEl=9zQ^5RYl}C{$?S<7S^{xCmu>CM5&0zS_NM0cad<*LgPaSdXi&>} zGGniKtebjks(IYplvl_RJuCL^C2u{SJ?c`M+Ojq23Jv?5veOOJB0J!=w;0F&#K~Oy z6-je1OIVOpk@XshBT9iP=vbnF){dLT`_w>7G4nNV_v2Yg8+hL>bOvhHj{eqK9}=d2 zpbAJ$sVsQ8CelF#nF|g#ly4Lp&y1z4^p;(uP4&gOK#gZ8M_a}7o86PT&GQG)pmYY8 zGF;JWrW@RFTBT?aH= zPI3js$P1(XgH!RYCb?*>Bn4ieY_Y4o z2;pXMiB+l%ga%qCDQtGA3c1N2P7;|NOD+kM*X519`gdkZ@w)AcPbN|6nw_5Rou!i3 z$)^x#>-*57NfYEBmgMdW?9>|XCadS44i&DbiO8AEh^PGGuQyKMm{{4{JCXW)o6`2$;@ZN?>?Qn>Jmk)X{cD*m z2=(chazQoD79uC zKZg%3&Y7t}s91Uqj(80_5>DWDK}2XnMI4NcCFe*Rf;kj^t;^u3lpitH`er^cBMeue zRSG9BL@g`|W1n*lUq0Ef{8mef52G(5S&k0Z3J)o!yF1q^rIVwdrOg|5-XR|urKE)4 zI@lag?fHPURZ_n9Dqb1BMzO{v#5C{2VgUFU>0%Yf`@(`e%L!z$(y?>oIsODp;lGs< z=~||{+am<3NZc$lDJd&w%m6Uru`tgsF%)kGQx+Xh@Qt^@j#0BGQ!s}I{|en!Fx8M= z5H(Q&n>zv7TYA@Bb)v;FahMqQaUWb!C-pg3+&^A5oq5%k=jWeGbs0D*n%HD(Hk*XW zRquQ37vG|wqo*kA_f8@}c{->O6v+TX`W|9PF;-Wh_R|tJyF7RCAm^jrp`j%wqt#@5 zA97U^azz)xPBfoFfkdXLtn5wgMr1i$amnD_@Ps&4CV&WHS&r67ig=~QbQ7BS<-63e z-CE?;g?^UV4)nuwsbk>M3*Yk%=Hl)t^aJuZtl;etYug%uDy^P`n|L5v9(Eueh~Gv^ zfpQGT>|GXwyAqHaoQ!O!wwGnJR#7o+-rDy`OD?x8@84BCx<6`F|E-9pC@&_YEJ4mM z$)`+9_aC%7IvQGBTAHsu88Z#dKgGMRB>Ddq@4gQI6z~4N{Fiw5b?g5{yrX6Oik|<+ zFgo*>BKRK^I{q(>PUwF_4yFG!mHChG`M<@^|3DZ1W608&+JySQ1{Qv;YFg=2|2;|h zKMIup=dno!#{Vq0{dMsF94BXBrKkBbPOc0lFMrs;wcC}3@B1zgat-}Zp^U)TteH!q zh=7EQH0q6u+a6|*Ix?04aIDZWCo7;`MG%bYrhCR5g6<)-+geTNI?lCsxUu%>P1Lbh zalheu8dQ&Z!0ol{=4F6`rZ*E5Gpt`0v94Q~T${%|7>2LE!|u@+V~eZiIec8h3}VNc zl*-UaZ+@=L!3@3*nsv`3MD=^Q!m;5RE*Sjg<_fwx#h8BB^x*B;uKdSy3z&fWwiy`t;SCDU@ZDmR&=R<+9wrjHJQY`hCzMaK`z z3tms?-Z9m7k{+wpbzLv!)NhYbiD%$9RWJ|g7(4s$EtY~wk1y6Zi5eXhwT6=}kL{#( zhvS)+oUfv8(@l%&Y9URG`maF80KK zak(#LzBJObpk3La53Bgt1{wpKgT-W^G5BH-c6I;on+4m%)Meh=nL_6G2;A5bz7ce< zU8?-7^dQTm(MH0-Fktx+G}_8iwxxk&x++2!MgcY<<{q9P)K4@{vGk4Io1{y6vRKoR z8#^CCy87KKzH)kMaC(KLf+9Xdt@Yscq&~pQoeCl+T{i=LhxqwBwOtP>T3Fc*R3K-@JQGPn)mx`@) z_+AV?WdVUIuXIO&A6_cV&Y_SB>&TvN4vY6BiO6KjH+uzYNysL?Z^qh`oYbZ4khI0c zqAT)*$Knss*~&&MCi1{$2|nCUKAgZaqA1FBr`U;@80U$YW@rubtB$03JQRHfM-C1y zQ+;T@qwXHQy=_d5&1uaZJFaTQQ=Ox6ffHl6{H!C^rS`$-9OIu`FA&FidWX;1iCO(z zkTtl|^8Fd3z|4fr=B2vicS_lTksGh8IVfRc!98a-|WHKjvBi6DGe!h6AR#KGnenZC8!Wrs$U|mQIuX`lXkH8*I1S z*;-OY`gvs0V^~JqAPym{d@}(@Zw)w6CQS9~=(BVIua7*t$b3(Q^XZDtEKb zUph2^Vxn@W#q)^QM|e&cl%7uR@96hmZdp0?=pi#<91qnqj@x7!Ix&g6ol>V#%;k>4 zH{>9sA6{eC8&cC>>NR0OJlt>#^#jQvHgmrDp}n~(ygeH$WZ-hU-7fS5jSdw0F3#EY zJ+0Y=r*}-;AXYz%eD~!c1IciTuiIz_SyQ23k*Q8!t(;PF`{=qh1R3r2j@~)8w0c!bb~|dxFWN7r+%mLZE{>n`KPIY?WLO$L59K*eKs^;4XFaG93 zKox*@@nWt zI3{8RJG1lIPouP}kky|22H8Sk0Un=C-00H6Yi(5X<>GPfW9Ud;gAL)aOs^~3MJ1d` zP||6lD~G&G*zO}Jh2yEpVV}*6x5_p#gh3HY4;NTK3NbxZ)KNi1V^-#p2n@DHkaZ^P z2UsX0S&GXTryGx8;~5heFiDtuCZi?C95C{)Dm;h!m>git&mhjkFbOY9x;_u4e}l7R z0LN(4#Y*5}_W_j;kw9nlLJDUG@w5yJdJ>jZIDL*itKMuL=T8)@n>^Q?-^`cHT0>0~ znKojp|26_c)Ye^Vi)i50Je7yyS+P2e-4t~Veu53)nZ1Nhn%rSa6UnYd>>ZNF}I`unx$86HcW)e5#1phnUTubNU_QKOI7J$2`~E;1t0Vm0=cud*AWb;RaFkvL}kQg_HBQgF!{w{YR=>q z-dlO`OIgtvj-XJ#Gd_k{@n~vIj>H7VUYU*PklN}>c&x$=nD1$&I!+4l*-iQD)dSDe znhjLbadi8TbeBeJp2M{O88ybk*!E*IuN_aP?YOSPGhTP&i>ei;lf@j~by zL)zW4o+Wlq`iKihcICT0b~%pzs7lY}5KVhFOVq>UGi5q#?lP3kM zzdKZp0^K!-l&`G-aewqk*$RroH@h$L_L~BD+(vZu(haFkKg%t%2#YUQKFm>0YqAKf zf;F=V2Q=cJ-vQL^u9x$P!#dR_xmKPZPU+|yqTbI5Xo{xx87m@yArOEdEw(w?lmE=Y zLW>i3AJ)gUiWu<8z8@Yr(dUk<-x{)|o`CLZM){k-=8QhGOu)RA{+)98u1!C41aeXBqJD#2JyvsAdqMKGLlr zNFed6gWNX*h)=raHa>ci6nD?}bUkA zAht%V<0O!~O_sKm5z)ba=5INxX+AyG=`FyvCZo^q;pni92mHC)5S(@YLYO! zy>j8OcH7W^*_3&Mjf6y8(0?{lqE|Pv7r~|TQ3W}Nf`~)pP*jOHz+=!7N9<7@Q{ihj zd$3wLJAsEY#TH%v01j`~7m#0*X-q+(x_^YHV^bCrE(nGa;FxpU7gD@7p_Z3{<-opo za^LWKF#r}t*fF3ob8^tS+BdYxTr*8xQuj5AMUk%#)30^UeRRT=SqX>Q>Cv?^fj{u& zhYtlFdC^;%Cy-8J5n-th6eoBsVqp~nbM*jKgNow?fTkPnpo9%0cQwa78ItvR;A|Am z=Bh+sJj7RCm+~vsUT2hlB3Ed-iwHblkW~{AMD)uCt=5_-hSF+H9lo67LizXI&pj36 zi~9tvoU-2Q5MM{?ynxOMn%51;+2a~J|FyNVw~~@yYLTT{065is4^FBfM#SoOugy1XYjlt; zkH}3&PVtN}CHb8}0velGiQ9{@l#aO*51EKa+XNeR3NaBiWvwhfn$*@eV@S#RCEx8% zv?qEtw+etKNq3x>RbCtx*34%LQ9_XS7`>vhOLZg{X|N^3A>qb>t+Vw2on?SRiPob+ zLP9O(xcwB_GI(?A((EyZPl*yk+GK?+EWNmDX*f^Y^zAqqQkX3)9b9Tup;q>shYt?m zu^+{mm<4L%q^|uKIhh_g!o*v^j4o%0mAnnU>mPrO6>Y${#&$epb>3%}X7Uz^~&yWXq{4dhpF-p=k z+ZL`=Rob>~+qP}nww;yEO53(sY1_7K-`uE7M9`;2qG??=RlwZYvG8Zp)I!5`5M&O#v3@ucbL`w72mlO3l|EH>S0HmVDyKR zuPs8+YQ%b)WWaXXe+e(h7zmMV0F`UsGcu^rzY!e=XiQx|Gw}rkY2(aexU?35WT~Ym zxrv9jWf2E+AA!?xg&EZG_@SadCb;gK#>uE!(!WcdP@kDCWgH2y%&-+L*Y|PJ9fO&P zvGv42rYbftJK?D@q|>V6k3;8lh<ugORXO7-}Lxip#3DCM$4 zzk+bCyhQ;nCWs1I0;So?YOWOaDI;UDtQ@kDVNeB>#9Vow*f=e$L`Aa+d9W)dyD^OM zwZ;t{w?!>-VVL!w2=UixzuZK?V_kkBRr-@{nW7wwz2mfTELZFv!X$-IKSht+bxG@P zTH6ZI1b6`W(R@1_!+-rhi;Ckab?@CvWkZ0w(xuI-NDusVC% zP`q2?#^6yj{$AO_6300lzuu^ZbjFOJK6KYY%0|=X9d*t-BUI1jf=-NZzdO)EEYUN6 zEq)Tb2Mo>!nrCHsE3o%w!DXyW*Xg5FkZlEaSWw0EpoJF7InDZO0Ovqnf zCxLdrjUp0Xaw)w2eL~#8S&wVZj>@~ClG@vwnjy2IXu;)!Ws~QX@aPA9p88Ye%Ng5K zaGRb(CTZBP=j$U2cKDi#NA{lRm%-(D3ctnZuNZ(euj>1Isbziwgd?P4yTv~9-UhPN zd_`FS@For*@gS9LT6r4Ejj0Vg5sk zmK7gl_Ykk!W-5j!FlhFA{OIT9iAFB+3e#>SAd_ z5mfg?gD?u;&i&d|E566=22sVP?O^Isu^w7eE1xRdmvr~@zgZKR<*}owq~yJMjIOabcR_9J{RCdI>$?V z9yb4@z`~x1Ej>b?1fcYcG5A-6LmfkB!CC({ILP^?NWb9A(kcSA9tP5}&tm zVT_KTSu>QaIzVcAS5L>!EZ3~y3*yWcvKA|Zk6AAgnBR+Qw`f*^!j!)#)7v{=c2BJV z>DHS^kulkRb30@Q`|Nb2B>)>;Vmp<>4c#1ix>ovtaP5z0-6Od~TWM{h=cuWyle&FriDRcZEA9O?y26NQn0Axsuclz5)s*gx{DuS1^;*|;8jMj zz=rgh4Z~_Yui%ja#5K_eI9YHi9UM5f9(NdPE4f;?Hmqw#T@0M|}#y0de88{oRXSc|EWG= z--2n2ic(!@Z$@KCs}#N;;AqHn;;?lzOuoPIzs6>kEQnF4rg3S)T%g=p#-r7 zqktMu&zPZgiQDG;^1%UV8Ew;4%A-lL4-m;~)Y1QoebO=fPr*+GQ588pr7!SPL5+^~ zuiz&wE;GYdJQUmCBZU6JTKsDM75MzK{4e11KSe{a{ehc0o2Zx>I-26Lu(14vviP^^ zuaw0` zQ!}&5t>iTIgp~B;qOCO5xY*P*RlvPHQs6@plfop$6EfC=ufop}kpj2?xd=J2ppci+ zWnz+wluC?B{%TxCjB3O{S6A0iUstuKyKiVnvF9-><(9QK0ffi%kilE!Q*Pp|_sk>f z=<(>1Znp6L!C59LeSxtcr=_E#MC`%^5_Z5l+AMitd3B9yd1+~GYHgFdKh4ir25K< zqWU9eh>n()?f;7z4AXx)iF8a~r}v-ncZUDo3`U&huXZqUf5+qhFoaR1QTzWDJ@gM| z?H?gTW`CH+{b%bK^Zx+r>)9Jw{~0o5`^PK$KRs#wiE8_|93n$~%YQ@>eHDMZ@XuhP zfAs&>{O9d}gQcE>Db4@fbcW?$@6A6N|Lc2`g_Z5ETY?JpAC3qn3s`vNXzZ$zmOyCJ z{2^04V8D`>>xu?zR%;a2OGy#sH-s&Z_`_JsO9KP-Qy#dMzOaCS@Ss)*@PJ^?1D+e> zpHW7l51W?GlOLbgY}}%mHwPUamu;6&_@xdc;)L*G2h=(YdhJ(LdY(RTJlP1Jl}lKs zIuz>h<=JhhtuB=~v^$MVJoR6$`9TBsg?;$b{sn1=-$6t|tREl1a9H&(hWrrD&WoTN zL9Za!FD}qoZCfmwqfLA*Sf96eY^`EmohPr3?0~S|-hWiWO@LxF4={`|IEEC7yjFaD z46sO`M=-P|_TDxcx~SaTi4pX)-v!36$uO{+rFwnq>cbH?JngcB5ceu=*n>J_y{CtU z2z<{)s*UZ#X2O|Gr}vrSZ%t4LAu{N6ZhHwOc|}oZj9%sM%`h7{JUwPtNf%s=1Fepy zVsZv0J#)t9L`>1OMFVmI#Z+_T=G^xH_uNbg>QYqM0}7XN7R5nxz~-n8N$P@9`N0aO z#r<=H=D_=+R5`>71SR)#^5)=7;VZmUd4=+MB~f$s=Fm)0=mJ)`%CZh6#|a7g#hr>M z;RUVom$J-?E+a`Nd``J%#hHpcr6}`RCsOx0H;Ht z(+LdsyomF|rSV0s^-q$ALK&mwgvu##-tY+HGenU6E9BE|V8{ z$2C=lW0^juN^7Tbm&+Z`+-zRjYBn{UlvtGGmmD3J*bAv0Ptw0!B$>;{)ie^6wzQ4U(SWjds*l&&w4F5Lt!5D%rM|ZV`Wg7C99nJ27kw)c*LSx+9 zk zf1*78y6tFP_KHfyB+0dGAOOR)`^%Jt;p5ABIb%&@L0Q_PY#+x?@53`J-^2pG<&2o2 zYYDg1$_e&1K;u_U$@9sWYA8q|J`;3Xla~cX$Fx^bUhs9%X#J}rly0!Wi8_=)Axn_5 z;zvj@>T>JORnuY z!=FN(_#l$_$pZxx!`P@sfrTWE6y;nE1wDNoA|7KQJY=${4@DL8?h%vS%923inNA$_ zmW}q@mW9KRRuGvwLKJ7KoSXw+JX`&<9Y$m)P+AC@8|j;>GVw%6G^eS#( zn8ijXaUyN*MYbhj%}rw}1dVGKY+x7qN#t5cWgMHQo|P&j{>`m$$4mXjmAjN}3+$s> z^HeBYRy-?kCSeA*9x~19+A$p+1+Cf%bqOxeRKw9}3X~*=Pe^*TG^)fOerTb{=peUe zXcSqhZPFJ<6OIUV(#;=q#ZUpO?V@z^Vr+?XavqR(jpc2;HrkaJ7+ zr1+>%>H>D-N@H0Z^o1z;eHI_W^D_ivTyyVH^jr%ReP_D$)c(fS$hd1EAuw+|d{n^7 z#4hBIMojs)?XVWV(u+tFAZ+oV-KC-^=`ji|ulF+Gf3anqjK``o<*i%hTn@-E?n z+VOtG70B(@JI51NWyS33)u`F=qzx-4um2e~*V`%3>#1rwiN;Txn&xOBP+1~%q0cFL z>*;o=2LTRTU?fkS_~O({{Dar)%bMku>;Oh$9<*FGPbvICg>rI2G#YUXITGC%L4S)? zcfw&ls1j$plt7K6%6!y{dhkTT?MjYDyv0AM~i!Y-}Fy=zL7*9_exjONQ?_kn1pqIevRrg3lkN0U?p&)i@7Aimi&R z-RAySHnx#V$lL8ywg|My%p+28RP7mHZVjpk&`Tr)p=<(lG?+;l|sEAX;5?#y)><8emLjNtGexkLa9N zf)QuyR6xMxo7>1K=4--LDGpV0G4J#r?IvKxT{&_X2(19%D{cf5U~hqIG*ku>5Z#%? z5Yd41X+LRbv~Nd=OQ7GWtj0PwWZ-SziIk=jquJ;CL>TZg+2~LSb7+v%in*a%A(D-X zd@#lF)0%=a8If0f&rNQe;pz9J%g8L9&nJ7LvzoN5L#R)c)CI?_Qyjo4EZdrrfUk%) zu3JIz)T^5iac%y!g-B_UCKNxTnISEdtTC7>RHS{=)7DpEpkY$mA48@>j)#}By0XV~atf`5}}moD>-XSwD!ctGpG}HZA7}X|?2q z9ftjLuoseE3$qy9mkh8&&e#t~+eX+xvRzBUH0Zu;wD_np>W(=z0=tGu1ZEKv9 z<1MLRUgnROW=0aVU#a=Zgk?tD0wlcnmVl31+fe{Gy+o$E^}@_RQSB-<7|Flbn!A3u zDcb#VP!u#ey#vSVSk(^K;F?B2ZrPe9jF7nE=R}qnuwFun>fN0NtOt$~j*npo=^EIq z&a>;Xkp&nL=;dyE{RWj1QfCL|?XvR94|vUDlONYMDUlU%s$o*&vjxX4HU-)D#qvi| z4|vT3b4`MLB&zJ+VR}#vJZ;%SXvVa2+~`zVRtR0~-YHJpNFxYXEXQ7u*2?M7FlQ>o zpTV_l3U!=W^}M{L)P6D{JCG5X%G|BUpDf*7r}kXJVF(b}cCpPe>4kMLy6i-cmyCW> z;|%@Yb(9@i{lwa(OQL&F?kXz3em=5J(`la4t_|A>mLzN~9Diw)B3OJ|KmyZe3c!;f z1kZ5ck2=hPWAAB9mD!+>EfI5Jp{ph=k=vCLDW2A7Lym>ms=B{qY`ZbJa%wcH*M` z5qx<6LL;iO3bdH>(eyKyzn_x4&hR-0SjwL-EyMTjQLJnIJRNQR+?pjQjiRptXjMv& z6dQ&6$0RYo?&35gWb~0qi?@OiQZb<-z0d_uc$%*~VNzqS_>^j~x=NstWDp^!kZMDQ z2S(O46?`YIv{XK0*S%mBbw{fW0hh1wrr|W}j48HvN(oTZPX#l41l&L{`U}QH#l883 zm&N9>YwbPwK{15cd;|laNT}+y$)_np^BEohn~IbqAG->WEP*wh}bL)Vy&x=S5#?3QG`}F_#sy4tUxo&@uMdo zVW1NBch&YHV{&=h%Itb~oR#l!pFk>L9$KL<_t><5?C*omjrJ|VCh?F+^1Wt7JpYzN zcH;VAI)N}{yp@S``6Bre*7s><#cK5;{Ume!B%`Gfk6oX}97-fHiwnyp$J7GS>;~g^ z3DGjV8n9fL_T|t4LhQ}HGg0b8w7E%I()WliYWIOOeu5Tx;j3lyy!5ufm?`A39fb}#=QT~Zfx~9XT2g+ zmPF4L_EtlV{new12dc3m^4^&7NM!g@QbObUbJ3RX_mlfKBt85Bc5D8@&|AXPd_Ltm zZEqDbf+)W2BczBMQ&NIPt*pE<03h0ESrZ~}8@{Co*_h!SGLff z`!Ip0I8fptwmFdM?!eP=_&c+wO_$fim8Ni%0FND+9vw2|&HxT|Pts1`_u>|^68K}- zCrQ{5nFVg9n~Sb>mW6fJG@B|FZSOi@U~OUzd2@_ExaydWeHCzC=D`Opr$Lx`a+kSK zk}ZeG6LQ!b71Upf`ifl57D|AI>gkc%hwJ4fcxFaB3?tb73$%ur1O^)Bs$6 zTn`IfD)>fxNDdR|1i$m5=73-{R#%tOq7?YKv_S_3sOED13oe;;0n zoah_^+za9gF(S?e=W4(W+Lcroj$iJ+rKwpwN0&jgg;Q79qlf%h~r^HIrY98%UX#`whlCYFDs~}&T zdPzc8NS&pfiDKCh34B#unWaBGJ`O-?!^zcVqX-JFRP1GRu)bj$T#>|hh^OeN^yqPQ z1EHHE6u22&M=PQ5cyZ|bkvs!0jG4;hzM&TDN-hI99dPLmUg%iesFNK(WI-w>Tc3cT zCciy6cA&?~&GsG6h!0kc5K}coD%1E0%gtw8r|Zo?c2WbZ6$(;bB)*7}#pFq(ED%#F z`Zg&|=(ow;-wEQPHU@YyWok>v1GTPK#V~`c+m%SBP=k-pES$%DyL_QNdw`+dcZg!) zY#ji#IVpULN9?S)k%1ejR43t%vM}lz$WcwbPt)Nv@xIOL8NA5LKm?IGNS$eB-ACbF3?BA`-Wug$! zVo3Z*z{>qTuy?!+k(bm@wD8X;eS~0^;|LDk-0>FS@;BgMK_^;C@$$b%k)?Xd`?526 zb51m3`I#rWq3eCGG6w`|5z02sV}}I9osz#0CY3+zE26LmqR%VbQe34Qib*A*6x+bG z@e6@pu;>WdjpofHpM+7{)v=u2y&DGPbVNG_;mQ5JiqcFcMeS+y3&tJ7kdl0p9RDY; z6p|HJjj(v!HB{Ati{C&)I`p6{o60E}e&d1ZBOrk7Q*RqI9-VyFNQ@Q01+eGz zFD1t&V8MVn17O3Fq1HS^xp1ACZA#7jtR|q+{j@RHGeX|KR_CLDU()(gVp3NzvYb(I z5*ktnVohaM+_$=JFGrn}yM_|s4Hl6nP1a{T8^l#}j8q5w{%tAndY#&TqPheiy`l>c zrovmsR)6zjY=yl7xM4Pxs!XNC<=eAB!9;ll;mcGmHA**Pj?8cfKkfWn#%KEgfy72V znM5Xz1ZrGDJ%j2}<;6_qOv(`MM*gyqo4=`+YgCN=k3pZ6kfz6um(Qxir%xw0>ZN1U z$>tx>EfY2<$BUnf`0F#x``^7yU$L*}i4@%zh22rd4?L=mMtF{{X2I3V#>tD>`$S!W zQ5r2@azE3eriXB<4GSX_9Lpu6BUJZ<5z@^aB2uL@#>hi}reNhS)Q$^vfULI)w9$^* zdpBnnO5?yMog! z9xUU@c)5M|=))_w`}3d1t4+N2r0sHf9X?F3!7YZfNNUB=6g+mrsZAPP~z6z3(SL&50)d`IH2Sp6ya=dEQDsC%xXrMc{_uI}yZJI!2x=}*6 z`|fGO_h}fDz9VdDJurDky8dRE+6RF$fG7|~6PVNh_Z;qLewi7D6!8vxyWjkjTK!gi z8SvG~vbx697k2O(8ND4BG{XSI1X5XKchLHUuPJUS0Zi{2Dl=aVtm zV|xYXo3!K=D`3O-aus$M7tcQCUkx2p-pArJCdwr`J8G!SjeoEeHa7RYxH^~u zS;@{7#Bc|@Yq_Oo<%r8n$CMS0;KwtIP~+cjEl83W)M`sv_Y?BlmqX$d=Ha#ADilqM z?%GG7%d7<($ks4Xv<^ue0;HiHTkKdW2e$;fxdvGhxz`@Jj;V2N!=Xi;gn!A049Goq zJ>?svTR6j2F%SA(M9D3plW;VhAMF_U776yQ4TlLZ%rI(&nwIU+jj}hOL`F3bSEbgZ zU2Gp{HqFRa64xEAR|jY9bk=a{SOtl_qM$-k9udR3-YM8**snP#wT~L?BnU%Vw@=UL zL0OAPBe{Wf;NV)+Uf<-V`BbeB#M^ZVQZk#m3sEn96E%hzr=|&tFsA*!{?_2`RHXL5 zsUr5~s*CZFp+d^RlJqtdOUr*Nh>e9s8r){r6d4raGbB82r5EHD+rb^t^_}r|zCeAJ zvDu4-pY*^#2zXYpZ2ZPg5ReGJhA{U$B2TQi6R|!tmQ6F#8I$!Z#V&pc?|X~HUJXMv z>2DXni^~Y3E9~K}+nxYh+z<}&Ua|M#as)FYkjF=#neCYByr9zvutgN)8ubcdYqP0v zD{1;5{yYF9j=Wpzb^g2l>W&K=!E90*0*b?N-1n2l*iAFobsr+(Q}w}Grye3ayq@V! zO@&qDb7?Dk?4^BQZY_;5#_j7fo=G8oBn^*PaBQ&6X!6GpoSN7T-r1*$vjwe@b=k4> z&-(q7h6s#<%Il@tnGl9^LmnGWPe^Jy8RATAo;RQnyJ_}AWD;tYoG*#6cz^ zba3FYObK&Vq`6!kdnhlxOvGsc6J&fLD0Zb$^aic{5N&1e+Pepd0@HA8g zSx=mQIK0-GhmY$8!PNkWVMj`t{lZLZe}n{X844BI(s$f6zbV?5a1aPE6_an#*r; zYs!Cn!r80e{f0Pa2f2Bh1@oKbQ&)6f32Vkayb11BLOo;Y&XW%{Wi8**EuEfDu7A7h z!%Nzn6V|OJ-h^ZyIe&leXtm7Lyn!h!^&+>tO@9MK%V4`~uFA7>=_SJ}mZCh64bOV_ z4LN@z5Jt~=C9tFJ!ONCP-gSZ|>b0w)Bi%dx4&W@Rss_8d6#s?enavf@WE)>|gk3JY zRco@+m%SNLiyhyDYRuoLkDEGyW}VGg%9o+ONt9vJbVFtd{w)X<%lv#aDS$d%qtg-o z39N98m)fa3&WwVvgH;dkkYs7>$CRWucKxa(kGns4lN>B!rbiIwkkdf&lqG*CxHpvs zn!-L7+OJ|+Tl9utS${bJK6R^uLlo}VeJ94?xq8LtJGJK15&J{0dm^PoO!dzRABR*} zUXjy=8erOouCq=;-_KGr4MM)nH+RW8P$w(oJj!yDG?5PM+j6w7*T;-In@_pkbW7g5 z-tXJv!0HczOG%h~F3&knZ6t!`0wq4Kh zT2Nuz-zTIhK>bw*n&><0%gap{mz}7fcWs-ZRQvRXdD^jF@;I_Fx}p)upl%*mJH!$u zUCF|3CS?vkr9CLhzw9fsr^%hXL9B6q7}FwGVBx<`TK{Yxr+grqyuBL@&@oiulV|#s zA1M_G8#=L~R<8R&H@PmFNzy=E^Q84?;)BC5g4IFMejuVo40k0?S0$)cULu9Y=aS3- zA;`l5*8Xw1C1zhYRYSmXObj<1xmZvH)Az=%7cZVBMua-t8x4c?)Z63;#oe}8xpGh< zxeti3Soi~o;X4Bc?R}QfcenSnMfZHMPW@P<_cQ6yqL8vY-v}ik@K?+r=6Z55B$bx!?CZo{zuIs{l9W1n7=4I zf2Zh3(nx(di7Ecyc$_~&@Mw%JX^j78dc;4;249|EUj&2y>-ObB^X2#T&wL-&f8`YX z(fD6;3K;2`+5STK=}>iZRd8zM#)JK-%G-}C$5}+}o12TTqB(FX|FyAEZ=6X2q*{L@ zmRdRU=seS?Yml08lz5z(sZA7ORue>(Lqo*saMAp6m{N8tad_u;@G-MsHIQ;W;gIEa zBV&KF_ttsadHLvliGob$2H&G!!zy+fufl`n!@}c?Lc#1Je`f8B7XNH=D>{NGsw?n& z?`Ungc2)Mg;;13Tbeak{tzW&ySwr3~teVnAMp|eGNDPLU`{Qm_0zrpzjC^!GQ7xgF zyAGeEjJ6KYhg5V;wVi^cjK7)my5HZwZ*ixKRK}C4jI%5wNZQp%= zTir-FsDHCdMztx*hhki!R$~!o5x$Fo5j~HNY>b*xv%_^9NtX8AlcT?D;F7QjbeUZ?>2^);!zxf>^leeII z5$+yC;VFmMC4W!|F7FMuV63v}^?`<`D=tdIj3p%kc(QP%If*gu=ZQNj4c{guhvsL~ zr;3S5Q&x%VV5D^~mMgc?}Ev%W0`TKH#FiG<4L7DHN5a&Bi33rH61Y zTd2>AFX@|H6x_xFXozeA;YqK_HDFYuJbEOV6&JyU+-fV*zT4}F#B&SvndpJ<-tX}9 zGb`&_UYK3FF{jRs&WB$In2P48Tv#+QV?N3*xL?ZEEl$h13@=z-*JGMl-aWIk{{&b* z9UJv=`oSQTAT4owXTB9r*3tj2bC(VBpdJ~sl)YO<_MEw6BJZmx9yuP>aQ+ik%cUBp zW*hkVpt5sctOV`3AYsSWS%G+uFNHT*DT81GR2^Qx=GL#EN1REs?9vQi=29N_Q6_0t*) z8=Dofp;`uKDI;gvWSb#8wc+8V*ygDFXJ_Kr`IzN_w($mnNY?AitPFJ5bVQGy2R%vO z-Jys6rftSL^B@TBuKdkVPO7o>wxU0BzS7uY9?C&GCP#$@BdUbo;MhT^p-*1@g-dQF-^-V=R1tNV$FzS2^|&kJsbyQz+9l|`uhaR%+9GF=A_$)}*$w1g>^ z9v94}?$t9@Ec0#en(f7C`nqI}WRK+M2!?PT203ECmTDXbAX<#0r-6;HNG0*#y~5d; zzPA7f=J$d40c9%|?+(dU(E+*%m^~^(t{Hx5hNIm~H%j&(ihjU+KQ(g^R#D?Q3)#{Z z$*vr906b--E=Lb&6qg87hG01aP%F3*Nk52b@YB|qRNAY2m7#1jTu0ip#Yo*dEl8Wd z=A;MRLpzjD{0_8Yvd&AMk2{x~a8X!{rhWu{6j^5w zB|sK%a<1#r`eO>-Q7r4=cq1y zKQGXc>L`f9wG`e?9QueBP~WF%6cc1MIZP=jw3gvJ`J*>?D01#9L9>h+7Y^W{2)CJ+0xKfc61MbmwS|l|8xh7x*x6gZA`#vD z?!r)nMqbkfvXkttVxN__5+O5+105QL4qVzm|2rnjvu~dkRdHp>jO>i986%Qtu&yyJ z;;rt^^W3b52S1e+qfd!rns7|kD8&R#%swwbf;tg$9oB?gb7N>F{LTvS- zGX-7J^#>0ISl29(xP@fMEtR5ja0?ApeBd1v26Det{D@5@#XvWBY?j0kBUwhO1sLZ) zN=ty0kA4s=YwE>+#Yk0Ia<<+A-HGC)(#_%9zyp`e6oOl{)=hN|Lcb2Nf9^-Gwid8a zpHy*e*VR1R(_esV=Urd6`2)`T3WNlr0 zhw8Ah`m_lkWy_=FAdxm1xpN(_%OfrE3xc1hk;7VevSHh7`>4b8T(om`vvZa(OvI;Z zNOQ9siQlDn)M}kVyWkn@bKVEM!RM1 z#N_sxuIGX=_Zbf4RX#CCmf$JG2I|dgi%+a5EP`#Jms5XR{KV;D z_%P(4nYU~@_|p>jm!c8vP@>|Bh1;M4r`gi5O^>!WgTThCT#krD-mx3sJuXh1D-6%` z)y`qo=^L{pRLVPIBLe}nLW8}mn4^16(#r3%&a;Owj`=0|Mbnydom;=} zue7a5v965k7Xbk+?~Z1Qre4GeXNv(N^{WcYQTvbEuQ)#Td1h+zHGD;7*;f^isz=H2 zZL9j_O#@kmA5oXzw_NcpLP=^_GZtzDld33Xk4lWjw3UV@oG^TwgggjuXh>>*&_F!E z+|50@$ah9wocz?`9I{PW#A0>tOU70{6NI!ouW+uLHDzhoG351LF3?mf6=xtd3lLVp zdZeUDwxB9>XPEa__8r~>CYYr70mp>CcU9w88ibLo=ijdnQkO!%>$YRb z8F>-Gn9Y&HeX+nEvz?;ZyT-P{Bodn!#|53Atbi3g{1nn|x!rsY{gVG+u`Bu{W)pj5)qwzN8Gtu?-jFm<)QtDs*v&wgsm(v}(JhwWBasUIrLgJdgN0p+E@Ma?_ zCWelb7t}O)m&|D{0#PzQgpZ>GeX=5=s-Dr z6!BRPxCmMt&N4u7KBPNK)wJ`T4p#BiEaE^gZ)jRdJLbMiX4*Re!JyeNnddi(CBJA& zr+N|-{z9@|-qt?-QZ+;x5FS!jT6Ujg1!OwnOHUutU&M5jIMtQZA5^^V1wNuo6!&FF z8uI1UBDtI>qvAd*8An>(?Q`=D7N^b1CwX$4n*Aa&urgo+*$cF^3KPJI_h^xIoC6h_ z_Rc906#N5HoR)bvvc}fr=%fq!Eph}@f?=?})%L0+463Mz#+jM5Qc9&#tIH)v?OKHm zK{)npL-XlUN+tdRyP1Ij{|@bR$NWn6d67Bu&g<;}dF{U|AWShm(;rQ8xZ_}Nq2B6` zT=j`ho!TMKBzHIDb=`uU_u1jG8*Zgm!j^Ee_cKWa53MoD#9AJ6_~lpK+GdhPt;o;E z`+7#Fg+_p7WfD<@QV1vb7m-e8V^W35>>G(L!nxu*@s4nHTKBA0O%>4j_JV-XjWks( zWY0uT_vgYpEOMd(oQ$4zYPRXs)02`eVGRt;b>iEp{T|v(Pm(RN`y|ic1jH#e8LQFJ zck9E_cFQPS6<{Y_A)a+Vczn|jBxdzDY?r5({Z3^b^}Fds6M%8NF0s}tR0bcqy6gUW zQKiw>0MeWyxdm#uvN`e&IU8lU2lPBtM?<>@uhSrQoplYBX>i88OVMZe1F_)y-@gsR z-L`w=jqx&Z>0wmch2tmr=O5-meoq0MzxmeZ)n;r)cet$J-T4c_|oV=Z?o;ZZn^&R&{A3f;sW@+$A zj0M8E54HI-NNYNQJg2H$jEl^nIB4U*HH6BlMx8uKs~q-$zC4*e%}>;flM>t@UoVtd zdIi>Mgx<98x_Q~~Q_!j`H#3rCm>9Bb8NypPo*sb3g`3VSXf)c&zG3hZQ;lt2-;7*3 zP0x7Tmx-QXYxXm!#JmD>G=g>m2H153==k2Trj?*ii6uHrIdTu<8d=IUN&{$BeX z{;jK^t)k9K-=w>zs2K|ms$BJ9C^F2Aw>8l?Y9{*^d2zxo?e#kK3g#imWY`L^Z7WR2 z1}M2Psl1kO%&0T7EwTanh?Vl2GY;KgK6g;)lj_rzu2D*GX?RvnWlSZ{>y(&Otj(>r zt`_>FSCWTS)QJxQmnhDk3YEijnet_1a7FNt-=z{u``~4N#ee^~y@dWaYD+_SPHyC? zbnDYPLL4O>Z`EyQ4kV*Sy8ITcyo`4T+u9b!9zZR{=Z|v^eZAet)6BA!{qfwc2R^N2 z4ZLo3&6;+W(|uJW3(*mLfbJ)*8HB~$=^N7F-4;Y|PoKQ6V5}G{oC!lWZmp=dN1Jj{ zGHv$Dy0B16dnLwJp)Vu%a)`)?cxrukycSUSBZNS0(1CXK7}@_lJc$?w8y~!O_S{`H%GGf5nRa(Bk|Z zE7EhMG59k(`ENGze;8F+|CcemJ&n^pqdsi^iu(M~_+O(wbj)l_e?ff;5;SBn7SRS> z;I zjX?&ccd70H=7UN`HsBCDPZ@9yT|d3cv5s?|>BOWPWH?{h>p2!EoNYg2JKR2V>D>JM z{1nA!562a=mvA2lBPcP8ZXAw193Fy@i$wwPgN)qawC9vy*FXCmdU=DX)~j2a~w7TdQ9p zsMe+N=4@2JdN>Ug#43^-Gc+F;H@Je3yUcEt~A^6@-*9z|YxqL)DfP5GE({`jeRe zx`dspYF+DkwR+>!#D#q9AL164Fwm|d>zD|wT-VAcT%a0k2a9x>yn({b3+x0oK zXzkdfYRSAHdRT}Pvk#D{f}ov-!z;I2HrCfLif|bKQR#b$NEE4x9l$#S2M@;r9NQA5 zBIK-62DH*WYiUz`ZkRQ@tco$G@SWue*^eo?TsSRd;&-{VB)29gSaP4n)hH{Q)%H<^ z#4rBsh{#9PCD=f-t>Cs`4-yWQoTwE-6NSd9LvKYDY9Mi=69`APkd@YC1OPb)se=v6 zZ2O8VXX>9hR$L5{N5ZbhUfGpx&Kjr@)W!%w=>j|lYJJ|mk_dqLeCpGLBY=oF)E&w9 zKx2g40mGxmJ}>Ow4k*5fEO{6>oC{#hMn)ivXRCZ}Z2vGPCXElj<}TI^{3P~B0~Nq| z*=vk;5gH)@+!LJ5ZJeN8xfZeg4SRQ5f51*PMCKG-v+C1nVSX&zMyZqg;zl-JiR8Ta zwkiL^9a|y_g6(op$38Y+#Qc_j2>&{lnTAGyVxP%*p5op-DzUL2-Tx-cGaH^RDBkua zv;S=KD_**(i2>=UO)4?&{S`L{EMNBY{Lz*5N>0l%`X*gd0WZZ`_49B&`ogXrdOtMM zB)a1sTlP|Ik;8}0U*DaYK7jL*ExWSiu~F5Em}1m(9Q6@9#4xN$xNP(TYJpY*s-4O9 zrgu~Aj+sIg{w{N115c&6BeB!(ta1z7{lP)>X#wC>O|C>y7-Bkc9A(Bu^zLkCr}mpy zJ02{EqqdZnRe)swXdl#*03-KHwU(ixAGRvFhdS5C;wQCYS}KsDLY@QeUfPY0aWj%N zQS}a*rBgtbI=e@w;iOvoXrFucvYE{-o9UzKQIAsgOHO4;qtLA8WZuapCh^h!e0MFb zew3%o-W4AOYw?9}w6<}=DWxNO<~|dPsub8^xcI0W$Yk~QwMBdu2#?_!p9zZXT;$Hq zuu8tG$tXgBFn`u{0ec5=(3))7gfaQdotrFwK_waWq_jPQL4A{>ffZ!efGVEnu;`(PFO$yWN#?;yV^RT`}1qZcODEY}3; zq6<|#+54!CX>ZeeN&1OztlbbUI+vp^Fpsu9DM2MIDa&qK-Lr;G;!?tFrZ^$gsF0CC zC&J*h;P$r?N4p`DXs1yLunlOd_tQcaRVw;;>NV6P5KIy5Nk$Gynzv%2 zAEIBmcdngKdkn3Ek-06A>lS{W$e7a?$V^adxLkpR<$mJv8mR~oh(`-6t0|P6OhcyQ zU|<#nVNg!Ga-hKRyu^_j9YrV+Y6*!6_(#o&b`D)sx4D|Qrsnu14K7q51xf=2HQf-T z4}^uW+*)s_e>t+GlnXUpHq|vvohsBjOtC@dA+DqZi@xDc^n$1cH9QsYY@yaWI94=V za&sN=&k;H*Tp&-GR!o)WJtlS(ithTny$gg2UKb!m^uyO-7YjuBWC~vU2$1=-%)X{>Sk|dVMar%>)pWsxu*c*wA)`23 zqHR3%IJ;}yVQ8)?PavR(zkPaKOOWciu^KS{C`Mkng6jB`a?%chs(sw zh|A3KZ#F_-&A(3hKg)ki`Tt~M$@(?@|4Bp3_{Y@$`;7l{@nd6cMB`{`Z}j!-V)IX9 z{Y%#ShcHvZRRo%zdVnA^e8-bl|1+%=s^Rzp-l@7u@c`h?ssW-FM)jEoR9WmL26 zbhw;T|1hw+?xO=+5}NY?<{uPJ((q0`L}Ka*^cYeZ(ggyHS3Ud)1#phnc=3JR;Qyzz zH-V?}+y2KZL?|;MGi3;8K1ZfZ88grGJV$0SgfbK|mJF3hh>|&ynNTvM3}qf7N@gqHtr9FIipWBl*)kocgabxSon~`QB^hhPfeytVj zP1S3orTD?<M$2p$mx_f7f%#P7X=>L)};2^g&Kd&}*hEHSiCQ|oE z#g~!i!VfP+?i$wfq9^BQp0Na=Vq5uF$Bb*}WN6C!CpUX*Bl@y-tUjH&%d@DTbh1xz zPlItcsD;YoSIp_;3SPT>aFlI$6G}JCk%vLvy+@bhO^7(7NwIxrZ0T~P5sIeyJd69& zZG=i3`%S%DFCJFdNb+t`n~2-C^e8Vcubxn=m7hv|d$RJ~%&OUn@R8l40o3e*|7I7% z{}s9Z*Jxc{Mn+Q!|7=&AAXrCp;?M|AEd1XE>+r+DI{xdww();{u#3Q-#PH|Y3rNJD z8yVj&3V#@_f~bNyMsKC1X^ZX%nOp+$R3{`>fMsqPPJW8TXFw{V}- zc7;w3`i*}Gts*h(vve9otf!@(ef;#6<2z#1H>cb8l=Ppkdq+pB-9B}K{7yy4r^dEx zqkXwC&kZ6;<)gN?JB!SMZEg@X1>1DQ!xrLbLb#5WD0>wdL`E3B&hTw9d`;RyEdQ2t zi^}W=H4Qs66D#$VA1o6b)WSLZ-}O@ODkG!~cF3+rwI6xA?yf-EO8hp`)s(JEAS5-) z>%RM|k?@GJd+*c4K^ww)I#xU{jcN;~cT zUf!c4e^lu|?7}VCYd6_?i|TBI#`oWPrOxNj`v%B*De_n%#!DyCuiao2eatPQp1#p3 z?vL<2;v3elX!O#8nhHjW&aK)$o1^GpLpi&o;~yn6Ao`Sr@3%|2;|({jlc{$K)-P_fr+5yMluY->@lwntl=9!p zOnUMDgK{9V%X3)V_tH*f`tJhk!j|K4YAJnm+?=7VSFu-c6cIyqR_*pZ?>ik>_`MKG z%{)Z4VJB7l!;T0C2v^*)Q|?%HDh-tj%llC7xA~cZm)9yZMIqBUf%6&F_ImH+@s#F9 zHpkeJb1v(hRAJ22FL`;w^d#?178EcdW}BPTG>#4+MhnK(Xp0Bd63XLxkfwzd0zCqp z*x9%597Ig{$0pmRQlyQl8M0+QwcI(->%(NI6kck}ko=T%FJwA6=F$P5N_EP`L1vva zQL@*_S}swpEVQmB1f0|uO^g@ z8{Xh#*Fy3yq{0IVs+n71xzXdC*F`&-PrK)`*PdlNnpS>km09@%*`t$OoM9fC^c=J; zmu5BHmKjDZTPpi-ngs~j64zfuLfTt*j?l4-vTBl^xU-~a5u(b$Y}mMWG)Oo%dS`ZH zk9FhGM2TIKiackxJ>mwREI~e`jf)^1#HyV}u$HdU-&nv{d6g`t>wXacWnp_>; z+iA?YwH^(h`RA*7+WJ2deI|0hdZFj3T|tVIQSG;dQ3w4hTmyYA=RiL1FJ(WLess~q--h(NJe%WQuaNZq$f<4^SvtLD$}y8u)sZwT z6IF5TpE*CgxVPIACHULvNsDT=mDC`zX3qB@rh$95m#F1&N7+Fb-|8DvPx>al;}mC& zgHs;O^H4_aa~bJJx1O1kG1KntA9^lLxme-lRU*dz`dZ@(%qUGtCi?l1O=#QLEBXS( zQ*uig9$}2mw`ay+|tP+eYc#^IZt9e-KbUD^IgbV*&q zZ*_NhAri@)&t4IZqXspXwwPCzQ9jWHrJI3|e$5vTv^v!1itkgG&Xv%=iF_!BOb}XW z=;kr0Rcq+pUulAIx8AX;-RFNp!m(8$?sK8Z``3-QXG1@Q?l_MYcj_nVY;F?yvnI14%7e0x zS@c?znVv>=O@HH#@V+0e^JI>}akPf1zC~X(M>Dq7a>p@rJty`jSJ%bTZ(pNV_Iq|# zebW0?KS(<6Yk`c-O=f+Ekqev8u_%njV;Eu@|IC8d9U{FR}M0doLQ7| z^-(F%FFeq$qmib@W=wF}Nj-t%`>&N@;~Y?Ovg25?D_pjT%ABS+TEO9{aj@JbClLFQ{>5_ za#EPItK%(^_oMqCHaG|0zo=Qbb2h7lO2e%1UC?ziWPNUk(0O8P`%T_pV~-m4XIY5) z(pQ$(eyrPhBYSya;@aby zS~96)8;qr)Bnt-qL+Pbz7S>4_3Ku%|)l>SFb66)`rB#ObHP5v#L3vlA>SLz7ytDKR?gofu9lbVo!8#7n$TzT>R_i^Qw zZ#SL%eJ&lHK4x;vcw~w7h4SfxqHiL^(hdQq3uVVtqdr;9Jtr;Pr^*nK;g~lw-S~3OKs%7yHCVRh8KD3uLmF8b0 zmbh`$fXtcvd7QIGKx#uU#~B!li{L4u$I>@$_G04X?O**!n!U)DkVWOzL-g_ZJ&zky zPn22o6h*TjJ3rVJk%8 zj<#9qI=YDl`S7HD#Y!fUyEfwBU|aJG&sBm(`Fn4bl;bFZyBPEg*sJr|J^HMusRAuu zcbxX)ub4=1_Us!H5S^kGa=l|*`cCi2u)unhjAEvDxhGOymOmgE`!N!!nW@7PY2I>B z-q(p9%GErwogS{@yQP23e_o3I<0bIE$WG!NA|HFMe6FghyqCXLs&l>z>QJ8O3gnKnQ`@O5vimELPboxWGq0b2dYW%Z zN*-DKaq{D2x2em+jXq5ew)PcG!y}2da>!L5H+zYknxS`o}I9a-PI`(V47c@?EE ziSPU_bXqpD9gpU&+%7-9v?{WB)VCles!UC^xZrtF(G{w2N!iP9JYjMg>8xA*({z0{RhGaYB;*8M34B61k#3rH?>|^2OEx>X0LCJ zQ|;u!qLTSs$~~3R2k#Q>xW_}64tjR^#$UTt)$i)WJEtC0r7c|l$ggx_!e*`eb@ctZ zpRf7X7=>%H25!N%c^zC;zC1|#sov0RZQvx=wH>owVSA)Z%8QnrworUi2ciA4(8BE1 z4F9zLr=^jB`}y%o2H`4=3(|}8--$M2lJ8W;NEp-<^IeOX61J80(TRVMOi0X^sci0bkIR9oTchyHo=6ti%6#)?EAvO8`(XD;fm2SD6RM+Hg;Fb-6K{M@ z4wijn7YmM`6UScP9eunSHzo1#_sLE5L<>ppvS5x%iyBXlvKtxk-y+R+pH)>yK2a5C zN&24rx~U<~tR!gFC1z3d>+dgtZ-OstMDJYm+&LO&T2mc4_{`Br*45kJ%=)sNkKR=B z79|nT&mVjF3GW|g^qf2MwX=?fQb;9yL| zKM%zORhGY7c_R)TiV3dyR{`cf9Yu%&rPo8n7xbYj>R%`G{i8$n;qoc|aL+^Kkv~rR z{NFdd29I$6sE+)7_T@CCFU1Ks>LrTAV>(0$xtCz|^XGoZ_&FYzf1G<+zT_cmK_b0e z&tz$7ZJYAh^YD3SI!;4g<(ABpc7_0Jl* z%wL5!#sBF7_4lch|L6f_J=}!v#AkZcxac1u=q)o zS#bs%i(~p_V_)J}8F@xOp5+!t&2w5dZM<}GY4Y73A&DB3yT?7$X4TX`iJ8^cj2;|} z_$}?lKP`IBpZ;`4WMPC6XY|ng-qW5wU7>jeX3OB~Uf27`UfvCR?(?y~7u%N8@8LK? z(e81cFK1rQrRp`moUYZ;z+E2tGE;jY#`ETjPYl@?nHa|x-e{DJiZ_jk4vL3UhSUF4 z89P!>b~nd5Kr^AKi1wBl?QOuN2)pPg1Vj*+^TEh|fNgU#~4Bpy*7rjzK>#R_Mz5T3{ex;LL@N8CHA# zm{H3le;{A1|AMn*MfmWgYR$@idgt@&+#RXb;C(JK+3r<|9FOB#*!=3(D5&yr5>~W)V6tOD7=FunGIn@#+|iD zQhv^#q0{lHY;sw?meNqMx)@Wal^|t(YGJi_mBGF`-j{UiBK50gDM{8&Q;{Q7R#_3t zN;ma_^2?*RknAHD?d8Ml=hqP|lJgc_xeU(8B+e7%^G?fy*T=)m*6hdRuX9eE-J{`; z5X2oLttd(xD$pn(C7PZuTN{#etYj0s_vo!^8SO<1mK|!*=vlcmmSAju81scF*~(Dz z$qXaY^K4T+r*|!h)l=gGWSRW6o#~#v>T}3uy_UGC$9yfC-J@6Kmx2B>3NL3w`iml| zYVYCjAzqE0z*Uay5}#;+c6y|?wmjUN=jMgiKQ@o~{^;{^WW1KU)L;F%tT#jOCS1eT z4b$vDl&U;Q!o0HZ=xr`zObx%~a*O6RH8+Xc=|xl7N|ORbyB?jdxT>7mk`fUELvWTN-)Y%LBH=WePKkzEwIS3KSrrF!0 za+HXde92Tr7gWe&+(w?}Ub_ z3`;xRu>uuZ*FHt3bTJynnIXK3t}`=rX1-G$;Tre9lsxlsfpRg{Xtjjx;qG27$5Odj zX9ul5%+dQN8M2H^?6q7%h*c$}=>(@C18s>kCyrB?WiVKjfyb|$q2#z%px4|(mB%ph zJ{g72Q=6wmNdjvryPLgAs7B*v zC&cE2r>}BcmQj!^9^! zs;}uZ?2MC`lgbT;*NmSzVE6Cp~V4v-Vt)IQr)H17g?B1xh!iyARZIq!!5Hi)N}4n|)0q^0r?oM3GI%xMf%{ z7p2CB7jX&1uGQC2uNF{t$=v!%#Ss!Hd`?lVdx8tWhpI&t3~DCom~j{~zI0vkJm8g) zFF#XuizhP1`0bWc-)CA`_Wmlmp-&eFsJYB&$+(o+A8lxD?JdNsIfiRF!+L)Nw+}^M z*s;~V${qzC3uY^a&c1AC?UuhY$Sm6WaXD!5mLK;@%su_j4)m43`25uxZx@FJXGY8# ze3MgGNxz@Xpgrq0%0b4;`Rv?pmYCGJSE($FJj_{sMk%pprDf?$FVQjJ*z33NG>e-D zxf*P3qZ@vbEpNoM$B0BT^{BRHy6a|b9C^vU%%R_Z7hAr@GU7W+E~myW-_|t!D6q#( zdm>_va^S8vYrOH|LJc;Ii6+S=!vRMr5hcgk*r;|B;ds#no%a0LaLexM+D!LvPcy$? zhI8TU&=OUU4!`J}1xXAS)(5x}M`ERn(b~ z8RgNi++dIHfATEEhI}Qu=05Vh`g+WmjLE zT~F1j`2Jxls4MN)@MgmUpP?G>MC;jrCrT3vIr*wb^@VTmkSsRldt3Y7kt%!^!@R}y(c@J58kGZ zHcj2$rbJvm^)etqi(A5Liz!MW?2hU|#U?s7`R(nQ7#(%*)j7r+iYDbA#HYeOq_$?9 zZo-O|mBQ)-*95URWlsh4%2>&ZBE+G9rR^^GUjI;h5bXwC+3 zd5S!fxns$FHd*N2Q@LaEFNvPNf4J5%5MY;ID>ncRwmg@mvq)`JmJ}fQCX{oe^CHP< zwY2IQ7TQ~9vivQ$eC;pa6S1sVt{y#pC7Ji<{i82vD~~%@$sVb$l+DVGsdn}kEFr$i z#qfN^_k?_uSmA2viBEO&|+lm9kpiV zI!SVzEr`Ix`^Aws--CU}#B)Kjib~7x4}2I^i+eU|%M9VEq8K-qucI$Njb?Sm-|*MZ zRnhQo6Q@JP@MY)vg}2m>V|?$wyBBO6z1UM9xs%-bzTRZfiN{JF-d0*@aeAJIDM6$A zGIzmI+wpN)R6tco&-h)ABa5tV3ue;!pX{0RXY~yfn9lS(xn*6W8M6GO;Kbkuormh- z=d_wsDgu99xc&+A%O*91b;#>k;ZHS^;?1IsD@2vGd2Sb4T3qLC}R_ilX6 zUVoTT`NPevSa?y)q}%Vzg}X+@4pEO&+wMC(py%U>@;hVjWq443q^GCP+O;ezM z3rAm{KacIDrVyY`&AL+}fAa1eb-!E$pEGOA_vVHDL8Zj9p+VITv(oh6&(Z04<=TH! z40CAQ&wI3#UEnww9w=J8`SrE9VUPQa68ITmr%Cst4}v6>8(Ng3(N$Agw&)Chh39=u!?ny62 zf-^*C>Rr$0eBl#HLsgC4cqhmk*k2Yo?dlUA`BkEBIYZT0A~F866qhJ^AVJwJL@l=D zdK!(v=>&wqoi{6|SM%9fLsBYKoW%R?ySseRaTHI_-Y5EWP}2NwQl9^9wyPs+sI8_0 zavmL{LoW@%IMJZnD+-GxOn3nJXTtN>*T3I2_)n=W?$6Z5{i>atwGTLq-urNhf`X;dy+ATQAbOxGvY%k}o9o@zkzZ508kax+LwoK@ z`<@7{qTO|Se_*B&8kUyW+jVYOtUjxhA1Rq5FVk$K)7aD3XW9tIR`4Um;2MqC5?&rO zwuHF7LyPQ##s@Xwf_|N=@4=U2^Zfc`D#Gf*f~uFp1{X6QnP?g(89y1%c$8$E^0uL& zAv4vfwPCz_ytRSKmzPMqnXApRE$JY(?lEQ1K^k`vGYjK>k6HWH-oUa^UK$4n-H&`H z;d!^I{LCSg%kQrptLHk_*VM<*9vx5aCL5?5i+N16M9?v=cc;~6=UxB&jHuh($7}I^ z(!Ckhb(1F-Wazq3_2^?nSyYs>J!Lj3iUtgM$= z*7lz!6@-|cr<5Hu^IQlf>B+K7{-$w%NHX3=aU)V`q<`$$W$LLw2aN=i4bRoiijgzP z-@F}CD^e=3omi%}z1e(q$MZ$+zKcvn8)cNR&T)MbAfwXzZM&^-Q4-}bn@z__dW+p* zZohNum(c2F0#UZmZKiKC4B(%zh*?}JiYIH{3%_l( zmU4myM^>Rc}t52pTH@ zEG&4j(c8)0P2S4ej$i%)0tUmukO&l942grIjll(%-EIHl-~Jlx?#XZK>vYx2l;6cv zfD^ODY?Y;d#0}()3*U8(}j^E44#>Ly+ z-PPLNU)aM3eDU(O^7Iw~Bn70T?A&bemf7Fa&Ym2`32ZJozTEeZ4<~pt6N%=u=llzU zBd}OFc;gfQ;dJ{426}slp+Lu;KQV9}3J&CR7=vR`z(W0r;r|Z@I~#(D;egBg6T|aG zgHuBO#ISH21_KIThcFx(E(S`3hcGw}4u|l?;$R41>LAx)F$gFREEa(;HXo*kLBWAH zJA`3SFbsqTe$LRj01StK%ny!$i@_jcfm8tb!#rRxgqRov!@|)RsGNbIVBpol!}Eiq zP~f*ghcOfe4p#OMhM%7pWGukM5Cj+khJoA%3zg~AcY4+)3bCK%8v7-W56NW9TG zJU>7WpJE(ZBRqzMU_cFk5j%Vxo*qc_=Ca@$sS;EsJ+5tSm;w(9h@`EG5q#=5Wrw8@Zz*7Llg2)dJ1OvHWpj2?^UI09R zwjCaer-y>_MFal<(E|{_prQ1zKwqH#5({h?{zocRL>36BT)=g3sBH(~3mU3J z`1^p`Nq`}sW5K;434A=b52)<~P7sBL$PWuF4uKEF080+pGa!B;kTVud80UcbA)zrG z9z#L&1%5^%n$GY z$_tqbz%UTK$H379u`-y87{Oiue4%;(1DOF-E`S~q0htRPgUSUC`j!*q5P%*u1_qW6 z3$+`79#ELW_lCy^Z3!9yjk)mjpm8h=2ghL{dI0EQpne8mXsA8FW1#eMXw5MQ6b9LYXg~|`m6NAbC0aO=aBLEK^ zbbaykpnC=c)MC)J1arng?K8l{p!O8-0LkfLnd0d|b0NS13!NXH9@MVkF=%`bM_}O4 zSQJkWs;4k9F)Va%VL)3{0(}Ac4Em%V(gVN)36(RR9zh%df+?uo1w06BJ02rka}3!1 z5WavOf$s)eA9}wSkak0JXAE%h(6t17fm1om17JvK4u;2|u_Fcp6c92N$OQ|{oq^{j z$b0aiBh*F!dRS;IfX86aJp(Xk%ms=dXsAwtxqu+^@V(*rLi12ytO#;7Ko0|rukaWS zqPrk>1_m0+1K1{r9S0sBIJ3jo0eT=DAizLEa~K0WfYpIufF9HyfQSJ^7l*F{JaB|{ z8W>@|3X*ZC{{Z<64jQjv5l9eRKzJa;2<$zGN`M1_TnC~T=$t_wPjJ6j6bea@R{*n1 zupU57q4p2dS_ooRECyu75cy#-AVh+!8(0ibz=F&foZtd}-F;~9gIEtFB@hf>;(_FT zAa(=}9eN!aI6^3f1Iq-(!1jgC1s`Wa$AXv(s*}K>fE9tz15pmtzk$SxKu-ZiP*VW0 z6cXxd0Y+f6LF|YIXCoh$6|lt6cnHLzpwvom9YM_!#LxdGt`mb1js+nN0bfwk`eQx3 zJ*}Kv?L5gPBsfKNoUYm7i>jQW+V1Y&oIp~X+MJ@wZuah+U^jAVgXbploF@ENq)ib> zw6U + + sicktoolbox + 1.0.104 + SICK Toolbox drivers for SICK laser rangefinders + + This package contains the ROS fork of the SICK LIDAR Matlab/C++ Toolbox, available from http://sicktoolbox.sourceforge.net/. + + The SICK LIDAR Matlab/C++ Toolbox offers stable and easy-to-use C++ drivers for SICK LMS 2xx and SICK LD LIDARs. Also included are config utilities, examples, and tutorials. + + + Chad Rockey + + BSD + + http://sicktoolbox.sourceforge.net/ + https://github.com/ros-drivers/sicktoolbox/issues + https://github.com/ros-drivers/sicktoolbox + + Jason Derenick + Thomas Miller + + catkin + + + +