From c3e9528392e7b8e101daa2005b68a3ccfb70a72f Mon Sep 17 00:00:00 2001 From: Chris <ct00659@surrey.ac.uk> Date: Mon, 18 Apr 2022 20:04:39 +0100 Subject: [PATCH] Added variance -- ready for target --- RWR/src/.gitignore | 45 + .../read_event_pub/include/event_array_sub.h | 47 - .../dvs_clustering_tracking/CMakeLists.txt | 1 + .../catkin_simple/.gitignore | 1 + .../catkin_simple/CMakeLists.txt | 9 + .../catkin_simple/README.md | 123 + .../cmake/catkin_simple-extras.cmake.em | 226 + .../catkin_simple/package.xml | 17 + .../test/scenarios/hello_world/.gitignore | 1 + .../hello_world/bar/include/bar/hello.h | 1 + .../hello_world/bar/msg/HeaderString.msg | 2 + .../scenarios/hello_world/bar/package.xml | 18 + .../scenarios/hello_world/bar/src/hello.cpp | 16 + .../hello_world/baz/include/baz/world.h | 12 + .../scenarios/hello_world/baz/package.xml | 13 + .../test/scenarios/hello_world/catkin_simple | 1 + .../scenarios/hello_world/foo/package.xml | 18 + .../scenarios/hello_world/foo/src/main.cpp | 9 + .../dvs_driver/88-retina.rules | 2 + .../dvs_driver/88-retinaDAVIS.rules | 2 + .../dvs_driver/CMakeLists.txt | 45 + .../include/dvs_driver/dvs_driver.h | 138 + .../dvs_driver/install.sh | 9 + .../dvs_driver/installDAVIS.sh | 9 + .../dvs_driver/package.xml | 13 + .../dvs_driver/src/dvs_driver.cpp | 410 ++ .../dvs_meanshift/.vscode/settings.json | 3 + .../dvs_meanshift/CMakeLists.txt | 76 + .../include/dvs_meanshift/color_meanshift.h | 18 + .../include/dvs_meanshift/meanshift.h | 151 + .../dvs_meanshift/include/graph3d/convolve.h | 69 + .../include/graph3d/disjoint-set.h | 79 + .../dvs_meanshift/include/graph3d/filter.h | 100 + .../dvs_meanshift/include/graph3d/image.h | 101 + .../dvs_meanshift/include/graph3d/imconv.h | 177 + .../dvs_meanshift/include/graph3d/imutil.h | 66 + .../dvs_meanshift/include/graph3d/misc.h | 65 + .../dvs_meanshift/include/graph3d/pnmfile.h | 211 + .../include/graph3d/segment-graph.h | 83 + .../include/graph3d/segment-image.h | 153 + .../dvs_meanshift/include/graph3d/segment.h | 19 + .../include/image_reconstruct/image_reconst.h | 35 + .../dvs_meanshift/launch/dvs_mono.launch | 39 + .../launch/dvs_segmentation.launch | 31 + .../dvs_meanshift/package.xml | 66 + .../dvs_meanshift/src/color_meanshift.cpp | 739 +++ .../dvs_meanshift/src/image_reconst.cpp | 568 +++ .../dvs_meanshift/src/meanshift.cpp | 1684 +++++++ .../dvs_meanshift/src/meanshift_node.cpp | 17 + .../dvs_meanshift/src/segment.cpp | 171 + .../dvs_clustering_tracking/libcaer/.cproject | 67 + .../libcaer/.gitignore | 11 + .../dvs_clustering_tracking/libcaer/.project | 26 + .../libcaer/.settings/language.settings.xml | 12 + .../org.eclipse.cdt.codan.core.prefs | 73 + .../libcaer/CMakeLists.txt | 223 + .../dvs_clustering_tracking/libcaer/COPYING | 23 + .../dvs_clustering_tracking/libcaer/ChangeLog | 95 + .../dvs_clustering_tracking/libcaer/README | 56 + .../libcaer/docs/.gitignore | 3 + .../libcaer/docs/CMakeLists.txt | 48 + .../libcaer/docs/libcaer_api.doxy.in | 2362 ++++++++++ .../libcaer/docs/libcaer_api_manual.pdf | Bin 0 -> 768173 bytes .../libcaer/examples/.gitignore | 3 + .../libcaer/examples/README | 7 + .../libcaer/examples/davis_simple.c | 140 + .../libcaer/examples/davis_simple.cpp | 142 + .../libcaer/examples/dvs128_simple.c | 116 + .../libcaer/examples/dvs128_simple.cpp | 118 + .../libcaer/include/.gitignore | 1 + .../libcaer/include/CMakeLists.txt | 10 + .../libcaer/include/devices/davis.h | 1823 ++++++++ .../libcaer/include/devices/dvs128.h | 169 + .../libcaer/include/devices/usb.h | 242 + .../libcaer/include/events/common.h | 780 ++++ .../libcaer/include/events/config.h | 332 ++ .../libcaer/include/events/ear.h | 334 ++ .../libcaer/include/events/frame.h | 1019 +++++ .../libcaer/include/events/imu6.h | 420 ++ .../libcaer/include/events/imu9.h | 497 ++ .../libcaer/include/events/packetContainer.h | 374 ++ .../libcaer/include/events/point1d.h | 335 ++ .../libcaer/include/events/point2d.h | 358 ++ .../libcaer/include/events/point3d.h | 381 ++ .../libcaer/include/events/point4d.h | 405 ++ .../libcaer/include/events/polarity.h | 367 ++ .../libcaer/include/events/sample.h | 304 ++ .../libcaer/include/events/special.h | 368 ++ .../libcaer/include/frame_utils.h | 26 + .../libcaer/include/frame_utils_opencv.h | 39 + .../libcaer/include/libcaer_in.h | 251 + .../libcaer/include/log.h | 89 + .../libcaer/include/portable_endian.h | 105 + .../libcaer/libcaer.pc.in | 12 + .../libcaer/libcaer_opencv.pc.in | 12 + .../libcaer/src/.gitignore | 2 + .../libcaer/src/CMakeLists.txt | 38 + .../libcaer/src/c11threads_posix.h | 398 ++ .../libcaer/src/davis_common.c | 4021 +++++++++++++++++ .../libcaer/src/davis_common.h | 165 + .../libcaer/src/davis_fx2.c | 70 + .../libcaer/src/davis_fx2.h | 35 + .../libcaer/src/davis_fx3.c | 190 + .../libcaer/src/davis_fx3.h | 39 + .../libcaer/src/device.c | 206 + .../libcaer/src/dvs128.c | 1319 ++++++ .../libcaer/src/dvs128.h | 119 + .../libcaer/src/events.c | 406 ++ .../libcaer/src/frame_utils.c | 651 +++ .../libcaer/src/frame_utils_opencv.cpp | 412 ++ .../dvs_clustering_tracking/libcaer/src/log.c | 143 + .../src/ringbuffer/portable_aligned_alloc.h | 34 + .../libcaer/src/ringbuffer/ringbuffer.c | 117 + .../libcaer/src/ringbuffer/ringbuffer.h | 24 + .../libcaer_catkin/65-inilabs.rules | 3 + .../libcaer_catkin/CMakeLists.txt | 30 + .../libcaer_catkin/cmake/libcaer-extras.cmake | 4 + .../libcaer_catkin/install.sh | 9 + .../libcaer_catkin/package.xml | 11 + .../src/dvs_clustering_tracking/rpg_dvs_ros | 1 + 120 files changed, 26887 insertions(+), 47 deletions(-) create mode 100644 RWR/src/.gitignore delete mode 100644 RWR/src/read_event_pub/include/event_array_sub.h create mode 120000 RWR/src/read_event_pub/src/dvs_clustering_tracking/CMakeLists.txt create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/.gitignore create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/CMakeLists.txt create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/README.md create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/cmake/catkin_simple-extras.cmake.em create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/package.xml create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/.gitignore create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/include/bar/hello.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/msg/HeaderString.msg create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/package.xml create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/src/hello.cpp create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/baz/include/baz/world.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/baz/package.xml create mode 120000 RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/catkin_simple create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/foo/package.xml create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/foo/src/main.cpp create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/88-retina.rules create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/88-retinaDAVIS.rules create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/CMakeLists.txt create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/include/dvs_driver/dvs_driver.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/install.sh create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/installDAVIS.sh create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/package.xml create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/src/dvs_driver.cpp create mode 100644 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/.vscode/settings.json create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/CMakeLists.txt create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/dvs_meanshift/color_meanshift.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/dvs_meanshift/meanshift.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/convolve.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/disjoint-set.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/filter.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/image.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/imconv.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/imutil.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/misc.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/pnmfile.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/segment-graph.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/segment-image.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/segment.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/image_reconstruct/image_reconst.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/launch/dvs_mono.launch create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/launch/dvs_segmentation.launch create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/package.xml create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/color_meanshift.cpp create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/image_reconst.cpp create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/meanshift.cpp create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/meanshift_node.cpp create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/segment.cpp create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.cproject create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.gitignore create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.project create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.settings/language.settings.xml create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.settings/org.eclipse.cdt.codan.core.prefs create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/CMakeLists.txt create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/COPYING create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/ChangeLog create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/README create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/docs/.gitignore create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/docs/CMakeLists.txt create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/docs/libcaer_api.doxy.in create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/docs/libcaer_api_manual.pdf create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/.gitignore create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/README create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/davis_simple.c create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/davis_simple.cpp create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/dvs128_simple.c create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/dvs128_simple.cpp create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/.gitignore create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/CMakeLists.txt create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/devices/davis.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/devices/dvs128.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/devices/usb.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/common.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/config.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/ear.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/frame.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/imu6.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/imu9.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/packetContainer.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point1d.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point2d.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point3d.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point4d.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/polarity.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/sample.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/special.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/frame_utils.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/frame_utils_opencv.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/libcaer_in.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/log.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/portable_endian.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/libcaer.pc.in create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/libcaer_opencv.pc.in create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/.gitignore create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/CMakeLists.txt create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/c11threads_posix.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_common.c create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_common.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx2.c create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx2.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx3.c create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx3.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/device.c create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/dvs128.c create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/dvs128.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/events.c create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/frame_utils.c create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/frame_utils_opencv.cpp create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/log.c create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/ringbuffer/portable_aligned_alloc.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/ringbuffer/ringbuffer.c create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/ringbuffer/ringbuffer.h create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/65-inilabs.rules create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/CMakeLists.txt create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/cmake/libcaer-extras.cmake create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/install.sh create mode 100755 RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/package.xml create mode 160000 RWR/src/read_event_pub/src/dvs_clustering_tracking/rpg_dvs_ros diff --git a/RWR/src/.gitignore b/RWR/src/.gitignore new file mode 100644 index 0000000..7727a19 --- /dev/null +++ b/RWR/src/.gitignore @@ -0,0 +1,45 @@ +**/build/ +**/devel/ +**/logs/ +**/.catkin_tools/ +**/.catkin_workspace +**/~.bashrc + +# Prerequisites +*.d + +# Compiled Object files +**.slo +**.lo +**.o +**.obj + +# Precompiled Headers +**.gch +**.pch + +# Compiled Dynamic libraries +**.so +**.dylib +**.dll + +# Fortran module files +**.mod +**.smod + +# Compiled Static libraries +*.lai +*.la +*.a +*.lib + +# Executables +*.exe +*.out +*.app + +#vscode +**.vscode + +#valgrind +**.log.txt diff --git a/RWR/src/read_event_pub/include/event_array_sub.h b/RWR/src/read_event_pub/include/event_array_sub.h deleted file mode 100644 index d8d6a37..0000000 --- a/RWR/src/read_event_pub/include/event_array_sub.h +++ /dev/null @@ -1,47 +0,0 @@ -#ifndef EVENT_ARRAY_SUB_H_ -#define EVENT_ARRAY_SUB_H_ - -#define EVENT_ARRAY_PUBLISHERS 3 -#define EVENT_ARRAY_SUBSCRIBERS 1 - -#include <ros/ros.h> -#include <dvs_msgs/Event.h> -#include <dvs_msgs/EventArray.h> -#include <dvs_msgs/stats.h> - -namespace event_array_sub { - -class EventArraySub -{ - public: - EventArraySub(ros::NodeHandle& nh); - ~EventArraySub(); - - private: - ros::NodeHandle nh_; - - void eventsCallback(const dvs_msgs::EventArray::ConstPtr& msg); - - void publishEventStats(); - - ros::Subscriber event_sub_; - - struct EventDetection { - ros::Publisher events_[2]; - ros::Publisher dirLR_; - float xy_means_[1]; - size_t xy_variance[1]; - bool traject; - size_t msgSz; - }; - size_t votesLeft; - size_t votesRight; - size_t trajCounter; - - EventDetection event_detection_stats_; - uint8_t counter, nCounter; -}; - -} //namespace - -#endif //EVENT_ARRAY_SUB_H_ \ No newline at end of file diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/CMakeLists.txt b/RWR/src/read_event_pub/src/dvs_clustering_tracking/CMakeLists.txt new file mode 120000 index 0000000..581e61d --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/CMakeLists.txt @@ -0,0 +1 @@ +/opt/ros/kinetic/share/catkin/cmake/toplevel.cmake \ No newline at end of file diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/.gitignore b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/.gitignore new file mode 100755 index 0000000..0d20b64 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/.gitignore @@ -0,0 +1 @@ +*.pyc diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/CMakeLists.txt b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/CMakeLists.txt new file mode 100755 index 0000000..2bb0702 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/CMakeLists.txt @@ -0,0 +1,9 @@ +cmake_minimum_required(VERSION 2.8.3) +project(catkin_simple) + +find_package(catkin REQUIRED) + +catkin_package( + CATKIN_DEPENDS catkin + CFG_EXTRAS catkin_simple-extras.cmake +) diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/README.md b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/README.md new file mode 100755 index 0000000..5b9f13a --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/README.md @@ -0,0 +1,123 @@ +# catkin simple + +This `catkin` package is designed to make the `CMakeLists.txt` of other `catkin` packages simpler. + +## CMakeLists.txt Example + +Here is an example of a package `foo` which depends on other catkin packages: + +```cmake +cmake_minimum_required(VERSION 2.8.3) +project(foo) + +find_package(catkin_simple REQUIRED) + +catkin_simple() + +cs_add_library(my_lib src/my_lib.cpp) + +cs_add_executable(my_exec src/main.cpp) +target_link_libraries(my_exec my_lib) + +cs_install() + +cs_install_scripts(scripts/my_script.py) + +cs_export() +``` + +Lets break this down, line by line. + +First is the standard CMake header: + +```cmake +cmake_minimum_required(VERSION 2.8.3) +project(foo) +``` + +Which defines the minimum CMake version and the name of this project. + +Next comes the `find_package` of `catkin_simple`: + +```cmake +find_package(catkin_simple REQUIRED) +``` + +This is just like `find_package` for any other `catkin` package. This command is required. + +### catkin_simple() + +Then you invoke `catkin_simple`: + +```cmake +catkin_simple() +``` + +This macro call gathers your `build_depend`'s from the `package.xml` of your package, then does a `find_package(...)` on each of them. + +By default, `find_package(...)` is called with the `QUIET` option and without the `REQUIRED` option. That way, if any of the build_depend's are not `catkin` packages then they are simply ignored. This means that if you depend on a `caktin` package which is not on your system, `catkin_simple` will not warn you about this, because there is no way to know if it is a missing `catkin` package or a system dependency. If this is not the desired behaviour, calling `catkin_simple(ALL_DEPS_REQUIRED)` will call `find_package(...)` on each dependency *with* the `REQUIRED` option. + +Packages which are successfully found and identified to be `catkin` packages are added to a list of "catkin build dependencies" for your package. This list of build dependencies is passed to `find_package(catkin REQUIRED COMPONENTS ...)`. This command is required. + +Next, this macro adds the local `include` folder and any `catkin` include directories to the include path with CMake's `include_directories(...)` macro, but the local `include` folder is only added if it exists. + +Finally, this macro will discover and build any ROS messages, services, and actions which reside in the `msg`, `srv`, action `action` folders, respectively. The automatic discovery and building of messages/services is only done if your package `build_depend`'s on `message_generation`, and message generation will complain if your package does not run_depend on `message_runtime`. + +This macro discovers and builds [dynamic_reconfigure](http://wiki.ros.org/dynamic_reconfigure) config files from the `cfg` folder. The automatic discovery only works if your package `build_depend`'s on `dynamic_reconfigure`, and dynamic reconfigure will complain if your package does not run_depend on `dynamic_reconfigure`. + +### cs_add_library() + +Next we create a library: + +```cmake +cs_add_library(my_lib src/my_lib.cpp) +``` + +This call does a few things, first it calls directly through to the normal CMake macro `add_library`, then it calls `target_link_libraries(my_lib ${catkin_LIBRARIES})` to link your new library against any catkin libraries you have build depended on in your package.xml. Finally it does some bookkeeping so that your library target can be implicitly used later. + +### cs_add_executable() + +Next we add a new executable: + +```cmake +cs_add_executable(my_exec src/main.cpp) +target_link_libraries(my_exec my_lib) +``` + +This works just like `cs_add_library`, but it calls CMake's `add_executable(...)` instead. + +Notice that here we have to explicitly call `target_link_libraries` for linking against our library, this is because there is no way to enforce order of target creation. The executable is still automatically linked against the catkin libraries. + +### cs_install() + +Next we install everything: + +```cmake +cs_install() + +cs_install_scripts(scripts/my_script.py) +``` + +The first macro call creates an installation rule for any libraries and executables you created with `cs_` prefixed commands. That call can also take zero to many additional targets you wish to install which were created without the `cs_` prefixed commands. This command is optional. + +The second macro call creates an installation rule for the given scripts, installing them to `${prefix}/lib/${pkg_name}/`. This command is optional. + +### cs_export() + +Finally, we export everything: + +```cmake +cs_export() +``` + +This command calls `catkin_package(...)` under the hood, extending that call with any libraries created and catkin_depends found automatically with `catkin_simple`. You can also pass in your own arguments to `catkin_package(...)` through this command. This command is required. + +## Known Limitations + +There are several known assumptions and incorrect behaviors in `catkin_simple` which are a result of the trade-off of correctness for convenience. + +* There is no warning when a catkin package is not found during `find_package`. +* There is over linking, as all libraries of all dependencies are linked against all targets indiscriminately. +* Assumes that the `include` folder is meant to be in the include path. +* If new .msg or .srv files are added, they will not be detected until you force CMake to run again +* All targets have a target dependency on any downstream message generation, which results in sub-optimal parallelization of targets, as there are unnecessary dependencies created. diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/cmake/catkin_simple-extras.cmake.em b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/cmake/catkin_simple-extras.cmake.em new file mode 100755 index 0000000..989f9f9 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/cmake/catkin_simple-extras.cmake.em @@ -0,0 +1,226 @@ +# Generated from: catkin_simple/cmake/catkin_simple-extras.cmake.em + +if(_CATKIN_SIMPLE_EXTRAS_INCLUDED_) + return() +endif() +set(_CATKIN_SIMPLE_EXTRAS_INCLUDED_ TRUE) + +include(CMakeParseArguments) + +@[if DEVELSPACE]@ +# cmake dir in develspace +set(catkin_simple_CMAKE_DIR "@(CMAKE_CURRENT_SOURCE_DIR)/cmake") +@[else]@ +# cmake dir in installspace +set(catkin_simple_CMAKE_DIR "@(PKG_CMAKE_DIR)") +@[end if]@ + +macro(catkin_simple) + # Arguments + # ALL_DEPS_REQUIRED -- Add the "REQUIRED" flag when calling + # FIND_PACKAGE() for each dependency + cmake_parse_arguments(cs_args "ALL_DEPS_REQUIRED" "" "" ${ARGN}) + + if(TARGET ${PROJECT_NAME}_package) + message(WARNING "Could not create target '${${PROJECT_NAME}_package}' for project ${PROJECT_NAME}, as it already exists.") + endif() + add_custom_target(${PROJECT_NAME}_package) + set(${PROJECT_NAME}_TARGETS) + set(${PROJECT_NAME}_LIBRARIES) + + find_package(catkin REQUIRED) + # call catkin_package_xml() if it has not been called before + if(NOT _CATKIN_CURRENT_PACKAGE) + catkin_package_xml() + endif() + + set(${PROJECT_NAME}_CATKIN_BUILD_DEPENDS) + set(${PROJECT_NAME}_CATKIN_BUILD_DEPENDS_EXPORTED_TARGETS) + foreach(dep ${${PROJECT_NAME}_BUILD_DEPENDS}) + # If this flag is defined, add the "REQUIRED" flag + # to all FIND_PACKAGE calls + if(cs_args_ALL_DEPS_REQUIRED) + find_package(${dep} REQUIRED) + else() + find_package(${dep} QUIET) + endif() + + if(${dep}_FOUND_CATKIN_PROJECT) + list(APPEND ${PROJECT_NAME}_CATKIN_BUILD_DEPENDS ${dep}) + list(APPEND ${PROJECT_NAME}_CATKIN_BUILD_DEPENDS_EXPORTED_TARGETS ${${dep}_EXPORTED_TARGETS}) + endif() + endforeach() + + # Let find_package(catkin ...) do the heavy lifting + find_package(catkin REQUIRED COMPONENTS ${${PROJECT_NAME}_CATKIN_BUILD_DEPENDS}) + + # add include directory if available + set(${PROJECT_NAME}_LOCAL_INCLUDE_DIR ${CMAKE_CURRENT_SOURCE_DIR}/include) + if(NOT IS_DIRECTORY ${${PROJECT_NAME}_LOCAL_INCLUDE_DIR}) + set(${PROJECT_NAME}_LOCAL_INCLUDE_DIR) + endif() + include_directories(${${PROJECT_NAME}_LOCAL_INCLUDE_DIR} ${catkin_INCLUDE_DIRS}) + + # perform action/msg/srv generation if necessary + if(message_generation_FOUND_CATKIN_PROJECT) + set(${PROJECT_NAME}_DO_MESSAGE_GENERATION FALSE) + # add action files if available + set(${PROJECT_NAME}_LOCAL_ACTION_DIR ${CMAKE_CURRENT_SOURCE_DIR}/action) + if(NOT IS_DIRECTORY ${${PROJECT_NAME}_LOCAL_ACTION_DIR}) + set(${PROJECT_NAME}_LOCAL_ACTION_DIR) + endif() + if(${PROJECT_NAME}_LOCAL_ACTION_DIR) + add_action_files(DIRECTORY action) + set(${PROJECT_NAME}_DO_MESSAGE_GENERATION TRUE) + endif() + + # add message files if available + set(${PROJECT_NAME}_LOCAL_MSG_DIR ${CMAKE_CURRENT_SOURCE_DIR}/msg) + if(NOT IS_DIRECTORY ${${PROJECT_NAME}_LOCAL_MSG_DIR}) + set(${PROJECT_NAME}_LOCAL_MSG_DIR) + endif() + if(${PROJECT_NAME}_LOCAL_MSG_DIR) + add_message_files(DIRECTORY msg) + set(${PROJECT_NAME}_DO_MESSAGE_GENERATION TRUE) + endif() + + # add service files if available + set(${PROJECT_NAME}_LOCAL_SRV_DIR ${CMAKE_CURRENT_SOURCE_DIR}/srv) + if(NOT IS_DIRECTORY ${${PROJECT_NAME}_LOCAL_SRV_DIR}) + set(${PROJECT_NAME}_LOCAL_SRV_DIR) + endif() + if(${PROJECT_NAME}_LOCAL_SRV_DIR) + add_service_files(DIRECTORY srv) + set(${PROJECT_NAME}_DO_MESSAGE_GENERATION TRUE) + endif() + + # generate messages if necessary + if(${PROJECT_NAME}_DO_MESSAGE_GENERATION) + # identify all build dependencies which contain messages + set(${PROJECT_NAME}_MSG_PACKAGES) + foreach(dep ${${PROJECT_NAME}_CATKIN_BUILD_DEPENDS}) + set(${PROJECT_NAME}_MSG_PACKAGE_FILE ${${dep}_DIR}/${dep}-msg-paths.cmake) + if(EXISTS ${${PROJECT_NAME}_MSG_PACKAGE_FILE}) + list(APPEND ${PROJECT_NAME}_MSG_PACKAGES ${dep}) + endif() + endforeach() + generate_messages(DEPENDENCIES ${${PROJECT_NAME}_MSG_PACKAGES}) + # add additional exported targets coming from generate_messages() + list(INSERT ${PROJECT_NAME}_CATKIN_BUILD_DEPENDS_EXPORTED_TARGETS 0 ${${PROJECT_NAME}_EXPORTED_TARGETS}) + endif() + endif() + + # generate dynamic reconfigure files + if(dynamic_reconfigure_FOUND_CATKIN_PROJECT) + set(${PROJECT_NAME}_LOCAL_CFG_DIR ${CMAKE_CURRENT_SOURCE_DIR}/cfg) + if(IS_DIRECTORY ${${PROJECT_NAME}_LOCAL_CFG_DIR}) + # create a list containing all the cfg files + file(GLOB ${PROJECT_NAME}_LOCAL_CFG_FILES RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}" "${${PROJECT_NAME}_LOCAL_CFG_DIR}/*.cfg") + if(${PROJECT_NAME}_LOCAL_CFG_FILES) + generate_dynamic_reconfigure_options(${${PROJECT_NAME}_LOCAL_CFG_FILES}) + # add build dep on gencfg + list(APPEND ${PROJECT_NAME}_CATKIN_BUILD_DEPENDS_EXPORTED_TARGETS ${PROJECT_NAME}_gencfg) + endif() + endif() + endif() +endmacro() + +macro(cs_add_targets_to_package) + add_dependencies(${PROJECT_NAME}_package ${ARGN}) + list(APPEND ${PROJECT_NAME}_TARGETS ${ARGN}) +endmacro() + +macro(cs_add_executable _target) + if(${_target} STREQUAL ${PROJECT_NAME}_package) + message(WARNING "Could not create executable with name '${_target}' as '${PROJECT_NAME}_package' is reserved for the top level target name for this project.") + endif() + cmake_parse_arguments(cs_add_executable_args "NO_AUTO_LINK;NO_AUTO_DEP" "" "" ${ARGN}) + add_executable(${_target} ${cs_add_executable_args_UNPARSED_ARGUMENTS}) + if(NOT cs_add_executable_args_NO_AUTO_LINK) + target_link_libraries(${_target} ${catkin_LIBRARIES}) + endif() + if(NOT cs_add_executable_args_NO_AUTO_DEP) + if(NOT "${${PROJECT_NAME}_CATKIN_BUILD_DEPENDS_EXPORTED_TARGETS}" STREQUAL "") + add_dependencies(${_target} ${${PROJECT_NAME}_CATKIN_BUILD_DEPENDS_EXPORTED_TARGETS}) + endif() + endif() + cs_add_targets_to_package(${_target}) +endmacro() + +macro(cs_add_library _target) + if(${_target} STREQUAL ${PROJECT_NAME}_package) + message(WARNING "Could not create library with name '${_target}' as '${PROJECT_NAME}_package' is reserved for the top level target name for this project.") + endif() + cmake_parse_arguments(cs_add_library "NO_AUTO_LINK;NO_AUTO_DEP;NO_AUTO_EXPORT" "" "" ${ARGN}) + add_library(${_target} ${cs_add_library_UNPARSED_ARGUMENTS}) + if(NOT cs_add_library_NO_AUTO_LINK) + target_link_libraries(${_target} ${catkin_LIBRARIES}) + endif() + if(NOT cs_add_library_NO_AUTO_DEP) + if(NOT "${${PROJECT_NAME}_CATKIN_BUILD_DEPENDS_EXPORTED_TARGETS}" STREQUAL "") + add_dependencies(${_target} ${${PROJECT_NAME}_CATKIN_BUILD_DEPENDS_EXPORTED_TARGETS}) + endif() + endif() + if(NOT cs_add_library_NO_AUTO_EXPORT) + list(APPEND ${PROJECT_NAME}_LIBRARIES ${_target}) + endif() + cs_add_targets_to_package(${_target}) +endmacro() + +macro(cs_install) + # Install targets (exec's and lib's) + foreach(_target ${${PROJECT_NAME}_TARGETS}) + get_target_property(${_target}_type ${_target} TYPE) + message(STATUS "Marking ${${_target}_type} \"${_target}\" of package \"${PROJECT_NAME}\" for installation") + endforeach() + install(TARGETS ${${PROJECT_NAME}_TARGETS} ${ARGN} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + if(EXISTS ${${PROJECT_NAME}_LOCAL_INCLUDE_DIR}) + # Install include directory + message(STATUS "Marking HEADER FILES in \"include\" folder of package \"${PROJECT_NAME}\" for installation") + install(DIRECTORY ${${PROJECT_NAME}_LOCAL_INCLUDE_DIR}/ + DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" PATTERN "*.hpp" + PATTERN ".svn" EXCLUDE + ) + endif() + # Install shared content located in commonly used folders + set(_shared_content_folders launch rviz urdf meshes maps worlds Media param) + foreach(_folder ${_shared_content_folders}) + if(IS_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/${_folder}) + message(STATUS "Marking SHARED CONTENT FOLDER \"${_folder}\" of package \"${PROJECT_NAME}\" for installation") + install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/${_folder}/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${_folder} + ) + endif() + endforeach() +endmacro() + +macro(cs_install_scripts) + install(PROGRAMS ${ARGN} DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) +endmacro() + +macro(cs_export) + cmake_parse_arguments(CS_PROJECT + "" "" "INCLUDE_DIRS;LIBRARIES;CATKIN_DEPENDS;DEPENDS;CFG_EXTRAS" + ${ARGN}) + + set(${PROJECT_NAME}_CATKIN_RUN_DEPENDS) + foreach(dep ${${PROJECT_NAME}_RUN_DEPENDS}) + find_package(${dep} QUIET) + if(${dep}_FOUND_CATKIN_PROJECT) + list(APPEND ${PROJECT_NAME}_CATKIN_RUN_DEPENDS ${dep}) + endif() + endforeach() + + catkin_package( + INCLUDE_DIRS ${${PROJECT_NAME}_LOCAL_INCLUDE_DIR} ${CS_PROJECT_INCLUDE_DIRS} + LIBRARIES ${${PROJECT_NAME}_LIBRARIES} ${CS_PROJECT_LIBRARIES} + CATKIN_DEPENDS ${${PROJECT_NAME}_CATKIN_RUN_DEPENDS} ${CS_PROJECT_CATKIN_DEPENDS} + DEPENDS ${CS_PROJECT_DEPENDS} + CFG_EXTRAS ${CS_PROJECT_CFG_EXTRAS} + ) +endmacro() diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/package.xml b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/package.xml new file mode 100755 index 0000000..3f6e070 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/package.xml @@ -0,0 +1,17 @@ +<?xml version="1.0"?> +<package> + <name>catkin_simple</name> + <version>0.1.1</version> + <description>catkin, simpler</description> + + <maintainer email="william@osrfoundation.org">William Woodall</maintainer> + <maintainer email="dthomas@osrfoundation.org">Dirk Thomas</maintainer> + <license>BSD</license> + + <author email="william@osrfoundation.org">William Woodall</author> + <author email="dthomas@osrfoundation.org">Dirk Thomas</author> + + <buildtool_depend>catkin</buildtool_depend> + <run_depend>catkin</run_depend> + +</package> \ No newline at end of file diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/.gitignore b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/.gitignore new file mode 100755 index 0000000..a0f0008 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/.gitignore @@ -0,0 +1 @@ +CMakeLists.txt diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/include/bar/hello.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/include/bar/hello.h new file mode 100755 index 0000000..9bb085a --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/include/bar/hello.h @@ -0,0 +1 @@ +void hello(); diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/msg/HeaderString.msg b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/msg/HeaderString.msg new file mode 100755 index 0000000..9741bda --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/msg/HeaderString.msg @@ -0,0 +1,2 @@ +Header header +string data diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/package.xml b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/package.xml new file mode 100755 index 0000000..d98d6e9 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/package.xml @@ -0,0 +1,18 @@ +<?xml version="1.0"?> +<package> + <name>bar</name> + <version>0.1.0</version> + <description>The bar package</description> + <maintainer email="william@osrfoundation.org">William Woodall</maintainer> + <license>BSD</license> + + <buildtool_depend>catkin</buildtool_depend> + <buildtool_depend>catkin_simple</buildtool_depend> + <run_depend>boost</run_depend> + <run_depend>message_runtime</run_depend> + <run_depend>std_msgs</run_depend> + <build_depend>boost-dev</build_depend> + <build_depend>message_generation</build_depend> + <build_depend>std_msgs</build_depend> + +</package> \ No newline at end of file diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/src/hello.cpp b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/src/hello.cpp new file mode 100755 index 0000000..3aed965 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/bar/src/hello.cpp @@ -0,0 +1,16 @@ +#include <bar/hello.h> +#include <bar/HeaderString.h> + +#include <iostream> + +#include <boost/thread.hpp> + + +inline void print_hello() { + std::cout << "Hello "; +} + +void hello() { + boost::thread t(print_hello); + t.join(); +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/baz/include/baz/world.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/baz/include/baz/world.h new file mode 100755 index 0000000..766f82c --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/baz/include/baz/world.h @@ -0,0 +1,12 @@ +#include <iostream> + +#include <boost/thread.hpp> + +void print_world() { + std::cout << "world!" << std::endl; +} + +void world() { + boost::thread t(print_world); + t.join(); +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/baz/package.xml b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/baz/package.xml new file mode 100755 index 0000000..db0518e --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/baz/package.xml @@ -0,0 +1,13 @@ +<?xml version="1.0"?> +<package> + <name>baz</name> + <version>0.1.0</version> + <description>The baz package</description> + <maintainer email="william@osrfoundation.org">William Woodall</maintainer> + <license>BSD</license> + + <buildtool_depend>catkin</buildtool_depend> + <run_depend>boost</run_depend> + <build_depend>boost-dev</build_depend> + +</package> \ No newline at end of file diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/catkin_simple b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/catkin_simple new file mode 120000 index 0000000..a8a4f8c --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/catkin_simple @@ -0,0 +1 @@ +../../.. \ No newline at end of file diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/foo/package.xml b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/foo/package.xml new file mode 100755 index 0000000..16121e4 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/foo/package.xml @@ -0,0 +1,18 @@ +<?xml version="1.0"?> +<package> + <name>foo</name> + <version>0.1.0</version> + <description>The foo package</description> + <maintainer email="william@osrfoundation.org">William Woodall</maintainer> + <license>BSD</license> + + <buildtool_depend>catkin</buildtool_depend> + <buildtool_depend>catkin_simple</buildtool_depend> + <run_depend>bar</run_depend> + <build_depend>bar</build_depend> + <run_depend>baz</run_depend> + <build_depend>baz</build_depend> + <run_depend>boost</run_depend> + <build_depend>boost-dev</build_depend> + +</package> \ No newline at end of file diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/foo/src/main.cpp b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/foo/src/main.cpp new file mode 100755 index 0000000..3f59650 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/catkin_simple/test/scenarios/hello_world/foo/src/main.cpp @@ -0,0 +1,9 @@ +#include <bar/hello.h> +#include <baz/world.h> + +int main(void) { + hello(); + world(); + + return 0; +} \ No newline at end of file diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/88-retina.rules b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/88-retina.rules new file mode 100755 index 0000000..4fb8b2b --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/88-retina.rules @@ -0,0 +1,2 @@ +SUBSYSTEM=="usb|usb_device", ATTR{idVendor}=="152a", ATTR{idProduct}=="8400", MODE="0666", GROUP="plugdev" + diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/88-retinaDAVIS.rules b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/88-retinaDAVIS.rules new file mode 100755 index 0000000..d50c201 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/88-retinaDAVIS.rules @@ -0,0 +1,2 @@ +SUBSYSTEM=="usb|usb_device", ATTR{idVendor}=="152a", ATTR{idProduct}=="840d", MODE="0666", GROUP="plugdev" + diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/CMakeLists.txt b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/CMakeLists.txt new file mode 100755 index 0000000..500ecd8 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/CMakeLists.txt @@ -0,0 +1,45 @@ +cmake_minimum_required(VERSION 2.8.3) +project(dvs_driver) + +# search for everything we need to build the package +find_package(catkin) + +# since we need eigen and boost search them as well +find_package(Boost REQUIRED COMPONENTS thread) + +include(FindPkgConfig) +pkg_check_modules(LIBUSB1 REQUIRED libusb-1.0) + +# export the dependencis of this package for who ever depends on us +catkin_package( + INCLUDE_DIRS include ${LIBUSB1_INCLUDE_DIRS} + DEPENDS libusb-1.0 + LIBRARIES dvs_driver +) + +# tell catkin where to find the headers for this project +include_directories( + include + ${LIBUSB1_INCLUDE_DIRS} + ${Boost_INCLUDE_DIRS} +) + +# make the library +add_library(dvs_driver + src/dvs_driver.cpp +) + +target_link_libraries(dvs_driver + ${LIBUSB1_LIBRARIES} + ${Boost_LIBRARIES} +) + +install(TARGETS dvs_driver + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/include/dvs_driver/dvs_driver.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/include/dvs_driver/dvs_driver.h new file mode 100755 index 0000000..458cbe1 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/include/dvs_driver/dvs_driver.h @@ -0,0 +1,138 @@ +// This file is part of DVS-ROS - the RPG DVS ROS Package +// +// DVS-ROS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// DVS-ROS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with DVS-ROS. If not, see <http://www.gnu.org/licenses/>. + +#ifndef DVS_DRIVER_H_ +#define DVS_DRIVER_H_ + +#include <libusb-1.0/libusb.h> +#include <boost/thread.hpp> +#include <vector> +#include <iostream> +#include <map> +#include <string> +#include <stdio.h> + +namespace dvs { + +// DVS USB interface +#define DVS128_VID 0x152A +#define DVS128_PID 0x8400 //this is for DVS +//#define DVS128_PID 0x840D //this is for DAVIS +#define DVS128_DID_TYPE 0x00 + +#define USB_IO_ENDPOINT 0x86 + +// DVS data decoding masks +#define DVS128_POLARITY_SHIFT 0 +#define DVS128_POLARITY_MASK 0x0001 +#define DVS128_Y_ADDR_SHIFT 8 +#define DVS128_Y_ADDR_MASK 0x007F +#define DVS128_X_ADDR_SHIFT 1 +#define DVS128_X_ADDR_MASK 0x007F +#define DVS128_SYNC_EVENT_MASK 0x8000 + +// USB vendor requests +#define VENDOR_REQUEST_START_TRANSFER 0xB3 +#define VENDOR_REQUEST_STOP_TRANSFER 0xB4 +#define VENDOR_REQUEST_SEND_BIASES 0xB8 +#define VENDOR_REQUEST_SET_SYNC_ENABLED 0xBE +#define VENDOR_REQUEST_RESET_TIMESTAMPS 0xBB + +struct Event { + uint16_t x, y; + bool polarity; + uint64_t timestamp; +}; + +class DVS_Driver { +public: + DVS_Driver(std::string dvs_serial_number = "", bool master = true); + ~DVS_Driver(); + + std::vector<Event> get_events(); + + bool change_parameters(uint32_t cas, uint32_t injGnd, uint32_t reqPd, uint32_t puX, + uint32_t diffOff, uint32_t req, uint32_t refr, uint32_t puY, + uint32_t diffOn, uint32_t diff, uint32_t foll, uint32_t Pr); + + void callback(struct libusb_transfer *transfer); + + void resetTimestamps(); + + inline std::string get_camera_id() { + return camera_id; + } + +private: + bool change_parameter(std::string parameter, uint32_t value); + bool send_parameters(); + + bool open_device(std::string dvs_serial_number = ""); + void close_device(); + + boost::mutex event_buffer_mutex; + boost::mutex device_mutex; + boost::thread* thread; + void run(); + + void event_translator(uint8_t *buffer, size_t bytesSent); + + // USB handle and buffer + libusb_device_handle *device_handle; + struct libusb_transfer *transfer; + unsigned char *buffer; + + // event buffer + std::vector<dvs::Event> event_buffer; + + // buffers + static const uint32_t bufferNumber = 8; + static const uint32_t bufferSize = 4096; + + uint64_t wrapAdd; + uint64_t lastTimestamp; + + class Parameter { + public: + Parameter(uint32_t min = 0, uint32_t max = 0, uint32_t value = 0) : + _min(min), _max(max), _value(value) {} + + uint32_t get_value() { return _value; } + + bool set_value(uint32_t value) { + if (value >= _min && value <= _max) { + _value = value; + return true; + } + else { + return false; + } + } + private: + uint32_t _min; + uint32_t _max; + uint32_t _value; + + }; + + // parameters + std::map<std::string, Parameter> parameters; + + // camera name + std::string camera_id; +}; + +} // namespace +#endif diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/install.sh b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/install.sh new file mode 100755 index 0000000..9dcf4ea --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/install.sh @@ -0,0 +1,9 @@ +#!/bin/bash +echo "Copying udev rule (needs root privileges)." +sudo cp 88-retina.rules /etc/udev/rules.d/ + +echo "Reloading udev rules." +sudo udevadm control --reload-rules +sudo udevadm trigger + +echo "Done!" diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/installDAVIS.sh b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/installDAVIS.sh new file mode 100755 index 0000000..bcb8981 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/installDAVIS.sh @@ -0,0 +1,9 @@ +#!/bin/bash +echo "Copying udev rule (needs root privileges)." +sudo cp 88-retinaDAVIS.rules /etc/udev/rules.d/ + +echo "Reloading udev rules." +sudo udevadm control --reload-rules +sudo udevadm trigger + +echo "Done!" diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/package.xml b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/package.xml new file mode 100755 index 0000000..f0541b2 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/package.xml @@ -0,0 +1,13 @@ +<?xml version="1.0"?> +<package> + <name>dvs_driver</name> + <version>0.0.0</version> + <description>The dvs_driver package</description> + <maintainer email="mueggler@ifi.uzh.ch">Elias Mueggler</maintainer> + <license>GNU GPL</license> + + <buildtool_depend>catkin</buildtool_depend> + + <export> + </export> +</package> diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/src/dvs_driver.cpp b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/src/dvs_driver.cpp new file mode 100755 index 0000000..90b5c61 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_driver/src/dvs_driver.cpp @@ -0,0 +1,410 @@ +// This file is part of DVS-ROS - the RPG DVS ROS Package +// +// DVS-ROS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// DVS-ROS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with DVS-ROS. If not, see <http://www.gnu.org/licenses/>. + +#include "dvs_driver/dvs_driver.h" + +namespace dvs { + +extern "C" { + +static void callback_wrapper(struct libusb_transfer *transfer) +{ + DVS_Driver *dvs_driver = (DVS_Driver *)transfer->user_data; + + dvs_driver->callback(transfer); +} + +} // extern "C" + +DVS_Driver::DVS_Driver(std::string dvs_serial_number, bool master) { + // initialize parameters (min, max, value) + parameters.insert(std::pair<std::string, Parameter>("cas", Parameter(0, 16777215, 1992))); + parameters.insert(std::pair<std::string, Parameter>("injGnd", Parameter(0, 16777215, 1108364))); + parameters.insert(std::pair<std::string, Parameter>("reqPd", Parameter(0, 16777215, 16777215))); + parameters.insert(std::pair<std::string, Parameter>("puX", Parameter(0, 16777215, 8159221))); + parameters.insert(std::pair<std::string, Parameter>("diffOff", Parameter(0, 16777215, 132))); + parameters.insert(std::pair<std::string, Parameter>("req", Parameter(0, 16777215, 309590))); + parameters.insert(std::pair<std::string, Parameter>("refr", Parameter(0, 16777215, 969))); + parameters.insert(std::pair<std::string, Parameter>("puY", Parameter(0, 16777215, 16777215))); + parameters.insert(std::pair<std::string, Parameter>("diffOn", Parameter(0, 16777215, 209996))); + parameters.insert(std::pair<std::string, Parameter>("diff", Parameter(0, 16777215, 13125))); + parameters.insert(std::pair<std::string, Parameter>("foll", Parameter(0, 16777215, 271))); + parameters.insert(std::pair<std::string, Parameter>("Pr", Parameter(0, 16777215, 217))); + + wrapAdd = 0; + lastTimestamp = 0; + + libusb_init(NULL); + + device_mutex.lock(); + if (open_device(dvs_serial_number)) { + std::cout << "Opened DVS with the following identification: " << camera_id << std::endl; + } + else { + if (dvs_serial_number.empty()) { + std::cout << "Could not find any DVS..." << std::endl; + } + else { + std::cout << "Could not find DVS with serial number " << dvs_serial_number << "..." << std::endl; + } + } + device_mutex.unlock(); + + // put into slave mode? + if (!master) { + std::cout << "Setting camera (" << camera_id << ") as slave!" << std::endl; + device_mutex.lock(); + + unsigned char enabled[1]; + enabled[0] = 0; + + libusb_control_transfer(device_handle, LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE, + VENDOR_REQUEST_SET_SYNC_ENABLED, 0, 0, enabled, sizeof(enabled), 0); + device_mutex.unlock(); + } + + thread = new boost::thread(boost::bind(&DVS_Driver::run, this)); +} + +DVS_Driver::~DVS_Driver() { + device_mutex.lock(); + close_device(); + device_mutex.unlock(); +} + +bool DVS_Driver::open_device(std::string dvs_serial_number) { + + // get device list + libusb_device **list = NULL; + ssize_t count = libusb_get_device_list(NULL, &list); + + // iterate over all USB devices + for (size_t idx = 0; idx < count; ++idx) { + libusb_device *device = list[idx]; + libusb_device_descriptor desc = {0}; + + int rc = libusb_get_device_descriptor(device, &desc); + assert(rc == 0); + +// printf("Vendor:Device = %04x:%04x\n", desc.idVendor, desc.idProduct); + + if (DVS128_VID == desc.idVendor && DVS128_PID == desc.idProduct) { + + // Open device to see its serial number + int e = libusb_open(device, &device_handle); + if (e) { + printf("Error opening device... Error code: %d", e); + continue; + } + + unsigned char sSerial[256]; + + e = libusb_get_string_descriptor_ascii(device_handle, desc.iSerialNumber, sSerial, sizeof(sSerial)); + if (e < 0) { + std::cout << "libusb: get error code: " << e << std::endl; + libusb_close(device_handle); + } + + if (std::string(reinterpret_cast<char*>(sSerial)) == dvs_serial_number || dvs_serial_number.empty()) { + + // claim interface + libusb_claim_interface(device_handle, 0); + + // figure out precise product + unsigned char sProduct[256]; + e = libusb_get_string_descriptor_ascii(device_handle, desc.iProduct, sProduct, sizeof(sProduct)); + if (e < 0) { + std::cout << "libusb: get error code: " << e << std::endl; + libusb_close(device_handle); + } + + camera_id = std::string(reinterpret_cast<char*>(sProduct)) + "-" + std::string(reinterpret_cast<char*>(sSerial)); + + // alloc transfer and setup + transfer = libusb_alloc_transfer(0); + + transfer->length = (int) bufferSize; + buffer = new unsigned char[bufferSize]; + transfer->buffer = buffer; + + transfer->dev_handle = device_handle; + transfer->endpoint = USB_IO_ENDPOINT; + transfer->type = LIBUSB_TRANSFER_TYPE_BULK; + transfer->callback = callback_wrapper; + transfer->user_data = this; + transfer->timeout = 0; + transfer->flags = LIBUSB_TRANSFER_FREE_BUFFER; + + // libusb_submit_transfer(transfer); + int status = libusb_submit_transfer(transfer); + if (status != LIBUSB_SUCCESS) { + std::cout << "Unable to submit libusb transfer: " << status << std::endl; + + // The transfer buffer is freed automatically here thanks to + // the LIBUSB_TRANSFER_FREE_BUFFER flag set above. + libusb_free_transfer(transfer); + } + + return true; + } + + libusb_close(device_handle); + } + } + return false; +} + +void DVS_Driver::close_device() { + // stop thread + thread->join(); + + // close transfer + int status = libusb_cancel_transfer(transfer); + if (status != LIBUSB_SUCCESS && status != LIBUSB_ERROR_NOT_FOUND) { + std::cout << "Unable to cancel libusb transfer: " << status << std::endl; + } + + libusb_close(device_handle); + libusb_exit(NULL); +} + +void DVS_Driver::run() { + timeval te; + te.tv_sec = 0; + te.tv_usec = 1000000; + + libusb_control_transfer(device_handle, + LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE, + VENDOR_REQUEST_START_TRANSFER, 0, 0, NULL, 0, 0); + + try { + int completed; + while(true) { + device_mutex.lock(); + libusb_handle_events_timeout(NULL, &te); + device_mutex.unlock(); + } + } + catch(boost::thread_interrupted const& ) { + //clean resources + std::cout << "Worker thread interrupted!" << std::endl; + } + + libusb_control_transfer(device_handle, + LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE, + VENDOR_REQUEST_STOP_TRANSFER, 0, 0, NULL, 0, 0); +} + +void DVS_Driver::callback(struct libusb_transfer *transfer) { + if (transfer->status == LIBUSB_TRANSFER_COMPLETED) { + // Handle data. + event_buffer_mutex.lock(); + event_translator(transfer->buffer, (size_t) transfer->actual_length); + event_buffer_mutex.unlock(); + } + + if (transfer->status != LIBUSB_TRANSFER_CANCELLED && transfer->status != LIBUSB_TRANSFER_NO_DEVICE) { + // Submit transfer again. + if (libusb_submit_transfer(transfer) == LIBUSB_SUCCESS) { + return; + } + } + + // Cannot recover (cancelled, no device, or other critical error). + // Signal this by adjusting the counter, free and exit. + libusb_free_transfer(transfer); +} + +void DVS_Driver::event_translator(uint8_t *buffer, size_t bytesSent) { + // Truncate off any extra partial event. + bytesSent &= (size_t) ~0x03; + + for (size_t i = 0; i < bytesSent; i += 4) { + if ((buffer[i + 3] & 0x80) == 0x80) { + // timestamp bit 15 is one -> wrap: now we need to increment + // the wrapAdd, uses only 14 bit timestamps + wrapAdd += 0x4000; + + // Detect big timestamp wrap-around. + if (wrapAdd == 0) { + // Reset lastTimestamp to zero at this point, so we can again + // start detecting overruns of the 32bit value. + lastTimestamp = 0; + } + } + else if ((buffer[i + 3] & 0x40) == 0x40) { + // timestamp bit 14 is one -> wrapAdd reset: this firmware + // version uses reset events to reset timestamps + wrapAdd = 0; + lastTimestamp = 0; + } + else { + // address is LSB MSB (USB is LE) + uint16_t addressUSB = le16toh(*((uint16_t * ) (&buffer[i]))); + + // same for timestamp, LSB MSB (USB is LE) + // 15 bit value of timestamp in 1 us tick + uint16_t timestampUSB = le16toh(*((uint16_t * ) (&buffer[i + 2]))); + + // Expand to 32 bits. (Tick is 1µs already.) + uint64_t timestamp = timestampUSB + wrapAdd; + + // Check monotonicity of timestamps. + if (timestamp < lastTimestamp) { + std::cout << "DVS128: non-monotonic time-stamp detected: lastTimestamp=" << lastTimestamp << ", timestamp=" << timestamp << "." << std::endl; + } + + lastTimestamp = timestamp; + + // Special Trigger Event (MSB is set) + if ((addressUSB & DVS128_SYNC_EVENT_MASK) != 0) { + std::cout << "got sync event on camera " << camera_id << "at " << timestamp << std::endl; + } + else { + // Invert x values (flip along the x axis). + uint16_t x = (uint16_t) (127 - ((uint16_t) ((addressUSB >> DVS128_X_ADDR_SHIFT) & DVS128_X_ADDR_MASK))); + uint16_t y = (uint16_t) (127 - ((uint16_t) ((addressUSB >> DVS128_Y_ADDR_SHIFT) & DVS128_Y_ADDR_MASK))); + bool polarity = (((addressUSB >> DVS128_POLARITY_SHIFT) & DVS128_POLARITY_MASK) == 0) ? (1) : (0); + + // std::cout << "Event: <x, y, t, p> = <" << x << ", " << y << ", " << timestamp << ", " << polarity << ">" << std::endl; + Event e; + e.x = x; + e.y = y; + e.timestamp = timestamp; + e.polarity = polarity; + event_buffer.push_back(e); + } + } + } +} + +std::vector<Event> DVS_Driver::get_events() { + event_buffer_mutex.lock(); + std::vector<Event> buffer_copy = event_buffer; + event_buffer.clear(); + event_buffer_mutex.unlock(); + return buffer_copy; +} + +void DVS_Driver::resetTimestamps() { + device_mutex.lock(); + libusb_control_transfer(device_handle, LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE, + VENDOR_REQUEST_RESET_TIMESTAMPS, 0, 0, NULL, 0, 0); + device_mutex.unlock(); +} + +bool DVS_Driver::change_parameter(std::string parameter, uint32_t value) { + // does parameter exist? + if (parameters.find(parameter) != parameters.end()) { + // did it change? (only if within range) + if (parameters[parameter].set_value(value)) { + return true; + } + else + return false; + } + else + return false; +} + +bool DVS_Driver::change_parameters(uint32_t cas, uint32_t injGnd, uint32_t reqPd, uint32_t puX, + uint32_t diffOff, uint32_t req, uint32_t refr, uint32_t puY, + uint32_t diffOn, uint32_t diff, uint32_t foll, uint32_t Pr) { + change_parameter("cas", cas); + change_parameter("injGnd", injGnd); + change_parameter("reqPd", reqPd); + change_parameter("puX", puX); + change_parameter("diffOff", diffOff); + change_parameter("req", req); + change_parameter("refr", refr); + change_parameter("puY", puY); + change_parameter("diffOn", diffOn); + change_parameter("diff", diff); + change_parameter("foll", foll); + change_parameter("Pr", Pr); + + return send_parameters(); +} + +bool DVS_Driver::send_parameters() { + uint8_t biases[12 * 3]; + + uint32_t cas = parameters["cas"].get_value(); + biases[0] = (uint8_t) (cas >> 16); + biases[1] = (uint8_t) (cas >> 8); + biases[2] = (uint8_t) (cas >> 0); + + uint32_t injGnd = parameters["injGnd"].get_value(); + biases[3] = (uint8_t) (injGnd >> 16); + biases[4] = (uint8_t) (injGnd >> 8); + biases[5] = (uint8_t) (injGnd >> 0); + + uint32_t reqPd = parameters["reqPd"].get_value(); + biases[6] = (uint8_t) (reqPd >> 16); + biases[7] = (uint8_t) (reqPd >> 8); + biases[8] = (uint8_t) (reqPd >> 0); + + uint32_t puX = parameters["puX"].get_value(); + biases[9] = (uint8_t) (puX >> 16); + biases[10] = (uint8_t) (puX >> 8); + biases[11] = (uint8_t) (puX >> 0); + + uint32_t diffOff = parameters["diffOff"].get_value(); + biases[12] = (uint8_t) (diffOff >> 16); + biases[13] = (uint8_t) (diffOff >> 8); + biases[14] = (uint8_t) (diffOff >> 0); + + uint32_t req = parameters["req"].get_value(); + biases[15] = (uint8_t) (req >> 16); + biases[16] = (uint8_t) (req >> 8); + biases[17] = (uint8_t) (req >> 0); + + uint32_t refr = parameters["refr"].get_value(); + biases[18] = (uint8_t) (refr >> 16); + biases[19] = (uint8_t) (refr >> 8); + biases[20] = (uint8_t) (refr >> 0); + + uint32_t puY = parameters["puY"].get_value(); + biases[21] = (uint8_t) (puY >> 16); + biases[22] = (uint8_t) (puY >> 8); + biases[23] = (uint8_t) (puY >> 0); + + uint32_t diffOn = parameters["diffOn"].get_value(); + biases[24] = (uint8_t) (diffOn >> 16); + biases[25] = (uint8_t) (diffOn >> 8); + biases[26] = (uint8_t) (diffOn >> 0); + + uint32_t diff = parameters["diff"].get_value(); + biases[27] = (uint8_t) (diff >> 16); + biases[28] = (uint8_t) (diff >> 8); + biases[29] = (uint8_t) (diff >> 0); + + uint32_t foll = parameters["foll"].get_value(); + biases[30] = (uint8_t) (foll >> 16); + biases[31] = (uint8_t) (foll >> 8); + biases[32] = (uint8_t) (foll >> 0); + + uint32_t Pr = parameters["Pr"].get_value(); + biases[33] = (uint8_t) (Pr >> 16); + biases[34] = (uint8_t) (Pr >> 8); + biases[35] = (uint8_t) (Pr >> 0); + + device_mutex.lock(); + libusb_control_transfer(device_handle, LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE, + VENDOR_REQUEST_SEND_BIASES, 0, 0, biases, sizeof(biases), 0); + device_mutex.unlock(); +} + +} // namespace diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/.vscode/settings.json b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/.vscode/settings.json new file mode 100644 index 0000000..c925ebc --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/.vscode/settings.json @@ -0,0 +1,3 @@ +{ + "C_Cpp.intelliSenseEngineFallback": "Disabled" +} \ No newline at end of file diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/CMakeLists.txt b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/CMakeLists.txt new file mode 100755 index 0000000..0861ef2 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/CMakeLists.txt @@ -0,0 +1,76 @@ +cmake_minimum_required(VERSION 2.8.3) +project(dvs_meanshift) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + cv_bridge + dvs_msgs + image_transport + pcl_ros + roscpp + rospy + sensor_msgs + std_msgs +) + +## System dependencies are found with CMake's conventions +find_package(Boost REQUIRED) +find_package(OpenCV REQUIRED) +find_package(PCL 1.7 REQUIRED) + +include_directories(${PCL_INCLUDE_DIRS}) +link_directories(${PCL_LIBRARY_DIRS}) +add_definitions(${PCL_DEFINITIONS}) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## 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 dvs_meanshift + CATKIN_DEPENDS cv_bridge dvs_msgs image_transport pcl_ros roscpp rospy sensor_msgs std_msgs + DEPENDS OpenCV boost +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +# include_directories(include) +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${OpenCV_INCLUDE_DIRS} + ${Boost_INCLUDE_DIRS} +) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(dvs_meanshift ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +# add_executable(dvs_meanshift_node src/dvs_meanshift_node.cpp) + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(dvs_meanshift_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +# target_link_libraries(dvs_meanshift_node +# ${catkin_LIBRARIES} +# ) + +add_executable(dvs_meanshift src/meanshift.cpp src/meanshift_node.cpp src/color_meanshift.cpp src/segment.cpp src/image_reconst.cpp) +target_link_libraries(dvs_meanshift ${catkin_LIBRARIES} ${PCL_COMMON_LIBRARIES} ${PCL_IO_LIBRARIES} ${OpenCV_LIBS}) +add_dependencies(dvs_meanshift ${catkin_EXPORTED_TARGETS} ) diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/dvs_meanshift/color_meanshift.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/dvs_meanshift/color_meanshift.h new file mode 100755 index 0000000..bd20d1b --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/dvs_meanshift/color_meanshift.h @@ -0,0 +1,18 @@ +/* + * color_meanshift.h + * + * Created on: Nov 2, 2016 + * Author: fran + */ + +#ifndef COLOR_MEANSHIFT_H_ +#define COLOR_MEANSHIFT_H_ + +#include <ros/ros.h> +#include <opencv2/core/core.hpp> + +void colorMeanShiftFilt(double *newPixelsPtr, const double *pixelsPtr, int mPixels, int maxPixelDim, const double *imagePtr, int numRows, int numCols, float spaceDivider, char *kernelFun, int maxIterNum, float tolFun); +//void colorMeanShiftFilt(double *newPixelsPtr, const double *pixelsPtr, int mPixels, int maxPixelDim, const double *imagePtr, int numRows, int numCols, float spaceDivider, char *kernelFun, int maxIterNum, float tolFun, double *newImagePtr); +void meanshiftCluster_Gaussian(cv::Mat dataPts, std::vector<double> *clusterCenterX, std::vector<double> *clusterCenterY, std::vector<double> *clusterCenterZ, std::vector<int> *point2Clusters, double bandwidth); + +#endif /* COLOR_MEANSHIFT_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/dvs_meanshift/meanshift.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/dvs_meanshift/meanshift.h new file mode 100755 index 0000000..d8197cf --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/dvs_meanshift/meanshift.h @@ -0,0 +1,151 @@ +/* + * dvs_meanshift.h + * + * Created on: Nov 2, 2016 + * Author: fran + */ + +#ifndef MEANSHIFT_H_ +#define MEANSHIFT_H_ + +#include <ros/ros.h> +#include <iostream> +#include <image_transport/image_transport.h> +#include <cv_bridge/cv_bridge.h> +#include <sensor_msgs/CameraInfo.h> +#include <sensor_msgs/Image.h> +#include <sensor_msgs/image_encodings.h> + +#include <opencv2/core/core.hpp> +#include <opencv2/imgproc/imgproc.hpp> +#include <opencv2/photo/photo.hpp> +#include <opencv2/highgui/highgui.hpp> +#include <opencv2/video/video.hpp> + +#include <dvs_msgs/Event.h> +#include <dvs_msgs/EventArray.h> +#include "graph3d/segment.h" + +#define TEST 0 +#define KALMAN_FILTERING 1 +#define BG_FILTERING 1 + + +#define DVSW 240 //240 +#define DVSH 180 //180 + +//#define DVSW 240 +//#define DVSH 180 + +namespace dvs_meanshift +{ + +class Meanshift { +public: + Meanshift(ros::NodeHandle & nh, ros::NodeHandle nh_private); + virtual ~Meanshift(); + +private: + ros::NodeHandle nh_; + + void cameraInfoCallback(const sensor_msgs::CameraInfo::ConstPtr& msg); + void eventsCallback(const dvs_msgs::EventArray::ConstPtr& msg); + void eventsCallback_simple(const dvs_msgs::EventArray::ConstPtr& msg); + + //void assignClusterColor(std::vector<int> * positionClusterColor, int numClusters, std::vector<int> matches, std::vector<int> oldPositions); + void assignClusterColor(std::vector<int> * positionClusterColor, int numClusters, std::vector<int> matches, std::vector<int> oldPositions, std::vector<int> activeTrajectories); + //void createKalmanFilter(); + void createKalmanFilter(cv::KalmanFilter *kf, cv::Mat *state, cv::Mat *meas); + + int lastPositionClusterColor; + + cv::Mat camera_matrix_, dist_coeffs_; + + ros::Subscriber event_sub_; + ros::Subscriber camera_info_sub_; + + image_transport::Publisher image_pub_; + image_transport::Publisher image_segmentation_pub_; + + + //DEBUG + image_transport::Publisher image_debug1_pub_; + image_transport::Publisher image_debug2_pub_; + //NOT DEBUG + + + cv::Mat last_image_; + bool used_last_image_; + + enum DisplayMethod + { + GRAYSCALE, RED_BLUE + } display_method_; + + //Meanshift params + //computing image calibration + double *outputFeatures; + int mPixels, maxPixelDim; + double *pixelsPtr; + double *imagePtr; + //double *positionsPtr; + double *initializationPtr; + int numRows, numCols, maxIterNum; + float spaceDivider, timeDivider; + char kernelFun[8]; + float tolFun; + + //Params for graph3d segmentation + static const int MAX_NUM_CLUSTERS = 256; + static const int MAX_NUM_TRAJECTORY_POINTS=16; + std::vector<cv::Vec3b> RGBColors; + std::vector<cv::Point> *allTrajectories; //It is an array of vectors of Points for storing trajectories (a maximum of 8 points should be stored) + std::vector<int> counterTrajectories; //It stores the last position occupied for each trajectory in allTrajectories + + float sigma; + int k; + int min_region; + int num_components; + + //Clusters + std::vector<double> prev_clustCentX, prev_clustCentY, prev_clustCentZ; + std::vector<int> prev_positionClusterColor; + std::vector<int> clustColor; + std::vector<int> prev_activeTrajectories; + + //Trajectories + //cv::Mat trajectories=cv::Mat(DVSH, DVSW, CV_8UC3); + cv::Mat trajectories; + + //Kalman filter parameters + //cv::KalmanFilter kf; + //cv::Mat state; + //cv::Mat meas; + + std::vector<cv::KalmanFilter> vector_of_kf; + std::vector<cv::Mat> vector_of_state; + std::vector<cv::Mat> vector_of_meas; + + //bool foundBlobs; + std::vector<bool> vector_of_foundBlobs; + int notFoundBlobsCount; + std::vector<bool> foundTrajectory; + //bool foundTrajectory; + int selectedTrajectory; + //double ticks; + std::vector<double> vector_of_ticks; + + //frame of times + cv::Mat BGAFframe; + + //Variance stuff + std::vector<uint64_t> preVariance(MAX_NUM_CLUSTERS-1, 0); + std::vector<uint32_t> counterFor(MAX_NUM_CLUSTERS-1, 0); + std::vector<uint32_t> counterBar(MAX_NUM_CLUSTERS-1, 0); + //Robot movement + ros::Publisher dirUB; +}; + +} // namespace + +#endif // MEANSHIFT_H_ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/convolve.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/convolve.h new file mode 100755 index 0000000..6c2a773 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/convolve.h @@ -0,0 +1,69 @@ +/* +Copyright (C) 2006 Pedro Felzenszwalb + +This program is free software; you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation; either version 2 of the License, or +(at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program; if not, write to the Free Software +Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +/* convolution */ + +#ifndef CONVOLVE_H +#define CONVOLVE_H + +#include <vector> +#include <algorithm> +#include <cmath> +#include "graph3d/image.h" + +/* convolve src with mask. dst is flipped! */ +static void convolve_even(image<float> *src, image<float> *dst, + std::vector<float> &mask) { + int width = src->width(); + int height = src->height(); + int len = mask.size(); + + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + float sum = mask[0] * imRef(src, x, y); + for (int i = 1; i < len; i++) { + sum += mask[i] * + (imRef(src, std::max(x-i,0), y) + + imRef(src, std::min(x+i, width-1), y)); + } + imRef(dst, y, x) = sum; + } + } +} + +/* convolve src with mask. dst is flipped! */ +static void convolve_odd(image<float> *src, image<float> *dst, + std::vector<float> &mask) { + int width = src->width(); + int height = src->height(); + int len = mask.size(); + + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + float sum = mask[0] * imRef(src, x, y); + for (int i = 1; i < len; i++) { + sum += mask[i] * + (imRef(src, std::max(x-i,0), y) - + imRef(src, std::min(x+i, width-1), y)); + } + imRef(dst, y, x) = sum; + } + } +} + +#endif diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/disjoint-set.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/disjoint-set.h new file mode 100755 index 0000000..061b68c --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/disjoint-set.h @@ -0,0 +1,79 @@ +/* +Copyright (C) 2006 Pedro Felzenszwalb + +This program is free software; you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation; either version 2 of the License, or +(at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program; if not, write to the Free Software +Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#ifndef DISJOINT_SET +#define DISJOINT_SET + +// disjoint-set forests using union-by-rank and path compression (sort of). + +typedef struct { + int rank; + int p; + int size; +} uni_elt; + +class universe { +public: + universe(int elements); + ~universe(); + int find(int x); + void join(int x, int y); + int size(int x) const { return elts[x].size; } + int num_sets() const { return num; } + +private: + uni_elt *elts; + int num; +}; + +universe::universe(int elements) { + elts = new uni_elt[elements]; + num = elements; + for (int i = 0; i < elements; i++) { + elts[i].rank = 0; + elts[i].size = 1; + elts[i].p = i; + } +} + +universe::~universe() { + delete [] elts; +} + +int universe::find(int x) { + int y = x; + while (y != elts[y].p) + y = elts[y].p; + elts[x].p = y; + return y; +} + +void universe::join(int x, int y) { + if (elts[x].rank > elts[y].rank) { + elts[y].p = x; + elts[x].size += elts[y].size; + } else { + elts[x].p = y; + elts[y].size += elts[x].size; + if (elts[x].rank == elts[y].rank) + elts[y].rank++; + } + num--; +} + +#endif diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/filter.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/filter.h new file mode 100755 index 0000000..438c5ac --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/filter.h @@ -0,0 +1,100 @@ +/* +Copyright (C) 2006 Pedro Felzenszwalb + +This program is free software; you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation; either version 2 of the License, or +(at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program; if not, write to the Free Software +Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +/* simple filters */ + +#ifndef FILTER_H +#define FILTER_H + +#include <vector> +#include <cmath> +#include "graph3d/image.h" +#include "graph3d/misc.h" +#include "graph3d/convolve.h" +#include "graph3d/imconv.h" + +#define WIDTH 4.0 + +/* normalize mask so it integrates to one */ +static void normalize(std::vector<float> &mask) { + int len = mask.size(); + float sum = 0; + for (int i = 1; i < len; i++) { + sum += fabs(mask[i]); + } + sum = 2*sum + fabs(mask[0]); + for (int i = 0; i < len; i++) { + mask[i] /= sum; + } +} + +/* make filters */ +#define MAKE_FILTER(name, fun) \ +static std::vector<float> make_ ## name (float sigma) { \ + sigma = std::max(sigma, 0.01F); \ + int len = (int)ceil(sigma * WIDTH) + 1; \ + std::vector<float> mask(len); \ + for (int i = 0; i < len; i++) { \ + mask[i] = fun; \ + } \ + return mask; \ +} + +MAKE_FILTER(fgauss, exp(-0.5*square(i/sigma))); + +/* convolve image with gaussian filter */ +static image<float> *smooth(image<float> *src, float sigma) { + std::vector<float> mask = make_fgauss(sigma); + normalize(mask); + + image<float> *tmp = new image<float>(src->height(), src->width(), false); + image<float> *dst = new image<float>(src->width(), src->height(), false); + convolve_even(src, tmp, mask); + convolve_even(tmp, dst, mask); + + delete tmp; + return dst; +} + +/* convolve image with gaussian filter */ +image<float> *smooth(image<uchar> *src, float sigma) { + image<float> *tmp = imageUCHARtoFLOAT(src); + image<float> *dst = smooth(tmp, sigma); + delete tmp; + return dst; +} + +/* compute laplacian */ +static image<float> *laplacian(image<float> *src) { + int width = src->width(); + int height = src->height(); + image<float> *dst = new image<float>(width, height); + + for (int y = 1; y < height-1; y++) { + for (int x = 1; x < width-1; x++) { + float d2x = imRef(src, x-1, y) + imRef(src, x+1, y) - + 2*imRef(src, x, y); + float d2y = imRef(src, x, y-1) + imRef(src, x, y+1) - + 2*imRef(src, x, y); + imRef(dst, x, y) = d2x + d2y; + } + } + return dst; +} + +#endif diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/image.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/image.h new file mode 100755 index 0000000..c542465 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/image.h @@ -0,0 +1,101 @@ +/* +Copyright (C) 2006 Pedro Felzenszwalb + +This program is free software; you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation; either version 2 of the License, or +(at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program; if not, write to the Free Software +Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +/* a simple image class */ + +#ifndef IMAGE_H +#define IMAGE_H + +#include <cstring> + +template <class T> +class image { + public: + /* create an image */ + image(const int width, const int height, const bool init = true); + + /* delete an image */ + ~image(); + + /* init an image */ + void init(const T &val); + + /* copy an image */ + image<T> *copy() const; + + /* get the width of an image. */ + int width() const { return w; } + + /* get the height of an image. */ + int height() const { return h; } + + /* image data. */ + T *data; + + /* row pointers. */ + T **access; + + private: + int w, h; +}; + +/* use imRef to access image data. */ +#define imRef(im, x, y) (im->access[y][x]) + +/* use imPtr to get pointer to image data. */ +#define imPtr(im, x, y) &(im->access[y][x]) + +template <class T> +image<T>::image(const int width, const int height, const bool init) { + w = width; + h = height; + data = new T[w * h]; // allocate space for image data + access = new T*[h]; // allocate space for row pointers + + // initialize row pointers + for (int i = 0; i < h; i++) + access[i] = data + (i * w); + + if (init) + memset(data, 0, w * h * sizeof(T)); +} + +template <class T> +image<T>::~image() { + delete [] data; + delete [] access; +} + +template <class T> +void image<T>::init(const T &val) { + T *ptr = imPtr(this, 0, 0); + T *end = imPtr(this, w-1, h-1); + while (ptr <= end) + *ptr++ = val; +} + + +template <class T> +image<T> *image<T>::copy() const { + image<T> *im = new image<T>(w, h, false); + memcpy(im->data, data, w * h * sizeof(T)); + return im; +} + +#endif + diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/imconv.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/imconv.h new file mode 100755 index 0000000..ba78bcc --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/imconv.h @@ -0,0 +1,177 @@ +/* +Copyright (C) 2006 Pedro Felzenszwalb + +This program is free software; you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation; either version 2 of the License, or +(at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program; if not, write to the Free Software +Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +/* image conversion */ + +#ifndef CONV_H +#define CONV_H + +#include <climits> +#include "graph3d/image.h" +#include "graph3d/imutil.h" +#include "graph3d/misc.h" + +#define RED_WEIGHT 0.299 +#define GREEN_WEIGHT 0.587 +#define BLUE_WEIGHT 0.114 + +static image<uchar> *imageRGBtoGRAY(image<rgb> *input) { + int width = input->width(); + int height = input->height(); + image<uchar> *output = new image<uchar>(width, height, false); + + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + imRef(output, x, y) = (uchar) + (imRef(input, x, y).r * RED_WEIGHT + + imRef(input, x, y).g * GREEN_WEIGHT + + imRef(input, x, y).b * BLUE_WEIGHT); + } + } + return output; +} + +static image<rgb> *imageGRAYtoRGB(image<uchar> *input) { + int width = input->width(); + int height = input->height(); + image<rgb> *output = new image<rgb>(width, height, false); + + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + imRef(output, x, y).r = imRef(input, x, y); + imRef(output, x, y).g = imRef(input, x, y); + imRef(output, x, y).b = imRef(input, x, y); + } + } + return output; +} + +static image<float> *imageUCHARtoFLOAT(image<uchar> *input) { + int width = input->width(); + int height = input->height(); + image<float> *output = new image<float>(width, height, false); + + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + imRef(output, x, y) = imRef(input, x, y); + } + } + return output; +} + +static image<float> *imageINTtoFLOAT(image<int> *input) { + int width = input->width(); + int height = input->height(); + image<float> *output = new image<float>(width, height, false); + + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + imRef(output, x, y) = imRef(input, x, y); + } + } + return output; +} + +static image<uchar> *imageFLOATtoUCHAR(image<float> *input, + float min, float max) { + int width = input->width(); + int height = input->height(); + image<uchar> *output = new image<uchar>(width, height, false); + + if (max == min) + return output; + + float scale = UCHAR_MAX / (max - min); + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + uchar val = (uchar)((imRef(input, x, y) - min) * scale); + imRef(output, x, y) = bound(val, (uchar)0, (uchar)UCHAR_MAX); + } + } + return output; +} + +static image<uchar> *imageFLOATtoUCHAR(image<float> *input) { + float min, max; + min_max(input, &min, &max); + return imageFLOATtoUCHAR(input, min, max); +} + +static image<long> *imageUCHARtoLONG(image<uchar> *input) { + int width = input->width(); + int height = input->height(); + image<long> *output = new image<long>(width, height, false); + + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + imRef(output, x, y) = imRef(input, x, y); + } + } + return output; +} + +static image<uchar> *imageLONGtoUCHAR(image<long> *input, long min, long max) { + int width = input->width(); + int height = input->height(); + image<uchar> *output = new image<uchar>(width, height, false); + + if (max == min) + return output; + + float scale = UCHAR_MAX / (float)(max - min); + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + uchar val = (uchar)((imRef(input, x, y) - min) * scale); + imRef(output, x, y) = bound(val, (uchar)0, (uchar)UCHAR_MAX); + } + } + return output; +} + +static image<uchar> *imageLONGtoUCHAR(image<long> *input) { + long min, max; + min_max(input, &min, &max); + return imageLONGtoUCHAR(input, min, max); +} + +static image<uchar> *imageSHORTtoUCHAR(image<short> *input, + short min, short max) { + int width = input->width(); + int height = input->height(); + image<uchar> *output = new image<uchar>(width, height, false); + + if (max == min) + return output; + + float scale = UCHAR_MAX / (float)(max - min); + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + uchar val = (uchar)((imRef(input, x, y) - min) * scale); + imRef(output, x, y) = bound(val, (uchar)0, (uchar)UCHAR_MAX); + } + } + return output; +} + +static image<uchar> *imageSHORTtoUCHAR(image<short> *input) { + short min, max; + min_max(input, &min, &max); + return imageSHORTtoUCHAR(input, min, max); +} + +#endif diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/imutil.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/imutil.h new file mode 100755 index 0000000..f59c65d --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/imutil.h @@ -0,0 +1,66 @@ +/* +Copyright (C) 2006 Pedro Felzenszwalb + +This program is free software; you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation; either version 2 of the License, or +(at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program; if not, write to the Free Software +Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +/* some image utilities */ + +#ifndef IMUTIL_H +#define IMUTIL_H + +#include "graph3d/image.h" +#include "graph3d/misc.h" + +/* compute minimum and maximum value in an image */ +template <class T> +void min_max(image<T> *im, T *ret_min, T *ret_max) { + int width = im->width(); + int height = im->height(); + + T min = imRef(im, 0, 0); + T max = imRef(im, 0, 0); + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + T val = imRef(im, x, y); + if (min > val) + min = val; + if (max < val) + max = val; + } + } + + *ret_min = min; + *ret_max = max; +} + +/* threshold image */ +template <class T> +image<uchar> *threshold(image<T> *src, int t) { + int width = src->width(); + int height = src->height(); + image<uchar> *dst = new image<uchar>(width, height); + + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + imRef(dst, x, y) = (imRef(src, x, y) >= t); + } + } + + return dst; +} + +#endif + diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/misc.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/misc.h new file mode 100755 index 0000000..4e4a439 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/misc.h @@ -0,0 +1,65 @@ +/* +Copyright (C) 2006 Pedro Felzenszwalb + +This program is free software; you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation; either version 2 of the License, or +(at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program; if not, write to the Free Software +Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +/* random stuff */ + +#ifndef MISC_H +#define MISC_H + +#include <cmath> + +#ifndef M_PI +#define M_PI 3.141592653589793 +#endif + +typedef unsigned char uchar; + +typedef struct { uchar r, g, b; } rgb; + +inline bool operator==(const rgb &a, const rgb &b) { + return ((a.r == b.r) && (a.g == b.g) && (a.b == b.b)); +} + +template <class T> +inline T abs(const T &x) { return (x > 0 ? x : -x); }; + +template <class T> +inline int sign(const T &x) { return (x >= 0 ? 1 : -1); }; + +template <class T> +inline T square(const T &x) { return x*x; }; + +template <class T> +inline T bound(const T &x, const T &min, const T &max) { + return (x < min ? min : (x > max ? max : x)); +} + +template <class T> +inline bool check_bound(const T &x, const T&min, const T &max) { + return ((x < min) || (x > max)); +} + +inline int vlib_round(float x) { return (int)(x + 0.5F); } + +inline int vlib_round(double x) { return (int)(x + 0.5); } + +inline double gaussian(double val, double sigma) { + return exp(-square(val/sigma)/2)/(sqrt(2*M_PI)*sigma); +} + +#endif diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/pnmfile.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/pnmfile.h new file mode 100755 index 0000000..acc98be --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/pnmfile.h @@ -0,0 +1,211 @@ +/* +Copyright (C) 2006 Pedro Felzenszwalb + +This program is free software; you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation; either version 2 of the License, or +(at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program; if not, write to the Free Software +Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +/* basic image I/O */ + +#ifndef PNM_FILE_H +#define PNM_FILE_H + +#include <cstdlib> +#include <climits> +#include <cstring> +#include <fstream> +#include "graph3d/image.h" +#include "graph3d/misc.h" + +#define BUF_SIZE 256 + +class pnm_error { }; + +static void read_packed(unsigned char *data, int size, std::ifstream &f) { + unsigned char c = 0; + + int bitshift = -1; + for (int pos = 0; pos < size; pos++) { + if (bitshift == -1) { + c = f.get(); + bitshift = 7; + } + data[pos] = (c >> bitshift) & 1; + bitshift--; + } +} + +static void write_packed(unsigned char *data, int size, std::ofstream &f) { + unsigned char c = 0; + + int bitshift = 7; + for (int pos = 0; pos < size; pos++) { + c = c | (data[pos] << bitshift); + bitshift--; + if ((bitshift == -1) || (pos == size-1)) { + f.put(c); + bitshift = 7; + c = 0; + } + } +} + +/* read PNM field, skipping comments */ +static void pnm_read(std::ifstream &file, char *buf) { + char doc[BUF_SIZE]; + char c; + + file >> c; + while (c == '#') { + file.getline(doc, BUF_SIZE); + file >> c; + } + file.putback(c); + + file.width(BUF_SIZE); + file >> buf; + file.ignore(); +} + +static image<uchar> *loadPBM(const char *name) { + char buf[BUF_SIZE]; + + /* read header */ + std::ifstream file(name, std::ios::in | std::ios::binary); + pnm_read(file, buf); + if (strncmp(buf, "P4", 2)) + throw pnm_error(); + + pnm_read(file, buf); + int width = atoi(buf); + pnm_read(file, buf); + int height = atoi(buf); + + /* read data */ + image<uchar> *im = new image<uchar>(width, height); + for (int i = 0; i < height; i++) + read_packed(imPtr(im, 0, i), width, file); + + return im; +} + +static void savePBM(image<uchar> *im, const char *name) { + int width = im->width(); + int height = im->height(); + std::ofstream file(name, std::ios::out | std::ios::binary); + + file << "P4\n" << width << " " << height << "\n"; + for (int i = 0; i < height; i++) + write_packed(imPtr(im, 0, i), width, file); +} + +static image<uchar> *loadPGM(const char *name) { + char buf[BUF_SIZE]; + + /* read header */ + std::ifstream file(name, std::ios::in | std::ios::binary); + pnm_read(file, buf); + if (strncmp(buf, "P5", 2)) + throw pnm_error(); + + pnm_read(file, buf); + int width = atoi(buf); + pnm_read(file, buf); + int height = atoi(buf); + + pnm_read(file, buf); + if (atoi(buf) > UCHAR_MAX) + throw pnm_error(); + + /* read data */ + image<uchar> *im = new image<uchar>(width, height); + file.read((char *)imPtr(im, 0, 0), width * height * sizeof(uchar)); + + return im; +} + +static void savePGM(image<uchar> *im, const char *name) { + int width = im->width(); + int height = im->height(); + std::ofstream file(name, std::ios::out | std::ios::binary); + + file << "P5\n" << width << " " << height << "\n" << UCHAR_MAX << "\n"; + file.write((char *)imPtr(im, 0, 0), width * height * sizeof(uchar)); +} + +static image<rgb> *loadPPM(const char *name) { + char buf[BUF_SIZE], doc[BUF_SIZE]; + + /* read header */ + std::ifstream file(name, std::ios::in | std::ios::binary); + pnm_read(file, buf); + if (strncmp(buf, "P6", 2)) + throw pnm_error(); + + pnm_read(file, buf); + int width = atoi(buf); + pnm_read(file, buf); + int height = atoi(buf); + + pnm_read(file, buf); + if (atoi(buf) > UCHAR_MAX) + throw pnm_error(); + + /* read data */ + image<rgb> *im = new image<rgb>(width, height); + file.read((char *)imPtr(im, 0, 0), width * height * sizeof(rgb)); + + return im; +} + +static void savePPM(image<rgb> *im, const char *name) { + int width = im->width(); + int height = im->height(); + std::ofstream file(name, std::ios::out | std::ios::binary); + + file << "P6\n" << width << " " << height << "\n" << UCHAR_MAX << "\n"; + file.write((char *)imPtr(im, 0, 0), width * height * sizeof(rgb)); +} + +template <class T> +void load_image(image<T> **im, const char *name) { + char buf[BUF_SIZE]; + + /* read header */ + std::ifstream file(name, std::ios::in | std::ios::binary); + pnm_read(file, buf); + if (strncmp(buf, "VLIB", 9)) + throw pnm_error(); + + pnm_read(file, buf); + int width = atoi(buf); + pnm_read(file, buf); + int height = atoi(buf); + + /* read data */ + *im = new image<T>(width, height); + file.read((char *)imPtr((*im), 0, 0), width * height * sizeof(T)); +} + +template <class T> +void save_image(image<T> *im, const char *name) { + int width = im->width(); + int height = im->height(); + std::ofstream file(name, std::ios::out | std::ios::binary); + + //file << "VLIB\n" << width << " " << height << "\n"; + file.write((char *)imPtr(im, 0, 0), width * height * sizeof(T)); +} + +#endif diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/segment-graph.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/segment-graph.h new file mode 100755 index 0000000..ec97b7f --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/segment-graph.h @@ -0,0 +1,83 @@ +/* +Copyright (C) 2006 Pedro Felzenszwalb + +This program is free software; you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation; either version 2 of the License, or +(at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program; if not, write to the Free Software +Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#ifndef SEGMENT_GRAPH +#define SEGMENT_GRAPH + +#include <algorithm> +#include <cmath> +#include "graph3d/disjoint-set.h" + +// threshold function +#define THRESHOLD(size, c) (c/size) + +typedef struct { + float w; + int a, b; +} edge; + +bool operator<(const edge &a, const edge &b) { + return a.w < b.w; +} + +/* + * Segment a graph + * + * Returns a disjoint-set forest representing the segmentation. + * + * num_vertices: number of vertices in graph. + * num_edges: number of edges in graph + * edges: array of edges. + * c: constant for treshold function. + */ +universe *segment_graph(int num_vertices, int num_edges, edge *edges, + float c) { + // sort edges by weight + std::sort(edges, edges + num_edges); + + // make a disjoint-set forest + universe *u = new universe(num_vertices); + + // init thresholds + float *threshold = new float[num_vertices]; + for (int i = 0; i < num_vertices; i++) + threshold[i] = THRESHOLD(1,c); + + // for each edge, in non-decreasing weight order... + for (int i = 0; i < num_edges; i++) { + edge *pedge = &edges[i]; + + // components conected by this edge + int a = u->find(pedge->a); + int b = u->find(pedge->b); + if (a != b) { + if ((pedge->w <= threshold[a]) && + (pedge->w <= threshold[b])) { + u->join(a, b); + a = u->find(a); + threshold[a] = pedge->w + THRESHOLD(u->size(a), c); + } + } + } + + // free up + delete threshold; + return u; +} + +#endif diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/segment-image.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/segment-image.h new file mode 100755 index 0000000..6079e79 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/segment-image.h @@ -0,0 +1,153 @@ +/* +Copyright (C) 2006 Pedro Felzenszwalb + +This program is free software; you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation; either version 2 of the License, or +(at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program; if not, write to the Free Software +Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#ifndef SEGMENT_IMAGE +#define SEGMENT_IMAGE + +#include <cstdlib> +#include "graph3d/image.h" +#include "graph3d/misc.h" +#include "graph3d/filter.h" +#include "graph3d/segment-graph.h" + +// random color +rgb random_rgb(){ + rgb c; + double r; + + c.r = (uchar)random(); + c.g = (uchar)random(); + c.b = (uchar)random(); + + return c; +} + +// dissimilarity measure between pixels +static inline float diff(image<float> *r, image<float> *g, image<float> *b, + int x1, int y1, int x2, int y2) { + return sqrt(square(imRef(r, x1, y1)-imRef(r, x2, y2)) + + square(imRef(g, x1, y1)-imRef(g, x2, y2)) + + square(imRef(b, x1, y1)-imRef(b, x2, y2))); +} + +/* + * Segment an image + * + * Returns a color image representing the segmentation. + * + * im: image to segment. + * sigma: to smooth the image. + * c: constant for treshold function. + * min_size: minimum component size (enforced by post-processing stage). + * num_ccs: number of connected components in the segmentation. + */ +image<rgb> *segment_image(image<rgb> *im, float sigma, float c, int min_size, int *num_ccs) { + int width = im->width(); + int height = im->height(); + + image<float> *r = new image<float>(width, height); + image<float> *g = new image<float>(width, height); + image<float> *b = new image<float>(width, height); + + // smooth each color channel + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + imRef(r, x, y) = imRef(im, x, y).r; + imRef(g, x, y) = imRef(im, x, y).g; + imRef(b, x, y) = imRef(im, x, y).b; + } + } + image<float> *smooth_r = smooth(r, sigma); + image<float> *smooth_g = smooth(g, sigma); + image<float> *smooth_b = smooth(b, sigma); + delete r; + delete g; + delete b; + + // build graph + edge *edges = new edge[width*height*4]; + int num = 0; + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + if (x < width-1) { + edges[num].a = y * width + x; + edges[num].b = y * width + (x+1); + edges[num].w = diff(smooth_r, smooth_g, smooth_b, x, y, x+1, y); + num++; + } + + if (y < height-1) { + edges[num].a = y * width + x; + edges[num].b = (y+1) * width + x; + edges[num].w = diff(smooth_r, smooth_g, smooth_b, x, y, x, y+1); + num++; + } + + if ((x < width-1) && (y < height-1)) { + edges[num].a = y * width + x; + edges[num].b = (y+1) * width + (x+1); + edges[num].w = diff(smooth_r, smooth_g, smooth_b, x, y, x+1, y+1); + num++; + } + + if ((x < width-1) && (y > 0)) { + edges[num].a = y * width + x; + edges[num].b = (y-1) * width + (x+1); + edges[num].w = diff(smooth_r, smooth_g, smooth_b, x, y, x+1, y-1); + num++; + } + } + } + delete smooth_r; + delete smooth_g; + delete smooth_b; + + // segment + universe *u = segment_graph(width*height, num, edges, c); + + // post process small components + for (int i = 0; i < num; i++) { + int a = u->find(edges[i].a); + int b = u->find(edges[i].b); + if ((a != b) && ((u->size(a) < min_size) || (u->size(b) < min_size))) + u->join(a, b); + } + delete [] edges; + *num_ccs = u->num_sets(); + + image<rgb> *output = new image<rgb>(width, height); + + // pick random colors for each component + rgb *colors = new rgb[width*height]; + for (int i = 0; i < width*height; i++) + colors[i] = random_rgb(); + + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + int comp = u->find(y * width + x); + imRef(output, x, y) = colors[comp]; + } + } + + delete [] colors; + delete u; + + return output; +} + +#endif diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/segment.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/segment.h new file mode 100755 index 0000000..3696ec7 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/graph3d/segment.h @@ -0,0 +1,19 @@ +/* + * segment.h + * + * Created on: Nov 3, 2016 + * Author: fran + */ + +#ifndef SEGMENT_H_ +#define SEGMENT_H_ + +#include <cv_bridge/cv_bridge.h> +#include <opencv2/core/core.hpp> +#include <opencv2/imgproc/imgproc.hpp> + + +void imadjust(const cv::Mat & src, cv::Mat & dst); +void im2segment(cv::Mat input, cv::Mat cv_image_output, float sigma, float k, int min_size, int *num_ccs); + +#endif /* SEGMENT_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/image_reconstruct/image_reconst.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/image_reconstruct/image_reconst.h new file mode 100755 index 0000000..c9a12e6 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/include/image_reconstruct/image_reconst.h @@ -0,0 +1,35 @@ +/* + * image_reconst.h + * + * Created on: Nov 3, 2016 + * Author: fran + */ + +#ifndef IMAGE_RECONST_H_ +#define IMAGE_RECONST_H_ + +#include <opencv2/core/core.hpp> +#include <opencv2/opencv.hpp> +//#include <opencv2/core/core_c.h> +#include "opencv2/highgui/highgui_c.h" +//#include "opencv2/core/core.hpp" + + +void dst(double *btest, double *bfinal, int h, int w); +void idst(double *btest, double *bfinal, int h, int w); +void transpose(double *mat, double *mat_t, int h, int w); + +void getGradientX(cv::Mat &img, cv::Mat &gx); +void getGradientY(cv::Mat &img, cv::Mat &gy); +void lapx(cv::Mat &gx, cv::Mat &gxx); +void lapy(cv::Mat &gy, cv::Mat &gyy); + +void poisson_solver(cv::Mat &img, cv::Mat &gxx, cv::Mat &gyy, cv::Mat &result); +void poisson_solver_jacobi(cv::Mat &img, cv::Mat &gxx, cv::Mat &gyy, cv::Mat &result); + + +//IPL Image versions (legacy) +void lapx( const IplImage *img, IplImage *gxx); +void lapy( const IplImage *img, IplImage *gyy); +void poisson_solver(const IplImage *img, IplImage *gxx , IplImage *gyy, cv::Mat &result); +#endif /* IMAGE_RECONST_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/launch/dvs_mono.launch b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/launch/dvs_mono.launch new file mode 100755 index 0000000..07ee3e7 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/launch/dvs_mono.launch @@ -0,0 +1,39 @@ +<launch> + <!-- camera driver --> + <node name="dvs_ros_driver" pkg="dvs_ros_driver" type="dvs_ros_driver" output = "screen"> + <rosparam command="load" file="$(find dvs_ros_driver)/config/fast.yaml" /> + </node> + + <!-- visualization --> + <node name="dvs_meanshift" pkg="dvs_meanshift" type="dvs_meanshift" output = "screen"> + <!-- <param name="display_method" value="grayscale"/> --> + <param name="display_method" value="red-blue"/> + <remap from="events" to="/dvs/events" /> + <remap from="camera_info" to="/dvs/camera_info" /> + </node> + + <!-- display --> + <node name="image_view" pkg="image_view" type="image_view" output = "screen"> + <remap from="image" to="dvs_rendering"/> + </node> + + <node name="image_view2" pkg="image_view" type="image_view" output = "screen"> + <remap from="image" to="dvs_segmentation"/> + </node> + + <node name="image_view3" pkg="image_view" type="image_view" output = "screen"> + <remap from="image" to="dvs_debug1"/> + </node> + + <node name="image_view4" pkg="image_view" type="image_view" output = "screen"> + <remap from="image" to="dvs_debug2"/> + </node> + + <!-- <node name="image_view2" pkg="image_view" type="image_view" output = "screen"> --> + <!-- <remap from="image" to="dvs_undistorted"/> --> + <!-- </node> --> + + <!-- configure --> + <!-- <node name="rqt_reconfigure" pkg="rqt_reconfigure" type="rqt_reconfigure" /> --> + +</launch> diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/launch/dvs_segmentation.launch b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/launch/dvs_segmentation.launch new file mode 100755 index 0000000..061b64d --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/launch/dvs_segmentation.launch @@ -0,0 +1,31 @@ +<launch> + <!-- camera driver --> + <node name="dvs_ros_driver" pkg="dvs_ros_driver" type="dvs_ros_driver" output = "screen"> + <rosparam command="load" file="$(find dvs_ros_driver)/config/fast.yaml" /> + </node> + + <!-- visualization --> + <node name="dvs_meanshift" pkg="dvs_meanshift" type="dvs_meanshift" output = "screen"> + <!-- <param name="display_method" value="grayscale"/> --> + <param name="display_method" value="red-blue"/> + <remap from="events" to="/dvs/events" /> + <remap from="camera_info" to="/dvs/camera_info" /> + </node> + + <!-- display --> + <node name="rqt_image_view" pkg="rqt_image_view" type="rqt_image_view" output = "screen"> + <remap from="image" to="dvs_rendering"/> + </node> + + <node name="image_view2" pkg="rqt_image_view" type="rqt_image_view" output = "screen"> + <remap from="image" to="dvs_segmentation"/> + </node> + + <!-- <node name="image_view3" pkg="image_view" type="image_view" output = "screen"> --> + <!-- <remap from="image" to="dvs_debug1"/> --> + <!-- </node> --> + + <!-- configure --> + <!-- <node name="rqt_reconfigure" pkg="rqt_reconfigure" type="rqt_reconfigure" /> --> + +</launch> diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/package.xml b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/package.xml new file mode 100755 index 0000000..05e2835 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/package.xml @@ -0,0 +1,66 @@ +<?xml version="1.0"?> +<package> + <name>dvs_meanshift</name> + <version>0.0.0</version> + <description>The dvs_meanshift package</description> + + <!-- One maintainer tag required, multiple allowed, one person per tag --> + <!-- Example: --> + <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> --> + <maintainer email="fran@todo.todo">fran</maintainer> + + + <!-- One license tag required, multiple allowed, one license per tag --> + <!-- Commonly used license strings: --> + <!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 --> + <license>TODO</license> + + + <!-- Url tags are optional, but mutiple are allowed, one per tag --> + <!-- Optional attribute type can be: website, bugtracker, or repository --> + <!-- Example: --> + <!-- <url type="website">http://wiki.ros.org/dvs_meanshift</url> --> + + + <!-- Author tags are optional, mutiple are allowed, one per tag --> + <!-- Authors do not have to be maintianers, but could be --> + <!-- Example: --> + <!-- <author email="jane.doe@example.com">Jane Doe</author> --> + + + <!-- The *_depend tags are used to specify dependencies --> + <!-- Dependencies can be catkin packages or system dependencies --> + <!-- Examples: --> + <!-- Use build_depend for packages you need at compile time: --> + <!-- <build_depend>message_generation</build_depend> --> + <!-- Use buildtool_depend for build tool packages: --> + <!-- <buildtool_depend>catkin</buildtool_depend> --> + <!-- Use run_depend for packages you need at runtime: --> + <!-- <run_depend>message_runtime</run_depend> --> + <!-- Use test_depend for packages you need only for testing: --> + <!-- <test_depend>gtest</test_depend> --> + <buildtool_depend>catkin</buildtool_depend> + <build_depend>cv_bridge</build_depend> + <build_depend>dvs_msgs</build_depend> + <build_depend>image_transport</build_depend> + <build_depend>pcl_ros</build_depend> + <build_depend>roscpp</build_depend> + <build_depend>rospy</build_depend> + <build_depend>sensor_msgs</build_depend> + <build_depend>std_msgs</build_depend> + <run_depend>cv_bridge</run_depend> + <run_depend>dvs_msgs</run_depend> + <run_depend>image_transport</run_depend> + <run_depend>pcl_ros</run_depend> + <run_depend>roscpp</run_depend> + <run_depend>rospy</run_depend> + <run_depend>sensor_msgs</run_depend> + <run_depend>std_msgs</run_depend> + + + <!-- The export tag contains other, unspecified, tags --> + <export> + <!-- Other tools can request additional information be placed here --> + + </export> +</package> \ No newline at end of file diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/color_meanshift.cpp b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/color_meanshift.cpp new file mode 100755 index 0000000..f1c8d2c --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/color_meanshift.cpp @@ -0,0 +1,739 @@ +#include <cstring> +#include <cmath> +#include <cstdlib> +#include "dvs_meanshift/color_meanshift.h" + +#define max(x,y) ((x)>(y)?(x):(y)) +#define min(x,y) ((x)<(y)?(x):(y)) + +#define _2D_to_linear(row, col, maxCol) ((row)*(maxCol)+(col)) +//#define _3D_to_linear(row, col, color, maxRow, maxCol) ((maxRow)*(maxCol)*(color)+(row)*(maxCol)+(col)) + +//#define _2D_to_linear(row, col, maxRow) ((col)*(maxRow)+(row)) +//#define _3D_to_linear(row, col, color, maxRow, maxCol) ((maxRow)*(maxCol)*(color)+(col)*(maxRow)+(row)) +//void colorMeanShiftFilt_helper_C(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[] ) + +/*void colorMeanShiftFilt(double *newPixelsPtr, const double *pixelsPtr, int mPixels, int maxPixelDim, const double *imagePtr, int numRows, int numCols, float spaceDivider, char *kernelFun, int maxIterNum, float tolFun, double *newImagePtr) +{ + // Copy the original pixel values to the new pixel matrix + memcpy(newPixelsPtr, pixelsPtr, maxPixelDim*mPixels*sizeof(double)); + + // Copy the original image to a new image + memcpy(newImagePtr, imagePtr, mPixels*sizeof(double)); + + // Help variables + double x,y; + int rX, rY; + int neighX, neighY; + bool bRepeat=false; + + double *delta = (double *) calloc(maxPixelDim,sizeof(double)); + double *dX = (double *) calloc(maxPixelDim,sizeof(double)); + double *neighVec = (double *) calloc(maxPixelDim,sizeof(double)); + double deltaGrad2; + + // Create an array that indicates if we reached the end of the optimization for each pixel + double *optimizedPointArray=new double[mPixels]; + + for (int iterNum=0; iterNum<maxIterNum; iterNum++) + { + bRepeat=false; + + for (int pointNum=0; pointNum<mPixels; pointNum++) + { + if (optimizedPointArray[pointNum]==1) // The optimization for this pixel has reached the threshold + continue; + + x=newPixelsPtr[_2D_to_linear(0, pointNum, maxPixelDim)]*spaceDivider; + y=newPixelsPtr[_2D_to_linear(1, pointNum, maxPixelDim)]*spaceDivider; + + // Reset the delta variables + delta[0]=0; delta[1]=0; delta[2]=0; + dX[0]=0; dX[1]=0; dX[2]=0; + + //ROS_ERROR("y = %d, x = %d, pointNum = %d, spaceDivider = %g", (int)floor(y), (int)floor(x), pointNum, spaceDivider); + + double sumF=0; + double dist2; + + + // Find the neighbors around point (rX,rY) + //for (neighX=max(0, floor(x)-1-spaceDivider); neighX<min(numCols, ceil(x)+spaceDivider); neighX++) + for (neighX=max(0, floor(x)-spaceDivider); neighX<min(numCols, ceil(x)+spaceDivider); neighX++) + { + //for (neighY=max(0,floor(y)-1-spaceDivider); neighY<min(numRows, ceil(y)+spaceDivider); neighY++) + for (neighY=max(0,floor(y)-spaceDivider); neighY<min(numRows, ceil(y)+spaceDivider); neighY++) + { + neighVec[0]=(neighX)/spaceDivider; + neighVec[1]=(neighY)/spaceDivider; + neighVec[2]=newImagePtr[neighY*numCols+neighX]; + + + delta[0]=newPixelsPtr[_2D_to_linear(0,pointNum,maxPixelDim)]-neighVec[0]; + delta[1]=newPixelsPtr[_2D_to_linear(1,pointNum,maxPixelDim)]-neighVec[1]; + delta[2]=newPixelsPtr[_2D_to_linear(2,pointNum,maxPixelDim)]-neighVec[2]; + + dist2 = delta[0]*delta[0] + delta[1]*delta[1] + delta[2]*delta[2]; + + double kres=(exp(-dist2/2.0)); + + dX[0] += kres*neighVec[0]; + dX[1] += kres*neighVec[1]; + dX[2] += kres*neighVec[2]; + + sumF+=kres; + + //ROS_ERROR("newImagePtr[%d, %d]= %g", (int)(neighX), (int)(neighY), neighVec[2]); + } + } + + deltaGrad2=0; + + + dX[0]=(sumF==0)?0:dX[0]/sumF; //check for NaNs + dX[1]=(sumF==0)?0:dX[1]/sumF; //check for NaNs + dX[2]=(sumF==0)?0:dX[2]/sumF; //check for NaNs + + double tmp0=newPixelsPtr[_2D_to_linear(0, pointNum, maxPixelDim)]-dX[0]; + double tmp1=newPixelsPtr[_2D_to_linear(1, pointNum, maxPixelDim)]-dX[1]; + double tmp2=newPixelsPtr[_2D_to_linear(2, pointNum, maxPixelDim)]-dX[2]; + + //double tmp1=newPixelsPtr[_2D_to_linear(i, pointNum, mPixels)]-dX[i]; + deltaGrad2 = tmp0*tmp0 + tmp1*tmp1 + tmp2*tmp2; + newPixelsPtr[_2D_to_linear(0, pointNum, maxPixelDim)]=dX[0]; + newPixelsPtr[_2D_to_linear(1, pointNum, maxPixelDim)]=dX[1]; + newPixelsPtr[_2D_to_linear(2, pointNum, maxPixelDim)]=dX[2]; + + //ROS_ERROR("newImagePtr[%d, %d]= %g", (int)pointNum/numCols, (int)pointNum%numCols, dX[0]); + + // Find the corresponding row and column of the point + newImagePtr[pointNum]=dX[2]; + + //ROS_ERROR("newImagePtr[%d, %d] = %g", pointCol, pointRow, dX[0]); + + if (deltaGrad2<tolFun) + optimizedPointArray[pointNum]=1; + else + bRepeat=true; + + } // end pointNum loop + + if (bRepeat==false) + break; + + } // end for(iterNum) loop + + // CLEAN-UP + //delete[] newImagePtr; + delete[] optimizedPointArray; + delete(delta); + delete(dX); + delete(neighVec); +}*/ + +/*void colorMeanShiftFilt(double *newPixelsPtr, const double *pixelsPtr, int mPixels, int maxPixelDim, const double *imagePtr, int numRows, int numCols, float spaceDivider, char *kernelFun, int maxIterNum, float tolFun) +{ + // Copy the original pixel values to the new pixel matrix + memcpy(newPixelsPtr, pixelsPtr, maxPixelDim*mPixels*sizeof(double)); + + // Copy the original image to a new image + double *newImagePtr=new double[mPixels]; + memcpy(newImagePtr, imagePtr, mPixels*sizeof(double)); + + // Help variables + double x,y; + int neighX, neighY; + bool bRepeat=false; + + double *delta = (double *) calloc(maxPixelDim,sizeof(double)); + double *dX = (double *) calloc(maxPixelDim,sizeof(double)); + double *neighVec = (double *) calloc(maxPixelDim,sizeof(double)); + double deltaGrad2; + + // Create an array that indicates if we reached the end of the optimization for each pixel + double *optimizedPointArray=new double[mPixels]; + + for (int iterNum=0; iterNum<maxIterNum; iterNum++) + { + bRepeat=false; + for (int pointNum=0; pointNum<mPixels; pointNum++) + { + if (optimizedPointArray[pointNum]==1) // The optimization for this pixel has reached the threshold + continue; + + x=newPixelsPtr[_2D_to_linear(0, pointNum, mPixels)]*spaceDivider; + y=newPixelsPtr[_2D_to_linear(1, pointNum, mPixels)]*spaceDivider; + + delta[0]=0; delta[1]=0; delta[2]=0; + dX[0]=0; dX[1]=0; dX[2]=0; + + //ROS_ERROR("y = %d, x = %d, pointNum = %d, spaceDivider = %g", (int)floor(y), (int)floor(x), pointNum, spaceDivider); + + double sumF=0; + double dist2, kres; + + // Find the neighbors around point (rX,rY) + for (neighX=max(0, floor(x)-1-spaceDivider); neighX<min(numCols, ceil(x)+spaceDivider); neighX++) + { + for (neighY=max(0,floor(y)-1-spaceDivider); neighY<min(numRows, ceil(y)+spaceDivider); neighY++) + { + neighVec[0]=(neighX+1)/spaceDivider; + neighVec[1]=(neighY+1)/spaceDivider; + neighVec[2]=newImagePtr[neighY*numCols+neighX]; + + delta[0]=newPixelsPtr[_2D_to_linear(0,pointNum,mPixels)]-neighVec[0]; + delta[1]=newPixelsPtr[_2D_to_linear(1,pointNum,mPixels)]-neighVec[1]; + delta[2]=newPixelsPtr[_2D_to_linear(2,pointNum,mPixels)]-neighVec[2]; + + dist2 = delta[0]*delta[0]+delta[1]*delta[1]+delta[2]*delta[2]; + + kres =(exp(-dist2/2.0)); + + dX[0]+= kres*neighVec[0]; + dX[1]+= kres*neighVec[1]; + dX[2]+= kres*neighVec[2]; + sumF +=kres; + } + } + + // Find the corresponding row and column of the point + int pointRow = pointNum/numCols; + int pointCol = pointNum%numCols; + + dX[0]=(sumF==0)?0:dX[0]/sumF; //check for NaNs + dX[1]=(sumF==0)?0:dX[1]/sumF; //check for NaNs + dX[2]=(sumF==0)?0:dX[2]/sumF; //check for NaNs + //double tmp1=newPixelsPtr[_2D_to_linear(i, pointNum, maxPixelDim)]-dX[i]; + double tmp1=newPixelsPtr[_2D_to_linear(0, pointNum, mPixels)]-dX[0]; + double tmp2=newPixelsPtr[_2D_to_linear(1, pointNum, mPixels)]-dX[1]; + double tmp3=newPixelsPtr[_2D_to_linear(2, pointNum, mPixels)]-dX[2]; + + deltaGrad2=tmp1*tmp1+tmp2*tmp2+tmp3*tmp3; + newPixelsPtr[_2D_to_linear(0, pointNum, mPixels)]=dX[0]; + newPixelsPtr[_2D_to_linear(1, pointNum, mPixels)]=dX[1]; + newPixelsPtr[_2D_to_linear(2, pointNum, mPixels)]=dX[2]; + //newImagePtr[pointRow*numCols+pointCol]=dX[2]; + newImagePtr[pointNum]=dX[2]; + + if (deltaGrad2<tolFun) + optimizedPointArray[pointNum]=1; + else + bRepeat=true; + + } // end pointNum loop + + if (bRepeat==false) + break; + + } // end for(iterNum) loop + + + // CLEAN-UP + delete[] newImagePtr; + delete[] optimizedPointArray; + delete(delta); + delete(dX); + delete(neighVec); +}*/ + +/*void meanshiftCluster_Gaussian(cv::Mat dataPts, std::vector<double> *clusterCenterX, std::vector<double> *clusterCenterY, std::vector<double> *clusterCenterZ, std::vector<int> *point2Clusters, double bandwidth) +{ + //Initialization + int numPts = dataPts.cols; + int numDim = dataPts.rows; + int numClust = 0; + double bandSq = bandwidth*bandwidth; + cv::Range rng = cv::Range(1,numPts); + + cv::Mat onesAux = cv::Mat::ones(1, dataPts.cols, dataPts.type()); + + std::vector<int> initPtInds; + for (int i = rng.start; i <= rng.end; i++) initPtInds.push_back(i); + double stopThresh = 1E-3*bandwidth; //when mean has converged + int numInitPts = numPts; //track if a points been seen already + cv::Mat beenVisitedFlag = cv::Mat(1, numPts, CV_32S, cv::Scalar::all(0)); //number of points to posibaly use as initilization points + cv::Mat clusterVotes; //used to resolve conflicts on cluster membership + + double lambda = 10.; + double myMeanX, myMeanY, myMeanZ, myOldMeanX, myOldMeanY, myOldMeanZ, totalWeightX, totalWeightY, totalWeightZ; + int stInd; + + //std::vector<double> clusterCenterX, clusterCenterY, clusterCenterZ; + + int tempInd; + + while (numInitPts>0) + { + tempInd = (rand()%numInitPts); //pick a random seed point + stInd = initPtInds[tempInd]; //use this point as start of mean + myMeanX = dataPts.at<double>(cv::Point(stInd, 0)); //intilize mean to this points location + myMeanY = dataPts.at<double>(cv::Point(stInd, 1)); + myMeanZ = dataPts.at<double>(cv::Point(stInd, 2)); + cv::Mat thisClusterVotes = cv::Mat(1, numPts, CV_32S, cv::Scalar::all(0)); //used to resolve conflicts on cluster membership + //ROS_ERROR_STREAM("Before getting into while myMean = ["<<myMeanX<<", "<<myMeanY<<", "<<myMeanZ<<"]"); + cv::Mat_<double> myMean = ( cv::Mat_<double>(3, 1) << myMeanX, myMeanY, myMeanZ); + + + + while(true) + { + cv::Mat dataX, dataY, dataZ; + dataX.push_back(dataPts.row(0)); + dataY.push_back(dataPts.row(1)); + dataZ.push_back(dataPts.row(2)); + + cv::Mat diffX = dataX - myMeanX; + cv::Mat diffY = dataY - myMeanY; + cv::Mat diffZ = dataZ - myMeanZ; + + ROS_ERROR_STREAM("Original = "<<diffX); + ROS_ERROR_STREAM("onesAux.rows = "<<onesAux.rows<<" cols = "<<onesAux.cols); + ROS_ERROR_STREAM("dataPts.rows = "<<dataPts.rows<<" cols = "<<dataPts.cols); + ROS_ERROR_STREAM("myMean.rows = "<<myMean.rows<<" cols = "<<myMean.cols); + + cv::Mat diff = dataPts - myMean*onesAux; + diffX.push_back(diff.row(0)); + diffY.push_back(diff.row(1)); + diffZ.push_back(diff.row(2)); + + ROS_ERROR_STREAM("Matricial "<<diff.row(0)); + exit(0); + + cv::Mat diffXX = diffX.mul(diffX); + cv::Mat diffYY = diffY.mul(diffY); + cv::Mat diffZZ = diffZ.mul(diffZ); + + cv::Mat sqDistToAll = diffXX + diffYY + diffZZ; //dist squared from mean to all points still active + cv::Mat inInds = (sqDistToAll < bandSq); // Puts 255 wherever it is true + //ROS_ERROR_STREAM("This is the size "<<inInds.size()); + //ROS_ERROR_STREAM("This is the size "<<thisClusterVotes.size()); + //inInds.convertTo(inInds, CV_8UC1); + //cv::add(thisClusterVotes, cv::Mat::ones(1, numPts, CV_32S), thisClusterVotes, inInds); //add a vote for all the in points belonging to this cluster + cv::add(thisClusterVotes, cv::Scalar(1), thisClusterVotes, inInds); //add a vote for all the in points belonging to this cluster + //ROS_ERROR_STREAM("thisclusterVotes = "<<inInds); + //ROS_ERROR_STREAM("thisclusterVotes = "<<thisClusterVotes); + //ROS_ERROR_STREAM("thisclusterVotes = "<<sqDistToAll); + //exit(0); + + cv::Mat selectedDataX, selectedDataY, selectedDataZ; + //cv::bitwise_and(dataX, cv::Scalar(255), selectedDataX, inInds); + //cv::bitwise_and(dataY, cv::Scalar(255), selectedDataY, inInds); + //cv::bitwise_and(dataZ, cv::Scalar(255), selectedDataZ, inInds); + //ROS_ERROR_STREAM("Before: dataX ="<<dataX); + dataX.setTo(0., inInds==0); + dataY.setTo(0., inInds==0); + dataZ.setTo(0., inInds==0); + //ROS_ERROR_STREAM("inInds ="<<inInds); + //ROS_ERROR_STREAM("After: dataX ="<<dataX); + + double numOfOnes = (double) (cv::sum(inInds)[0])/255; //inInds is active if inInds[i]==255 + //ROS_ERROR_STREAM("Num of Ones ="<<numOfOnes); + //ROS_ERROR_STREAM("inInds ="<<inInds); + //exit(0); + myOldMeanX = myMeanX; myOldMeanY = myMeanY; myOldMeanZ = myMeanZ; + myMeanX = cv::sum(dataX)[0]/numOfOnes; + myMeanY = cv::sum(dataY)[0]/numOfOnes; + myMeanZ = cv::sum(dataZ)[0]/numOfOnes; + + + //ROS_ERROR_STREAM("inInds="<<inInds); + //ROS_ERROR_STREAM("After: dataX="<<dataX); + + diffX = dataX - myMeanX; + diffY = dataY - myMeanY; + diffZ = dataZ - myMeanZ; + + diffXX = diffXX.mul(diffXX); + diffYY = diffYY.mul(diffYY); + diffZZ = diffZZ.mul(diffZZ); + + cv::Mat weightX, weightY, weightZ; + cv::exp(diffXX/lambda, weightX); + cv::exp(diffYY/lambda, weightY); + cv::exp(diffZZ/lambda, weightZ); + //cv::Mat wDataX = weightX.mul(selectedDataX); + //cv::Mat wDataY = weightY.mul(selectedDataY); + //cv::Mat wDataZ = weightZ.mul(selectedDataZ); + + weightX.setTo(0., inInds==0); //Again, because the exp and the x - u make invalid values non-zero (inInds) + weightY.setTo(0., inInds==0); + weightZ.setTo(0., inInds==0); + + cv::Mat wDataX = weightX.mul(dataX); + cv::Mat wDataY = weightY.mul(dataY); + cv::Mat wDataZ = weightZ.mul(dataZ); + totalWeightX = cv::sum(weightX)[0]; + totalWeightY = cv::sum(weightY)[0]; + totalWeightZ = cv::sum(weightZ)[0]; + myMeanX = cv::sum(wDataX)[0]/totalWeightX; + myMeanY = cv::sum(wDataY)[0]/totalWeightY; + myMeanZ = cv::sum(wDataZ)[0]/totalWeightZ; + + //cv::add(beenVisitedFlag, cv::Scalar(1.f), beenVisitedFlag, inInds); + beenVisitedFlag.setTo(1, inInds); + //ROS_ERROR_STREAM("myMean = ["<<myMeanX<<", "<<myMeanY<<", "<<myMeanZ<<"]"); + //exit(0); + // if mean doesn't move much stop this cluster + if((myMeanX-myOldMeanX)*(myMeanX-myOldMeanX) + (myMeanY-myOldMeanY)*(myMeanY-myOldMeanY) + (myMeanZ-myOldMeanZ)*(myMeanZ-myOldMeanZ) < stopThresh) + { + //check for merge possibilities + int mergeWith = -1; + double distToOther; + for(int cN = 0; cN<numClust; cN++) //Careful!! cN goes from 1 to numClust!!! + { + double distToOther = (myMeanX - (*clusterCenterX)[cN])*(myMeanX - (*clusterCenterX)[cN]) + (myMeanY - (*clusterCenterY)[cN])*(myMeanY - (*clusterCenterY)[cN]) + (myMeanZ - (*clusterCenterZ)[cN])*(myMeanZ - (*clusterCenterZ)[cN]); //distance from posible new clust max to old clust max + //ROS_ERROR_STREAM("Distance to others "<<distToOther<<" and cN "<<cN); + //ROS_ERROR_STREAM("myMean = ["<<myMeanX<<", "<<myMeanY<<", "<<myMeanZ<<"]"); + //ROS_ERROR_STREAM("clusterCenter = ["<<clusterCenterX[cN]<<", "<<clusterCenterY[cN]<<", "<<clusterCenterZ[cN]<<"]"); + if(distToOther < bandwidth/2) //if its within bandwidth/2 merge new and old + { + mergeWith = cN; + break; + } + } + + if(mergeWith > -1) + { + (*clusterCenterX)[mergeWith] = 0.5*(myMeanX+(*clusterCenterX)[mergeWith]); + (*clusterCenterY)[mergeWith] = 0.5*(myMeanY+(*clusterCenterY)[mergeWith]); + (*clusterCenterZ)[mergeWith] = 0.5*(myMeanZ+(*clusterCenterZ)[mergeWith]); + + cv::Mat newClusterVotes = cv::Mat(clusterVotes.row(mergeWith)) + thisClusterVotes; + newClusterVotes.copyTo(clusterVotes.row(mergeWith)); + } + else + { + numClust = numClust+1; //increment clusters + (*clusterCenterX).push_back(myMeanX); //record the mean + (*clusterCenterY).push_back(myMeanY); + (*clusterCenterZ).push_back(myMeanZ); + + clusterVotes.push_back(thisClusterVotes); // add the new row for the new cluster + } + break; + } + } + + std::vector<int> newInitPtInds; //we can initialize with any of the points not yet visited + for(int i=0; i<numPts; i++) + if (beenVisitedFlag.at<int>(cv::Point(i, 0)) == 0) + newInitPtInds.push_back(i); + initPtInds = newInitPtInds; + numInitPts = initPtInds.size(); //number of active points in set + + //ROS_ERROR_STREAM("Num. of values still un clustered "<<numInitPts); + //ROS_ERROR_STREAM("beenVisitedFlag "<<beenVisitedFlag); + //for(int i=0; i<initPtInds.size(); ++i) + // std::cerr<<initPtInds[i] << ' '; + } + //exit(0); + //[val,data2cluster] = max(clusterVotes,[],1); //a point belongs to the cluster with the most votes + + cv::Mat TclusterVotes = clusterVotes.t(); + + double min, max; + for(int i=0; i<TclusterVotes.rows; i++) + { + cv::minMaxIdx(cv::Mat(TclusterVotes.row(i)), &min, &max); + (*point2Clusters).push_back((int)max); + } + + //ROS_ERROR_STREAM("Inside "<<(*point2Clusters).size()); + //ROS_ERROR_STREAM("Number of clusters " <<numClust<<"and "<<clusterCenterX.size()); +}*/ + + + +void meanshiftCluster_Gaussian(cv::Mat dataPts, std::vector<double> *clusterCenterX, std::vector<double> *clusterCenterY, std::vector<double> *clusterCenterZ, std::vector<int> *point2Clusters, double bandwidth) +{ + //Initialization + int numPts = dataPts.cols; + int numDim = dataPts.rows; + int numClust = 0; + double bandSq = bandwidth*bandwidth; + cv::Range rng = cv::Range(0,numPts-1); + + cv::Mat onesAux = cv::Mat::ones(1, dataPts.cols, dataPts.type()); + + std::vector<int> initPtInds; + for (int i = rng.start; i <= rng.end; i++) initPtInds.push_back(i); + double stopThresh = 1E-3*bandwidth; //when mean has converged + int numInitPts = numPts; //track if a points been seen already + cv::Mat beenVisitedFlag = cv::Mat(1, numPts, CV_32S, cv::Scalar::all(0)); //number of points to posibaly use as initilization points + cv::Mat clusterVotes; //used to resolve conflicts on cluster membership + + double lambda = 10.; + double myMeanX, myMeanY, myMeanZ, myOldMeanX, myOldMeanY, myOldMeanZ, totalWeightX, totalWeightY, totalWeightZ; + int stInd; + + //std::vector<double> clusterCenterX, clusterCenterY, clusterCenterZ; + + + int tempInd; + + while (numInitPts>0) + { + //ROS_ERROR_STREAM("iniPtInds"); + //for(int i=0; i<initPtInds.size(); i++) + // std::cerr<<initPtInds[i]<<" "; + //std::cerr<<std::endl; + + + tempInd = (rand()%numInitPts); //pick a random seed point + //ROS_ERROR_STREAM("numInitPts ="<<numInitPts); + + //std::cin.ignore(); + stInd = initPtInds[tempInd]; //use this point as start of mean + /**********REMOVE THIS******************************/ + //stInd = initPtInds[numInitPts-1]; + /**********REMOVE THIS******************************/ + myMeanX = dataPts.at<double>(cv::Point(stInd, 0)); //intilize mean to this points location + myMeanY = dataPts.at<double>(cv::Point(stInd, 1)); + myMeanZ = dataPts.at<double>(cv::Point(stInd, 2)); + cv::Mat thisClusterVotes = cv::Mat(1, numPts, CV_32S, cv::Scalar::all(0)); //used to resolve conflicts on cluster membership + //ROS_ERROR_STREAM("Before getting into while myMean = ["<<myMeanX<<", "<<myMeanY<<", "<<myMeanZ<<"]"); + cv::Mat_<double> myMean = ( cv::Mat_<double>(3, 1) << myMeanX, myMeanY, myMeanZ); + + + while(true) + { + cv::Mat myDataPts; + dataPts.copyTo(myDataPts); + + //ROS_ERROR_STREAM("Original = "<<diffX); + //ROS_ERROR_STREAM("onesAux.rows = "<<onesAux.rows<<" cols = "<<onesAux.cols); + //ROS_ERROR_STREAM("dataPts.rows = "<<dataPts.rows<<" cols = "<<dataPts.cols); + //ROS_ERROR_STREAM("myMean.rows = "<<myMean.rows<<" cols = "<<myMean.cols); + + cv::Mat diff = myDataPts - myMean*onesAux; + cv::Mat diffdiff = diff.mul(diff); + cv::Mat sqDistToAll = diffdiff.row(0) +diffdiff.row(1) + diffdiff.row(2); //dist squared from mean to all points still active + + cv::Mat inInds = (sqDistToAll < bandSq); // Puts 255 wherever it is true + cv::add(thisClusterVotes, cv::Scalar(1), thisClusterVotes, inInds); //add a vote for all the in points belonging to this cluster + cv::Mat mask3 = cv::repeat(inInds==0, 3, 1); + + //ROS_ERROR_STREAM("BEFORE myMean = "<<myMean); + //ROS_ERROR_STREAM("sqDistToAll = "<<sqDistToAll); + //ROS_ERROR_STREAM("diffX = "<<diff.row(0)); + //ROS_ERROR_STREAM("diffdiffX = "<<diffdiff.row(0)); + //ROS_ERROR_STREAM("thisClusterVotes = "<<thisClusterVotes); + //ROS_ERROR_STREAM("dataPts = "<<dataPts); + + myDataPts.setTo(0, mask3); + double numOfOnes = (double) (cv::sum(inInds)[0])/255; //inInds is active if inInds[i]==255 + + myOldMeanX = myMeanX; myOldMeanY = myMeanY; myOldMeanZ = myMeanZ; + + myMeanX = cv::sum(myDataPts.row(0))[0]/numOfOnes; + myMeanY = cv::sum(myDataPts.row(1))[0]/numOfOnes; + myMeanZ = cv::sum(myDataPts.row(2))[0]/numOfOnes; + + myMean = ( cv::Mat_<double>(3, 1) << myMeanX, myMeanY, myMeanZ); + + //ROS_ERROR_STREAM("MIDDLE myMean = "<<myMean); + + diff = myDataPts - myMean*onesAux; + diffdiff = diff.mul(diff); + + cv::Mat weight; + cv::exp(diffdiff/lambda, weight); + + weight.setTo(0., mask3); //Again, because the exp and the x - u make invalid values non-zero (inInds) + cv::Mat wData = weight.mul(myDataPts); + + totalWeightX = cv::sum(weight.row(0))[0]; + totalWeightY = cv::sum(weight.row(1))[0]; + totalWeightZ = cv::sum(weight.row(2))[0]; + myMeanX = cv::sum(wData.row(0))[0]/totalWeightX; + myMeanY = cv::sum(wData.row(1))[0]/totalWeightY; + myMeanZ = cv::sum(wData.row(2))[0]/totalWeightZ; + + myMean = ( cv::Mat_<double>(3, 1) << myMeanX, myMeanY, myMeanZ); + //ROS_ERROR_STREAM("AFTER: myMean = "<<myMeanX<<","<<myMeanY<<","<<myMeanZ); + //exit(0); + + beenVisitedFlag.setTo(1, inInds); + //ROS_ERROR_STREAM("beenVisitedFlag = "<<beenVisitedFlag); + + // if mean doesn't move much stop this cluster + //ROS_ERROR_STREAM("Norm = "<<(myMeanX-myOldMeanX)*(myMeanX-myOldMeanX) + (myMeanY-myOldMeanY)*(myMeanY-myOldMeanY) + (myMeanZ-myOldMeanZ)*(myMeanZ-myOldMeanZ)); + if((myMeanX-myOldMeanX)*(myMeanX-myOldMeanX) + (myMeanY-myOldMeanY)*(myMeanY-myOldMeanY) + (myMeanZ-myOldMeanZ)*(myMeanZ-myOldMeanZ) < stopThresh*stopThresh) + { + //check for merge posibilities + //ROS_ERROR_STREAM("Dentro!! "); + int mergeWith = -1; + double distToOther; + for(int cN = 0; cN<numClust; cN++) //Careful!! cN goes from 1 to numClust!!! + { + double distToOther = (myMeanX - (*clusterCenterX)[cN])*(myMeanX - (*clusterCenterX)[cN]) + (myMeanY - (*clusterCenterY)[cN])*(myMeanY - (*clusterCenterY)[cN]) + (myMeanZ - (*clusterCenterZ)[cN])*(myMeanZ - (*clusterCenterZ)[cN]); //distance from posible new clust max to old clust max + //ROS_ERROR_STREAM("Dentro!! "); + //ROS_ERROR_STREAM("distToOther " <<distToOther); + if(distToOther < (bandwidth/2)*(bandwidth/2)) //if its within bandwidth/2 merge new and old + { + mergeWith = cN; + break; + } + } + + if(mergeWith > -1) + { + //ROS_ERROR_STREAM("Merging cluster with #"<<mergeWith); + //ROS_ERROR_STREAM("NumClust = "<<numClust); + //exit(0); + + (*clusterCenterX)[mergeWith] = 0.5*(myMeanX+(*clusterCenterX)[mergeWith]); + (*clusterCenterY)[mergeWith] = 0.5*(myMeanY+(*clusterCenterY)[mergeWith]); + (*clusterCenterZ)[mergeWith] = 0.5*(myMeanZ+(*clusterCenterZ)[mergeWith]); + + cv::Mat newClusterVotes = cv::Mat(clusterVotes.row(mergeWith)) + thisClusterVotes; + newClusterVotes.copyTo(clusterVotes.row(mergeWith)); + + //ROS_ERROR_STREAM("clusterVotes = "<<clusterVotes); + //exit(0); + } + else + { + //ROS_ERROR_STREAM("Creating new cluster"); + (*clusterCenterX).push_back(myMeanX); //record the mean + (*clusterCenterY).push_back(myMeanY); + (*clusterCenterZ).push_back(myMeanZ); + numClust = numClust+1; //increment clusters + + clusterVotes.push_back(thisClusterVotes); // add the new row for the new cluster + + //ROS_ERROR_STREAM("clusterVotes = "<<clusterVotes); + //ROS_ERROR_STREAM("ClusterCenterX = "<<(*clusterCenterX)[numClust-1]); + //ROS_ERROR_STREAM("ClusterCenterY = "<<(*clusterCenterY)[numClust-1]); + //ROS_ERROR_STREAM("ClusterCenterZ = "<<(*clusterCenterZ)[numClust-1]); + //exit(0); + } + break; + } + } + + std::vector<int> newInitPtInds; //we can initialize with any of the points not yet visited + for(int i=0; i<numPts; i++) + if (beenVisitedFlag.at<int>(cv::Point(i, 0)) == 0) + newInitPtInds.push_back(i); + initPtInds = newInitPtInds; + numInitPts = initPtInds.size(); //number of active points in set + } + + cv::Mat TclusterVotes = clusterVotes.t(); + cv::Point minLoc; + cv::Point maxLoc; + double min, max; + for(int i=0; i<TclusterVotes.rows; i++) + { + cv::minMaxLoc(cv::Mat(TclusterVotes.row(i)), &min, &max, &minLoc, &maxLoc); + (*point2Clusters).push_back(maxLoc.x); + } + + //ROS_ERROR_STREAM("Number of clusters " <<numClust<<" and "<<(*clusterCenterX).size()); + //ROS_ERROR_STREAM("Tclusters rows " <<TclusterVotes.rows<<" cols "<<TclusterVotes.cols); +} + +void colorMeanShiftFilt(double *newPixelsPtr, const double *pixelsPtr, int mPixels, int maxPixelDim, const double *imagePtr, int numRows, int numCols, float spaceDivider, char *kernelFun, int maxIterNum, float tolFun) +{ + // Copy the original pixel values to the new pixel matrix + memcpy(newPixelsPtr, pixelsPtr, maxPixelDim*mPixels*sizeof(double)); + + // Copy the original image to a new image + double *newImagePtr=new double[mPixels]; + memcpy(newImagePtr, imagePtr, mPixels*sizeof(double)); + + // Help variables + double x,y,val; + int neighX, neighY; + bool bRepeat=false; + + double *delta = (double *) calloc(maxPixelDim,sizeof(double)); + double *dX = (double *) calloc(maxPixelDim,sizeof(double)); + double *neighVec = (double *) calloc(maxPixelDim,sizeof(double)); + double deltaGrad2; + + // Create an array that indicates if we reached the end of the optimization for each pixel + double *optimizedPointArray=new double[mPixels]; + + for (int iterNum=0; iterNum<maxIterNum; iterNum++) + { + bRepeat=false; + + cv::Mat XX=cv::Mat(numRows, numCols, CV_64F, newPixelsPtr); + cv::Mat YY=cv::Mat(numRows, numCols, CV_64F, newPixelsPtr+mPixels); + cv::Mat MM=cv::Mat(numRows, numCols, CV_64F, newPixelsPtr+2*mPixels); + + for (int pointNum=0; pointNum<mPixels; pointNum++) + { + if (optimizedPointArray[pointNum]==1) // The optimization for this pixel has reached the threshold + continue; + + x=newPixelsPtr[_2D_to_linear(0, pointNum, mPixels)]; + y=newPixelsPtr[_2D_to_linear(1, pointNum, mPixels)]; + val=newPixelsPtr[_2D_to_linear(2, pointNum, mPixels)]; + + //ROS_ERROR("y = %d, x = %d, pointNum = %d, spaceDivider = %g", (int)floor(y), (int)floor(x), pointNum, spaceDivider); + double sumF; + + int x_coord = max(0, floor(x*spaceDivider)-1-spaceDivider); + int y_coord = max(0, floor(y*spaceDivider)-1-spaceDivider); + int width = min(2*spaceDivider+1, numCols-x_coord); + int height= min(2*spaceDivider+1, numRows-y_coord); + + cv::Mat submatXX = XX(cv::Rect(x_coord, y_coord, width, height)).clone(); + cv::Mat submatYY = YY(cv::Rect(x_coord, y_coord, width, height)).clone(); + cv::Mat submatMM = MM(cv::Rect(x_coord, y_coord, width, height)).clone(); + + cv::Mat delta_XX, delta_YY, delta_MM, dist2_matrix, kres_matrix; + delta_XX = x - submatXX; + delta_YY = y - submatYY; + delta_MM = val - submatMM; + dist2_matrix = delta_XX.mul(delta_XX) + delta_YY.mul(delta_YY) + delta_MM.mul(delta_MM); + cv::exp(dist2_matrix/(-2.0), kres_matrix); //kres =(exp(-dist2/2.0)); + + dX[0] = cv::sum(kres_matrix.mul(submatXX))[0];//cv::sum() returns a cvScalar, to get the value we need .val(0) + dX[1] = cv::sum(kres_matrix.mul(submatYY))[0]; + dX[2] = cv::sum(kres_matrix.mul(submatMM))[0]; + sumF = cv::sum(kres_matrix)[0]; + + // Find the corresponding row and column of the point + + dX[0]=(sumF==0)?0:dX[0]/sumF; //check for NaNs + dX[1]=(sumF==0)?0:dX[1]/sumF; //check for NaNs + dX[2]=(sumF==0)?0:dX[2]/sumF; //check for NaNs + + double tmp1=newPixelsPtr[_2D_to_linear(0, pointNum, mPixels)]-dX[0]; + double tmp2=newPixelsPtr[_2D_to_linear(1, pointNum, mPixels)]-dX[1]; + double tmp3=newPixelsPtr[_2D_to_linear(2, pointNum, mPixels)]-dX[2]; + + deltaGrad2=tmp1*tmp1+tmp2*tmp2+tmp3*tmp3; + newPixelsPtr[_2D_to_linear(0, pointNum, mPixels)]=dX[0]; + newPixelsPtr[_2D_to_linear(1, pointNum, mPixels)]=dX[1]; + newPixelsPtr[_2D_to_linear(2, pointNum, mPixels)]=dX[2]; + + newImagePtr[pointNum]=dX[2]; + + if (deltaGrad2<tolFun) + optimizedPointArray[pointNum]=1; + else + bRepeat=true; + + } // end pointNum loop + + if (bRepeat==false) + break; + + } // end for(iterNum) loop + + + // CLEAN-UP + delete[] newImagePtr; + delete[] optimizedPointArray; + delete(delta); + delete(dX); + delete(neighVec); +} + + + diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/image_reconst.cpp b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/image_reconst.cpp new file mode 100755 index 0000000..1d58720 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/image_reconst.cpp @@ -0,0 +1,568 @@ +/* + * image_reconst.cpp + * + * Created on: Nov 3, 2016 + * Author: fran + */ + +/* +######################### Poisson Image Editing ############################ + +Copyright (C) 2012 Siddharth Kherada +Copyright (C) 2006-2012 Natural User Interface Group + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. " + +############################################################################## +*/ + +#include <iostream> +#include <stdio.h> +#include <stdlib.h> +#include <complex> +#include "image_reconstruct/image_reconst.h" +#include <math.h> +#include <omp.h> + +//using namespace std; +//using namespace cv; + +#define pi 3.1416 + +#define ATF at<float> +#define AT3F at<Vec3f> +#define ATB at<uchar> +#define AT3B at<Vec3b> + +/////////////////////Poisson Equation Solver by FFT///////////////////// +void dst(double *btest, double *bfinal, int h, int w) +{ + + unsigned long int idx; + + cv::Mat temp = cv::Mat(2 * h + 2, 1, CV_32F); + cv::Mat res = cv::Mat(h, 1, CV_32F); + + int p = 0; + + for (int i = 0; i<w; i++) + { + temp.ATF(0, 0) = 0.0; + + for (int j = 0, r = 1; j<h; j++, r++) + { + idx = j*w + i; + temp.ATF(r, 0) = (float)btest[idx]; + } + + temp.ATF(h + 1, 0) = 0.0; + + for (int j = h - 1, r = h + 2; j >= 0; j--, r++) + { + idx = j*w + i; + temp.ATF(r, 0) = (float)(-1 * btest[idx]); + } + + cv::Mat planes[] = { cv::Mat_<float>(temp), cv::Mat::zeros(temp.size(), CV_32F) }; + + cv::Mat complex1; + merge(planes, 2, complex1); + + dft(complex1, complex1, 0, 0); + + cv::Mat planes1[] = { cv::Mat::zeros(complex1.size(), CV_32F), cv::Mat::zeros(complex1.size(), CV_32F) }; + + split(complex1, planes1); + + std::complex<double> two_i = std::sqrt(std::complex<double>(-1)); + + double fac = -2 * imag(two_i); + + for (int c = 1, z = 0; c<h + 1; c++, z++) + { + res.ATF(z, 0) = (float)(planes1[1].ATF(c, 0) / fac); + } + + for (int q = 0, z = 0; q<h; q++, z++) + { + idx = q*w + p; + bfinal[idx] = res.ATF(z, 0); + } + p++; + } + +} + +void idst(double *btest, double *bfinal, int h, int w) +{ + int nn = h + 1; + dst(btest, bfinal, h, w); + #pragma omp parallel for + for (int i = 0; i<h; i++) + for (int j = 0; j<w; j++) + { + unsigned long int idx = i*w + j; + bfinal[idx] = (double)(2 * bfinal[idx]) / nn; + } + +} + +void transpose(double *mat, double *mat_t, int h, int w) +{ + + cv::Mat tmp = cv::Mat(h, w, CV_32FC1); + int p = 0; + + #pragma omp parallel for + for (int i = 0; i < h; i++) + { + for (int j = 0; j < w; j++) + { + + unsigned long int idx = i*(w)+j; + tmp.ATF(i, j) = (float)(mat[idx]); + } + } + cv::Mat tmp_t = tmp.t(); + + unsigned long int idx; + for (int i = 0; i < tmp_t.size().height; i++) + for (int j = 0; j<tmp_t.size().width; j++) + { + idx = i*tmp_t.size().width + j; + mat_t[idx] = tmp_t.ATF(i, j); + } + +} + + +void getGradientX(cv::Mat &img, cv::Mat &gx) +{ + int height = img.rows; + int width = img.cols; + cv::Mat cat = repeat(img, 1, 2); + /*cat.col(width) = 0;*/ + cv::Mat roimat = cat(cv::Rect(1, 0, width, height)); + gx = roimat - img; + gx.col(width - 1) = 0; +} + +// calculate vertical gradient, gy(i, j) = img(i, j+1) - img(i, j) +void getGradientY(cv::Mat &img, cv::Mat &gy) +{ + int height = img.rows; + int width = img.cols; + cv::Mat cat = repeat(img, 2, 1); + /*cat.row(height) = 0;*/ + cv::Mat roimat = cat(cv::Rect(0, 1, width, height)); + gy = roimat - img; + gy.row(height - 1) = 0; +} + +// calculate horizontal gradient, gxx(i+1, j) = gx(i+1, j) - gx(i, j) +void lapx(cv::Mat &gx, cv::Mat &gxx) +{ + int height = gx.rows; + int width = gx.cols; + cv::Mat cat = repeat(gx, 1, 2); + /*cat.col(width - 1) = 0;*/ + cv::Mat roi = cat(cv::Rect(width - 1, 0, width, height)); + gxx = gx - roi; + gxx.col(0) = 0; +} + +// calculate vertical gradient, gyy(i, j+1) = gy(i, j+1) - gy(i, j) +void lapy(cv::Mat &gy, cv::Mat &gyy) +{ + int height = gy.rows; + int width = gy.cols; + cv::Mat cat = repeat(gy, 2, 1); + /*cat.row(height - 1) = 0;*/ + cv::Mat roi = cat(cv::Rect(0, height - 1, width, height)); + gyy = gy - roi; + gyy.row(0) = 0; +} + + + +void poisson_solver(cv::Mat &img, cv::Mat &gxx, cv::Mat &gyy, cv::Mat &result){ + + int w = img.cols; + int h = img.rows; + int channel = img.channels(); + + unsigned long int idx; + + cv::Mat lap = gxx + gyy; + + cv::Mat bound(img); + bound(cv::Rect(1, 1, w - 2, h - 2)) = 0; + double *dir_boundary = new double[h*w]; + +#pragma omp parallel for + for (int i = 1; i < h - 1; i++) + for (int j = 1; j < w - 1; j++) + { + unsigned long int idx = i*w + j; + if ( i == 1 || i == h - 2 || j == 1 || j == w - 2 ) + dir_boundary[idx] = (int)bound.ATF(i, (j + 1)) + (int)bound.ATF(i, (j - 1)) + (int)bound.ATF(i - 1, j) + (int)bound.ATF(i + 1, j); + else dir_boundary[idx] = 0; + + } + + + cv::Mat diff(h, w, CV_32FC1); + +#pragma omp parallel for + for (int i = 0; i<h; i++) + { + for (int j = 0; j<w; j++) + { + unsigned long int idx = i*w + j; + diff.ATF(i, j) = (float)(lap.ATF(i, j) - dir_boundary[idx]); + } + } + + double *btemp = new double[(h - 2)*(w - 2)]; +#pragma omp parallel for + for (int i = 0; i < h - 2; i++) + { + for (int j = 0; j < w - 2; j++) + { + unsigned long int idx = i*(w - 2) + j; + btemp[idx] = diff.ATF(i + 1, j + 1); + + } + } + + double *bfinal = new double[(h - 2)*(w - 2)]; + double *bfinal_t = new double[(h - 2)*(w - 2)]; + double *denom = new double[(h - 2)*(w - 2)]; + double *fres = new double[(h - 2)*(w - 2)]; + double *fres_t = new double[(h - 2)*(w - 2)]; + + + dst(btemp, bfinal, h - 2, w - 2); + + transpose(bfinal, bfinal_t, h - 2, w - 2); + + dst(bfinal_t, bfinal, w - 2, h - 2); + + transpose(bfinal, bfinal_t, w - 2, h - 2); + + int cx = 1; + int cy = 1; + + for (int i = 0; i < w - 2; i++, cy++) + { + for (int j = 0, cx = 1; j < h - 2; j++, cx++) + { + idx = j*(w - 2) + i; + denom[idx] = (float)2 * cos(pi*cy / ((double)(w - 1))) - 2 + 2 * cos(pi*cx / ((double)(h - 1))) - 2; + + } + } + + for (idx = 0; (int)idx < (w - 2)*(h - 2); idx++) + { + bfinal_t[idx] = bfinal_t[idx] / denom[idx]; + } + + + idst(bfinal_t, fres, h - 2, w - 2); + + transpose(fres, fres_t, h - 2, w - 2); + + idst(fres_t, fres, w - 2, h - 2); + + transpose(fres, fres_t, w - 2, h - 2); + + + img.convertTo(result, CV_8UC1); + + + cv::Mat tmp = cv::Mat(h-2, w-2, CV_64F, fres_t); + double min, max; + cv::minMaxLoc(tmp, &min, &max); + + + #pragma omp parallel for + for (int i = 0; i < h - 2; i++) + { + for (int j = 0; j < w - 2; j++) + { + unsigned long int idx = i*(w - 2) + j; + //if (fres_t[idx] < 0.0) + // result.ATB(i+1, j+1) = 0; + //else if (fres_t[idx] > 255.0) + // result.ATB(i+1, j+1) = 255; + //else + // result.ATB(i+1, j+1) = (int)fres_t[idx]; + result.ATB(i+1,j+1) = (int) (255*(fres_t[idx]-min)/(max-min)); + } + } + +} + +void poisson_solver_jacobi(cv::Mat &img, cv::Mat &gxx, cv::Mat &gyy, cv::Mat &result) { + int w = img.cols; + int h = img.rows; + int channel = img.channels(); + + unsigned long int idx; + + cv::Mat lap = gxx + gyy; + + cv::Mat bound(img); + bound(cv::Rect(1, 1, w - 2, h - 2)) = 0; + double *dir_boundary = new double[h*w]; + + #pragma omp parallel for + for (int i = 1; i < h - 1; i++) + for (int j = 1; j < w - 1; j++) + { + idx = i*w + j; + if (i == 1 || i == h - 2 || j == 1 || j == w - 2) + dir_boundary[idx] = (int)bound.ATF(i, (j + 1)) + (int)bound.ATF(i, (j - 1)) + (int)bound.ATF(i - 1, j) + (int)bound.ATF(i + 1, j); + else dir_boundary[idx] = 0; + + } + + + cv::Mat diff(h, w, CV_32FC1); + #pragma omp parallel for + for (int i = 0; i < h; i++) + { + for (int j = 0; j < w; j++) + { + idx = i*w + j; + diff.ATF(i, j) = (float)(-lap.ATF(i, j) + dir_boundary[idx]); + } + } + + double *gtest = new double[(h - 2)*(w - 2)]; + #pragma omp parallel for + for (int i = 0; i < h - 2; i++) + { + for (int j = 0; j < w - 2; j++) + { + idx = i*(w - 2) + j; + gtest[idx] = diff.ATF(i + 1, j + 1); + + } + } + //Iteration begins + cv::Mat U = cv::Mat::zeros(img.size(), CV_32FC3); + int k = 0; + while (k <= 3000){ + #pragma omp parallel for + for (int i = 1; i < h - 1; i++) + { + for (int j = 1; j < w - 1; j++) + { + U.ATF(i, j) = (float)((U.ATF(i + 1, j) + U.ATF(i, j + 1) + U.ATF(i - 1, j) + U.ATF(i, j - 1) + diff.ATF(i, j)) / 4.0); + } + } + k++; + } + + img.convertTo(result, CV_8UC1); + #pragma omp parallel for + for (int i = 1; i < h - 1; i++) + { + for (int j = 1; j < w - 1; j++) + { + if (U.ATF(i,j) < 0.0) + result.ATB(i , j ) = 0; + else if (U.ATF(i, j) > 255.0) + result.ATB(i, j) = 255; + else + result.ATB(i , j ) = (int)U.ATF(i, j); + } + } +} + + +//IplImage versions + +void lapx( const IplImage *img, IplImage *gxx) +{ + int w = img->width; + int h = img->height; + int channel = img->nChannels; + + cvZero( gxx ); + for(int i=0;i<h;i++) + for(int j=0;j<w-1;j++) + for(int c=0;c<channel;++c) + { + CV_IMAGE_ELEM(gxx,float,i,(j+1)*channel+c) = + (float)CV_IMAGE_ELEM(img,float,i,(j+1)*channel+c) - (float)CV_IMAGE_ELEM(img,float,i,j*channel+c); + } +} +void lapy( const IplImage *img, IplImage *gyy) +{ + int w = img->width; + int h = img->height; + int channel = img->nChannels; + + cvZero( gyy ); + for(int i=0;i<h-1;i++) + for(int j=0;j<w;j++) + for(int c=0;c<channel;++c) + { + CV_IMAGE_ELEM(gyy,float,i+1,j*channel+c) = + (float)CV_IMAGE_ELEM(img,float,(i+1),j*channel+c) - (float)CV_IMAGE_ELEM(img,float,i,j*channel+c); + + } +} + +void poisson_solver(const IplImage *img, IplImage *gxx , IplImage *gyy, cv::Mat &result) +{ + + int w = img->width; + int h = img->height; + int channel = img->nChannels; + + unsigned long int idx,idx1; + + IplImage *lap = cvCreateImage(cvGetSize(img), 32, 1); + + for(int i =0;i<h;i++) + for(int j=0;j<w;j++) + CV_IMAGE_ELEM(lap,float,i,j)=CV_IMAGE_ELEM(gyy,float,i,j)+CV_IMAGE_ELEM(gxx,float,i,j); + + //cv::Mat bound(img); + cv::Mat bound = cv::cvarrToMat(img); + + for(int i =1;i<h-1;i++) + for(int j=1;j<w-1;j++) + { + bound.at<uchar>(i,j) = 0.0; + } + + double *f_bp = new double[h*w]; + + + for(int i =1;i<h-1;i++) + for(int j=1;j<w-1;j++) + { + idx=i*w + j; + f_bp[idx] = -4*(int)bound.at<uchar>(i,j) + (int)bound.at<uchar>(i,(j+1)) + (int)bound.at<uchar>(i,(j-1)) + + (int)bound.at<uchar>(i-1,j) + (int)bound.at<uchar>(i+1,j); + } + + + cv::Mat diff = cv::Mat(h,w,CV_32FC1); + for(int i =0;i<h;i++) + { + for(int j=0;j<w;j++) + { + idx = i*w+j; + diff.at<float>(i,j) = (CV_IMAGE_ELEM(lap,float,i,j) - f_bp[idx]); + } + } + double *gtest = new double[(h-2)*(w-2)]; + for(int i = 0 ; i < h-2;i++) + { + for(int j = 0 ; j < w-2; j++) + { + idx = i*(w-2) + j; + gtest[idx] = diff.at<float>(i+1,j+1); + + } + } + ///////////////////////////////////////////////////// Find DST ///////////////////////////////////////////////////// + + double *gfinal = new double[(h-2)*(w-2)]; + double *gfinal_t = new double[(h-2)*(w-2)]; + double *denom = new double[(h-2)*(w-2)]; + double *f3 = new double[(h-2)*(w-2)]; + double *f3_t = new double[(h-2)*(w-2)]; + double *img_d = new double[(h)*(w)]; + + dst(gtest,gfinal,h-2,w-2); + + transpose(gfinal,gfinal_t,h-2,w-2); + + dst(gfinal_t,gfinal,w-2,h-2); + + transpose(gfinal,gfinal_t,w-2,h-2); + + int cx=1; + int cy=1; + + for(int i = 0 ; i < w-2;i++,cy++) + { + for(int j = 0,cx = 1; j < h-2; j++,cx++) + { + idx = j*(w-2) + i; + denom[idx] = (float) 2*cos(pi*cy/( (double) (w-1))) - 2 + 2*cos(pi*cx/((double) (h-1))) - 2; + + } + } + + for(idx = 0 ; idx < (w-2)*(h-2) ;idx++) + { + gfinal_t[idx] = gfinal_t[idx]/denom[idx]; + } + + + idst(gfinal_t,f3,h-2,w-2); + + transpose(f3,f3_t,h-2,w-2); + + idst(f3_t,f3,w-2,h-2); + + transpose(f3,f3_t,w-2,h-2); + + for(int i = 0 ; i < h;i++) + { + for(int j = 0 ; j < w; j++) + { + idx = i*w + j; + img_d[idx] = (double)CV_IMAGE_ELEM(img,uchar,i,j); + } + } + for(int i = 1 ; i < h-1;i++) + { + for(int j = 1 ; j < w-1; j++) + { + idx = i*w + j; + img_d[idx] = 0.0; + } + } + int id1,id2; + for(int i = 1,id1=0 ; i < h-1;i++,id1++) + { + for(int j = 1,id2=0 ; j < w-1; j++,id2++) + { + idx = i*w + j; + idx1= id1*(w-2) + id2; + img_d[idx] = f3_t[idx1]; + } + } + + for(int i = 0 ; i < h;i++) + { + for(int j = 0 ; j < w; j++) + { + idx = i*w + j; + if(img_d[idx] < 0.0) + result.at<uchar>(i,j) = 0; + else if(img_d[idx] > 255.0) + result.at<uchar>(i,j) = 255.0; + else + result.at<uchar>(i,j) = img_d[idx]; + } + } + +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/meanshift.cpp b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/meanshift.cpp new file mode 100755 index 0000000..5eca46e --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/meanshift.cpp @@ -0,0 +1,1684 @@ + +#include "dvs_meanshift/meanshift.h" +#include "dvs_meanshift/color_meanshift.h" +#include "image_reconstruct/image_reconst.h" +#include <time.h> + +//remove this include, just for debugging +#include "graph3d/pnmfile.h" +#include <std_msgs/Float32.h> + +#define min(x,y) ((x)<(y)?(x):(y)) + +double epsilon = 1E-10; +int counterGlobal = 0; +const int MAX_DISTANCE = 500; //actually the real distance is sqrt(MAX_DISTANCE) + +bool firstevent = true; +double firsttimestamp; + +//std::ofstream foutX("/home/fran/0_tmp/kk/shapes_rotation_totalevents.txt"); +//std::ofstream fouttotalproc("/home/fran/0_tmp/kk/shapes_rotation_totalprocessing_f.txt"); +//std::ofstream foutX("/home/fran/0_tmp/kk/shapes_rotation_2_totalevents.txt"); +//std::ofstream fouttotalproc("/home/fran/0_tmp/kk/shapes_rotation_2_totalprocessing_f.txt"); +//std::ofstream foutX("/home/fran/0_tmp/kk/shapes_translation_totalevents.txt"); +//std::ofstream fouttotalproc("/home/fran/0_tmp/kk/shapes_translation_totalprocessing_f.txt"); +//std::ofstream foutX("/home/fran/0_tmp/kk/shapes_translation_2_totalevents.txt"); +//std::ofstream fouttotalproc("/home/fran/0_tmp/kk/shapes_translation_2_totalprocessing_f.txt"); +//std::ofstream foutX("/home/fran/0_tmp/kk/shapes_6dof_totalevents.txt"); +//std::ofstream fouttotalproc("/home/fran/0_tmp/kk/shapes_6dof_totalprocessing_f.txt"); +//std::ofstream foutX("/home/fran/0_tmp/kk/shapes_6dof_2_totalevents.txt"); +//std::ofstream fouttotalproc("/home/fran/0_tmp/kk/shapes_6dof_2_totalprocessing_f.txt"); +//std::ofstream foutnumclust("/home/fran/0_tmp/kk/shapes_translation_numclusters_f.txt"); +//std::ofstream foutnumclust("/home/fran/0_tmp/kk/shapes_rotation_numclusters_f.txt"); +//std::ofstream foutnumclust("/home/fran/0_tmp/kk/shapes_6dof_numclusters_f.txt"); +//std::ofstream foutnumclust("/home/fran/0_tmp/kk/shapes_6dof_2_numclusters_f.txt"); +//std::ofstream foutnumclust("/home/fran/0_tmp/kk/shapes_rotation_2_numclusters_f.txt"); +//std::ofstream foutnumclust("/home/fran/0_tmp/kk/shapes_translation_2_numclusters_f.txt"); + +#if KALMAN_FILTERING +std::ofstream foutX("/home/fran/0_tmp/kk/traj.txt"); +//std::ofstream foutX_estim("/home/fran/0_tmp/kk/filt_traj.txt"); +//std::ofstream foutT("/home/fran/0_tmp/kk/timetraj.txt"); +#endif + +namespace dvs_meanshift { + +void writeMatToFile(cv::Mat & m, const char* filename) +{ + std::ofstream fout(filename); + + if(!fout) + { + std::cout<<"File Not Opened"<<std::endl; return; + } + + for(int i=0; i<m.rows; i++) + { + for(int j=0; j<m.cols; j++) + { + fout<<m.at<double>(i,j)<<"\t"; + } + fout<<std::endl; + } + fout.close(); +} + +class Parallel_pixel_cosine: public cv::ParallelLoopBody +{ + +public: + + Parallel_pixel_cosine(cv::Mat imgg) : img(imgg) + { + } + + void operator() (const cv::Range &r) const + { + for(int j=r.start; j<r.end; ++j) + { + double* current = const_cast<double*>(img.ptr<double>(j)); + double* last = current + img.cols; + + for (; current != last; ++current) + *current = (double) cos((double) *current); + } + } + +private: + cv::Mat img; +}; + +void meshgrid(const cv::Mat &xgv, const cv::Mat &ygv, cv::Mat1i &X, cv::Mat1i &Y) +{ + cv::repeat(xgv.reshape(1,1), ygv.total(), 1, X); + cv::repeat(ygv.reshape(1,1).t(), 1, xgv.total(), Y); +} + +// helper function (maybe that goes somehow easier) + void meshgridTest(const cv::Range &xgv, const cv::Range &ygv, cv::Mat1i &X, cv::Mat1i &Y) +{ + std::vector<int> t_x, t_y; + for (int i = xgv.start; i <= xgv.end; i++) t_x.push_back(i); + for (int i = ygv.start; i <= ygv.end; i++) t_y.push_back(i); + + meshgrid(cv::Mat(t_x), cv::Mat(t_y), X, Y); +} + +void findClosestCluster(std::vector<int> * clustID, std::vector<double> clustX, std::vector<double> clustY,std::vector<double>clustX_old,std::vector<double> clustY_old) +{ + + //for (int i = 0; i<clustX.size(); i++) + // ROS_ERROR_STREAM("ClusterCenter("<<i+1<<",:)=["<<clustX.at(i)<<","<<clustY.at(i)<<"];"); + //for (int i = 0; i<clustX_old.size(); i++) + // ROS_ERROR_STREAM("prev_ClusterCenter("<<i+1<<",:)=["<<clustX_old.at(i)<<","<<clustY_old.at(i)<<"];"); + + std::vector<double> distvalue (clustX.size()); + double tmp; + + for(int i=0; i<clustX.size(); i++) + { + distvalue[i]=MAX_DISTANCE; + (*clustID).push_back(-1); //no match when clustID is -1 + for(int j=0; j<clustX_old.size(); j++) + { + tmp= (clustX[i]*DVSW-clustX_old[j]*DVSW)*(clustX[i]*DVSW-clustX_old[j]*DVSW) + (clustY[i]*DVSH-clustY_old[j]*DVSH)*(clustY[i]*DVSH-clustY_old[j]*DVSH); + if(tmp<distvalue[i]) + { + distvalue[i]=tmp; + (*clustID)[i]=j; + //ROS_ERROR_STREAM("Cluster "<<i+1<<" same than old cluster "<<j+1<<". Distance = "<<distvalue[i]); + } + } + } +} + +/* +void Meanshift::assignClusterColor(std::vector<int> * positionClusterColor, int numClusters, std::vector<int> matches, std::vector<int> oldPositions) +{ + + if (matches.size()==0) //no mask --> assing all new colors + { + for(int i=0; i<numClusters; i++) + { + (*positionClusterColor).push_back(lastPositionClusterColor); + lastPositionClusterColor = lastPositionClusterColor+1; + } + } + else + { + for(int i=0; i<numClusters; i++) + { + if(matches[i]==-1) //No match with previous clusters --> new cluster, new color + { + (*positionClusterColor).push_back(lastPositionClusterColor); + lastPositionClusterColor = lastPositionClusterColor+1; + } + else //Match with previous cluster --> assign color of previous cluster + { + (*positionClusterColor).push_back(oldPositions[matches[i]]); + } + } + + } +}*/ + +void Meanshift::assignClusterColor(std::vector<int> * positionClusterColor, int numClusters, std::vector<int> matches, std::vector<int> oldPositions, std::vector<int> activeTrajectories) +{ + + if (matches.size()==0) //no mask --> assing all new colors + { + for(int i=0; i<numClusters; i++) + { + (*positionClusterColor).push_back(lastPositionClusterColor); + lastPositionClusterColor = lastPositionClusterColor+1; + } + } + else + { + for(int i=0; i<numClusters; i++) + { + if(matches[i]==-1) //No match with previous clusters --> new cluster, new color + { + //Check if the new position is being used + while ( activeTrajectories.end() != find (activeTrajectories.begin(), activeTrajectories.end(), (lastPositionClusterColor & (MAX_NUM_CLUSTERS-1)))) + lastPositionClusterColor++; + + (*positionClusterColor).push_back(lastPositionClusterColor); + lastPositionClusterColor = lastPositionClusterColor+1; + } + else //Match with previous cluster --> assign color of previous cluster + { + (*positionClusterColor).push_back(oldPositions[matches[i]]); + } + } + + } +} + +Meanshift::Meanshift(ros::NodeHandle & nh, ros::NodeHandle nh_private) : nh_(nh) +{ + used_last_image_ = false; + + // get parameters of display method + std::string display_method_str; + nh_private.param<std::string>("display_method", display_method_str, ""); + display_method_ = (display_method_str == std::string("grayscale")) ? GRAYSCALE : RED_BLUE; + + // setup subscribers and publishers + //event_sub_ = nh_.subscribe("events", 1, &Meanshift::eventsCallback, this); + + //Change this back to events + event_sub_ = nh_.subscribe("/AADC_AudiTT/camera_front/events", 1, &Meanshift::eventsCallback_simple, this); + camera_info_sub_ = nh_.subscribe("camera_info", 1, &Meanshift::cameraInfoCallback, this); + + image_transport::ImageTransport it_(nh_); + + image_pub_ = it_.advertise("dvs_rendering", 1); + image_segmentation_pub_ = it_.advertise("dvs_segmentation", 1); + + dirUB = nh_.advertise<std_msgs::String>("/obj_det", 1); + + + for(int i = 0; i < MAX_NUM_CLUSTERS ; ++i) + { + preVariance[i] = 0; + counterFor[i] = 0; + counterBar[i] = 0; + } + + //DEBUGGING + image_debug1_pub_ = it_.advertise("dvs_debug1", 1); + image_debug2_pub_ = it_.advertise("dvs_debug2", 1); + //NOT DEBUGGING + + //Initializing params for color meanshift + //computing image calibration + numRows=DVSH; numCols=DVSW; + mPixels=numRows*numCols; maxPixelDim=3; + + spaceDivider=7; timeDivider = 5; + maxIterNum=1; + tolFun=0.0001; + kernelFun[0] = 'g'; kernelFun[1] = 'a'; kernelFun[2] = 'u'; kernelFun[3] = 's'; + kernelFun[4] = 's'; kernelFun[5] = 'i'; kernelFun[6] = 'a'; kernelFun[7] = 'n'; + + //Initialize pointers + outputFeatures = NULL; imagePtr = NULL; pixelsPtr = NULL; + initializationPtr=new double[maxPixelDim*mPixels/4]; + + /*for (int i = 0; i < numRows; i++) + for (int j = 0; j < numCols; j++) + { + initializationPtr[i*numCols + j]=j/spaceDivider;//x + initializationPtr[mPixels+i*numCols+j]=i/spaceDivider;//y + initializationPtr[2*mPixels+i*numCols+j]=0;//img + + }*/ + + //Write xposition, yposition, and image in the same vector + for (int i = 0; i < numRows/2; i++) + for (int j = 0; j < numCols/2; j++) + { + initializationPtr[i*numCols/2 + j]=j/spaceDivider;//x + initializationPtr[mPixels/4+i*numCols/2+j]=i/spaceDivider;//y + initializationPtr[2*mPixels/4+i*numCols/2+j]=0;//img + + } + + //Initialize params for graph3d segmentation + sigma = 0.75; + k = 500; + min_region = (int)(numRows*numCols*0.01); + num_components = 0; + + //Initialization of random seed + srand(time(NULL));//Random seed initialization + //asm("rdtsc\n" + // "mov edi, eax\n" + // "call srand"); + + //Create first the RGB values and then assign it to the clusters + //(hopefully, this will keep some stability in the cluster colors along consecutive frames) + //Assume we won't have more than 50 clusters + for(int i=0; i<MAX_NUM_CLUSTERS; i++) + { + RGBColors.push_back(cv::Vec3b((uchar)random(), (uchar)random(), (uchar)random())); + //counterTrajectories.push_back(0);//initialize counter trajectories to all zeros + } + counterTrajectories=std::vector<int>(MAX_NUM_CLUSTERS,0); + + lastPositionClusterColor=0; + + //Initializing trajectories + trajectories = cv::Mat(numRows, numCols, CV_8UC3); + trajectories = cv::Scalar(128,128,128); + + //Initialize trajectory matrix + allTrajectories = new std::vector<cv::Point>[MAX_NUM_CLUSTERS]; + for(int i = 0; i < MAX_NUM_CLUSTERS; i++) + { + allTrajectories[i] = std::vector<cv::Point>(MAX_NUM_TRAJECTORY_POINTS); + } + prev_activeTrajectories=std::vector<int>(MAX_NUM_CLUSTERS,0); + + //Init Kalman filter + //createKalmanFilter(); + vector_of_kf=std::vector<cv::KalmanFilter>(MAX_NUM_CLUSTERS); + vector_of_meas=std::vector<cv::Mat>(MAX_NUM_CLUSTERS); + vector_of_state=std::vector<cv::Mat>(MAX_NUM_CLUSTERS); + for(int i=0; i<vector_of_kf.size(); i++) + createKalmanFilter(&(vector_of_kf[i]), &(vector_of_state[i]), &(vector_of_meas[i])); + + selectedTrajectory = -1; + //foundBlobs = false; + vector_of_foundBlobs=std::vector<bool>(MAX_NUM_CLUSTERS,false); + notFoundBlobsCount = 0; + //foundTrajectory=false; + foundTrajectory = std::vector<bool>(MAX_NUM_CLUSTERS, false); + //ticks = 0; + vector_of_ticks=std::vector<double> (MAX_NUM_CLUSTERS,0.0); + + //BG activity filtering + BGAFframe = cv::Mat(numRows, numCols, CV_32FC1); + BGAFframe =cv::Scalar(0.); +} + +Meanshift::~Meanshift() +{ + delete [] initializationPtr; + +#if KALMAN_FILTERING + foutX.close(); + //foutX_estim.close(); + //foutT.close(); +#endif + image_pub_.shutdown(); + image_segmentation_pub_.shutdown(); + image_debug1_pub_.shutdown(); +} + +void Meanshift::cameraInfoCallback(const sensor_msgs::CameraInfo::ConstPtr& msg) +{ + camera_matrix_ = cv::Mat(3, 3, CV_64F); + for (int i = 0; i < 3; i++) + for (int j = 0; j < 3; j++) + camera_matrix_.at<double>(cv::Point(i, j)) = msg->K[i+j*3]; + + dist_coeffs_ = cv::Mat(msg->D.size(), 1, CV_64F); + for (int i = 0; i < msg->D.size(); i++) + dist_coeffs_.at<double>(i) = msg->D[i]; +} + + +void Meanshift::createKalmanFilter(cv::KalmanFilter *kf, cv::Mat *state, cv::Mat *meas) +{ + /* + * This implementation takes 6 states position, velocity, and dimensions of the bounding box + int stateSize = 6; + int measSize = 4; + int contrSize = 0; + + unsigned int type = CV_32F; + + //cv::KalmanFilter kf(stateSize, measSize, contrSize, type); + kf.init(stateSize, measSize, contrSize, type); + + cv::Mat state(stateSize, 1, type); // [x,y,v_x,v_y,w,h] + cv::Mat meas(measSize, 1, type); // [z_x,z_y,z_w,z_h] + // [E_x,E_y,E_v_x,E_v_y,E_w,E_h] + + // Transition State Matrix A + // Note: set dT at each processing step! + // [ 1 0 dT 0 0 0 ] + // [ 0 1 0 dT 0 0 ] + // [ 0 0 1 0 0 0 ] + // [ 0 0 0 1 0 0 ] + // [ 0 0 0 0 1 0 ] + // [ 0 0 0 0 0 1 ] + cv::setIdentity(kf.transitionMatrix); + + // Measure Matrix H + // [ 1 0 0 0 0 0 ] + // [ 0 1 0 0 0 0 ] + // [ 0 0 0 0 1 0 ] + // [ 0 0 0 0 0 1 ] + kf.measurementMatrix = cv::Mat::zeros(measSize, stateSize, type); + kf.measurementMatrix.at<float>(0) = 1.0f; + kf.measurementMatrix.at<float>(7) = 1.0f; + kf.measurementMatrix.at<float>(16) = 1.0f; + kf.measurementMatrix.at<float>(23) = 1.0f; + + // Process Noise Covariance Matrix Q + // [ Ex 0 0 0 0 0 ] + // [ 0 Ey 0 0 0 0 ] + // [ 0 0 Ev_x 0 0 0 ] + // [ 0 0 0 Ev_y 0 0 ] + // [ 0 0 0 0 Ew 0 ] + // [ 0 0 0 0 0 Eh ] + //cv::setIdentity(kf.processNoiseCov, cv::Scalar(1e-2)); + kf.processNoiseCov.at<float>(0) = 1e-2; + kf.processNoiseCov.at<float>(7) = 1e-2; + kf.processNoiseCov.at<float>(14) = 5.0f; + kf.processNoiseCov.at<float>(21) = 5.0f; + kf.processNoiseCov.at<float>(28) = 1e-2; + kf.processNoiseCov.at<float>(35) = 1e-2; + + // Measures Noise Covariance Matrix R + cv::setIdentity(kf.measurementNoiseCov, cv::Scalar(1e-1)); + */ + + + /* + * This implementation is only for one kalman filter + */ + int stateSize = 4; + int measSize = 2; + int contrSize = 0; + + unsigned int type = CV_32F; + + kf->init(stateSize, measSize, contrSize, type); + + //cv::Mat state(stateSize, 1, type); // [x,y,v_x,v_y] + //cv::Mat meas(measSize, 1, type); // [z_x,z_y] + state->create(stateSize,1,type); + meas->create(measSize,1,type); + // [E_x,E_y,E_v_x,E_v_y] + + + // Transition State Matrix A + // Note: set dT at each processing step! + // [ 1 0 dT 0 ] + // [ 0 1 0 dT] + // [ 0 0 1 0 ] + // [ 0 0 0 1 ] + cv::setIdentity(kf->transitionMatrix); + + // Measure Matrix H + // [ 1 0 0 0 ] + // [ 0 1 0 0 ] + kf->measurementMatrix = cv::Mat::zeros(measSize, stateSize, type); + kf->measurementMatrix.at<float>(0) = 1.0f; + kf->measurementMatrix.at<float>(5) = 1.0f; + + // Process Noise Covariance Matrix Q + // [ Ex 0 0 0 ] + // [ 0 Ey 0 0 ] + // [ 0 0 Ev_x 0 ] + // [ 0 0 0 Ev_y ] + //cv::setIdentity(kf.processNoiseCov, cv::Scalar(1e-2)); + kf->processNoiseCov.at<float>(0) = 1e-2;//original values + kf->processNoiseCov.at<float>(5) = 1e-2; + kf->processNoiseCov.at<float>(10) = 5.0f; + kf->processNoiseCov.at<float>(15) = 5.0f; + + kf->processNoiseCov.at<float>(0) = 1e-2; + kf->processNoiseCov.at<float>(5) = 1e-2; + kf->processNoiseCov.at<float>(10) = 7.0f; + kf->processNoiseCov.at<float>(15) = 7.0f; + + // Measures Noise Covariance Matrix R + cv::setIdentity(kf->measurementNoiseCov, cv::Scalar(1e-1)); +} + + + +void Meanshift::eventsCallback(const dvs_msgs::EventArray::ConstPtr& msg) +{ + // only create image if at least one subscriber + if (image_pub_.getNumSubscribers() > 0) + { + cv_bridge::CvImage cv_image; + + if (display_method_ == RED_BLUE) + { + cv_image.encoding = "bgr8"; + + if (last_image_.rows == msg->height && last_image_.cols == msg->width) + { + last_image_.copyTo(cv_image.image); + used_last_image_ = true; + } + else + { + cv_image.image = cv::Mat(msg->height, msg->width, CV_8UC3); + cv_image.image = cv::Scalar(128, 128, 128); + } + + for (int i = 0; i < msg->events.size(); ++i) + { + const int x = msg->events[i].x; + const int y = msg->events[i].y; + + cv_image.image.at<cv::Vec3b>(cv::Point(x, y)) = ( + msg->events[i].polarity == true ? cv::Vec3b(255, 0, 0) : cv::Vec3b(0, 0, 255)); + } + } + else + { + cv_image.encoding = "mono8"; + cv_image.image = cv::Mat(msg->height, msg->width, CV_8U); + cv_image.image = cv::Scalar(128); + + cv::Mat on_events = cv::Mat(msg->height, msg->width, CV_8U); + on_events = cv::Scalar(0); + + cv::Mat off_events = cv::Mat(msg->height, msg->width, CV_8U); + off_events = cv::Scalar(0); + + // count events per pixels with polarity + for (int i = 0; i < msg->events.size(); ++i) + { + const int x = msg->events[i].x; + const int y = msg->events[i].y; + + if (msg->events[i].polarity == 1) + on_events.at<uint8_t>(cv::Point(x, y))++; + else + off_events.at<uint8_t>(cv::Point(x, y))++; + } + + // scale image + cv::normalize(on_events, on_events, 0, 128, cv::NORM_MINMAX, CV_8UC1); + cv::normalize(off_events, off_events, 0, 127, cv::NORM_MINMAX, CV_8UC1); + + cv_image.image += on_events; + cv_image.image -= off_events; + } + image_pub_.publish(cv_image.toImageMsg()); + } + + if (image_segmentation_pub_.getNumSubscribers() > 0) + { + cv_bridge::CvImage cv_segments; + //cv_bridge::CvImage cv_debug1; + //cv_bridge::CvImage cv_debug2; + + + //Doing color meanshift + cv::Mat timestamp_matrix = cv::Mat(numRows, numCols, CV_64F); + timestamp_matrix = cv::Scalar(0.); + cv::Mat timestamp_matrix_out; + + //Reading time of first event and saving it + //ROS_ERROR("Reading values from timestamp_matrix_out: %d", (int) msg->events.size()); + uint64_t first_timestamp = msg->events[0].ts.toNSec(); + // count events per pixels with polarity + for (int i = 0; i < msg->events.size(); ++i) + { + const int x = msg->events[i].x; + const int y = msg->events[i].y; + + double event_timestamp = (0.001*(double)(msg->events[i].ts.toNSec()-first_timestamp));//now in usecs + + if (msg->events[i].polarity == 1) + timestamp_matrix.at<double>(cv::Point(x, y))= event_timestamp*0.001; + else + timestamp_matrix.at<double>(cv::Point(x, y))=-event_timestamp*0.001; + } + + //First create the interface and + //cv_debug1.image =result_image; + //cv::Mat img_hist_equalized; + //cv::equalizeHist(result_image, img_hist_equalized); //equalize the histogram + //cv_debug1.image = img_hist_equalized; + + + + //POISSON SOLVER IMPLEMENTATION + /*----------------------------------------------------------------------------* / + cv::Mat debugIm1= cv::Mat(numRows, numCols, CV_8UC1); + + double min, max; + cv::minMaxLoc(timestamp_matrix, &min, &max); + + cv::normalize(timestamp_matrix, debugIm1, 0, 255, cv::NORM_MINMAX, CV_8UC1); + + // Here, we are assuming that our image is a gradient already (gx and gy) + cv::Mat gxx = cv::Mat(numRows, numCols, CV_64F); + cv::Mat gyy = cv::Mat(numRows, numCols, CV_64F); + + cv::Mat tmp; + debugIm1.convertTo(tmp, CV_64F); + tmp = (tmp/255)*(max-min)+min; + + + lapx(tmp, gxx); + lapy(tmp, gyy); + + cv::Mat lapfnc = cv::Mat(numRows, numCols, CV_64F); + cv::Mat fcos = cv::Mat(numRows, numCols, CV_64F); + cv::Mat denom = cv::Mat(numRows, numCols, CV_64F); + cv::Mat output = cv::Mat(numRows, numCols, CV_64F); + lapfnc = gxx+gyy; + cv::dct(lapfnc, fcos); + + cv::Mat1i XX, YY; + cv::Mat XX_bis, YY_bis; + meshgridTest(cv::Range(0,numCols-1), cv::Range(0, numRows-1), XX, YY); + + XX.convertTo(XX_bis, CV_64F); YY.convertTo(YY_bis, CV_64F); + XX_bis = CV_PI*XX_bis/numCols; YY_bis=CV_PI*YY_bis/numRows; + + parallel_for_(cv::Range(0,XX_bis.rows), Parallel_pixel_cosine(XX_bis)); + parallel_for_(cv::Range(0,YY_bis.rows), Parallel_pixel_cosine(YY_bis)); + + denom = 2*XX_bis-2 + 2*YY_bis-2; + + double first_elem =fcos.at<double>(cv::Point(0, 0)); + cv::divide(fcos, denom, fcos); + fcos.at<double>(cv::Point(0, 0))=first_elem; // remove the Inf + + cv::idct(fcos, output); + double min_bis, max_bis; + cv::minMaxLoc(output, &min_bis, &max_bis); + output = output - min_bis; + cv::Mat result_image, output_norm; + cv::normalize(output, output_norm, 0, 255, cv::NORM_MINMAX, CV_8UC1); + + cv::medianBlur(output_norm,result_image,3); + /*----------------------------------------------------------------------------*/ + //Alternatively, one can use only the time + cv::Mat result_image; + cv::normalize(timestamp_matrix, result_image, 0, 255, cv::NORM_MINMAX, CV_8UC1); + /*----------------------------------------------------------------------------*/ + + //cv::Mat kk1; + //result_image.convertTo(kk1, CV_64F); + //writeMatToFile(kk1,"/home/fran/kk1.txt"); + + //cv_debug1.encoding = "mono8"; + //cv_debug1.image = result_image; + //image_debug1_pub_.publish(cv_debug1.toImageMsg()); + + cv::Mat temporalIm, temporalImSubsampled; + result_image.convertTo(temporalIm, CV_64F); + temporalIm = temporalIm/timeDivider; + cv::pyrDown(temporalIm, temporalImSubsampled, cv::Size(numCols/2, numRows/2)); + //Initialize positions (only once) + outputFeatures=new double[maxPixelDim*mPixels/4]; + pixelsPtr=new double[maxPixelDim*mPixels/4]; + imagePtr=new double[mPixels/4]; + + memcpy(pixelsPtr, initializationPtr, maxPixelDim*mPixels/4*sizeof(double)); //copy event the 0s image + memcpy(pixelsPtr+2*mPixels/4, (void*)(temporalImSubsampled.data), mPixels/4*sizeof(double)); //copy event the 0s image + memcpy(imagePtr, (void*)(temporalImSubsampled.data), mPixels/4*sizeof(double)); //copy event the 0s image + + //extract the features + colorMeanShiftFilt(outputFeatures, pixelsPtr, mPixels/4, maxPixelDim, imagePtr, \ + numRows/2, numCols/2, spaceDivider, kernelFun, maxIterNum, tolFun); + + cv::Mat meanshiftIm; + cv::Mat meanshiftIm_small = cv::Mat(numRows/2, numCols/2, CV_64F, outputFeatures+2*mPixels/4); + meanshiftIm_small = meanshiftIm_small*timeDivider; + cv::pyrUp(meanshiftIm_small, meanshiftIm, cv::Size(numCols, numRows)); + + //cv::Mat kk = cv::Mat(numRows, numCols, CV_64F, imagePtr); + //kk = kk*timeDivider; + //writeMatToFile(kk,"/home/fran/imagePtr.txt"); + + //do the segmentation +// cv::Mat filtered_im = cv::Mat(numRows, numCols, CV_64F, outputFeatures+2*mPixels); +// filtered_im = filtered_im*timeDivider; + cv::Mat meanshiftImNormalized; + //meanshift_im.convertTo(meanshift_im_normalized,CV_8UC1); + cv::normalize(meanshiftIm, meanshiftImNormalized, 0, 255, cv::NORM_MINMAX, CV_8UC1); + + //cv_debug2.encoding = "mono8"; + //cv_debug2.image = meanshift_im_normalized; + //image_debug2_pub_.publish(cv_debug2.toImageMsg()); + + //meanshift_im_normalized= cv::imread("/home/fran/mug.pgm", CV_LOAD_IMAGE_GRAYSCALE); + + //tmp has the values that are non-zero + + cv_segments.encoding = "bgr8"; + cv_segments.image =cv::Mat(numRows, numCols, CV_8UC3); + //cv_segments.image =cv::Mat(128, 128, CV_8UC3); + im2segment(meanshiftImNormalized, cv_segments.image, sigma, k, min_region, &num_components); + image_segmentation_pub_.publish(cv_segments.toImageMsg()); + + //cv::Mat mask; + //mask = (abs(timestamp_matrix) > 1E-6); // Puts 255 wherever it is true + //mask.convertTo(mask, CV_64F); + //writeMatToFile(mask,"/home/fran/mask.txt"); + + //cv::Mat finalOutput; + //cv::bitwise_and(cv_segments.image, cv::Scalar(255,255,255), finalOutput, mask); + //cv_segments.image = finalOutput; + //image_debug2_pub_.publish(cv_segments.toImageMsg()); + //------------------------------------------------------------------------------------- + + delete[] imagePtr; + delete [] outputFeatures; + delete [] pixelsPtr; + } +} + +/*void Meanshift::eventsCallback_simple(const dvs_msgs::EventArray::ConstPtr& msg) +{ + // only create image if at least one subscriber + if (image_pub_.getNumSubscribers() > 0) + { + cv_bridge::CvImage cv_image; + + if (display_method_ == RED_BLUE) + { + cv_image.encoding = "bgr8"; + + if (last_image_.rows == msg->height && last_image_.cols == msg->width) + { + last_image_.copyTo(cv_image.image); + used_last_image_ = true; + } + else + { + cv_image.image = cv::Mat(msg->height, msg->width, CV_8UC3); + cv_image.image = cv::Scalar(128, 128, 128); + } + + for (int i = 0; i < msg->events.size(); ++i) + { + const int x = msg->events[i].x; + const int y = msg->events[i].y; + + cv_image.image.at<cv::Vec3b>(cv::Point(x, y)) = ( + msg->events[i].polarity == true ? cv::Vec3b(255, 0, 0) : cv::Vec3b(0, 0, 255)); + } + } + else + { + cv_image.encoding = "mono8"; + cv_image.image = cv::Mat(msg->height, msg->width, CV_8U); + cv_image.image = cv::Scalar(128); + + cv::Mat on_events = cv::Mat(msg->height, msg->width, CV_8U); + on_events = cv::Scalar(0); + + cv::Mat off_events = cv::Mat(msg->height, msg->width, CV_8U); + off_events = cv::Scalar(0); + + // count events per pixels with polarity + for (int i = 0; i < msg->events.size(); ++i) + { + const int x = msg->events[i].x; + const int y = msg->events[i].y; + + if (msg->events[i].polarity == 1) + on_events.at<uint8_t>(cv::Point(x, y))++; + else + off_events.at<uint8_t>(cv::Point(x, y))++; + } + + // scale image + cv::normalize(on_events, on_events, 0, 128, cv::NORM_MINMAX, CV_8UC1); + cv::normalize(off_events, off_events, 0, 127, cv::NORM_MINMAX, CV_8UC1); + + cv_image.image += on_events; + cv_image.image -= off_events; + } + image_pub_.publish(cv_image.toImageMsg()); + } + + if (image_segmentation_pub_.getNumSubscribers() > 0) + { + cv_bridge::CvImage cv_segments; + + //Doing color meanshift + cv::Mat diffTimestampMatrix = cv::Mat(numRows, numCols, CV_64F, cv::Scalar::all(0.)); + cv::Mat timestampMatrix = cv::Mat(numRows, numCols, CV_64F, cv::Scalar::all(0.)); + + uint64_t first_timestamp = msg->events[0].ts.toNSec(); + double final_timestamp = (1E-6*(double)(msg->events[(msg->events.size())-1].ts.toNSec()-first_timestamp)); + + // count events per pixels with polarity + cv::Mat data=cv::Mat(3, msg->events.size(), CV_64F, cv::Scalar::all(0.)); + int counter = 0; + + //std::ofstream foutX("/home/fran/xpos.txt"); + //std::ofstream foutY("/home/fran/ypos.txt"); + //std::ofstream foutTime("/home/fran/timestamp.txt"); + + for (int i = 0; i < msg->events.size(); i++) + { + const int x = msg->events[i].x; + const int y = msg->events[i].y; + + double event_timestamp = (1E-6*(double)(msg->events[i].ts.toNSec()-first_timestamp));//now in usecs + + //if (timestampMatrix.at<double>(cv::Point(x,y))> epsilon) + // diffTimestampMatrix.at<double>(cv::Point(x, y)) = event_timestamp -timestampMatrix.at<double>(cv::Point(x, y)); + //timestampMatrix.at<double>(cv::Point(x, y))= event_timestamp; + + if (event_timestamp < 15) + { + data.at<double>(cv::Point(i, 0))= (double)x/numCols; + data.at<double>(cv::Point(i, 1))= (double)y/numRows; + data.at<double>(cv::Point(i, 2))= event_timestamp/final_timestamp;//normalized + counter++; + } + else + { + //ROS_ERROR_STREAM("I'm using "<<counter<<" out of "<<msg->events.size()); + break; + } + //foutX<<x<<"\t"; foutY<<y<<"\t"; foutTime<<event_timestamp<<"\t"; + } + //foutX.close(); foutY.close(); foutTime.close(); + +/* + cv::Mat data=cv::Mat(3, 66, CV_64F, cv::Scalar::all(0.)); + int counter = 0; + std::ifstream foutX("/home/fran/xpos.txt"); + std::ifstream foutY("/home/fran/ypos.txt"); + std::ifstream foutTime("/home/fran/timestamp.txt"); + final_timestamp = 9.963; + for (int i = 0; i < 66; i++) + { + double x, y, event_timestamp; + foutX>>x; foutY>>y; foutTime>>event_timestamp; + data.at<double>(cv::Point(i, 0))= x/numCols; + data.at<double>(cv::Point(i, 1))= y/numRows; + data.at<double>(cv::Point(i, 2))= event_timestamp/final_timestamp; + } + foutX.close(); foutY.close(); foutTime.close(); +* / + + //---------------------------------------------------------------------------- + //Alternatively, one can use only the time + //cv::Mat result_image; + //cv::normalize(diffTimestampMatrix, result_image, 0, 255, cv::NORM_MINMAX, CV_8UC1); + //---------------------------------------------------------------------------- + + cv::Mat clusterCenters; + cv::Mat segmentation=cv::Mat(numRows, numCols, CV_8UC3); + segmentation = cv::Scalar(128,128,128); + + std::vector<double> clustCentX, clustCentY, clustCentZ; + std::vector<int> point2Clusters; + double bandwidth = 0.2; + std::vector<cv::Vec3b> RGBColors; + cv::RNG rng(12345); + + //ROS_ERROR_STREAM("Just before meanshift "<<msg->events.size()); + meanshiftCluster_Gaussian(data, &clustCentX, &clustCentY, &clustCentZ, &point2Clusters, bandwidth); + + //Now, draw the different segments with a color + for(int i=0; i<clustCentX.size(); i++) + RGBColors.push_back(cv::Vec3b((uchar)random(), (uchar)random(), (uchar)random())); + + counter =0; + for (int i = 0; i < msg->events.size(); i++) + { + const int x = msg->events[i].x; + const int y = msg->events[i].y; + double ts = (1E-6*(double)(msg->events[i].ts.toNSec()-first_timestamp));//now in usecs + + if(ts<15) + { + segmentation.at<cv::Vec3b>(cv::Point(x,y))=RGBColors[point2Clusters[i]]; + counter++; + } + else + { + break; + } + //ROS_ERROR_STREAM("segmentation["<<x<<","<<y<<"] = "<<RGBColors[point2Clusters[i]]); + } + + cv_segments.encoding = "bgr8"; + cv_segments.image =segmentation; + image_segmentation_pub_.publish(cv_segments.toImageMsg()); + //std::cin.ignore(); + + //Saving RGB image + //if (counterGlobal>20) + //{ + // char filename[80]; + // sprintf(filename,"/home/fran/RGB_%0d.png", counterGlobal+1); + // cv::imwrite(filename , segmentation); + // exit(0); + //} + //counterGlobal++; + //------------------------------------------------------------------------------------- + + } +}*/ + +void Meanshift::eventsCallback_simple(const dvs_msgs::EventArray::ConstPtr& msg) +{ + // only create image if at least one subscriber + if (image_pub_.getNumSubscribers() > 0) + { + cv_bridge::CvImage cv_image; + + if (display_method_ == RED_BLUE) + { + cv_image.encoding = "bgr8"; + + if (last_image_.rows == msg->height && last_image_.cols == msg->width) + { + last_image_.copyTo(cv_image.image); + used_last_image_ = true; + } + else + { + cv_image.image = cv::Mat(msg->height, msg->width, CV_8UC3); + cv_image.image = cv::Scalar(128, 128, 128); + } + + for (int i = 0; i < msg->events.size(); ++i) + { + const int x = msg->events[i].x; + const int y = msg->events[i].y; + + cv_image.image.at<cv::Vec3b>(cv::Point(x, y)) = ( + msg->events[i].polarity == true ? cv::Vec3b(255, 0, 0) : cv::Vec3b(0, 0, 255)); + } + + //Write the total number of events + //foutX<<msg->events.size()<<std::endl; + } + else + { + cv_image.encoding = "mono8"; + cv_image.image = cv::Mat(msg->height, msg->width, CV_8U); + cv_image.image = cv::Scalar(128); + + cv::Mat on_events = cv::Mat(msg->height, msg->width, CV_8U); + on_events = cv::Scalar(0); + + cv::Mat off_events = cv::Mat(msg->height, msg->width, CV_8U); + off_events = cv::Scalar(0); + + // count events per pixels with polarity + for (int i = 0; i < msg->events.size(); ++i) + { + const int x = msg->events[i].x; + const int y = msg->events[i].y; + + if (msg->events[i].polarity == 1) + on_events.at<uint8_t>(cv::Point(x, y))++; + else + off_events.at<uint8_t>(cv::Point(x, y))++; + } + + // scale image + cv::normalize(on_events, on_events, 0, 128, cv::NORM_MINMAX, CV_8UC1); + cv::normalize(off_events, off_events, 0, 127, cv::NORM_MINMAX, CV_8UC1); + + cv_image.image += on_events; + cv_image.image -= off_events; + } + image_pub_.publish(cv_image.toImageMsg()); + } + +/* + // only create image if at least one subscriber + if (image_debug1_pub_.getNumSubscribers() > 0) + { + cv_bridge::CvImage cv_image; + + if (display_method_ == RED_BLUE) + { + cv_image.encoding = "bgr8"; + + if (last_image_.rows == msg->height && last_image_.cols == msg->width) + { + last_image_.copyTo(cv_image.image); + used_last_image_ = true; + } + else + { + cv_image.image = cv::Mat(msg->height, msg->width, CV_8UC3); + cv_image.image = cv::Scalar(128, 128, 128); + } + + if(firstevent) + { + firsttimestamp = (1E-6*(double)(msg->events[0].ts.toNSec())); + firstevent = false; + } + + double maxTs; + int posx, posy; + double usTime = 16.0; + double ts; + for (int i = 0; i < msg->events.size(); ++i) + { + const int x = msg->events[i].x; + const int y = msg->events[i].y; + ts = (1E-6*(double)(msg->events[i].ts.toNSec())) - firsttimestamp; +#if BG_FILTERING + //BGAFframe.at<float>(cv::Point(x,y))=(float)(1E-6*(double)(msg->events[i].ts.toNSec())); + BGAFframe.at<float>(cv::Point(x,y))=0.; + maxTs = -1; + //ROS_ERROR_STREAM("NEW EVENT "<<x<<","<<y<<":"<<ts); + for(int ii=-1; ii<=1; ii++) + for(int jj=-1; jj<=1; jj++) + { + posx = x + ii; + posy = y + jj; + if(posx<0) + posx = 0; + if(posy<0) + posy=0; + if(posx>numRows-1) + posx = numRows-1; + if(posy>numCols-1) + posy = numCols-1; + + if(BGAFframe.at<float>(cv::Point(posx,posy)) > maxTs) + maxTs = BGAFframe.at<float>(cv::Point(posx,posy)); + + //ROS_ERROR_STREAM(posx<<","<<posy<<":"<<BGAFframe.at<float>(cv::Point(posx,posy))); + } + //ROS_ERROR_STREAM("maxTs: "<<maxTs); + BGAFframe.at<float>(cv::Point(x,y))=ts; + //ROS_ERROR_STREAM(BGAFframe.at<float>(cv::Point(x,y)) - maxTs); + + if(BGAFframe.at<float>(cv::Point(x,y)) >= (maxTs + usTime)) + { + continue; + //ROS_ERROR_STREAM("HERE"); + } + +#endif + cv_image.image.at<cv::Vec3b>(cv::Point(x, y)) = ( + msg->events[i].polarity == true ? cv::Vec3b(255, 0, 0) : cv::Vec3b(0, 0, 255)); + } + //ROS_ERROR_STREAM("DONE--------------------------------------------"); + + //Write the total number of events + //foutX<<msg->events.size()<<std::endl; + } + image_debug1_pub_.publish(cv_image.toImageMsg()); + } +*/ + + + if (image_segmentation_pub_.getNumSubscribers() > 0) + { + cv_bridge::CvImage cv_segments; + + //Doing color meanshift + //cv::Mat diffTimestampMatrix = cv::Mat(numRows, numCols, CV_64F, cv::Scalar::all(0.)); + //cv::Mat timestampMatrix = cv::Mat(numRows, numCols, CV_64F, cv::Scalar::all(0.)); + + uint64_t first_timestamp = msg->events[0].ts.toNSec(); + double final_timestamp = (1E-6*(double)(msg->events[(msg->events.size())-1].ts.toNSec()-first_timestamp)); + std::vector<bool> activeEvents(msg->events.size()); + + int counterIn = 0; + int counterOut = 0; + + int beginEvent = 0; + int packet; + if(DVSW==240) + packet = 1800; + else + packet = 1500; + //ROS_ERROR_STREAM("Before while"); + + + while(beginEvent < msg->events.size()) + { + //if(msg->events.size()>15e3) + //ROS_ERROR_STREAM("BEGIN packet "<<beginEvent); + //SELECT SMALL PACKETS OF MAXIMUM 1500 events + counterIn = 0; + counterOut = 0; + //ROS_ERROR_STREAM("Computing events ["<<beginEvent<<","<<min(beginEvent+packet, msg->events.size())<<"]"); + //ROS_ERROR_STREAM("SIZE of current package is "<<msg->events.size()<<"];"); + + // count events per pixels with polarity + cv::Mat data=cv::Mat(3, min(packet, msg->events.size()-beginEvent), CV_64F, cv::Scalar::all(0.)); + + //std::ofstream foutX("/home/fran/xpos.txt"); + //std::ofstream foutY("/home/fran/ypos.txt"); + //std::ofstream foutTime("/home/fran/timestamp.txt"); + + //Filter events + //cv::Mat BGAFframe = cv::Mat(numRows, numCols, CV_32FC1); + //frame =cv::Scalar(-1); + + if(firstevent) + { + firsttimestamp = (1E-6*(double)(msg->events[10].ts.toNSec())); + firstevent = false; + } + + double maxTs; + int posx, posy; + double usTime = 10.0; + double ts; + + + + for (int i = beginEvent; i < min(beginEvent+packet, msg->events.size()); i++) + { + //SELECT SMALL PACKETS OF MAXIMUM 1000 events + const int x = msg->events[counterIn].x; + const int y = msg->events[counterIn].y; + + double event_timestamp = (1E-6*(double)(msg->events[counterIn].ts.toNSec()-first_timestamp));//now in usecs + + ts = (1E-6*(double)(msg->events[i].ts.toNSec())) - firsttimestamp; +#if BG_FILTERING + //BGAFframe.at<float>(cv::Point(x,y))=(float)(1E-6*(double)(msg->events[i].ts.toNSec())); + BGAFframe.at<float>(cv::Point(x,y))=0.; + maxTs = -1; + //calculate maximum in a 3x3 neighborhood + for(int ii=-1; ii<=1; ii++) + for(int jj=-1; jj<=1; jj++) + { + posx = x + ii; + posy = y + jj; + if(posx<0) + posx = 0; + if(posy<0) + posy=0; + if(posx>numRows-1) + posx = numRows-1; + if(posy>numCols-1) + posy = numCols-1; + + if(BGAFframe.at<float>(cv::Point(posx,posy)) > maxTs) + maxTs = BGAFframe.at<float>(cv::Point(posx,posy)); + } + + BGAFframe.at<float>(cv::Point(x,y))=ts; + //if nothing happened in usTime, remove the event + if(BGAFframe.at<float>(cv::Point(x,y)) >= (maxTs + usTime)) + { + activeEvents.at(counterIn)=false; + counterIn++; + } + else + { +#endif + data.at<double>(cv::Point(counterOut, 0))= (double)x/numCols; + data.at<double>(cv::Point(counterOut, 1))= (double)y/numRows; + //data.at<double>(cv::Point(counter, 2))= event_timestamp/final_timestamp;//normalized + double tau = 10000; + data.at<double>(cv::Point(counterOut, 2))= exp(-(final_timestamp-event_timestamp)/tau);//normalized + activeEvents.at(counterIn)=true; + counterIn++; + counterOut++; +#if BG_FILTERING + } +#endif + + + + //foutX<<x<<"\t"; foutY<<y<<"\t"; foutTime<<event_timestamp<<"\t"; + } + double last_timestamp = (1E-6*(double)(msg->events[counterIn-1].ts.toNSec()));//now in usecs + //foutX.close(); foutY.close(); foutTime.close(); + + cv::Mat clusterCenters; + cv::Mat segmentation=cv::Mat(numRows, numCols, CV_8UC3); + segmentation = cv::Scalar(128,128,128); + + cv::Mat traj = cv::Mat(numRows, numCols, CV_8UC3); + traj = cv::Scalar(128,128,128); + + std::vector<double> clustCentX, clustCentY, clustCentZ; + std::vector<int> point2Clusters; + std::vector<int> positionClusterColor; + std::vector<int> assign_matches; + + + //double bandwidth = 0.05; + double bandwidth = 0.15; + //double bandwidth = 0.15; + //double bandwidth = 0.20; + //double bandwidth = 0.25; + //double bandwidth = 0.50; + //cv::RNG rng(12345); + +/* if(counterGlobal==0) + { + //clock_t start, end; + //double elapsed; + //start = clock(); + //clustCentZ_old = clustCentZ; + + meanshiftCluster_Gaussian(data, &clustCentX, &clustCentY, &clustCentZ, &point2Clusters, bandwidth); + + assignClusterColor(&positionClusterColor, clustCentX.size(), assign_matches, prev_positionClusterColor); //assign new colors to clusters + + prev_clustCentX = clustCentX; + prev_clustCentY = clustCentY; + prev_positionClusterColor = positionClusterColor; + //std::vector<int> checkvector (clustCentX.size(), -1); + //ROS_ERROR_STREAM("Total number of clusters is "<<clustCentX.size()); + + + //end = clock(); + //elapsed = ((double) (end - start)) / CLOCKS_PER_SEC; + //ROS_ERROR_STREAM("Num. packets = "<<data.cols<<" elapsed time = "<<elapsed<<". Time/packet = "<<elapsed/data.cols); + + //Moved to initialization + //Now, draw the different segments with a color + //for(int i=0; i<clustCentX.size(); i++) + // RGBColors.push_back(cv::Vec3b((uchar)random(), (uchar)random(), (uchar)random())); + + counter =0; + for (int i = beginEvent; i < min(beginEvent+packet, msg->events.size()); i++) + { + const int x = msg->events[counter].x; + const int y = msg->events[counter].y; + double ts = (1E-6*(double)(msg->events[counter].ts.toNSec()-first_timestamp));//now in usecs + + //if(ts<15) + //{ + //segmentation.at<cv::Vec3b>(cv::Point(x,y))=RGBColors[point2Clusters[counter]]; + //segmentation.at<cv::Vec3b>(cv::Point(x,y))=RGBColors[(positionClusterColor[point2Clusters[counter]])%MAX_NUM_CLUSTERS]; + segmentation.at<cv::Vec3b>(cv::Point(x,y))=RGBColors[(positionClusterColor[point2Clusters[counter]])&MAX_NUM_CLUSTERS]; //cheaper than % (mod operation) + //} + //else + // break; + counter++; + } + } + else + { + +*/ + + //fouttotalproc<<min(packet, msg->events.size()-beginEvent)<<std::endl; + + meanshiftCluster_Gaussian(data, &clustCentX, &clustCentY, &clustCentZ, &point2Clusters, bandwidth); + + //Assign new color or use color from previous clusters? + //if(counterGlobal>0)//not the first time + findClosestCluster(&assign_matches, clustCentX, clustCentY, prev_clustCentX, prev_clustCentY); //no match when clustID is -1 + + //assignClusterColor(&positionClusterColor, clustCentX.size(), assign_matches, prev_positionClusterColor); //assign new colors to clusters + assignClusterColor(&positionClusterColor, clustCentX.size(), assign_matches, prev_positionClusterColor, prev_activeTrajectories); //assign new colors to clusters + + //foutnumclust<<clustCentX.size()<<std::endl; + + int tmpColorPos; + float estimClustCenterX=-1., estimClustCenterY=-1.; + //std::vector<int> activeTrajectories(MAX_NUM_CLUSTERS,0); + std::vector<int> activeTrajectories; + + if(point2Clusters.size()>400) //update positions only when there is enough change (>25%) + { + for(int i=0; i<clustCentX.size(); i++) + { + estimClustCenterX=-1., estimClustCenterY=-1.; + + tmpColorPos = (positionClusterColor[i])&(MAX_NUM_CLUSTERS-1); + + //Check if the new position is being used + /*int idx = 0; + for (int idx=0; idx<prev_activeTrajectories.size(); idx++) + if(tmpColorPos == prev_activeTrajectories[idx]) + break;*/ + std::vector<int>::iterator it; + it = find (prev_activeTrajectories.begin(), prev_activeTrajectories.end(), tmpColorPos); + + if(it==prev_activeTrajectories.end())//if the element tmpcolorpos is not found in the vector + { + //Initialize the trajectory (just the counter) + //allTrajectories[tmpColorPos] = std::vector<cv::Point>(MAX_NUM_TRAJECTORY_POINTS); + counterTrajectories[tmpColorPos]=0; + +#if KALMAN_FILTERING + foundTrajectory[tmpColorPos] = false; + createKalmanFilter(&(vector_of_kf[tmpColorPos]), &(vector_of_state[tmpColorPos]), &(vector_of_meas[tmpColorPos])); + vector_of_foundBlobs[tmpColorPos]=false; + vector_of_ticks[tmpColorPos]=0.0; +#endif + } + + /* + if(prev_activeTrajectories[tmpColorPos]==0) //TODO: when the cluster is tracked all the time, it is active when I go back with &MAX_NUM_CLUSTERS + { + //Initialize the trajectory (just the counter) + //allTrajectories[tmpColorPos] = std::vector<cv::Point>(MAX_NUM_TRAJECTORY_POINTS); + counterTrajectories[tmpColorPos]=0; + }*/ + +#if KALMAN_FILTERING + if(counterTrajectories[tmpColorPos]>25 & !foundTrajectory[tmpColorPos]) + { + //selectedTrajectory = tmpColorPos; + foundTrajectory[tmpColorPos] = true; + } + //if(foundTrajectory[tmpColorPos] & selectedTrajectory == tmpColorPos) //More than 25 points in the trajectory, start w/ KF + if(foundTrajectory[tmpColorPos]) //More than 25 points in the trajectory, start w/ KF + { + //double precTick = ticks; + //ticks = (double) cv::getTickCount(); + //double dT = (ticks - precTick) / cv::getTickFrequency(); //seconds + + /* In case we use only 1 kalman filter + if((last_timestamp - ticks) > 1) + { + double precTick = ticks; + ticks = last_timestamp; + double dT = (ticks - precTick)/1000; //seconds + + if (foundBlobs) + { + // >>>> Matrix A + kf.transitionMatrix.at<float>(2) = dT; + kf.transitionMatrix.at<float>(7) = dT; + // <<<< Matrix A + state = kf.predict(); + estimClustCenterX = state.at<float>(0); + estimClustCenterY = state.at<float>(1); + } + + meas.at<float>(0) = clustCentX[i]*DVSW; + meas.at<float>(1) = clustCentY[i]*DVSH; //[z_x, z_y] + + if (!foundBlobs) // First detection! + { + // >>>> Initialization + kf.errorCovPre.at<float>(0) = 1; // px + kf.errorCovPre.at<float>(5) = 1; // px + kf.errorCovPre.at<float>(10) = 2; + kf.errorCovPre.at<float>(15) = 2; + + state.at<float>(0) = meas.at<float>(0); + state.at<float>(1) = meas.at<float>(1); + state.at<float>(2) = 0; + state.at<float>(3) = 0; //[z_x, z_y, v_x, v_y] + // <<<< Initialization + + kf.statePost = state; + + foundBlobs = true; + } + else + kf.correct(meas); // Kalman Correction + + if(estimClustCenterX>=0.) //initialized to -1 + { + //ROS_ERROR_STREAM("Estimated point = ["<<estimClustCenterX<<", "<<estimClustCenterY<<"];"); + //ROS_ERROR_STREAM("Measured point = ["<<clustCentX[i]<<", "<<clustCentY[i]<<"];"); + cv::circle(trajectories, cv::Point(clustCentX[i]*DVSW, clustCentY[i]*DVSH), 2, cv::Scalar( 0, 0, 255 ),-1,8); + cv::circle(trajectories, cv::Point(estimClustCenterX, estimClustCenterY), 2, cv::Scalar( 255, 0, 0),-1,8); + foutX<<clustCentX[i]*DVSW<<" "<<clustCentY[i]*DVSH<<std::endl; + foutX_estim<<estimClustCenterX<<" "<<estimClustCenterY<<std::endl; + foutT<<dT<<std::endl; + } + } + */ + + if((last_timestamp - vector_of_ticks[tmpColorPos]) > 1) + { + double precTick = vector_of_ticks[tmpColorPos]; + vector_of_ticks[tmpColorPos] = last_timestamp; + double dT = (vector_of_ticks[tmpColorPos] - precTick)/1000; //seconds + //if (foundBlobs) + if(vector_of_foundBlobs[tmpColorPos]) + { + // >>>> Matrix A + vector_of_kf[tmpColorPos].transitionMatrix.at<float>(2) = dT; + vector_of_kf[tmpColorPos].transitionMatrix.at<float>(7) = dT; + // <<<< Matrix A + vector_of_state[tmpColorPos] = vector_of_kf[tmpColorPos].predict(); + estimClustCenterX = vector_of_state[tmpColorPos].at<float>(0); + estimClustCenterY = vector_of_state[tmpColorPos].at<float>(1); + } + vector_of_meas[tmpColorPos].at<float>(0) = clustCentX[i]*DVSW; + vector_of_meas[tmpColorPos].at<float>(1) = clustCentY[i]*DVSH; //[z_x, z_y] + + + //if (!foundBlobs) // First detection! + if(!vector_of_foundBlobs[tmpColorPos]) + { + // >>>> Initialization + vector_of_kf[tmpColorPos].errorCovPre.at<float>(0) = 1; // px + vector_of_kf[tmpColorPos].errorCovPre.at<float>(5) = 1; // px + vector_of_kf[tmpColorPos].errorCovPre.at<float>(10) = 2; + vector_of_kf[tmpColorPos].errorCovPre.at<float>(15) = 2; + + vector_of_state[tmpColorPos].at<float>(0) = vector_of_meas[tmpColorPos].at<float>(0); + vector_of_state[tmpColorPos].at<float>(1) = vector_of_meas[tmpColorPos].at<float>(1); + vector_of_state[tmpColorPos].at<float>(2) = 0; + vector_of_state[tmpColorPos].at<float>(3) = 0; //[z_x, z_y, v_x, v_y] + // <<<< Initialization + + vector_of_kf[tmpColorPos].statePost = vector_of_state[tmpColorPos]; + + //foundBlobs = true; + vector_of_foundBlobs[tmpColorPos]=true; + } + else + vector_of_kf[tmpColorPos].correct(vector_of_meas[tmpColorPos]); // Kalman Correction + + if(estimClustCenterX>=0.) //initialized to -1 + { + //ROS_ERROR_STREAM("Estimated difference = ["<<abs(estimClustCenterX/DVSW -clustCentX[i]) <<", "<<abs(estimClustCenterY/DVSH-clustCentY[i])<<"];"); + //ROS_ERROR_STREAM("Estimated point = ["<<estimClustCenterX<<", "<<estimClustCenterY<<"];"); + //ROS_ERROR_STREAM("Measured point = ["<<clustCentX[i]<<", "<<clustCentY[i]<<"];"); + //cv::circle(trajectories, cv::Point(clustCentX[i]*DVSW, clustCentY[i]*DVSH), 2, cv::Scalar( 0, 0, 255 ),-1,8); + //cv::circle(trajectories, cv::Point(estimClustCenterX, estimClustCenterY), 2, cv::Scalar( 255, 0, 0),-1,8); + + //foutX<<tmpColorPos<<" "<<clustCentX[i]*DVSW<<" "<<clustCentY[i]*DVSH<<" "<<estimClustCenterX<<" "<<estimClustCenterY<<std::endl; + + //foutX_estim<<estimClustCenterX<<" "<<estimClustCenterY<<std::endl; + //foutT<<dT<<std::endl; + //foutX<<"Estimated difference = ["<<abs(estimClustCenterX/DVSW -clustCentX[i]) <<", "<<abs(estimClustCenterY/DVSH-clustCentY[i])<<"];"<<std::endl; + + // !!!!!!CAREFUL **************************************************************************************** + //ACTIVATE THIS !!!!! + //clustCentX[i] = estimClustCenterX/DVSW; + //clustCentY[i] = estimClustCenterY/DVSH; + // CAREFUL **************************************************************************************** + } + } + } +#endif + + cv::Point end(clustCentX[i]*DVSW, clustCentY[i]*DVSH); +/* +#if KALMAN_FILTERING + //frame, event, colorCluster, X,Y, filtX, filtY + foutX<<counterGlobal+1<<" "<<(double)(1E-6*(msg->events[beginEvent].ts.toNSec()-msg->events[0].ts.toNSec()))<<" " <<tmpColorPos<<" "<<clustCentX[i]*DVSW<<" "<<clustCentY[i]*DVSH<<" "<<estimClustCenterX<<" "<<estimClustCenterY<<std::endl; +#endif +*/ + + allTrajectories[tmpColorPos][(counterTrajectories[tmpColorPos]) & (MAX_NUM_TRAJECTORY_POINTS-1)]=end; + counterTrajectories[tmpColorPos]++; + //activeTrajectories[tmpColorPos]=1; + activeTrajectories.push_back(tmpColorPos); + } + + prev_clustCentX = clustCentX; + prev_clustCentY = clustCentY; + prev_positionClusterColor = positionClusterColor; + prev_activeTrajectories = activeTrajectories; + + trajectories = cv::Scalar(128,128,128); + int first=1; + for(int i=0; i<activeTrajectories.size(); i++) + { + int tmpval = activeTrajectories[i]; + if (counterTrajectories[tmpval]>1) + { + if(counterTrajectories[tmpval]<=MAX_NUM_TRAJECTORY_POINTS) + { + for(int j=1; j<counterTrajectories[tmpval]; j++) //instead of % I use &(power of 2 -1): it is more efficient + cv::line( trajectories, allTrajectories[tmpval][j-1], allTrajectories[tmpval][j], cv::Scalar( RGBColors[tmpval].val[0], RGBColors[tmpval].val[1], RGBColors[tmpval].val[2]), 2, 1); + } + else + { + int j=1; + int pos = counterTrajectories[tmpval]; + while(j<MAX_NUM_TRAJECTORY_POINTS) + { + cv::line( trajectories, allTrajectories[tmpval][pos & (MAX_NUM_TRAJECTORY_POINTS-1)], allTrajectories[tmpval][(pos+1)&(MAX_NUM_TRAJECTORY_POINTS-1)], cv::Scalar( RGBColors[tmpval].val[0], RGBColors[tmpval].val[1], RGBColors[tmpval].val[2]), 2, 1); + pos = pos+1; + j++; + } + } + } + + } + } + + trajectories.copyTo(segmentation); //Always keep trajectories + +/* +#if TEST + char filename[80]; + sprintf(filename,"/home/fran/0_tmp/kk/RGB_%0d.png", counterGlobal+1); + cv::imwrite(filename , segmentation); + + sprintf(filename,"/home/fran/0_tmp/kk/RGB_%0d.txt", counterGlobal+1); + std::ofstream foutallT(filename); + + for(int k=0; k<activeTrajectories.size(); k++) + if(counterTrajectories[activeTrajectories[k]]>0) + { + foutallT<<"ClusterID "<<activeTrajectories[k]<<" with "<<counterTrajectories[activeTrajectories[k]]<<" elems: = ["; + for(int j=0; j<counterTrajectories[activeTrajectories[k]]; j++) //instead of % I use &(power of 2 -1): it is more efficient + { + foutallT<<"("<<allTrajectories[activeTrajectories[k]][j].x<<", "<<allTrajectories[activeTrajectories[k]][j].y<<"), "; + } + foutallT<<"];\n"; + } + + foutallT.close(); +#endif +*/ + +#if TEST + char filename1[80]; + sprintf(filename1,"/home/fran/0_tmp/kk/rgb_%0d.txt", counterGlobal+1); + std::ofstream foutX(filename1); +#endif + counterIn =0; + counterOut=0; + + std::vector<uint64_t> xVar(MAX_NUM_CLUSTERS-1, 0); + std::vector<uint64_t> yVar(MAX_NUM_CLUSTERS-1, 0); + std::vector<uint64_t> xMean(MAX_NUM_CLUSTERS-1, 0); + std::vector<uint64_t> xMean(MAX_NUM_CLUSTERS-1, 0); + std::vector<uint64_t> numEvents2Cluster(MAX_NUM_CLUSTERS-1, 0); + std::vector<uint64_t> Variance(MAX_NUM_CLUSTERS-1, 0); + + + for (int i = beginEvent; i < min(beginEvent+packet, msg->events.size()); i++) + { + if(activeEvents.at(counterIn)) //Label it only if it is not noise + { + const int x = msg->events[counterIn].x; + const int y = msg->events[counterIn].y; + double ts = (1E-6*(double)(msg->events[counterIn].ts.toNSec()-first_timestamp));//now in usecs + + //VARIANCE CALUCLATION + int idx = positionClusterColor[point2Clusters[counterOut]])&(MAX_NUM_CLUSTERS-1) + numEvents2Cluster[idx] = numEvents2Cluster[idx] + 1; + + xMean[idx] = xMean[idx] + x; + yMean[idx] = yMean[idx] + y; + + //xVar[idx] = xVar[idx] + ((x - clustCentX[idx]) * (x - clustCentX[idx])); + //yVar[idx] = yVar[idx] + ((x - clustCentY[idx]) * (x - clustCentY[idx])); + + //xVar = xVar + ((msg->events[i].x - avg_x) * (msg->events[i].x - avg_x)); + + + segmentation.at<cv::Vec3b>(cv::Point(x,y))=RGBColors[(positionClusterColor[point2Clusters[counterOut]])&(MAX_NUM_CLUSTERS-1)]; //cheaper than % (mod operation) +#if TEST + //foutX<<x<<" "<<y<<" "<<ts<<" "<<msg->events[counter].polarity<<'\n'; + //foutX<<x<<'\t'<<'\t'<<y<<'\t'<<ts<<'\t'<<(int)(msg->events[counter].polarity)<<'\t'<<(int)((positionClusterColor[point2Clusters[counter]])&(MAX_NUM_CLUSTERS-1))<<'\n'; +#endif + counterOut++; + } + //} + //else + //{ + // break; + //} + counterIn++; + } + counterIn = 0; + for (int i = beginEvent; i < min(beginEvent+packet, msg->events.size()); i++) + { + const int x = msg->events[counterIn].x; + const int y = msg->events[counterIn].y; + + if(activeEvents.at(counterIn) && (numEvents2Cluster[i] != 0)) //Label it only if it is not noise + { + xMean[i] = xMean[i] / numEvents2Cluster[i]; + yMean[i] = yMean[i] / numEvents2Cluster[i]; + } + else + { + counterIn++; + } + + } + counterIn = 0; + for (int i = beginEvent; i < min(beginEvent+packet, msg->events.size()); i++) + { + const int x = msg->events[counterIn].x; + const int y = msg->events[counterIn].y; + + if(activeEvents.at(counterIn) && (numEvents2Cluster[i] != 0)) //Label it only if it is not noise + { + xVar[idx] = xVar[idx] + ((x - xMean[i]) * (x - xMean[i])); + yVar[idx] = yVar[idx] + ((y - yMean[i]) * (y - yMean[i])); + } + else + { + counterIn++; + } + } + + + + std_msgs::String dir; + for(int i = 0 ; i <= MAX_NUM_CLUSTERS-1; ++i) + { + if(numEvents2Cluster[i] != 0) + { + xVar[i] = xVar[i] / numEvents2Cluster[i]; + yVar[i] = yVar[i] / numEvents2Cluster[i]; + Variance[i] = (xVar[i] + yVar[i] / 2); + + Variance[i] + 10 > preVariance[i] ? counterFor[i]++ : counterBar[i]++; + + if(counterBar[i] > 10) + { + counterFor[i] = 0; + counterBar[i] = 0; + } + + if(counterFor[i] > 5) + { + if(clustCentY[i]*DVSH < 75) + dir.data = "above"; + else if (clustCentY[i]*DVSH > 45) + dir.data = "below"; + else + dir.data = "none"; + } + } + + preVariance[i] = Variance[i]; + + dirUB.publish(dir); + } + } + + char filename2[80]; + sprintf(filename2,"/home/fran/0_tmp/kk/rgb_%0d.png", counterGlobal+1); + cv::imwrite(filename2, segmentation); + + +// } + + + cv_segments.encoding = "bgr8"; + cv_segments.image = segmentation; + image_segmentation_pub_.publish(cv_segments.toImageMsg()); + + //std::cin.ignore(); + + beginEvent +=packet; + +//#if TEST + //char filename[80]; + //sprintf(filename,"/home/fran/0_tmp/kk/rgb_%0d.jpg", counterGlobal+1); + //cv::imwrite(filename , segmentation); + //sprintf(filename,"/home/fran/0_tmp/kk/cc_%0d.txt", counterGlobal+1); + //std::ofstream foutcc(filename); + //for (int i = 0; i<clustCentX.size(); i++) + // foutcc<<"ClusterCenter("<<i+1<<",:)=["<<clustCentX.at(i)*DVSW<<","<<clustCentY.at(i)*DVSH<<"];"<<std::endl; + //foutcc.close(); +//#endif + //Saving RGB image +/* + if (counterGlobal>0) + { + //std::cin.ignore(); + //for (int i = 0; i<clustCentX.size(); i++) + // ROS_ERROR_STREAM("ClusterCenter("<<i+1<<",:)=["<<clustCentX.at(i)<<","<<clustCentY.at(i)<<","<<clustCentZ.at(i)<<"];"); + + //std::cout<<"clustperevent=["<<point2Clusters[0]; + //for (int i = 1; i<point2Clusters.size(); i++) + // std::cout<<","<<point2Clusters[i]; + //std::cout<<"];"<<std::endl; + + char filename[80]; + sprintf(filename,"/home/fran/0_tmp/kk/RGB_%0d.png", counterGlobal+1); + cv::imwrite(filename , segmentation); + //exit(0); + + //char filename[80]; + //sprintf(filename,"/home/fran/0_tmp/kk/RGB_%0d.txt", counterGlobal+1); + //std::ofstream foutX(filename); + //foutX<<counter<<"\n"; + //foutX.close(); + } +*/ + + + /*if(msg->events.size()>15e3) + { + char filename[80]; + sprintf(filename,"/home/fran/0_tmp/kk/RGB_%0d.png", counterGlobal+1); + cv::imwrite(filename , segmentation); + exit(0); + }*/ + counterGlobal++; + } + } +} + + + + +} // namespace diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/meanshift_node.cpp b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/meanshift_node.cpp new file mode 100755 index 0000000..879b219 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/meanshift_node.cpp @@ -0,0 +1,17 @@ + + +#include "dvs_meanshift/meanshift.h" + +int main(int argc, char* argv[]) +{ + ros::init(argc, argv, "dvs_meanshift"); + + ros::NodeHandle nh; + ros::NodeHandle nh_private("~"); + + dvs_meanshift::Meanshift meanshift(nh, nh_private); + + ros::spin(); + + return 0; +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/segment.cpp b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/segment.cpp new file mode 100755 index 0000000..e64a0c8 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/dvs_meanshift/src/segment.cpp @@ -0,0 +1,171 @@ +/* +Copyright (C) 2006 Pedro Felzenszwalb + +This program is free software; you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation; either version 2 of the License, or +(at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with this program; if not, write to the Free Software +Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include <cstdio> +#include <cstdlib> +#include "graph3d/segment.h" +#include "graph3d/image.h" +#include "graph3d/misc.h" +#include "graph3d/pnmfile.h" +#include "graph3d/segment-image.h" + + +/*#include <cstdio> +#include <cstdlib> +#include <cv_bridge/cv_bridge.h> +#include <opencv2/core/core.hpp> +#include <opencv2/imgproc/imgproc.hpp> +#include "graph3d/image.h" +#include "graph3d/misc.h" +#include "graph3d/pnmfile.h" +#include "graph3d/segment-image.h" + + +int main(int argc, char **argv) { + if (argc != 6) { + fprintf(stderr, "usage: %s sigma k min input(ppm) output(ppm)\n", argv[0]); + return 1; + } + + float sigma = atof(argv[1]); + float k = atof(argv[2]); + int min_size = atoi(argv[3]); + + printf("loading input image.\n"); + image<rgb> *input = loadPPM(argv[4]); + + printf("processing\n"); + int num_ccs; + image<rgb> *seg = segment_image(input, sigma, k, min_size, &num_ccs); + savePPM(seg, argv[5]); + + + printf("got %d components\n", num_ccs); + printf("done! uff...thats hard work.\n"); + + return 0; +}*/ + + + +//void imadjust(const cv::Mat & src, cv::Mat & dst, int tol = 1, cv::Vec2i in = cv::Vec2i(0, 255), cv::Vec2i out = cv::Vec2i(0, 255)) +void imadjust(const cv::Mat & src, cv::Mat & dst) +{ + // src : input CV_8UC1 image + // dst : output CV_8UC1 imge + // tol : tolerance, from 0 to 100. + // in : src image bounds + // out : dst image buonds + + int in[2]; in[0]=0; in[1]=255; + int out[2]; out[0]=0; out[1]=255; + int tol =1; + + + + dst = src.clone(); + + tol = std::max(0, std::min(100, tol)); + + if (tol > 0) + { + // Compute in and out limits + + // Histogram + std::vector<int> hist(256, 0); + for (int r = 0; r < src.rows; ++r) { + for (int c = 0; c < src.cols; ++c) { + hist[src.at<uint8_t>(cv::Point(r,c))]++; + } + } + + // Cumulative histogram + std::vector<int> cum = hist; + for (int i = 1; i < hist.size(); ++i) { + cum[i] = cum[i - 1] + hist[i]; + } + + // Compute bounds + int total = src.rows * src.cols; + int low_bound = total * tol / 100; + int upp_bound = total * (100-tol) / 100; + in[0] = distance(cum.begin(), lower_bound(cum.begin(), cum.end(), low_bound)); + in[1] = distance(cum.begin(), lower_bound(cum.begin(), cum.end(), upp_bound)); + + } + + // Stretching + float scale = float(out[1] - out[0]) / float(in[1] - in[0]); + for (int r = 0; r < dst.rows; ++r) + { + for (int c = 0; c < dst.cols; ++c) + { + int vs = std::max(src.at<uint8_t>(cv::Point(r, c)) - in[0], 0); + + + int vd = std::min(int(vs * scale + 0.5f) + out[0], out[1]); + dst.at<uint8_t>(cv::Point(r, c)) = cv::saturate_cast<uchar>(vd); + } + } +} + +//This function is just an interface to call the segment_image function +void im2segment(cv::Mat input, cv::Mat cv_image_output, float sigma, float k, int min_size, int *num_ccs) +{ + + image<rgb> *inputIm=new image<rgb>(input.cols, input.rows); + + + for (int y = 0; y < input.rows; y++) { + for (int x = 0; x < input.cols; x++) { + imRef(inputIm, x, y).r = input.at<uint8_t>(cv::Point(x, y)); + imRef(inputIm, x, y).g = input.at<uint8_t>(cv::Point(x, y)); + imRef(inputIm, x, y).b = input.at<uint8_t>(cv::Point(x, y)); + } + } + + std::cout<<"I'm here!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!"<<std::endl; + savePPM(inputIm, "/home/fran/input_image.ppm"); + + image<rgb> *seg = segment_image(inputIm, sigma, k, min_size, num_ccs); + + //cv_image_output.encoding = "bgr8"; + //cv_image_output.image =cv::Mat(input.rows, input.cols, CV_8UC3); + + for (int y = 0; y < input.rows; y++) { + for (int x = 0; x < input.cols; x++) { + //output.at<uint8_t>(cv::Point(x, y))=imRef(seg, x, y); + cv_image_output.at<cv::Vec3b>(cv::Point(x, y)) = ( \ + cv::Vec3b(imRef(seg,x,y).b, imRef(seg,x,y).g, imRef(seg,x,y).r)); + } + } + + + /*image<uchar> *inputTmp=new image<uchar>(input.cols, input.rows);; + for (int y = 0; y < input.rows; y++) { + for (int x = 0; x < input.cols; x++) { + imRef(inputTmp, x, y) = input.at<uint8_t>(cv::Point(x, y)); + } + } + savePGM(inputTmp, "/home/fran/input_image.ppm"); + */ + + //printf("got %d components\n", num_ccs); + //printf("done! uff...thats hard work.\n"); +} + diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.cproject b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.cproject new file mode 100755 index 0000000..98ae393 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.cproject @@ -0,0 +1,67 @@ +<?xml version="1.0" encoding="UTF-8" standalone="no"?> +<?fileVersion 4.0.0?><cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage"> + <storageModule moduleId="org.eclipse.cdt.core.settings"> + <cconfiguration id="cdt.managedbuild.toolchain.gnu.base.1733434747"> + <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.toolchain.gnu.base.1733434747" moduleId="org.eclipse.cdt.core.settings" name="Default"> + <externalSettings/> + <extensions> + <extension id="org.eclipse.cdt.core.ELF" point="org.eclipse.cdt.core.BinaryParser"/> + <extension id="org.eclipse.cdt.core.GmakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> + <extension id="org.eclipse.cdt.core.CWDLocator" point="org.eclipse.cdt.core.ErrorParser"/> + <extension id="org.eclipse.cdt.core.GCCErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> + <extension id="org.eclipse.cdt.core.GASErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> + <extension id="org.eclipse.cdt.core.GLDErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> + </extensions> + </storageModule> + <storageModule moduleId="cdtBuildSystem" version="4.0.0"> + <configuration artifactName="${ProjName}" buildProperties="" description="" id="cdt.managedbuild.toolchain.gnu.base.1733434747" name="Default" parent="org.eclipse.cdt.build.core.emptycfg"> + <folderInfo id="cdt.managedbuild.toolchain.gnu.base.1733434747.361979371" name="/" resourcePath=""> + <toolChain id="cdt.managedbuild.toolchain.gnu.base.1216366819" name="cdt.managedbuild.toolchain.gnu.base" superClass="cdt.managedbuild.toolchain.gnu.base"> + <targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="cdt.managedbuild.target.gnu.platform.base.894778321" name="Debug Platform" osList="linux,hpux,aix,qnx" superClass="cdt.managedbuild.target.gnu.platform.base"/> + <builder enableAutoBuild="true" id="cdt.managedbuild.target.gnu.builder.base.714995375" keepEnvironmentInBuildfile="false" managedBuildOn="false" name="Gnu Make Builder" parallelBuildOn="true" parallelizationNumber="optimal" superClass="cdt.managedbuild.target.gnu.builder.base"/> + <tool id="cdt.managedbuild.tool.gnu.archiver.base.1646610619" name="GCC Archiver" superClass="cdt.managedbuild.tool.gnu.archiver.base"/> + <tool id="cdt.managedbuild.tool.gnu.cpp.compiler.base.2073536060" name="GCC C++ Compiler" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.base"/> + <tool id="cdt.managedbuild.tool.gnu.c.compiler.base.1181955887" name="GCC C Compiler" superClass="cdt.managedbuild.tool.gnu.c.compiler.base"> + <option id="gnu.c.compiler.option.preprocessor.def.symbols.617236572" name="Defined symbols (-D)" superClass="gnu.c.compiler.option.preprocessor.def.symbols" useByScannerDiscovery="false" valueType="definedSymbols"> + <listOptionValue builtIn="false" value="_DEFAULT_SOURCE=1"/> + <listOptionValue builtIn="false" value="_XOPEN_SOURCE=700"/> + </option> + <option id="gnu.c.compiler.option.include.paths.10561483" name="Include paths (-I)" superClass="gnu.c.compiler.option.include.paths" useByScannerDiscovery="false" valueType="includePath"> + <listOptionValue builtIn="false" value="/usr/include/libusb-1.0"/> + </option> + <inputType id="cdt.managedbuild.tool.gnu.c.compiler.input.1645890299" superClass="cdt.managedbuild.tool.gnu.c.compiler.input"/> + </tool> + <tool id="cdt.managedbuild.tool.gnu.c.linker.base.226870374" name="GCC C Linker" superClass="cdt.managedbuild.tool.gnu.c.linker.base"> + <inputType id="cdt.managedbuild.tool.gnu.c.linker.input.749058961" superClass="cdt.managedbuild.tool.gnu.c.linker.input"> + <additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/> + <additionalInput kind="additionalinput" paths="$(LIBS)"/> + </inputType> + </tool> + <tool id="cdt.managedbuild.tool.gnu.cpp.linker.base.1405901520" name="GCC C++ Linker" superClass="cdt.managedbuild.tool.gnu.cpp.linker.base"/> + <tool id="cdt.managedbuild.tool.gnu.assembler.base.1784132232" name="GCC Assembler" superClass="cdt.managedbuild.tool.gnu.assembler.base"> + <inputType id="cdt.managedbuild.tool.gnu.assembler.input.115896780" superClass="cdt.managedbuild.tool.gnu.assembler.input"/> + </tool> + </toolChain> + </folderInfo> + </configuration> + </storageModule> + <storageModule moduleId="org.eclipse.cdt.core.externalSettings"/> + </cconfiguration> + </storageModule> + <storageModule moduleId="cdtBuildSystem" version="4.0.0"> + <project id="libcaer.null.970779615" name="libcaer"/> + </storageModule> + <storageModule moduleId="org.eclipse.cdt.core.LanguageSettingsProviders"/> + <storageModule moduleId="refreshScope" versionNumber="2"> + <configuration configurationName="Default"> + <resource resourceType="PROJECT" workspacePath="/libcaer"/> + </configuration> + </storageModule> + <storageModule moduleId="org.eclipse.cdt.internal.ui.text.commentOwnerProjectMappings"/> + <storageModule moduleId="scannerConfiguration"> + <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/> + <scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.base.1733434747;cdt.managedbuild.toolchain.gnu.base.1733434747.361979371;cdt.managedbuild.tool.gnu.c.compiler.base.1181955887;cdt.managedbuild.tool.gnu.c.compiler.input.1645890299"> + <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/> + </scannerConfigBuildInfo> + </storageModule> +</cproject> diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.gitignore b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.gitignore new file mode 100755 index 0000000..7b08def --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.gitignore @@ -0,0 +1,11 @@ +/build/ +CMakeCache.txt +CMakeFiles/ +Makefile +cmake_install.cmake +/install_manifest.txt +/libcaer.pc +*~ +*.swp +*.swo +*.sh diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.project b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.project new file mode 100755 index 0000000..c74470c --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.project @@ -0,0 +1,26 @@ +<?xml version="1.0" encoding="UTF-8"?> +<projectDescription> + <name>libcaer</name> + <comment></comment> + <projects> + </projects> + <buildSpec> + <buildCommand> + <name>org.eclipse.cdt.managedbuilder.core.genmakebuilder</name> + <arguments> + </arguments> + </buildCommand> + <buildCommand> + <name>org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder</name> + <triggers>full,incremental,</triggers> + <arguments> + </arguments> + </buildCommand> + </buildSpec> + <natures> + <nature>org.eclipse.cdt.core.cnature</nature> + <nature>org.eclipse.cdt.managedbuilder.core.managedBuildNature</nature> + <nature>org.eclipse.cdt.managedbuilder.core.ScannerConfigNature</nature> + <nature>org.eclipse.cdt.codan.core.codanNature</nature> + </natures> +</projectDescription> diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.settings/language.settings.xml b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.settings/language.settings.xml new file mode 100755 index 0000000..f5dd61d --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.settings/language.settings.xml @@ -0,0 +1,12 @@ +<?xml version="1.0" encoding="UTF-8" standalone="no"?> +<project> + <configuration id="cdt.managedbuild.toolchain.gnu.base.1733434747" name="Default"> + <extension point="org.eclipse.cdt.core.LanguageSettingsProvider"> + <provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/> + <provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/> + <provider-reference id="org.eclipse.cdt.managedbuilder.core.GCCBuildCommandParser" ref="shared-provider"/> + <provider-reference id="org.eclipse.cdt.managedbuilder.core.GCCBuiltinSpecsDetector" ref="shared-provider"/> + <provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/> + </extension> + </configuration> +</project> diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.settings/org.eclipse.cdt.codan.core.prefs b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.settings/org.eclipse.cdt.codan.core.prefs new file mode 100755 index 0000000..d2a09ff --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/.settings/org.eclipse.cdt.codan.core.prefs @@ -0,0 +1,73 @@ +eclipse.preferences.version=1 +onBuild=true +org.eclipse.cdt.codan.checkers.errnoreturn=Warning +org.eclipse.cdt.codan.checkers.errnoreturn.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},implicit\=>false} +org.eclipse.cdt.codan.checkers.errreturnvalue=Error +org.eclipse.cdt.codan.checkers.errreturnvalue.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.checkers.nocommentinside=Error +org.eclipse.cdt.codan.checkers.nocommentinside.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.checkers.nolinecomment=-Error +org.eclipse.cdt.codan.checkers.nolinecomment.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.checkers.noreturn=Error +org.eclipse.cdt.codan.checkers.noreturn.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},implicit\=>false} +org.eclipse.cdt.codan.internal.checkers.AbstractClassCreation=Error +org.eclipse.cdt.codan.internal.checkers.AbstractClassCreation.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.AmbiguousProblem=Error +org.eclipse.cdt.codan.internal.checkers.AmbiguousProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.AssignmentInConditionProblem=Warning +org.eclipse.cdt.codan.internal.checkers.AssignmentInConditionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.AssignmentToItselfProblem=Error +org.eclipse.cdt.codan.internal.checkers.AssignmentToItselfProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.CaseBreakProblem=Warning +org.eclipse.cdt.codan.internal.checkers.CaseBreakProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},no_break_comment\=>"no break",last_case_param\=>false,empty_case_param\=>false} +org.eclipse.cdt.codan.internal.checkers.CatchByReference=Warning +org.eclipse.cdt.codan.internal.checkers.CatchByReference.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},unknown\=>false,exceptions\=>()} +org.eclipse.cdt.codan.internal.checkers.CircularReferenceProblem=Error +org.eclipse.cdt.codan.internal.checkers.CircularReferenceProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.ClassMembersInitialization=Warning +org.eclipse.cdt.codan.internal.checkers.ClassMembersInitialization.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},skip\=>true} +org.eclipse.cdt.codan.internal.checkers.FieldResolutionProblem=-Error +org.eclipse.cdt.codan.internal.checkers.FieldResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.FunctionResolutionProblem=Error +org.eclipse.cdt.codan.internal.checkers.FunctionResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.InvalidArguments=Error +org.eclipse.cdt.codan.internal.checkers.InvalidArguments.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.InvalidTemplateArgumentsProblem=Error +org.eclipse.cdt.codan.internal.checkers.InvalidTemplateArgumentsProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.LabelStatementNotFoundProblem=Error +org.eclipse.cdt.codan.internal.checkers.LabelStatementNotFoundProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.MemberDeclarationNotFoundProblem=Error +org.eclipse.cdt.codan.internal.checkers.MemberDeclarationNotFoundProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.MethodResolutionProblem=Error +org.eclipse.cdt.codan.internal.checkers.MethodResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.NamingConventionFunctionChecker=-Info +org.eclipse.cdt.codan.internal.checkers.NamingConventionFunctionChecker.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},pattern\=>"^[a-z]",macro\=>true,exceptions\=>()} +org.eclipse.cdt.codan.internal.checkers.NonVirtualDestructorProblem=Warning +org.eclipse.cdt.codan.internal.checkers.NonVirtualDestructorProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.OverloadProblem=Error +org.eclipse.cdt.codan.internal.checkers.OverloadProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.RedeclarationProblem=Error +org.eclipse.cdt.codan.internal.checkers.RedeclarationProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.RedefinitionProblem=Error +org.eclipse.cdt.codan.internal.checkers.RedefinitionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.ReturnStyleProblem=Warning +org.eclipse.cdt.codan.internal.checkers.ReturnStyleProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.ScanfFormatStringSecurityProblem=Warning +org.eclipse.cdt.codan.internal.checkers.ScanfFormatStringSecurityProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.StatementHasNoEffectProblem=Warning +org.eclipse.cdt.codan.internal.checkers.StatementHasNoEffectProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true,exceptions\=>()} +org.eclipse.cdt.codan.internal.checkers.SuggestedParenthesisProblem=Warning +org.eclipse.cdt.codan.internal.checkers.SuggestedParenthesisProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},paramNot\=>false} +org.eclipse.cdt.codan.internal.checkers.SuspiciousSemicolonProblem=Warning +org.eclipse.cdt.codan.internal.checkers.SuspiciousSemicolonProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},else\=>false,afterelse\=>false} +org.eclipse.cdt.codan.internal.checkers.TypeResolutionProblem=-Error +org.eclipse.cdt.codan.internal.checkers.TypeResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +org.eclipse.cdt.codan.internal.checkers.UnusedFunctionDeclarationProblem=Warning +org.eclipse.cdt.codan.internal.checkers.UnusedFunctionDeclarationProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true} +org.eclipse.cdt.codan.internal.checkers.UnusedStaticFunctionProblem=Warning +org.eclipse.cdt.codan.internal.checkers.UnusedStaticFunctionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true} +org.eclipse.cdt.codan.internal.checkers.UnusedVariableDeclarationProblem=Warning +org.eclipse.cdt.codan.internal.checkers.UnusedVariableDeclarationProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},macro\=>true,exceptions\=>("@(\#)","$Id")} +org.eclipse.cdt.codan.internal.checkers.VariableResolutionProblem=Error +org.eclipse.cdt.codan.internal.checkers.VariableResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true}} +useParentScope=false diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/CMakeLists.txt b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/CMakeLists.txt new file mode 100755 index 0000000..18ea7e6 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/CMakeLists.txt @@ -0,0 +1,223 @@ +# Init CMake (require at least version 2.6) +CMAKE_MINIMUM_REQUIRED(VERSION 2.6) + +# General build settings +IF (NOT CMAKE_BUILD_TYPE) + SET(CMAKE_BUILD_TYPE "Release" CACHE STRING "Possible build types: None Debug Release RelWithDebInfo MinSizeRel") +ENDIF() + +IF (NOT ENABLE_OPENCV) + SET(ENABLE_OPENCV 0 CACHE BOOL "Enable support for frame enhancements using OpenCV") +ENDIF() + +# Project name and version +PROJECT(libcaer C CXX) +SET(PROJECT_VERSION_MAJOR 2) +SET(PROJECT_VERSION_MINOR 0) +SET(PROJECT_VERSION_PATCH 0) +SET(PROJECT_VERSION_NOREV ${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}) +IF (NOT PROJECT_REVISION) + # EXECUTE_PROCESS(COMMAND svnversion OUTPUT_VARIABLE PROJECT_REVISION OUTPUT_STRIP_TRAILING_WHITESPACE) + EXECUTE_PROCESS(COMMAND git rev-parse HEAD OUTPUT_VARIABLE PROJECT_REVISION OUTPUT_STRIP_TRAILING_WHITESPACE) +ENDIF() +SET(PROJECT_VERSION ${PROJECT_VERSION_NOREV}-r${PROJECT_REVISION}) + +# Define installation paths. +INCLUDE(GNUInstallDirs) + +# Set compiler info +SET(CC_CLANG FALSE) +SET(CC_GCC FALSE) +SET(CC_ICC FALSE) +SET(CC_MSVC FALSE) + +IF ("${CMAKE_C_COMPILER_ID}" STREQUAL "Clang") + SET(CC_CLANG TRUE) +ELSEIF ("${CMAKE_C_COMPILER_ID}" STREQUAL "GNU") + SET(CC_GCC TRUE) +ELSEIF ("${CMAKE_C_COMPILER_ID}" STREQUAL "Intel") + SET(CC_ICC TRUE) +ELSEIF ("${CMAKE_C_COMPILER_ID}" STREQUAL "MSVC") + SET(CC_MSVC TRUE) +ENDIF() + +# Set operating system info +SET(OS_UNIX FALSE) +SET(OS_LINUX FALSE) +SET(OS_MACOSX FALSE) +SET(OS_WINDOWS FALSE) + +IF (UNIX) + SET(OS_UNIX TRUE) + ADD_DEFINITIONS(-DOS_UNIX=1) +ENDIF() + +IF (UNIX AND "${CMAKE_SYSTEM_NAME}" MATCHES "Linux") + SET(OS_LINUX TRUE) + ADD_DEFINITIONS(-DOS_LINUX=1) +ENDIF() + +IF (UNIX AND APPLE AND "${CMAKE_SYSTEM_NAME}" MATCHES "Darwin") + SET(OS_MACOSX TRUE) + ADD_DEFINITIONS(-DOS_MACOSX=1) +ENDIF() + +IF (WIN32 AND "${CMAKE_SYSTEM_NAME}" MATCHES "Windows") + SET(OS_WINDOWS TRUE) + ADD_DEFINITIONS(-DOS_WINDOWS=1) +ENDIF() + +# Test if we are on a big-endian architecture +INCLUDE(TestBigEndian) +TEST_BIG_ENDIAN(SYSTEM_BIGENDIAN) + +# Check size of various types +INCLUDE(CheckTypeSize) +CHECK_TYPE_SIZE("size_t" SIZEOF_SIZE_T) +CHECK_TYPE_SIZE("void *" SIZEOF_VOID_PTR) + +IF (NOT "${SIZEOF_VOID_PTR}" STREQUAL "${SIZEOF_SIZE_T}") + MESSAGE(SEND_ERROR "Size of void * and size_t must be the same!") +ENDIF() + +# Check threads support (almost nobody implements C11 threads yet!) +FIND_PACKAGE(Threads) +SET(HAVE_PTHREADS FALSE) +SET(HAVE_WIN32_THREADS FALSE) + +IF (OS_UNIX AND DEFINED "CMAKE_USE_PTHREADS_INIT") + IF (${CMAKE_USE_PTHREADS_INIT}) + SET(HAVE_PTHREADS TRUE) + ADD_DEFINITIONS(-DHAVE_PTHREADS=1) + ENDIF() +ENDIF() + +IF (OS_WINDOWS AND DEFINED "CMAKE_USE_WIN32_THREADS_INIT") + IF (${CMAKE_USE_WIN32_THREADS_INIT}) + SET(HAVE_WIN32_THREADS TRUE) + ADD_DEFINITIONS(-DHAVE_WIN32_THREADS=1) + ENDIF() +ENDIF() + +# Add system defines for header features +IF (OS_UNIX AND HAVE_PTHREADS) + # POSIX system (Unix, Linux, MacOS X) + ADD_DEFINITIONS(-D_XOPEN_SOURCE=700) + ADD_DEFINITIONS(-D_DEFAULT_SOURCE=1) + + IF (OS_MACOSX) + ADD_DEFINITIONS(-D_DARWIN_C_SOURCE=1) + ENDIF() +ENDIF() + +# C11 standard needed (atomics, threads) +IF (CC_GCC OR CC_CLANG) + SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -std=c11") + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") +ENDIF() + +# Enable all warnings for GCC / Clang +IF (CC_GCC OR CC_CLANG) + SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -pedantic -Wall -Wextra") + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -pedantic -Wall -Wextra") + + IF (CC_GCC) + # Enable all useful warnings manually in GCC. + SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wunused -Wundef -Wformat=2 -Winit-self -Wuninitialized") + SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wpointer-arith -Wcast-qual -Wcast-align -Wwrite-strings") + SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wstrict-prototypes -Wmissing-prototypes -Wredundant-decls") + SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wmissing-declarations -Wnested-externs -Wstack-protector") + SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wshadow -Wbad-function-cast -Wfloat-equal") + SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wconversion -Wstrict-overflow=2") + SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wjump-misses-init -Wunsuffixed-float-constants -Wdouble-promotion") + ENDIF() + + IF (CC_CLANG) + # Enable all warnings in Clang easily. + SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Weverything -Wno-packed -Wno-padded -Wno-unreachable-code-break") + SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wno-disabled-macro-expansion -Wno-reserved-id-macro -Wno-vla") + SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wno-parentheses-equality -Wno-covered-switch-default") + SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wno-used-but-marked-unused -Wno-cast-align") + ENDIF() +ENDIF() + +# Search for external libraries with pkg-config +INCLUDE(FindPkgConfig) + +# Basic USB device support +PKG_CHECK_MODULES(LIBUSB1 REQUIRED libusb-1.0>=1.0.17) +SET(LIBCAER_INCDIRS ${LIBUSB1_INCLUDE_DIRS}) +SET(LIBCAER_LIBDIRS ${LIBUSB1_LIBRARY_DIRS}) +SET(LIBCAER_LIBS ${LIBUSB1_LIBRARIES}) + +IF (ENABLE_OPENCV) + # Require new OpenCV 3.1 at least. + PKG_CHECK_MODULES(OPENCV3 REQUIRED opencv>=3.1) + + SET(LIBCAER_INCDIRS ${LIBCAER_INCDIRS} ${OPENCV3_INCLUDE_DIRS}) + SET(LIBCAER_LIBDIRS ${LIBCAER_LIBDIRS} ${OPENCV3_LIBRARY_DIRS}) + SET(LIBCAER_LIBS ${LIBCAER_LIBS} ${OPENCV3_LIBRARIES}) +ENDIF() + +# Threads support +SET(LIBCAER_LIBS ${LIBCAER_LIBS} ${CMAKE_THREAD_LIBS_INIT}) + +# Add local directory to include paths +SET(LIBCAER_INCDIRS ${LIBCAER_INCDIRS} ${CMAKE_SOURCE_DIR}/include/) + +INCLUDE_DIRECTORIES(${LIBCAER_INCDIRS}) +LINK_DIRECTORIES(${LIBCAER_LIBDIRS}) + +# Set full RPATH +SET(CMAKE_INSTALL_RPATH ${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_LIBDIR}) +SET(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) +IF (OS_MACOSX) + SET(CMAKE_MACOSX_RPATH TRUE) +ENDIF() + +# Subdirectories +ADD_SUBDIRECTORY(include) +ADD_SUBDIRECTORY(src) + +# Generate pkg-config file +FOREACH (LIB ${CMAKE_THREAD_LIBS_INIT}) + SET(PRIVATE_LIBS "${LIB} ${PRIVATE_LIBS}") +ENDFOREACH() + +IF (ENABLE_OPENCV) + # Use different pkg-config file to specify OpenCV support + CONFIGURE_FILE(libcaer_opencv.pc.in libcaer.pc @ONLY) +ELSE() + CONFIGURE_FILE(libcaer.pc.in libcaer.pc @ONLY) +ENDIF() + +INSTALL(FILES ${CMAKE_BINARY_DIR}/libcaer.pc DESTINATION ${CMAKE_INSTALL_LIBDIR}/pkgconfig) + +# Automatic documentation generation support +FIND_PACKAGE(Doxygen) + +IF (DOXYGEN_FOUND) + ADD_SUBDIRECTORY(docs) +ENDIF() + +# Print info summary for debug purposes +MESSAGE(STATUS "Project version is: ${PROJECT_VERSION}") +MESSAGE(STATUS "Compiler is Clang: ${CC_CLANG}") +MESSAGE(STATUS "Compiler is GCC: ${CC_GCC}") +MESSAGE(STATUS "Compiler is IntelCC: ${CC_ICC}") +MESSAGE(STATUS "Compiler is MS VisualC: ${CC_MSVC}") +MESSAGE(STATUS "OS is Unix: ${OS_UNIX}") +MESSAGE(STATUS "OS is Linux: ${OS_LINUX}") +MESSAGE(STATUS "OS is MacOS X: ${OS_MACOSX}") +MESSAGE(STATUS "OS is Windows: ${OS_WINDOWS}") +MESSAGE(STATUS "System is big-endian: ${SYSTEM_BIGENDIAN}") +MESSAGE(STATUS "Thread support is PThreads: ${HAVE_PTHREADS}") +MESSAGE(STATUS "Thread support is Win32 Threads: ${HAVE_WIN32_THREADS}") +MESSAGE(STATUS "C flags are: ${CMAKE_C_FLAGS}") +MESSAGE(STATUS "CXX flags are: ${CMAKE_CXX_FLAGS}") +MESSAGE(STATUS "Include directories are: ${LIBCAER_INCDIRS}") +MESSAGE(STATUS "Library directories are: ${LIBCAER_LIBDIRS}") +MESSAGE(STATUS "Linked libraries are: ${LIBCAER_LIBS}") +MESSAGE(STATUS "Compiled source files are: ${LIBCAER_SRC_FILES}") +MESSAGE(STATUS "Final install libdir is: ${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_LIBDIR}") +MESSAGE(STATUS "Final install includedir is: ${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_INCLUDEDIR}/${CMAKE_PROJECT_NAME}") diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/COPYING b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/COPYING new file mode 100755 index 0000000..f09927e --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/COPYING @@ -0,0 +1,23 @@ +Copyright (c) 2014-2015, Luca Longinotti, iniLabs Ltd. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. +2. Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + +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/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/ChangeLog b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/ChangeLog new file mode 100755 index 0000000..2b00a65 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/ChangeLog @@ -0,0 +1,95 @@ +Release 1.0.3 - 28.03.2016 +INCOMPATIBLE CHANGES +- davis_fx2.c: removed specific FX2 code, now uses same backend as FX3 + for sending all configuration values, due to new firmware version 3 + for FX2 DAVIS small-board cameras. A firmware update is required, + please follow the instructions at http://inilabs.com/support/reflashing/. + +NEW FEATURES +- frame.h: add function caerFrameEventGetPixelArrayCGFormat() to + Frame Event, allows to get a copy of the pixels array in the + standard computer graphics format (pixel (0, 0) in upper left + corner) efficently. +- davis.h: add DAVIS_CONFIG_APS_ADC_TEST_MODE parameter to APS module. + +Release 1.0.2 - 08.01.2016 +IMCOMPATIBLE CHANGES +- frame.h: rename channel number to color channels and add color + filter information, to better specify the information needed + to reconstruct color frames. The 'enum caer_frame_event_color_channels' + and 'enum caer_frame_event_color_filter' hold the possible values. + This change is backwards-compatible with older frame format! +- davis.h, dvs128.h: changed info data structure's integers to be + signed for better cross-language compatibility. Also 'deviceID' + can now be compared directly with 'sourceID' from event packets. +- davis.h: changed type of 'apsColorFilter' in info data structure + to take advantage of new 'enum caer_frame_event_color_filter'. + +NEW FEATURES +- common.h: add generic functions for event packet copying, with + support for packet size reductions (copy only valid). +- libcaer.h: add generic clear, get and set functions for bitfields, + and use them in all the event functions to avoid errors. +- config.h: add device configuration event type, for tracking + of device configuration changes in the event stream. +- log.c: add timezone information to log message time information. +- dvs128_simple.cpp, davis_simple.cpp: add C++11 example variants. +- Enable more Clang compiler warnings. + +BUG FIXES +- davis_common.c: only update the ROI size information if ROI + updates actually came in from the device. +- Fix and improve documentation, especially for the frame event. +- Fix off-by-one in event's GetEvent() function's warning log message. +- device.c: mark global function pointer arrays static. +- common.h, frame.h: fix compilation of inline functions in + strict C++11 mode. + + +Release 1.0.1 - 06.11.2015 +INCOMPATIBLE CHANGES +- Requires firmware version 2 and logic revision 7449. +- usb.h: improved caerDeviceDataStart() API to also allow for + notification of data acquisition shutdown, to be able to react + to abnormal shutdown cases, like when a device is unplugged. +- frame.h: changed in-memory format for easier handling and compatibility + with the other event formats (all-in-one memory block). +- davis.h: rename DAVIS240 APSOVERFLOWLEVEL to APSOVERFLOWLEVELBN. + +NEW FEATURES +- Headers are C++ compatible and stand-alone now. +- MacOS X support. +- Added pkg-config file for library. +- Full API documentation (see docs/ for PDF). +- Various cmake/build improvements. Support out-of-tree builds. +- Add iterator macros for EventPackets. +- frame.h: added ROI region ID tracking, as well as ROI position. + Added caerFrameEventGetExposureLength() and caerFrameEventGetTimestamp(), + which is defined as the median of the exposure times. + Added caerFrameEventPacketGetPixelsSize() and caerFrameEventPacketGetPixelsMaxIndex() + for EventPacket-level size information. + Added caerFrameEventGetPixelsSize() and caerFrameEventGetPixelsMaxIndex() + for Event-level size information. +- log.h: added caerLogFileDescriptorsSet() to allow logging to + up to two different file descriptors (defaults to STDERR only). +- davis.h: added chipID check macros. +- davis.h: added DAVIS_CONFIG_APS_SNAPSHOT to take one frame snapshots. +- dvs128.h: added DVS128_CONFIG_DVS_TS_MASTER to select timestamp + master or slave behavior (timestamp synchronization). +- davis_common.c: added support for outputting only reset read or + signal read frames, for debugging purposes. +- c11threads_posix.h: C11-compatible thread abstraction, for + both Linux and MacOS X, based on POSIX Threads. + +BUG FIXES +- Relaxed atomic operations memory constraints for better + performance on weakly-ordered architectures (like ARM). +- log.c: call tzset() before localtime_r(), as per standard. +- davis_common.c: improved Region of Interest support (APS). +- davis_fx2.c: keep GlobalShutter flag correctly in-sync. +- davis_fx3.c: fixed support for new FX3 devices. +- packetContainer.h: handle container being NULL by returning NULL. + + +Release 1.0.0 - 02.10.2015 +- Initial release. diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/README b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/README new file mode 100755 index 0000000..5d09310 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/README @@ -0,0 +1,56 @@ +libcaer +==== + +Minimal C library to access, configure and get data out of AER sensors, +such as the Dynamic Vision Sensor (DVS) or DAVIS cameras. + +REQUIREMENTS: + +cmake >= 2.6 +gcc >= 4.9 or clang >= 3.6 +libusb >= 1.0.17 + +Please make sure that you have the various development packages installed +for the above dependencies. They are usually called PKG-dev or PKG-devel. + +INSTALLATION: + +1) configure: + +$ cmake -DCMAKE_INSTALL_PREFIX=/usr . + +2) build: + +$ make + +3) install: + +$ make install + +DOCUMENTATION: + +The API documentation for a release can be found at docs/libcaer_api_manual.pdf. +Also check the examples/ directory and the iniLabs Support website. + +For the development tree, you can generate the documentation using: + +$ make doc - to generate docs/latex/ and docs/html/ documentation files. +$ make pdf - to generate a PDF from the LaTeX sources at docs/latex/refman.pdf. + +USAGE: + +See examples/ directory. Usual usage is (simplified): + +h = caerDeviceOpen(TYPE); +caerDeviceSendDefaultConfig(h); +caerDeviceDataStart(h); + +loop: + c = caerDeviceDataGet(h); + work with c (container) and its event packets + +caerDeviceDataStop(h); +caerDeviceClose(&h); + +All configuration parameters and event types are specified in the +public headers and documented there. diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/docs/.gitignore b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/docs/.gitignore new file mode 100755 index 0000000..f5133a9 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/docs/.gitignore @@ -0,0 +1,3 @@ +/libcaer_api.doxy +/html/ +/latex/ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/docs/CMakeLists.txt b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/docs/CMakeLists.txt new file mode 100755 index 0000000..2ad5c8a --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/docs/CMakeLists.txt @@ -0,0 +1,48 @@ +IF (NOT DOXYGEN_FOUND) + # Only support call from main cmake. + RETURN() +ENDIF() + +# Doxygen directories and configuration. HTML and Latex are generated. +SET(DOXYGEN_OUTPUT_DIR ${CMAKE_BINARY_DIR}/docs/) +SET(DOXYGEN_CONFIG ${DOXYGEN_OUTPUT_DIR}/libcaer_api.doxy) +SET(DOXYGEN_LATEX_OUTPUT_DIR ${DOXYGEN_OUTPUT_DIR}/latex/) +SET(DOXYGEN_LATEX_OUTPUT ${DOXYGEN_LATEX_OUTPUT_DIR}/refman.tex) +SET(DOXYGEN_HTML_OUTPUT_DIR ${DOXYGEN_OUTPUT_DIR}/html/) +SET(DOXYGEN_HTML_OUTPUT ${DOXYGEN_HTML_OUTPUT_DIR}/index.html) + +CONFIGURE_FILE(libcaer_api.doxy.in libcaer_api.doxy @ONLY) + +ADD_CUSTOM_COMMAND( + OUTPUT ${DOXYGEN_LATEX_OUTPUT} ${DOXYGEN_HTML_OUTPUT} + COMMAND ${DOXYGEN_EXECUTABLE} ${DOXYGEN_CONFIG} + WORKING_DIRECTORY ${CMAKE_SOURCE_DIR}/include/ + DEPENDS ${DOXYGEN_CONFIG}) + +# Generate documentation with 'make doc'. +ADD_CUSTOM_TARGET(doc DEPENDS ${DOXYGEN_LATEX_OUTPUT} ${DOXYGEN_HTML_OUTPUT}) + +# Automatically generate PDF from Latex. +FIND_PACKAGE(LATEX) + +IF (NOT LATEX_COMPILER) + MESSAGE(STATUS "latex command LATEX_COMPILER not found, but usually required by Doxygen.") +ENDIF() + +IF (NOT MAKEINDEX_COMPILER) + MESSAGE(STATUS "makeindex command MAKEINDEX_COMPILER not found, but usually required by Doxygen.") +ENDIF() + +IF (NOT DVIPS_CONVERTER) + MESSAGE(STATUS "dvips command DVIPS_CONVERTER not found, but usually required by Doxygen.") +ENDIF() + +# Generate PDF documentation. +ADD_CUSTOM_COMMAND( + OUTPUT ${DOXYGEN_LATEX_OUTPUT_DIR}/refman.pdf + COMMAND make + WORKING_DIRECTORY ${DOXYGEN_LATEX_OUTPUT_DIR} + DEPENDS ${DOXYGEN_LATEX_OUTPUT}) + +# Generate PDF from Latex with 'make pdf'. +ADD_CUSTOM_TARGET(pdf DEPENDS ${DOXYGEN_LATEX_OUTPUT_DIR}/refman.pdf) diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/docs/libcaer_api.doxy.in b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/docs/libcaer_api.doxy.in new file mode 100755 index 0000000..df70e7b --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/docs/libcaer_api.doxy.in @@ -0,0 +1,2362 @@ +# Doxyfile 1.8.9.1 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project. +# +# All text after a double hash (##) is considered a comment and is placed in +# front of the TAG it is preceding. +# +# All text after a single 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 +#--------------------------------------------------------------------------- + +# This tag specifies the encoding used for all characters in the config file +# that follow. The default is UTF-8 which is also the encoding used for all text +# before the first occurrence of this tag. Doxygen uses libiconv (or the iconv +# built into libc) for the transcoding. See http://www.gnu.org/software/libiconv +# for the list of possible encodings. +# The default value is: UTF-8. + +DOXYFILE_ENCODING = UTF-8 + +# The PROJECT_NAME tag is a single word (or a sequence of words surrounded by +# double-quotes, unless you are using Doxywizard) that should identify the +# project for which the documentation is generated. This name is used in the +# title of most generated pages and in a few other places. +# The default value is: My Project. + +PROJECT_NAME = "@PROJECT_NAME@" + +# 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 = "@PROJECT_VERSION@" + +# Using the PROJECT_BRIEF tag one can provide an optional one line description +# for a project that appears at the top of each page and should give viewer a +# quick idea about the purpose of the project. Keep the description short. + +PROJECT_BRIEF = + +# With the PROJECT_LOGO tag one can specify a logo or an icon that is included +# in the documentation. The maximum height of the logo should not exceed 55 +# pixels and the maximum width should not exceed 200 pixels. Doxygen will copy +# the logo to the output directory. + +PROJECT_LOGO = + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path +# into which the generated documentation will be written. 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 = @DOXYGEN_OUTPUT_DIR@ + +# 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 causes +# performance problems for the file system. +# The default value is: NO. + +CREATE_SUBDIRS = NO + +# If the ALLOW_UNICODE_NAMES tag is set to YES, doxygen will allow non-ASCII +# characters to appear in the names of generated files. If set to NO, non-ASCII +# characters will be escaped, for example _xE3_x81_x84 will be used for Unicode +# U+3044. +# The default value is: NO. + +ALLOW_UNICODE_NAMES = 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. +# Possible values are: Afrikaans, Arabic, Armenian, Brazilian, Catalan, Chinese, +# Chinese-Traditional, Croatian, Czech, Danish, Dutch, English (United States), +# Esperanto, Farsi (Persian), Finnish, French, German, Greek, Hungarian, +# Indonesian, Italian, Japanese, Japanese-en (Japanese with English messages), +# Korean, Korean-en (Korean with English messages), Latvian, Lithuanian, +# Macedonian, Norwegian, Persian (Farsi), Polish, Portuguese, Romanian, Russian, +# Serbian, Serbian-Cyrillic, Slovak, Slovene, Spanish, Swedish, Turkish, +# Ukrainian and Vietnamese. +# The default value is: English. + +OUTPUT_LANGUAGE = English + +# If the BRIEF_MEMBER_DESC tag is set to YES, 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. +# The default value is: YES. + +BRIEF_MEMBER_DESC = YES + +# If the REPEAT_BRIEF tag is set to YES, 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. +# The default value is: YES. + +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 and 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. +# The default value is: NO. + +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. +# The default value is: NO. + +INLINE_INHERITED_MEMB = NO + +# If the FULL_PATH_NAMES tag is set to YES, 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 +# The default value is: YES. + +FULL_PATH_NAMES = YES + +# 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. +# +# Note that you can specify absolute paths here, but also relative paths, which +# will be relative from the directory where doxygen is started. +# This tag requires that the tag FULL_PATH_NAMES is set to YES. + +STRIP_FROM_PATH = + +# 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 list of include paths that are normally passed to the compiler +# using the -I flag. + +STRIP_FROM_INC_PATH = + +# 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. +# The default value is: NO. + +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-style will behave just like regular Qt- +# style comments (thus requiring an explicit @brief command for a brief +# description.) +# The default value is: NO. + +JAVADOC_AUTOBRIEF = NO + +# If the QT_AUTOBRIEF tag is set to YES then doxygen will interpret the first +# line (until the first dot) of a Qt-style comment as the brief description. If +# set to NO, the Qt-style will behave just like regular Qt-style comments (thus +# requiring an explicit \brief command for a brief description.) +# The default value is: NO. + +QT_AUTOBRIEF = NO + +# 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 behavior. 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 behavior instead. +# +# Note that setting this tag to YES also means that rational rose comments are +# not recognized any more. +# The default value is: NO. + +MULTILINE_CPP_IS_BRIEF = NO + +# If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the +# documentation from any documented member that it re-implements. +# The default value is: YES. + +INHERIT_DOCS = YES + +# 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. +# The default value is: NO. + +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. +# Minimum value: 1, maximum value: 16, default value: 4. + +TAB_SIZE = 4 + +# This tag can be used to specify a number of aliases that act 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 = + +# This tag can be used to specify a number of word-keyword mappings (TCL only). +# A mapping has the form "name=value". For example adding "class=itcl::class" +# will allow you to use the command class in the itcl::class meaning. + +TCL_SUBST = + +# 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. +# The default value is: NO. + +OPTIMIZE_OUTPUT_FOR_C = YES + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java or +# Python sources only. Doxygen will then generate output that is more tailored +# for that language. For instance, namespaces will be presented as packages, +# qualified scopes will look different, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_JAVA = NO + +# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran +# sources. Doxygen will then generate output that is tailored for Fortran. +# The default value is: NO. + +OPTIMIZE_FOR_FORTRAN = NO + +# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL +# sources. Doxygen will then generate output that is tailored for VHDL. +# The default value is: NO. + +OPTIMIZE_OUTPUT_VHDL = NO + +# Doxygen selects the parser to use depending on the extension of the files it +# parses. With this tag you can assign which parser to use for a given +# extension. Doxygen has a built-in mapping, but you can override or extend it +# using this tag. The format is ext=language, where ext is a file extension, and +# language is one of the parsers supported by doxygen: IDL, Java, Javascript, +# C#, C, C++, D, PHP, Objective-C, Python, Fortran (fixed format Fortran: +# FortranFixed, free formatted Fortran: FortranFree, unknown formatted Fortran: +# Fortran. In the later case the parser tries to guess whether the code is fixed +# or free formatted code, this is the default for Fortran type files), VHDL. For +# instance to make doxygen treat .inc files as Fortran files (default is PHP), +# and .f files as C (default is Fortran), use: inc=Fortran f=C. +# +# Note: For files without extension you can use no_extension as a placeholder. +# +# Note that for custom extensions you also need to set FILE_PATTERNS otherwise +# the files are not read by doxygen. + +EXTENSION_MAPPING = + +# If the MARKDOWN_SUPPORT tag is enabled then doxygen pre-processes all comments +# according to the Markdown format, which allows for more readable +# documentation. See http://daringfireball.net/projects/markdown/ for details. +# The output of markdown processing is further processed by doxygen, so you can +# mix doxygen, HTML, and XML commands with Markdown formatting. Disable only in +# case of backward compatibilities issues. +# The default value is: YES. + +MARKDOWN_SUPPORT = YES + +# When enabled doxygen tries to link words that correspond to documented +# classes, or namespaces to their corresponding documentation. Such a link can +# be prevented in individual cases by putting a % sign in front of the word or +# globally by setting AUTOLINK_SUPPORT to NO. +# The default value is: YES. + +AUTOLINK_SUPPORT = YES + +# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want +# to include (a tag file for) the STL sources as input, then you should set this +# tag to YES in order to let doxygen match functions declarations and +# definitions whose arguments contain STL classes (e.g. func(std::string); +# versus func(std::string) {}). This also make the inheritance and collaboration +# diagrams that involve STL classes more complete and accurate. +# The default value is: NO. + +BUILTIN_STL_SUPPORT = NO + +# If you use Microsoft's C++/CLI language, you should set this option to YES to +# enable parsing support. +# The default value is: NO. + +CPP_CLI_SUPPORT = NO + +# Set the SIP_SUPPORT tag to YES if your project consists of sip (see: +# http://www.riverbankcomputing.co.uk/software/sip/intro) sources only. Doxygen +# will parse them like normal C++ but will assume all classes use public instead +# of private inheritance when no explicit protection keyword is present. +# The default value is: NO. + +SIP_SUPPORT = NO + +# For Microsoft's IDL there are propget and propput attributes to indicate +# getter and setter methods for a property. Setting this option to YES will make +# doxygen to replace the get and set methods by a property in the documentation. +# This will only work if the methods are indeed getting or setting a simple +# type. If this is not the case, or you want to show the methods anyway, you +# should set this option to NO. +# The default value is: YES. + +IDL_PROPERTY_SUPPORT = 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. +# The default value is: NO. + +DISTRIBUTE_GROUP_DOC = YES + +# Set the SUBGROUPING tag to YES 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. +# The default value is: YES. + +SUBGROUPING = YES + +# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and unions +# are shown inside the group in which they are included (e.g. using \ingroup) +# instead of on a separate page (for HTML and Man pages) or section (for LaTeX +# and RTF). +# +# Note that this feature does not work in combination with +# SEPARATE_MEMBER_PAGES. +# The default value is: NO. + +INLINE_GROUPED_CLASSES = NO + +# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and unions +# with only public data fields or simple typedef fields will be shown inline in +# the documentation of the scope in which they are defined (i.e. file, +# namespace, or group documentation), provided this scope is documented. If set +# to NO, structs, classes, and unions are shown on a separate page (for HTML and +# Man pages) or section (for LaTeX and RTF). +# The default value is: NO. + +INLINE_SIMPLE_STRUCTS = NO + +# When TYPEDEF_HIDES_STRUCT tag is enabled, a typedef of a struct, union, or +# enum is documented as struct, union, or enum with the name of the typedef. So +# typedef struct TypeS {} TypeT, will appear in the documentation as a struct +# with name TypeT. When disabled the typedef will appear as a member of a file, +# namespace, or class. And the struct will be named TypeS. This can typically be +# useful for C code in case the coding convention dictates that all compound +# types are typedef'ed and only the typedef is referenced, never the tag name. +# The default value is: NO. + +TYPEDEF_HIDES_STRUCT = NO + +# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This +# cache is used to resolve symbols given their name and scope. Since this can be +# an expensive process and often the same symbol appears multiple times in the +# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small +# doxygen will become slower. If the cache is too large, memory is wasted. The +# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range +# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536 +# symbols. At the end of a run doxygen will report the cache usage and suggest +# the optimal cache size from a speed point of view. +# Minimum value: 0, maximum value: 9, default value: 0. + +LOOKUP_CACHE_SIZE = 0 + +#--------------------------------------------------------------------------- +# 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 respectively EXTRACT_STATIC tags are set to YES. +# Note: This will also disable the warnings about undocumented members that are +# normally produced when WARNINGS is set to YES. +# The default value is: NO. + +EXTRACT_ALL = NO + +# If the EXTRACT_PRIVATE tag is set to YES, all private members of a class will +# be included in the documentation. +# The default value is: NO. + +EXTRACT_PRIVATE = NO + +# If the EXTRACT_PACKAGE tag is set to YES, all members with package or internal +# scope will be included in the documentation. +# The default value is: NO. + +EXTRACT_PACKAGE = NO + +# If the EXTRACT_STATIC tag is set to YES, all static members of a file will be +# included in the documentation. +# The default value is: NO. + +EXTRACT_STATIC = YES + +# 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. Does not have any effect +# for Java sources. +# The default value is: YES. + +EXTRACT_LOCAL_CLASSES = YES + +# This flag is only useful for Objective-C code. If 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, only methods in the interface are +# included. +# The default value is: NO. + +EXTRACT_LOCAL_METHODS = NO + +# If this flag is set to YES, the members of anonymous namespaces will be +# extracted and appear in the documentation as a namespace called +# 'anonymous_namespace{file}', where file will be replaced with the base name of +# the file that contains the anonymous namespace. By default anonymous namespace +# are hidden. +# The default value is: NO. + +EXTRACT_ANON_NSPACES = NO + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, doxygen will hide all +# undocumented members inside documented classes or files. If set to NO 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. +# The default value is: NO. + +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, these classes will be included in the various overviews. This option +# has no effect if EXTRACT_ALL is enabled. +# The default value is: NO. + +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, these declarations will be +# included in the documentation. +# The default value is: NO. + +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, these +# blocks will be appended to the function's detailed documentation block. +# The default value is: NO. + +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 then the documentation +# will be excluded. Set it to YES to include the internal documentation. +# The default value is: NO. + +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. +# The default value is: system dependent. + +CASE_SENSE_NAMES = YES + +# If the HIDE_SCOPE_NAMES tag is set to NO then doxygen will show members with +# their full class and namespace scopes in the documentation. If set to YES, the +# scope will be hidden. +# The default value is: NO. + +HIDE_SCOPE_NAMES = NO + +# If the HIDE_COMPOUND_REFERENCE tag is set to NO (default) then doxygen will +# append additional text to a page's title, such as Class Reference. If set to +# YES the compound reference will be hidden. +# The default value is: NO. + +HIDE_COMPOUND_REFERENCE= NO + +# If the SHOW_INCLUDE_FILES tag is set to YES then doxygen will put a list of +# the files that are included by a file in the documentation of that file. +# The default value is: YES. + +SHOW_INCLUDE_FILES = YES + +# If the SHOW_GROUPED_MEMB_INC tag is set to YES then Doxygen will add for each +# grouped member an include statement to the documentation, telling the reader +# which file to include in order to use the member. +# The default value is: NO. + +SHOW_GROUPED_MEMB_INC = NO + +# If the FORCE_LOCAL_INCLUDES tag is set to YES then doxygen will list include +# files with double quotes in the documentation rather than with sharp brackets. +# The default value is: NO. + +FORCE_LOCAL_INCLUDES = NO + +# If the INLINE_INFO tag is set to YES then a tag [inline] is inserted in the +# documentation for inline members. +# The default value is: YES. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES 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. +# The default value is: YES. + +SORT_MEMBER_DOCS = YES + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the brief +# descriptions of file, namespace and class members alphabetically by member +# name. If set to NO, the members will appear in declaration order. Note that +# this will also influence the order of the classes in the class list. +# The default value is: NO. + +SORT_BRIEF_DOCS = NO + +# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the +# (brief and detailed) documentation of class members so that constructors and +# destructors are listed first. If set to NO the constructors will appear in the +# respective orders defined by SORT_BRIEF_DOCS and SORT_MEMBER_DOCS. +# Note: If SORT_BRIEF_DOCS is set to NO this option is ignored for sorting brief +# member documentation. +# Note: If SORT_MEMBER_DOCS is set to NO this option is ignored for sorting +# detailed member documentation. +# The default value is: NO. + +SORT_MEMBERS_CTORS_1ST = NO + +# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the hierarchy +# of group names into alphabetical order. If set to NO the group names will +# appear in their defined order. +# The default value is: NO. + +SORT_GROUP_NAMES = 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 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. +# The default value is: NO. + +SORT_BY_SCOPE_NAME = NO + +# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to do proper +# type resolution of all parameters of a function it will reject a match between +# the prototype and the implementation of a member function even if there is +# only one candidate or it is obvious which candidate to choose by doing a +# simple string match. By disabling STRICT_PROTO_MATCHING doxygen will still +# accept a match between prototype and implementation in such cases. +# The default value is: NO. + +STRICT_PROTO_MATCHING = 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. +# The default value is: YES. + +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. +# The default value is: YES. + +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. +# The default value is: YES. + +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. +# The default value is: YES. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional documentation +# sections, marked by \if <section_label> ... \endif and \cond <section_label> +# ... \endcond blocks. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines that the +# initial value of a variable or macro / define can have 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 value of individual variables and macros / defines can be +# controlled using \showinitializer or \hideinitializer command in the +# documentation regardless of this setting. +# Minimum value: 0, maximum value: 10000, default value: 30. + +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. +# The default value is: YES. + +SHOW_USED_FILES = YES + +# Set the SHOW_FILES tag to NO to disable the generation of the Files page. This +# will remove the Files entry from the Quick Index and from the Folder Tree View +# (if specified). +# The default value is: YES. + +SHOW_FILES = YES + +# Set the SHOW_NAMESPACES tag to NO to disable the generation of the Namespaces +# page. This will remove the Namespaces entry from the Quick Index and from the +# Folder Tree View (if specified). +# The default value is: YES. + +SHOW_NAMESPACES = 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 command input-file, where command is the value of the +# FILE_VERSION_FILTER tag, and input-file is the name of an input file provided +# by doxygen. Whatever the program writes to standard output is used as the file +# version. For an example see the documentation. + +FILE_VERSION_FILTER = + +# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed +# by doxygen. The layout file controls the global structure of the generated +# output files in an output format independent way. To create the layout file +# that represents doxygen's defaults, run doxygen with the -l option. You can +# optionally specify a file name after the option, if omitted DoxygenLayout.xml +# will be used as the name of the layout file. +# +# Note that if you run doxygen from a directory containing a file called +# DoxygenLayout.xml, doxygen will parse it automatically even if the LAYOUT_FILE +# tag is left empty. + +LAYOUT_FILE = + +# The CITE_BIB_FILES tag can be used to specify one or more bib files containing +# the reference definitions. This must be a list of .bib files. The .bib +# extension is automatically appended if omitted. This requires the bibtex tool +# to be installed. See also http://en.wikipedia.org/wiki/BibTeX for more info. +# For LaTeX the style of the bibliography can be controlled using +# LATEX_BIB_STYLE. To use this feature you need bibtex and perl available in the +# search path. See also \cite for info how to create references. + +CITE_BIB_FILES = + +#--------------------------------------------------------------------------- +# Configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated to +# standard output by doxygen. If QUIET is set to YES this implies that the +# messages are off. +# The default value is: NO. + +QUIET = NO + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated to standard error (stderr) by doxygen. If WARNINGS is set to YES +# this implies that the warnings are on. +# +# Tip: Turn warnings on while writing the documentation. +# The default value is: YES. + +WARNINGS = YES + +# If the WARN_IF_UNDOCUMENTED tag 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. +# The default value is: YES. + +WARN_IF_UNDOCUMENTED = YES + +# If the WARN_IF_DOC_ERROR tag 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. +# The default value is: YES. + +WARN_IF_DOC_ERROR = YES + +# This WARN_NO_PARAMDOC option can be enabled to get warnings for functions that +# are documented, but have no documentation for their parameters or return +# value. If set to NO, doxygen will only warn about wrong or incomplete +# parameter documentation, but not about the absence of documentation. +# The default value is: NO. + +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) +# The default value is: $file:$line: $text. + +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 standard +# error (stderr). + +WARN_LOGFILE = + +#--------------------------------------------------------------------------- +# Configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag is 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. +# Note: If this tag is empty the current directory is searched. + +INPUT = + +# This tag can be used to specify the character encoding of the source files +# that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses +# libiconv (or the iconv built into libc) for the transcoding. See the libiconv +# documentation (see: http://www.gnu.org/software/libiconv) for the list of +# possible encodings. +# The default value is: UTF-8. + +INPUT_ENCODING = UTF-8 + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard patterns (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, *.idl, *.ddl, *.odl, *.h, *.hh, *.hxx, *.hpp, +# *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc, *.m, *.markdown, +# *.md, *.mm, *.dox, *.py, *.f90, *.f, *.for, *.tcl, *.vhd, *.vhdl, *.ucf, +# *.qsf, *.as and *.js. + +FILE_PATTERNS = + +# The RECURSIVE tag can be used to specify whether or not subdirectories should +# be searched for input files as well. +# The default value is: NO. + +RECURSIVE = YES + +# The EXCLUDE tag can be used to specify files and/or directories that should be +# 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. +# +# Note that relative paths are relative to the directory from which doxygen is +# run. + +EXCLUDE = + +# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or +# directories that are symbolic links (a Unix file system feature) are excluded +# from the input. +# The default value is: NO. + +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 EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names +# (namespaces, classes, functions, etc.) that should be excluded from the +# output. The symbol name can be a fully qualified name, a word, or if the +# wildcard * is used, a substring. Examples: ANamespace, AClass, +# AClass::ANamespace, ANamespace::*Test +# +# Note that the wildcards are matched against the file with absolute path, so to +# exclude all test directories use the pattern */test/* + +EXCLUDE_SYMBOLS = + +# 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. +# The default value is: NO. + +EXAMPLE_RECURSIVE = NO + +# The IMAGE_PATH tag can be used to specify one or more files or directories +# that contain images that are to be 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: +# +# <filter> <input-file> +# +# where <filter> is the value of the INPUT_FILTER tag, and <input-file> 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. +# +# Note that the filter must not add or remove lines; it is applied before the +# code is scanned, but not when the output code is generated. If lines are added +# or removed, the anchors will not be placed correctly. + +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 information on how +# filters are used. If the FILTER_PATTERNS tag is empty or if none of the +# patterns match the file name, INPUT_FILTER is applied. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER) will also be used to filter the input files that are used for +# producing the source files to browse (i.e. when SOURCE_BROWSER is set to YES). +# The default value is: NO. + +FILTER_SOURCE_FILES = NO + +# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file +# pattern. A pattern will override the setting for FILTER_PATTERN (if any) and +# it is also possible to disable source filtering for a specific pattern using +# *.ext= (so without naming a filter). +# This tag requires that the tag FILTER_SOURCE_FILES is set to YES. + +FILTER_SOURCE_PATTERNS = + +# If the USE_MDFILE_AS_MAINPAGE tag refers to the name of a markdown file that +# is part of the input, its contents will be placed on the main page +# (index.html). This can be useful if you have a project on for instance GitHub +# and want to reuse the introduction page also for the doxygen output. + +USE_MDFILE_AS_MAINPAGE = + +#--------------------------------------------------------------------------- +# 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 that +# also VERBATIM_HEADERS is set to NO. +# The default value is: NO. + +SOURCE_BROWSER = NO + +# Setting the INLINE_SOURCES tag to YES will include the body of functions, +# classes and enums directly into the documentation. +# The default value is: NO. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES will instruct doxygen to hide any +# special comment blocks from generated source code fragments. Normal C, C++ and +# Fortran comments will always remain visible. +# The default value is: YES. + +STRIP_CODE_COMMENTS = YES + +# If the REFERENCED_BY_RELATION tag is set to YES then for each documented +# function all documented functions referencing it will be listed. +# The default value is: NO. + +REFERENCED_BY_RELATION = NO + +# If the REFERENCES_RELATION tag is set to YES then for each documented function +# all documented entities called/used by that function will be listed. +# The default value is: NO. + +REFERENCES_RELATION = NO + +# If the REFERENCES_LINK_SOURCE tag is set to YES and SOURCE_BROWSER tag is set +# to YES then the hyperlinks from functions in REFERENCES_RELATION and +# REFERENCED_BY_RELATION lists will link to the source code. Otherwise they will +# link to the documentation. +# The default value is: YES. + +REFERENCES_LINK_SOURCE = YES + +# If SOURCE_TOOLTIPS is enabled (the default) then hovering a hyperlink in the +# source code will show a tooltip with additional information such as prototype, +# brief description and links to the definition and documentation. Since this +# will make the HTML file larger and loading of large files a bit slower, you +# can opt to disable this feature. +# The default value is: YES. +# This tag requires that the tag SOURCE_BROWSER is set to YES. + +SOURCE_TOOLTIPS = 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. +# +# To use it do the following: +# - Install the latest version of global +# - Enable SOURCE_BROWSER and USE_HTAGS in the config file +# - Make sure the INPUT points to the root of the source tree +# - Run doxygen as normal +# +# Doxygen will invoke htags (and that will in turn invoke gtags), so these +# tools must be available from the command line (i.e. in the search path). +# +# The result: instead of the source browser generated by doxygen, the links to +# source code will now point to the output of htags. +# The default value is: NO. +# This tag requires that the tag SOURCE_BROWSER is set to YES. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set the YES 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. +# See also: Section \class. +# The default value is: YES. + +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. +# The default value is: YES. + +ALPHABETICAL_INDEX = YES + +# The COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns in +# which the alphabetical index list will be split. +# Minimum value: 1, maximum value: 20, default value: 5. +# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. + +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 a prefix (or a list of prefixes) that should be ignored +# while generating the index headers. +# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES, doxygen will generate HTML output +# The default value is: NO. + +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. +# The default directory is: html. +# This tag requires that the tag GENERATE_HTML is set to YES. + +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). +# The default value is: .html. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a user-defined HTML header file for +# each generated HTML page. If the tag is left blank doxygen will generate a +# standard header. +# +# To get valid HTML the header file that includes any scripts and style sheets +# that doxygen needs, which is dependent on the configuration options used (e.g. +# the setting GENERATE_TREEVIEW). It is highly recommended to start with a +# default header using +# doxygen -w html new_header.html new_footer.html new_stylesheet.css +# YourConfigFile +# and then modify the file new_header.html. See also section "Doxygen usage" +# for information on how to generate the default header that doxygen normally +# uses. +# Note: The header is subject to change so you typically have to regenerate the +# default header when upgrading to a newer version of doxygen. For a description +# of the possible markers and block names see the documentation. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_HEADER = + +# The HTML_FOOTER tag can be used to specify a user-defined HTML footer for each +# generated HTML page. If the tag is left blank doxygen will generate a standard +# footer. See HTML_HEADER for more information on how to generate a default +# footer and what special commands can be used inside the footer. See also +# section "Doxygen usage" for information on how to generate the default footer +# that doxygen normally uses. +# This tag requires that the tag GENERATE_HTML is set to YES. + +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 left blank doxygen will generate a default style sheet. +# See also section "Doxygen usage" for information on how to generate the style +# sheet that doxygen normally uses. +# Note: It is recommended to use HTML_EXTRA_STYLESHEET instead of this tag, as +# it is more robust and this tag (HTML_STYLESHEET) will in the future become +# obsolete. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_STYLESHEET = + +# The HTML_EXTRA_STYLESHEET tag can be used to specify additional user-defined +# cascading style sheets that are included after the standard style sheets +# created by doxygen. Using this option one can overrule certain style aspects. +# This is preferred over using HTML_STYLESHEET since it does not replace the +# standard style sheet and is therefore more robust against future updates. +# Doxygen will copy the style sheet files to the output directory. +# Note: The order of the extra style sheet files is of importance (e.g. the last +# style sheet in the list overrules the setting of the previous ones in the +# list). For an example see the documentation. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_EXTRA_STYLESHEET = + +# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or +# other source files which should be copied to the HTML output directory. Note +# that these files will be copied to the base HTML output directory. Use the +# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these +# files. In the HTML_STYLESHEET file, use the file name only. Also note that the +# files will be copied as-is; there are no commands or markers available. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_EXTRA_FILES = + +# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen +# will adjust the colors in the style sheet and background images according to +# this color. Hue is specified as an angle on a colorwheel, see +# http://en.wikipedia.org/wiki/Hue for more information. For instance the value +# 0 represents red, 60 is yellow, 120 is green, 180 is cyan, 240 is blue, 300 +# purple, and 360 is red again. +# Minimum value: 0, maximum value: 359, default value: 220. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_HUE = 220 + +# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of the colors +# in the HTML output. For a value of 0 the output will use grayscales only. A +# value of 255 will produce the most vivid colors. +# Minimum value: 0, maximum value: 255, default value: 100. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_SAT = 100 + +# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to the +# luminance component of the colors in the HTML output. Values below 100 +# gradually make the output lighter, whereas values above 100 make the output +# darker. The value divided by 100 is the actual gamma applied, so 80 represents +# a gamma of 0.8, The value 220 represents a gamma of 2.2, and 100 does not +# change the gamma. +# Minimum value: 40, maximum value: 240, default value: 80. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_GAMMA = 80 + +# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML +# page will contain the date and time when the page was generated. Setting this +# to NO can help when comparing the output of multiple runs. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_TIMESTAMP = NO + +# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML +# documentation will contain sections that can be hidden and shown after the +# page has loaded. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_DYNAMIC_SECTIONS = NO + +# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of entries +# shown in the various tree structured indices initially; the user can expand +# and collapse entries dynamically later on. Doxygen will expand the tree to +# such a level that at most the specified number of entries are visible (unless +# a fully collapsed tree already exceeds this amount). So setting the number of +# entries 1 will produce a full collapsed tree by default. 0 is a special value +# representing an infinite number of entries and will result in a full expanded +# tree by default. +# Minimum value: 0, maximum value: 9999, default value: 100. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_INDEX_NUM_ENTRIES = 100 + +# If the GENERATE_DOCSET tag is set to YES, additional index files will be +# generated that can be used as input for Apple's Xcode 3 integrated development +# environment (see: http://developer.apple.com/tools/xcode/), introduced with +# OSX 10.5 (Leopard). To create a documentation set, doxygen will generate a +# Makefile in the HTML output directory. Running make will produce the docset in +# that directory and running make install will install the docset in +# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at +# startup. See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html +# for more information. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_DOCSET = NO + +# This tag determines the name of the docset feed. A documentation feed provides +# an umbrella under which multiple documentation sets from a single provider +# (such as a company or product suite) can be grouped. +# The default value is: Doxygen generated docs. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_FEEDNAME = "Doxygen generated docs" + +# This tag specifies a string that should uniquely identify the documentation +# set bundle. This should be a reverse domain-name style string, e.g. +# com.mycompany.MyDocSet. Doxygen will append .docset to the name. +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_BUNDLE_ID = org.doxygen.Project + +# The DOCSET_PUBLISHER_ID tag specifies a string that should uniquely identify +# the documentation publisher. This should be a reverse domain-name style +# string, e.g. com.mycompany.MyDocSet.documentation. +# The default value is: org.doxygen.Publisher. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_PUBLISHER_ID = org.doxygen.Publisher + +# The DOCSET_PUBLISHER_NAME tag identifies the documentation publisher. +# The default value is: Publisher. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_PUBLISHER_NAME = Publisher + +# If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three +# additional HTML index files: index.hhp, index.hhc, and index.hhk. The +# index.hhp is a project file that can be read by Microsoft's HTML Help Workshop +# (see: http://www.microsoft.com/en-us/download/details.aspx?id=21138) on +# Windows. +# +# The HTML Help Workshop contains a compiler that can convert all HTML output +# generated by doxygen into a single compiled HTML file (.chm). Compiled HTML +# files are now used as the Windows 98 help format, and will replace the old +# Windows help format (.hlp) on all Windows platforms in the future. Compressed +# HTML files also contain an index, a table of contents, and you can search for +# words in the documentation. The HTML workshop also contains a viewer for +# compressed HTML files. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_HTMLHELP = NO + +# 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. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +CHM_FILE = + +# 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. +# The file has to be specified with full path. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +HHC_LOCATION = + +# 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). +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +GENERATE_CHI = NO + +# The CHM_INDEX_ENCODING is used to encode HtmlHelp index (hhk), content (hhc) +# and project file content. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +CHM_INDEX_ENCODING = + +# 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. Furthermore it +# enables the Previous and Next buttons. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members to +# the table of contents of the HTML help documentation and to the tree view. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +TOC_EXPAND = NO + +# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and +# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated that +# can be used as input for Qt's qhelpgenerator to generate a Qt Compressed Help +# (.qch) of the generated HTML documentation. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_QHP = NO + +# If the QHG_LOCATION tag is specified, the QCH_FILE tag can be used to specify +# the file name of the resulting .qch file. The path specified is relative to +# the HTML output folder. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QCH_FILE = + +# The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help +# Project output. For more information please see Qt Help Project / Namespace +# (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#namespace). +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_NAMESPACE = org.doxygen.Project + +# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt +# Help Project output. For more information please see Qt Help Project / Virtual +# Folders (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#virtual- +# folders). +# The default value is: doc. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_VIRTUAL_FOLDER = doc + +# If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom +# filter to add. For more information please see Qt Help Project / Custom +# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom- +# filters). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_CUST_FILTER_NAME = + +# The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the +# custom filter to add. For more information please see Qt Help Project / Custom +# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom- +# filters). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_CUST_FILTER_ATTRS = + +# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this +# project's filter section matches. Qt Help Project / Filter Attributes (see: +# http://qt-project.org/doc/qt-4.8/qthelpproject.html#filter-attributes). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_SECT_FILTER_ATTRS = + +# The QHG_LOCATION tag can be used to specify the location of Qt's +# qhelpgenerator. If non-empty doxygen will try to run qhelpgenerator on the +# generated .qhp file. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHG_LOCATION = + +# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files will be +# generated, together with the HTML files, they form an Eclipse help plugin. To +# install this plugin and make it available under the help contents menu in +# Eclipse, the contents of the directory containing the HTML and XML files needs +# to be copied into the plugins directory of eclipse. The name of the directory +# within the plugins directory should be the same as the ECLIPSE_DOC_ID value. +# After copying Eclipse needs to be restarted before the help appears. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_ECLIPSEHELP = NO + +# A unique identifier for the Eclipse help plugin. When installing the plugin +# the directory name containing the HTML and XML files should also have this +# name. Each documentation set should have its own identifier. +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_ECLIPSEHELP is set to YES. + +ECLIPSE_DOC_ID = org.doxygen.Project + +# If you want full control over the layout of the generated HTML pages it might +# be necessary to disable the index and replace it with your own. The +# DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) at top +# of each HTML page. A value of NO enables the index and the value YES disables +# it. Since the tabs in the index contain the same information as the navigation +# tree, you can set this option to YES if you also set GENERATE_TREEVIEW to YES. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +DISABLE_INDEX = NO + +# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index +# structure should be generated to display hierarchical information. If the tag +# value 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 +# (i.e. any modern browser). Windows users are probably better off using the +# HTML help feature. Via custom style sheets (see HTML_EXTRA_STYLESHEET) one can +# further fine-tune the look of the index. As an example, the default style +# sheet generated by doxygen has an example that shows how to put an image at +# the root of the tree instead of the PROJECT_NAME. Since the tree basically has +# the same information as the tab index, you could consider setting +# DISABLE_INDEX to YES when enabling this option. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_TREEVIEW = NO + +# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values that +# doxygen will group on one line in the generated HTML documentation. +# +# Note that a value of 0 will completely suppress the enum values from appearing +# in the overview section. +# Minimum value: 0, maximum value: 20, default value: 4. +# This tag requires that the tag GENERATE_HTML is set to YES. + +ENUM_VALUES_PER_LINE = 4 + +# 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. +# Minimum value: 0, maximum value: 1500, default value: 250. +# This tag requires that the tag GENERATE_HTML is set to YES. + +TREEVIEW_WIDTH = 250 + +# If the EXT_LINKS_IN_WINDOW option is set to YES, doxygen will open links to +# external symbols imported via tag files in a separate window. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +EXT_LINKS_IN_WINDOW = NO + +# Use this tag to change the font size of LaTeX formulas included as images in +# the HTML documentation. When you change the font size after a successful +# doxygen run you need to manually remove any form_*.png images from the HTML +# output directory to force them to be regenerated. +# Minimum value: 8, maximum value: 50, default value: 10. +# This tag requires that the tag GENERATE_HTML is set to YES. + +FORMULA_FONTSIZE = 10 + +# Use the FORMULA_TRANPARENT tag to determine whether or not the images +# generated for formulas are transparent PNGs. Transparent PNGs are not +# supported properly for IE 6.0, but are supported on all modern browsers. +# +# Note that when changing this option you need to delete any form_*.png files in +# the HTML output directory before the changes have effect. +# The default value is: YES. +# This tag requires that the tag GENERATE_HTML is set to YES. + +FORMULA_TRANSPARENT = YES + +# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see +# http://www.mathjax.org) which uses client side Javascript for the rendering +# instead of using pre-rendered bitmaps. Use this if you do not have LaTeX +# installed or if you want to formulas look prettier in the HTML output. When +# enabled you may also need to install MathJax separately and configure the path +# to it using the MATHJAX_RELPATH option. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +USE_MATHJAX = NO + +# When MathJax is enabled you can set the default output format to be used for +# the MathJax output. See the MathJax site (see: +# http://docs.mathjax.org/en/latest/output.html) for more details. +# Possible values are: HTML-CSS (which is slower, but has the best +# compatibility), NativeMML (i.e. MathML) and SVG. +# The default value is: HTML-CSS. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_FORMAT = HTML-CSS + +# When MathJax is enabled you need to specify the location relative to the HTML +# output directory using the MATHJAX_RELPATH option. The destination directory +# should contain the MathJax.js script. For instance, if the mathjax directory +# is located at the same level as the HTML output directory, then +# MATHJAX_RELPATH should be ../mathjax. The default value points to the MathJax +# Content Delivery Network so you can quickly see the result without installing +# MathJax. However, it is strongly recommended to install a local copy of +# MathJax from http://www.mathjax.org before deployment. +# The default value is: http://cdn.mathjax.org/mathjax/latest. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest + +# The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax +# extension names that should be enabled during MathJax rendering. For example +# MATHJAX_EXTENSIONS = TeX/AMSmath TeX/AMSsymbols +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_EXTENSIONS = + +# The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces +# of code that will be used on startup of the MathJax code. See the MathJax site +# (see: http://docs.mathjax.org/en/latest/output.html) for more details. For an +# example see the documentation. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_CODEFILE = + +# When the SEARCHENGINE tag is enabled doxygen will generate a search box for +# the HTML output. The underlying search engine uses javascript and DHTML and +# should work on any modern browser. Note that when using HTML help +# (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets (GENERATE_DOCSET) +# there is already a search function so this one should typically be disabled. +# For large projects the javascript based search engine can be slow, then +# enabling SERVER_BASED_SEARCH may provide a better solution. It is possible to +# search using the keyboard; to jump to the search box use <access key> + S +# (what the <access key> is depends on the OS and browser, but it is typically +# <CTRL>, <ALT>/<option>, or both). Inside the search box use the <cursor down +# key> to jump into the search results window, the results can be navigated +# using the <cursor keys>. Press <Enter> to select an item or <escape> to cancel +# the search. The filter options can be selected when the cursor is inside the +# search box by pressing <Shift>+<cursor down>. Also here use the <cursor keys> +# to select a filter and <Enter> or <escape> to activate or cancel the filter +# option. +# The default value is: YES. +# This tag requires that the tag GENERATE_HTML is set to YES. + +SEARCHENGINE = YES + +# When the SERVER_BASED_SEARCH tag is enabled the search engine will be +# implemented using a web server instead of a web client using Javascript. There +# are two flavors of web server based searching depending on the EXTERNAL_SEARCH +# setting. When disabled, doxygen will generate a PHP script for searching and +# an index file used by the script. When EXTERNAL_SEARCH is enabled the indexing +# and searching needs to be provided by external tools. See the section +# "External Indexing and Searching" for details. +# The default value is: NO. +# This tag requires that the tag SEARCHENGINE is set to YES. + +SERVER_BASED_SEARCH = NO + +# When EXTERNAL_SEARCH tag is enabled doxygen will no longer generate the PHP +# script for searching. Instead the search results are written to an XML file +# which needs to be processed by an external indexer. Doxygen will invoke an +# external search engine pointed to by the SEARCHENGINE_URL option to obtain the +# search results. +# +# Doxygen ships with an example indexer (doxyindexer) and search engine +# (doxysearch.cgi) which are based on the open source search engine library +# Xapian (see: http://xapian.org/). +# +# See the section "External Indexing and Searching" for details. +# The default value is: NO. +# This tag requires that the tag SEARCHENGINE is set to YES. + +EXTERNAL_SEARCH = NO + +# The SEARCHENGINE_URL should point to a search engine hosted by a web server +# which will return the search results when EXTERNAL_SEARCH is enabled. +# +# Doxygen ships with an example indexer (doxyindexer) and search engine +# (doxysearch.cgi) which are based on the open source search engine library +# Xapian (see: http://xapian.org/). See the section "External Indexing and +# Searching" for details. +# This tag requires that the tag SEARCHENGINE is set to YES. + +SEARCHENGINE_URL = + +# When SERVER_BASED_SEARCH and EXTERNAL_SEARCH are both enabled the unindexed +# search data is written to a file for indexing by an external tool. With the +# SEARCHDATA_FILE tag the name of this file can be specified. +# The default file is: searchdata.xml. +# This tag requires that the tag SEARCHENGINE is set to YES. + +SEARCHDATA_FILE = searchdata.xml + +# When SERVER_BASED_SEARCH and EXTERNAL_SEARCH are both enabled the +# EXTERNAL_SEARCH_ID tag can be used as an identifier for the project. This is +# useful in combination with EXTRA_SEARCH_MAPPINGS to search through multiple +# projects and redirect the results back to the right project. +# This tag requires that the tag SEARCHENGINE is set to YES. + +EXTERNAL_SEARCH_ID = + +# The EXTRA_SEARCH_MAPPINGS tag can be used to enable searching through doxygen +# projects other than the one defined by this configuration file, but that are +# all added to the same external search index. Each project needs to have a +# unique id set via EXTERNAL_SEARCH_ID. The search mapping then maps the id of +# to a relative location where the documentation can be found. The format is: +# EXTRA_SEARCH_MAPPINGS = tagname1=loc1 tagname2=loc2 ... +# This tag requires that the tag SEARCHENGINE is set to YES. + +EXTRA_SEARCH_MAPPINGS = + +#--------------------------------------------------------------------------- +# Configuration options related to the LaTeX output +#--------------------------------------------------------------------------- + +# If the GENERATE_LATEX tag is set to YES, doxygen will generate LaTeX output. +# The default value is: YES. + +GENERATE_LATEX = YES + +# 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. +# The default directory is: latex. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_OUTPUT = latex + +# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be +# invoked. +# +# Note that when enabling USE_PDFLATEX this option is only used for generating +# bitmaps for formulas in the HTML output, but not in the Makefile that is +# written to the output directory. +# The default file is: latex. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_CMD_NAME = latex + +# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to generate +# index for LaTeX. +# The default file is: makeindex. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +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. +# The default value is: NO. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +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 (210 x 297 mm), letter (8.5 x 11 inches), legal (8.5 x +# 14 inches) and executive (7.25 x 10.5 inches). +# The default value is: a4. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +PAPER_TYPE = a4 + +# The EXTRA_PACKAGES tag can be used to specify one or more LaTeX package names +# that should be included in the LaTeX output. To get the times font for +# instance you can specify +# EXTRA_PACKAGES=times +# If left blank no extra packages will be included. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +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. See +# section "Doxygen usage" for information on how to let doxygen write the +# default header to a separate file. +# +# Note: Only use a user-defined header if you know what you are doing! The +# following commands have a special meaning inside the header: $title, +# $datetime, $date, $doxygenversion, $projectname, $projectnumber, +# $projectbrief, $projectlogo. Doxygen will replace $title with the empty +# string, for the replacement values of the other commands the user is referred +# to HTML_HEADER. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_HEADER = + +# The LATEX_FOOTER tag can be used to specify a personal LaTeX footer for the +# generated LaTeX document. The footer should contain everything after the last +# chapter. If it is left blank doxygen will generate a standard footer. See +# LATEX_HEADER for more information on how to generate a default footer and what +# special commands can be used inside the footer. +# +# Note: Only use a user-defined footer if you know what you are doing! +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_FOOTER = + +# The LATEX_EXTRA_STYLESHEET tag can be used to specify additional user-defined +# LaTeX style sheets that are included after the standard style sheets created +# by doxygen. Using this option one can overrule certain style aspects. Doxygen +# will copy the style sheet files to the output directory. +# Note: The order of the extra style sheet files is of importance (e.g. the last +# style sheet in the list overrules the setting of the previous ones in the +# list). +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_EXTRA_STYLESHEET = + +# The LATEX_EXTRA_FILES tag can be used to specify one or more extra images or +# other source files which should be copied to the LATEX_OUTPUT output +# directory. Note that the files will be copied as-is; there are no commands or +# markers available. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_EXTRA_FILES = + +# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated is +# prepared for conversion to PDF (using ps2pdf or pdflatex). 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. +# The default value is: YES. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +PDF_HYPERLINKS = YES + +# If the USE_PDFLATEX tag is set to YES, doxygen will use pdflatex to generate +# the PDF file directly from the LaTeX files. Set this option to YES, to get a +# higher quality PDF documentation. +# The default value is: YES. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +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. +# The default value is: NO. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_BATCHMODE = NO + +# If the LATEX_HIDE_INDICES tag is set to YES then doxygen will not include the +# index chapters (such as File Index, Compound Index, etc.) in the output. +# The default value is: NO. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_HIDE_INDICES = NO + +# If the LATEX_SOURCE_CODE tag is set to YES then doxygen will include source +# code with syntax highlighting in the LaTeX output. +# +# Note that which sources are shown also depends on other settings such as +# SOURCE_BROWSER. +# The default value is: NO. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_SOURCE_CODE = NO + +# The LATEX_BIB_STYLE tag can be used to specify the style to use for the +# bibliography, e.g. plainnat, or ieeetr. See +# http://en.wikipedia.org/wiki/BibTeX and \cite for more info. +# The default value is: plain. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_BIB_STYLE = plain + +#--------------------------------------------------------------------------- +# 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 too pretty with other RTF +# readers/editors. +# The default value is: NO. + +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. +# The default directory is: rtf. +# This tag requires that the tag GENERATE_RTF is set to YES. + +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. +# The default value is: NO. +# This tag requires that the tag GENERATE_RTF is set to YES. + +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 some other Word compatible readers that support those +# fields. +# +# Note: WordPad (write) and others do not support links. +# The default value is: NO. +# This tag requires that the tag GENERATE_RTF is set to YES. + +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. +# +# See also section "Doxygen usage" for information on how to generate the +# default style sheet that doxygen normally uses. +# This tag requires that the tag GENERATE_RTF is set to YES. + +RTF_STYLESHEET_FILE = + +# Set optional variables used in the generation of an RTF document. Syntax is +# similar to doxygen's config file. A template extensions file can be generated +# using doxygen -e rtf extensionFile. +# This tag requires that the tag GENERATE_RTF is set to YES. + +RTF_EXTENSIONS_FILE = + +# If the RTF_SOURCE_CODE tag is set to YES then doxygen will include source code +# with syntax highlighting in the RTF output. +# +# Note that which sources are shown also depends on other settings such as +# SOURCE_BROWSER. +# The default value is: NO. +# This tag requires that the tag GENERATE_RTF is set to YES. + +RTF_SOURCE_CODE = NO + +#--------------------------------------------------------------------------- +# Configuration options related to the man page output +#--------------------------------------------------------------------------- + +# If the GENERATE_MAN tag is set to YES, doxygen will generate man pages for +# classes and files. +# The default value is: NO. + +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. A directory man3 will be created inside the directory specified by +# MAN_OUTPUT. +# The default directory is: man. +# This tag requires that the tag GENERATE_MAN is set to YES. + +MAN_OUTPUT = man + +# The MAN_EXTENSION tag determines the extension that is added to the generated +# man pages. In case the manual section does not start with a number, the number +# 3 is prepended. The dot (.) at the beginning of the MAN_EXTENSION tag is +# optional. +# The default value is: .3. +# This tag requires that the tag GENERATE_MAN is set to YES. + +MAN_EXTENSION = .3 + +# The MAN_SUBDIR tag determines the name of the directory created within +# MAN_OUTPUT in which the man pages are placed. If defaults to man followed by +# MAN_EXTENSION with the initial . removed. +# This tag requires that the tag GENERATE_MAN is set to YES. + +MAN_SUBDIR = + +# 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 value is: NO. +# This tag requires that the tag GENERATE_MAN is set to YES. + +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. +# The default value is: NO. + +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. +# The default directory is: xml. +# This tag requires that the tag GENERATE_XML is set to YES. + +XML_OUTPUT = xml + +# 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. +# The default value is: YES. +# This tag requires that the tag GENERATE_XML is set to YES. + +XML_PROGRAMLISTING = YES + +#--------------------------------------------------------------------------- +# Configuration options related to the DOCBOOK output +#--------------------------------------------------------------------------- + +# If the GENERATE_DOCBOOK tag is set to YES, doxygen will generate Docbook files +# that can be used to generate PDF. +# The default value is: NO. + +GENERATE_DOCBOOK = NO + +# The DOCBOOK_OUTPUT tag is used to specify where the Docbook pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be put in +# front of it. +# The default directory is: docbook. +# This tag requires that the tag GENERATE_DOCBOOK is set to YES. + +DOCBOOK_OUTPUT = docbook + +# If the DOCBOOK_PROGRAMLISTING tag is set to YES, doxygen will include the +# program listings (including syntax highlighting and cross-referencing +# information) to the DOCBOOK output. Note that enabling this will significantly +# increase the size of the DOCBOOK output. +# The default value is: NO. +# This tag requires that the tag GENERATE_DOCBOOK is set to YES. + +DOCBOOK_PROGRAMLISTING = NO + +#--------------------------------------------------------------------------- +# Configuration options for the AutoGen Definitions output +#--------------------------------------------------------------------------- + +# If the GENERATE_AUTOGEN_DEF tag is set to YES, doxygen will generate an +# AutoGen Definitions (see http://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. +# The default value is: NO. + +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. +# The default value is: NO. + +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. +# The default value is: NO. +# This tag requires that the tag GENERATE_PERLMOD is set to YES. + +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. +# The default value is: YES. +# This tag requires that the tag GENERATE_PERLMOD is set to YES. + +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. +# This tag requires that the tag GENERATE_PERLMOD is set to YES. + +PERLMOD_MAKEVAR_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the preprocessor +#--------------------------------------------------------------------------- + +# If the ENABLE_PREPROCESSING tag is set to YES, doxygen will evaluate all +# C-preprocessor directives found in the sources and include files. +# The default value is: YES. + +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, only conditional compilation will be +# performed. Macro expansion can be done in a controlled way by setting +# EXPAND_ONLY_PREDEF to YES. +# The default value is: NO. +# This tag requires that the tag ENABLE_PREPROCESSING is set 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_DEFINED tags. +# The default value is: NO. +# This tag requires that the tag ENABLE_PREPROCESSING is set to YES. + +EXPAND_ONLY_PREDEF = NO + +# If the SEARCH_INCLUDES tag is set to YES, the include files in the +# INCLUDE_PATH will be searched if a #include is found. +# The default value is: YES. +# This tag requires that the tag ENABLE_PREPROCESSING is set to YES. + +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. +# This tag requires that the tag SEARCH_INCLUDES is set to YES. + +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. +# This tag requires that the tag ENABLE_PREPROCESSING is set to YES. + +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 e.g. +# 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. +# This tag requires that the tag ENABLE_PREPROCESSING is set to YES. + +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 that overrules the +# definition found in the source code. +# This tag requires that the tag ENABLE_PREPROCESSING is set to YES. + +EXPAND_AS_DEFINED = + +# If the SKIP_FUNCTION_MACROS tag is set to YES then doxygen's preprocessor will +# remove all references to 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. +# The default value is: YES. +# This tag requires that the tag ENABLE_PREPROCESSING is set to YES. + +SKIP_FUNCTION_MACROS = YES + +#--------------------------------------------------------------------------- +# Configuration options related to external references +#--------------------------------------------------------------------------- + +# The TAGFILES tag can be used to specify one or more tag files. For each tag +# file the location of the external documentation should be added. 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. See the +# section "Linking to external documentation" for more information about the use +# of tag files. +# Note: 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. See section "Linking to +# external documentation" for more information about the usage of tag files. + +GENERATE_TAGFILE = + +# If the ALLEXTERNALS tag is set to YES, all external class will be listed in +# the class index. If set to NO, only the inherited external classes will be +# listed. +# The default value is: NO. + +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. +# The default value is: YES. + +EXTERNAL_GROUPS = YES + +# If the EXTERNAL_PAGES tag is set to YES, all external pages will be listed in +# the related pages index. If set to NO, only the current project's pages will +# be listed. +# The default value is: YES. + +EXTERNAL_PAGES = YES + +# The PERL_PATH should be the absolute path and name of the perl script +# interpreter (i.e. the result of 'which perl'). +# The default file (with absolute path) is: /usr/bin/perl. + +PERL_PATH = /usr/bin/perl + +#--------------------------------------------------------------------------- +# Configuration options related to the dot tool +#--------------------------------------------------------------------------- + +# If the CLASS_DIAGRAMS tag is set to YES, doxygen will generate a class diagram +# (in HTML and LaTeX) for classes with base or super classes. Setting the tag to +# NO turns the diagrams off. Note that this option also works with HAVE_DOT +# disabled, but it is recommended to install and use dot, since it yields more +# powerful graphs. +# The default value is: YES. + +CLASS_DIAGRAMS = YES + +# You can define message sequence charts within doxygen comments using the \msc +# command. Doxygen will then run the mscgen tool (see: +# http://www.mcternan.me.uk/mscgen/)) to produce the chart and insert it in the +# documentation. The MSCGEN_PATH tag allows you to specify the directory where +# the mscgen tool resides. If left empty the tool is assumed to be found in the +# default search path. + +MSCGEN_PATH = + +# You can include diagrams made with dia in doxygen documentation. Doxygen will +# then run dia to produce the diagram and insert it in the documentation. The +# DIA_PATH tag allows you to specify the directory where the dia binary resides. +# If left empty dia is assumed to be found in the default search path. + +DIA_PATH = + +# 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. +# The default value is: YES. + +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 (see: +# http://www.graphviz.org/), 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 value is: NO. + +HAVE_DOT = NO + +# The DOT_NUM_THREADS specifies the number of dot invocations doxygen is allowed +# to run in parallel. When set to 0 doxygen will base this on the number of +# processors available in the system. You can set it explicitly to a value +# larger than 0 to get control over the balance between CPU load and processing +# speed. +# Minimum value: 0, maximum value: 32, default value: 0. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_NUM_THREADS = 0 + +# When you want a differently looking font in the dot files that doxygen +# generates you can specify the font name using DOT_FONTNAME. You need to make +# sure dot is able to find the font, which can be done by putting it in a +# standard location or by setting the DOTFONTPATH environment variable or by +# setting DOT_FONTPATH to the directory containing the font. +# The default value is: Helvetica. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_FONTNAME = Helvetica + +# The DOT_FONTSIZE tag can be used to set the size (in points) of the font of +# dot graphs. +# Minimum value: 4, maximum value: 24, default value: 10. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_FONTSIZE = 10 + +# By default doxygen will tell dot to use the default font as specified with +# DOT_FONTNAME. If you specify a different font using DOT_FONTNAME you can set +# the path where dot can find it using this tag. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_FONTPATH = + +# If the CLASS_GRAPH tag is 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 CLASS_DIAGRAMS tag to NO. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +CLASS_GRAPH = YES + +# If the COLLABORATION_GRAPH tag is 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. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +COLLABORATION_GRAPH = YES + +# If the GROUP_GRAPHS tag is set to YES then doxygen will generate a graph for +# groups, showing the direct groups dependencies. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +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. +# The default value is: NO. +# This tag requires that the tag HAVE_DOT is set to YES. + +UML_LOOK = NO + +# If the UML_LOOK tag is enabled, the fields and methods are shown inside the +# class node. If there are many fields or methods and many nodes the graph may +# become too big to be useful. The UML_LIMIT_NUM_FIELDS threshold limits the +# number of items for each type to make the size more manageable. Set this to 0 +# for no limit. Note that the threshold may be exceeded by 50% before the limit +# is enforced. So when you set the threshold to 10, up to 15 fields may appear, +# but if the number exceeds 15, the total amount of fields shown is limited to +# 10. +# Minimum value: 0, maximum value: 100, default value: 10. +# This tag requires that the tag HAVE_DOT is set to YES. + +UML_LIMIT_NUM_FIELDS = 10 + +# If the TEMPLATE_RELATIONS tag is set to YES then the inheritance and +# collaboration graphs will show the relations between templates and their +# instances. +# The default value is: NO. +# This tag requires that the tag HAVE_DOT is set to YES. + +TEMPLATE_RELATIONS = NO + +# If the INCLUDE_GRAPH, ENABLE_PREPROCESSING and SEARCH_INCLUDES 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. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +INCLUDE_GRAPH = YES + +# If the INCLUDED_BY_GRAPH, ENABLE_PREPROCESSING and SEARCH_INCLUDES 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. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +INCLUDED_BY_GRAPH = YES + +# If the CALL_GRAPH tag is 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. +# The default value is: NO. +# This tag requires that the tag HAVE_DOT is set to YES. + +CALL_GRAPH = NO + +# If the CALLER_GRAPH tag is set to YES then doxygen will generate a caller +# 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 caller graphs for selected +# functions only using the \callergraph command. +# The default value is: NO. +# This tag requires that the tag HAVE_DOT is set to YES. + +CALLER_GRAPH = NO + +# If the GRAPHICAL_HIERARCHY tag is set to YES then doxygen will graphical +# hierarchy of all classes instead of a textual one. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +GRAPHICAL_HIERARCHY = YES + +# If the DIRECTORY_GRAPH tag is 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. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +DIRECTORY_GRAPH = YES + +# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images +# generated by dot. +# Note: If you choose svg you need to set HTML_FILE_EXTENSION to xhtml in order +# to make the SVG files visible in IE 9+ (other browsers do not have this +# requirement). +# Possible values are: png, jpg, gif and svg. +# The default value is: png. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_IMAGE_FORMAT = png + +# If DOT_IMAGE_FORMAT is set to svg, then this option can be set to YES to +# enable generation of interactive SVG images that allow zooming and panning. +# +# Note that this requires a modern browser other than Internet Explorer. Tested +# and working are Firefox, Chrome, Safari, and Opera. +# Note: For IE 9+ you need to set HTML_FILE_EXTENSION to xhtml in order to make +# the SVG files visible. Older versions of IE do not have SVG support. +# The default value is: NO. +# This tag requires that the tag HAVE_DOT is set to YES. + +INTERACTIVE_SVG = NO + +# The DOT_PATH tag 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. +# This tag requires that the tag HAVE_DOT is set to YES. + +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). +# This tag requires that the tag HAVE_DOT is set to YES. + +DOTFILE_DIRS = + +# The MSCFILE_DIRS tag can be used to specify one or more directories that +# contain msc files that are included in the documentation (see the \mscfile +# command). + +MSCFILE_DIRS = + +# The DIAFILE_DIRS tag can be used to specify one or more directories that +# contain dia files that are included in the documentation (see the \diafile +# command). + +DIAFILE_DIRS = + +# When using plantuml, the PLANTUML_JAR_PATH tag should be used to specify the +# path where java can find the plantuml.jar file. If left blank, it is assumed +# PlantUML is not used or called during a preprocessing step. Doxygen will +# generate a warning when it encounters a \startuml command in this case and +# will not generate output for the diagram. + +PLANTUML_JAR_PATH = + +# When using plantuml, the specified paths are searched for files specified by +# the !include statement in a plantuml block. + +PLANTUML_INCLUDE_PATH = + +# The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of nodes +# that will be shown in the graph. If the number of nodes in a graph becomes +# larger than this value, doxygen will truncate the graph, which is visualized +# by representing a node as a red box. Note that doxygen if the number of direct +# children of the root node in a graph is already larger than +# DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note that +# the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH. +# Minimum value: 0, maximum value: 10000, default value: 50. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_GRAPH_MAX_NODES = 50 + +# 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 the size of a graph can be further restricted by +# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction. +# Minimum value: 0, maximum value: 1000, default value: 0. +# This tag requires that the tag HAVE_DOT is set to YES. + +MAX_DOT_GRAPH_DEPTH = 0 + +# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent +# background. This is disabled by default, because dot on Windows does not seem +# to support this out of the box. +# +# 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). +# The default value is: NO. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_TRANSPARENT = NO + +# Set the DOT_MULTI_TARGETS tag to YES to 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. +# The default value is: NO. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_MULTI_TARGETS = NO + +# If the GENERATE_LEGEND tag is set to YES doxygen will generate a legend page +# explaining the meaning of the various boxes and arrows in the dot generated +# graphs. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +GENERATE_LEGEND = YES + +# If the DOT_CLEANUP tag is set to YES, doxygen will remove the intermediate dot +# files that are used to generate the various graphs. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_CLEANUP = YES diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/docs/libcaer_api_manual.pdf b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/docs/libcaer_api_manual.pdf new file mode 100755 index 0000000000000000000000000000000000000000..0c71255bfedd1b3ae02726630988538210902fea GIT binary patch literal 768173 zcmb5VV{m3c*ZzCQwrx##$95+6#P-CtHL-2moH&`-wr$%v^Zd^_b)KsC{V->L=-O4i zckQm-)xT@?)oW2Gh<>LBGO)o?OwSK2!!i>y5!)JC!1D6KGX8M4Ga+V_H?&Z8vW8`p zBL*@t!7_d~cW`tf=49c7Wt1_oF?0G!3}gnf691p;KfP8?CJw}m->nRsOhiqLY>iD| z`T1cTog7RItYO_&C(>nY@i>rwUA@sBV(VEUcK-qo$PB=Q@UZZ>7mGX4ETx4>wl4hY zx`JjqNGj6#7Dfm97_aGIwwV^9Z4NbNOdZRD9#)VilSyCq2S@&Vn2R-=m!&TDDVkHU z)}KxpI<FyFQ~)BL*qH1fakw|U4zFU|&>(2JcXLqH&sr!WNIO8jWN~J2+1*VJ#Rl|; zepigKto|*IwL_3}6)Y@bm7rgU(E`{MNFYdc!WcSERX;;-Q(bhv6pX(ixfu|fWi?ZR zc%UzhSdLK`Gz{f+#u+z>Tq5YRe?PZG8dFI&7kygTDtzC1G)UkoHr9$*C*gS7G%pgl z-%}Xt@CHYTjgWoXM(Hw^f?T;TWI=x?M^;pq&498XkQj$4fEX4sniwP#0Df3SnUZfX z;UGK>osvhYX~YeQU5FX>9UtX%CJen3fN<U4lUg|sA!+a&VGg!V#&rrBYWQ6n{yS(O zVDPwQ-h8_rSekbC4L*~+oX`(dk<X7r@&S-k2%oK=#L5X-*)IVbs9LX)LZA#9BL^lS z<fKSE6e_L;0aBPPl$<al7J82hHRhL$zz?iXu3BIjW?BT{4r87T9{{H$S&bHAfICa` zi!O#ZcTgR}Ed-X!7%_i~XgJJaSvL{Ow@d~>=`1Xe1iI6G$1u)sx!e<PdlgpeX86*c zT`+rP>ddGlG($@963XFsCaTU7eIH}PuOqCE;#l=r>=Q+bDSBdlEXwqm?n@vnK3G@A zN$u=9=HR2dw^JVM(&?D_oh?grG&Vp%^ux`ayXq_=@TJ~%VR^~NXQodZ=}7>$Z3C-q zgXlGOZEI}V1MPZedtJ--vM|EH$WEi!#`Htkl>RlFP#Qmj7Bht9=+R{IVrso{IR_(Z zsipnrTa#O6;(ceNY(%VNtBub1dNM7RZ2;lq{8**HYqRMGIK!w|1E0Cu>+3f(j8@Lt zB-4-gE4rGDkGmzY6_M7T&UE}d<SU=>UKvQPCcV~*Em77wjW%jm_v5S=OtNd_vK-_q zAMoi@6hV?eM?yie--Ju#!~*0iOQ5TpC|Dm_+j<{-jZdbZtJ9Ul8!xz=NJ;{c^BiHU z@REoKBp<%L<=yUImu6SI+kH&W)8x;b<XnpZTbt53Z{37?l;dv^hVJ}Q_Nhu%@$vAI z$pzGWSc=*{poQ#;BTV1SQB`o`Gc6P+Ugcq<d=`of1j{4^-6b6OadLlkx7;!fu9JUf zFPJJjq)rtOwEmjP$!er?@ya>6+5Ew~mBH>G19#*K>9f?0w$3WlQXDX6iW72CdVOj* zY5iqjq(xzMUy*1H(Oi7W#&ddsa*CALV<vVtK~vF%+*R>Wx=xf^`z^csAy5OU+MVNc zrL!;H_IU|rDe-8HF0qaXLsy3(1FKMeP5kcrl}T5CdWJI-VnJ`8d00~inh3-a`<OPq zc<|8Ge!A9XSl!=l3dUr`9S2QA`YX}0?Nw9n$hp5m`L<Ht(s7kybSSpaO@B4{L#S?o z6!%DR=jDT@xx>g2;*6cvdNHy~L_x<~>nTT0m8XWdsa3wJ%q=Q^B0r4)Yw~KKdS}D@ zrJh;w0)^1`WrR@7O=Yn7L+$6~RJ+(0SZRRy2CRvV@&5y|zjyzEBr_Aszu}ULiS7Tx zB`X*Ezv6O1Q&t|I3%PTu<{GHo<MN^$PI?3EkpQ0_kKK^aRu@KZZ1?j!zuG#|RgB6j zSYEtzam4<;ro+(vRKBV_$ERsQ5}Yij(DMfl!@m4_Ca3_F(hWbVc6Ik>@ZAY7G~*mF zJQu;L33_p27M~)j&rgJ^C-9fJtX)XVETW?Xj7eKG%IIilG)B229Q0@fD{3&Txj_Ml z#84VL48o+-Z8hj3>k0F;CEV4Ze*d?;tby8ru!w6Tf3AL3P=~l#3H13Fd)zF2)73a) zDNC-O`m9!fXna3Q#u=f4PE_;+;>}zzk&7xO0(hdJnJjzsL2^2w0yOjDKU;1H3V-tU z^dn7VWMoL{lW+$Wg;w^tD8mwteg?DI6&oRAE=`B^dK`=ETXvS<NTSM-at5_<!L$Ya z1Tg!NIYn=$*{x`R!#d5_GhODVL;_E}WCl^}`<V=I7_C!La-X9aNRQ`!fO6RGWc&4K zA(M+vduAB39E%SBf`)`SAtvW0oK+fy4+R$!>j_{H1`m{V|Jz}y9|;X9e+^&q2g>a` zxJcwRe4-+1B+8#<2n3W!NkFfp%t$D5-rhD2N+h8$>V5=BE;4IjPLQwg{dC|uxRMm* zX%KOK3Oa}&#Hw8k(>Iu%=?EHU0#o8xSmitp(y~NQTVd)MX>&jIZ^o$S+XS77;sE~$ z*cKGIdsMrAW%IOHvfN`FL2=PJ9sl<pPLIKf&2B6$+B#>u_AU%9&)to_r!B&22BI2U zTXu8hGub8*ey`L{9;&PBn<FJDsR>gHR*sD_sfkurW`ZXr$E5V3dF{eOZZ_ZRV8*^j zq_S3-2|oEYBk_$BYYQ88-GZyUIeGuNy8}j?eT*8f>S2~#o-UUWCWh3h1aq@%tS1}n z$AmuwQ)lb%*%kLerUPUIu~$|(8uaeBOZaZxE*vKodsGI+0Zem2y<RUDyO%eoK64%4 zt+N@M1^g(%9LBJ@!@lsL*Tr-W(@1D0YF+ehBU>-Q24Ah}HpFb6dKkKsm_J=-A;96N z<xB*I?a!FkU%8@VUJyK|#yTNilWx}St|$h-m?4B7A+}~EKJ<~cWG7rK4l@Pi@m2_t ze5ED=E{<v{n;k0_90M5)d@q<1fwN7K_dg>`BT*KZ^VK9-gT!wNukm$<j>*}EBAYXu zuGcL>LVoL^tRI@VI)-diIgHN9j~!=dzM3lCr(}|3)%30J7^FcqtAg>EAVe>JF`C@# z(0g-$ygE)k@-+)E?44P@yh`5i?GaQT@*_1B_T5YPR#OmIN)Exq@*nJco;j$f+YT28 zh{%OMz|?GD!7y^L^Jg6miU)HyVVGJdanrBtgcB@U1xj&*<qlyO9Iql?A-}D^C-4MI zDI}nhVFh%Ckae*i&0%p!s~DzIa(!ojf5UKva>zf_5?P`AbOC+GdXZJYa9-;7*w?J3 zde4W|RlR$XegF9JT=ViI&-XAb>b(zp^HU#9yWvAzE(C28W^tjnpVD9#Jcw%qZn%Kx zA}m<y=gR%I+5YHlp*PQbd01^aU}w*w+FJhMdo{THojA$ci=5pLdQi47K{RB8Kl0$1 z=V!`nzH|LsGJaq6&AoHYVHH`hODf7b6*_2VakL#>)n``^c{TUVntE@PvhP1wS8T_= zrvHvGz;;0PBpEZ~=U~}1T_oj5v6}jqh;?&DcLEoIPfxos$J&cyRqqp4Vfu3g%(cKI z+&$XkHPCmK5iV(3R_d6eFzDNl{EH@rP7(^(t>pxBrQXPj{%Ob+H~Hni|3drI^Cb~t ziQC(db#y0v-_BMxde*y_V`OJ59lt0;>}Nb#2OF2v7an@Xe(2t)eXOtR`M#8~$)Ulg zh=tDE;rMWIH&T?g$D=^bYl`Wa|4~uICl2gd)&YgZ4kJoIx|0&xf_avnIudVKxjTWa zQvx?xN)@AS%jAmBgiSL1sbkk64x_g3m|}uDnOd_Y=1w9E5yzH;FPMgG#^e7K5>_VG ze-siR@c$DM77ng|7Lvbl_a6J-xcd`>*M<S6`<Do41jOwLw%vKpjg1y@2`1nDEdJ`} zS66}9NzxhkZlgL-P-bTKC+igpI!ivjHPfQ#7$u}t{ms6N)8sR1-NUczuxNM`gA91b z!RFL+gQF^Yc629D?iI%Tn86o#<*7jkBrPxeVDK+Qf?xL6gZ9a^@%CKXx18tJf`ID- z`aVw0y}%G)@2&q1*Y|!^ef*VY@<Egt(*U6GV{1=p2MnTGG&DQsFCbz_tbxox(6K>g zC5$9*iC?sv+)NN1kcvG|VqB6{YMhRV+!PYxe%e3lITY0dbxIFuPit@!6rlK++#iuj z_8bPBM@7$1KoApB!{=^co@7eI&W0myz#<w^u-`4n1%oiIl0<}sW{CgoBgCFg{tlfc zjlxB;&rk$kBSC09K;l^DCP|W)AYlkR=gd`x_w*7`_+{h=WFC%l7vfCNKt+rm2cIJD zrRc@R*^ftoWKJb8q!f+i^O6W~6jg%88SniS`zKQrggKRq)YO;>$$&U;K$9d+_U2k@ zSpO!HDfSQZv@j%`ffe$73JLr%<4P~*NNIxv2?dS|CKq{ZzXUi{Z6YCq)Np=75c=rQ z%6>i|*&h}uNR(R(kceF6D91^bbSybNT;vD@C5#W#EruY;K)knu1QnJ4L7IaY78MUX zfk8K(H@Mc6%)UpaASs!QK={+%_bm2_On;daNk;;E6j3rT6mz&cqD`mw$auIr==Ho; zlXGyjr1$xLaqx8Kb~*Xs9%*(sS27TC)B{80)4cfIe6q;C>By3C@o?ok?HZmrL(vQA zgj9No$E%$w;kgd>yPkAIk}27Q4xjl8W5t`t`OTV9&KZTxS<~-_o=>a4%SW<AayBHP zQt4G?!&`&k)A77s_tE40I!_5#&Nma9q>Q+*n)v)wq6H5r{m;&aC~76?AHD>2wJ!mg zpjZ`T2PkBlv*+%z$BeM@2r1_isRyQqk7bXq1nVR@6?wf`UyJ0+AG118vqWc?XMqc% z3%W(Cu0<YNHQrigoqI4fKAi-3HB=6;-{kUW<=RiL%ebx5uxZMP``t-0xm{F_!rE88 z2zbyWW5fH$2X_DTd1wP`<k#tB!N|(&#<kfAtKGZ}WmrG1^pkup1-~r3&{$3QDt=69 z6A*$EsSLH7eux!y-{<@4<wU0!l^k*dofW96<z)iiEWQ*%`Zz41CiF95BhLWiF4}_C zdKqXX@z>u_S=5rXKAchmr0k9buZuM-f0$>rqI%&o#;r%01vs;SD+%Qy5?7v{_LRTA z&Q=PP-IpNVUun{I^na^bk65Hq(aETndKkypw0Wo8K5X(mY10(Iz(|;dOW;{}J~|AD z;h}zx{vp6d7g?ta<3a#yleM%`QTV1?$hf8bkjA|o2rGOH(Q9CD=6g!9+=6e>2F!;Y zA1~V4kxTVJi<P2$Aay)tlK+;rmG{f@Ecoldt;$#V=|XeMj=AFA5$cs=PyE69;hM?k z%Zw_1_#5gAL7W|$BsxaeZM4L*Ik|)5LQ1#t!V_kgGFstf_OM*h)<ngZsn=*ZCP;{X zUjL2?=euVg&^~)uD448+17DdcqO=!f3on`p1**($x`Q)$?~6dq2(^Iu&ZncW-qt%L zI{|ijyy&PxUR~T)PBo<D(&EWoJ73NVb)<5)Kg(e?2I*YBQu6mZ6O|c8R@&HNL5}Xa z>f47U#JI2e=%`q5>3!r+jWq2=y*Hg0EDw%yjWX7hj-tT$Cu{YutzCKhZ`{>p+%Y9S z7#t`eYCG2(dz>D@w@idUk=(Jc&;VG)W1N|t<HPF*s~e7jZ4{UP$#ixmwtr<h%YQMQ z^WQfI|F4(wior{XmC+Z2g9;709N!ICLA4q%2jpnpPfL6MeEWJ+5^B{@gK61YmIh-N zqaWGnn6h&<Q!~bkWV1?uAtYL98UHncbH&2n876c+LTTzm28^GX(n#Qa<zhA#5v0hC zH~zzb>%g@u!MyJ+Oo11UlGVx5kEz<hk%%qJB!uHwhqX6s^rN;E+7!`PyEYYfQ75!< z8#!uEJw4vua7T=K(}NkG;9J1X44(Xe(D)HSr33n&NPnS~;)q?+h#QS8zJg@!_zXDQ z34BgKFv6i#04;w6SjujL8=CO1sb0!{K#rIUGW>zDtb~ahDOy$F0lET;y4;NDP!Ubq zu~33CI}jAlEJO+i(Y2t57tBkBcpT>|xiXHqE(!$WTPVmD=3*MAVT7j4w@`fXXSxBf zVW5&9Wxr4<KD{h7Q97`re=3C%T!9xKt%Vf0!$eAbZqUj~Rf{63z&s8|nhFi_N8v}V zB=R40Y7D&6S{8_(hW$Fof5_E&0zhbtW}rz^tB~M?z#9T>{x(AjLg0?z^nV)-W>8mP zDd#|`eh_hhF~Kf9G>HWS*wqq27hFm(7JX$Pg@%0*TT*%tG<y65&L(ke5J@fQyl6C# zM_6(n?q`2|tprdYKvKQP4wX7g$vil)RBSwM^t3sW3t7QIG!+bm;s}mkLL_SL6Q2aj zKo9wcjH+FrKr8tOc@V}?D3}a%FqlFbviiJ|uGh1E^ws#yz~1Eye$9A$_vcH~`^V?n zmM`z8J9_l-Fu}p~rq_Fm+tYUN4I|RxszP{yl0sFh=2+8MAVRZOwUoV5_?wb;(rz{4 zs;lJN=l;`UO3`xSZZZ0i^Yp-%ht6X2#c%6&C9krOsq!ilXA>Rq?8QazZuz1X0&Tag zL7H;T0e3F%a^=j0R*oivCF(4d*;XBo($^A6fvOPs@;_gza^<Ji&f88>Jz_<gZAzU; zcZ|-{&59mMlJXytU(6aFs*+O#5?hOXWA-)vBlQTN8azp$Dk{yi=o#Ek8lC4kOKW{y z4~`!m?3W$c9wWrk9yaqBzjr>})DYxEcJ8UyJE#$xvKFOB-RZlkOH~PVr~0PGj8xVp zlPpP&n?gPt8IkCsG9*)$N{>*E4uH8WRV6*w&a376d=Qtxz15Ukuz-9hCdc$v!VC>H z^taC?XLGN+N+5y!?4BgS_6oimp|=BG+927P`*>!KO}70Vu?~Y2!G3<<wt2W@joTre zgBDUvdGHP_kS~w2M0|%^&|W2{yQaMA?F79eJK)N%_hP=pE<aZd-$U_zf22&qbKWwC zi|5@&Zn-k+VbyFB=E`EmOEW^Z@}9Jrt6q}v5u?79s8dt`r<=d6Z0J`Cd5#v1F<<aH zNN|QdcY7IT^^k3bH5pQg^yNA&g{wdmRMRanACiX%uQn}G$<fZ?f&KAq8K3muZ|9`+ zTJY|dcfn#~hG9xgi@?|-NZmb<o#yrbhWsn)y&lx>i@DFL)cGN#cfzgMTY7Rsyx(a~ z51v2vY;LF68BTx`nazkuMtwCs?N}RRA`EBd2Xf{Yg9z<lS1w(jn(M>EXG*$TLZhA> zn|4k3W}IhN@mx%AHXS|bJ8^`Y<1aU7wi;wt_l>5L*}kKLY`3~dx%Bpr3*_BBK9MR- zY}g&um6V+tcS13wPQkk)(t~4lf5ub^6{pA^$Bp=2iW1HEU@u_@@;o0t{PoJ@Psz=y zB1NYpxb^QNqiXjPbUja{+HH8~UMitt-@usMmFXaKCUI9C7gHeY>@2M+TxKmxsv89? z8LepPOG*yf@*mC#YX6)mj%RwwZGgNnZZ}GP{!g@XGO_<F+S&gL?f?J6^?i2uUsrdu zPV1fI`TW!<>U2yQw!|agX_9Rq4y*Ygy6GZoUt1{+r5$ony{7ebV8+I)iPSfFl?u%j zQ<Lqd14aAa+_9wo0Nb#khxQ%N@gv6AcGY!IwAFORIU&XQMNpW*X)17+6@$`n!G(WK z921!M&tMbS&nAy3nxsYz#O2oDR=|m#f1CHmo=~<UIfNx?kM&Yt=x1PhEt4evc^5ge z2s?%?6bn6e%&4TG;;*2OLupv40BlWd<buLV%iBFSyuoH^h!8GEg~pkPa1C?tLneWS zRE?LeD=+s$*Dfn+>&Hnp;H%4ZM_`cjD>sFPA4}3H?v&C-lv3j>;lF_;NEg6!oR zK^AB`jVlp&PRa2K`K9az?)d?r^9O*5NrDq;DiqNxR8)SGQa}9b5v7njg@J<9$guDh z@2J;spz5f+$fC9A;Ie+jiMwh638y=`$Em#QNi9fJuS&lQ*oSIN{Y~!GxbnG3)!CTy zK~#^(&4)tEhywyrtI03U^5(qx2vT1MaXds7)a`Ik&?S%2QPBTrqlw1ymLZam6UD18 zxTi2%T4wnZE~1FtUaKLL6+$A5%Sg|o*iqd2QG}8!>Mt0+8r0__#S)L6;<N}UF^5tr zE-(>i#xlPO^3u2=fP+f;2Oy$)2bIe8T1rg!fJtzlKnOTNQU{bO0oWp;?FZ-{6bEvj z;7*oNv_b(7CkZ_3ZG8<T8wotTE<~U2ZyBE-k7s(_0w4CVh{weE3Q|NHM^hC@F?CEn z2Q!{Ijhxc~>FBRZO0<ODw;sHUhE)Tdm{^)tO`%oauFjO#T^$MszDHQn%V`xf5LtSg zrz}lu`_gN(Z%FcVTCM7(=bgon<r(uN@-ik?4;83BRIjY&Y(^IKxWIM*V6m!hPVR9O z&bw0Fy|320tX)N2xub-eluM=aYUg&>p#{$Y#=3wMFzNm3g>DOFqdC>k4P)MwjO+6h ziEaRIhN<O7H9}QtfqQHg)Wn$4UBCb{RQs9%h>f276Xz;l^qq&-90L&tT!zmgD}q>k zfdrgj-IBNUtTSE@E9{CK3FBXK?w>O?Y#8Z=4{2$cW=3p0r8V?1P@OOO<)Qbqm<=z; z6*B~nm)%4ow_mYPMXaet>Rc};zutf<bx*F;#hKLeyg|BeD6Z{jHy&K*ZM03Cu9=!{ z$aM=4;YgD#(*!{%v|LiXW|;1j)4RR#_QV{ZT=4Gl><SsVlk>#fN4o{p@z!UFXQvEJ z-<o$yFU$RP3hdTx9cGvdZQ|AQ(0LMXH*+I(1<DDeyloY}Gm;vHkX|83;lmUy$4}jU zA36FG;yU~CeVIL)kye~~TdUVe8HpMYb&+8ysoF5D^sM@g=ceg7!&hehaQS+2u}mNf z<DzMh*XZIsV6$De^u$qYgd@gNkfyw8Rudwx`Juz&xCZ$!eRWsuY}EpjK(I2daWj2> zl8s9c1rd7zxCI69HjYtEEXr#KFUwgTI=xi;W>n?yY2w4>E`vl$N3|oA_-;T+3#{XL z2dYIa6heg;tt!ro<+(jtJ#^S!d(k1)-NjPewPe22Rj)E{bMu4w(4vcc8DB#2YpMU1 zlN)3v<ss7q6eKiT;LH0EX#{RO)lzS@Z|oE{HGJpsYvBbT&4G~f_%#9m92X8LR@OtW z*%w_$VlQ3h-mX`6a!~xX7mut@2^`Kz7maR;jcrbzmT&Q8m^|TW2~#8+4ID2e2^=*| ztAB;o|Fff}uVOiGJo8uA?$VCon4k#=&T&LHB3AtyzoY3(xL$~KtunN9-gSIUAH^!j zc&1U;_1U#AU~@*2^?x$`@8KrLzd`-)lU)BrbvBlNH({jzbND%Q^@;wUfc<V84jObg zc@JBGye~cj{F+7#sdGN0d8?ZRe*B@?LQ2-);+x$u3X#aCZ{NXWHT<Ud5rNxvw1#hB zUywyDS*Qg#R&HsWPH5qGdzt|3P=>eMU#don!Xf0mXtZ2C`CXE*qz`h;-(uUAVo1!* zP@!m+RPAFcu)ZOB&#Qh90h|VpkoY${pwph>XX5|LrG?h5%pZd<&ppQXCoolFoDIG& zP}iu;*A=!Gb#6r&km3#*E>O@iaR{$;?BAzeQl%;N^N`%eE|2avR3V^&7OJ6@(5TFn zP_oBwXf}1qL=T$UZ}|~Di`*g4EH1}DY*_(-Q#VJqBcaCEQ?D${j_4;<R+0{gYk(9I z6$iNpLJd!npm&H<X{FPvJfG^9Vi?S?3SjxW?flZF+x-FWB3T!Kq223eVNw_FF%#PG z3!i+S=I6MOVRpU)h<_?-?KlZgUPBFuR3#vG0d$4DNb{Vz)&o-`Em!mJs2qp)xqk9C zN+T{b^z%|xtD@7M;iKMZvnCS*r;0q1Q?V3^i4h<=EfP|(W~<;)?|R!(gbZ~9E@@*^ zQ%c{YLXxzTq(w&3jH6ReDe@BLhr!P1B<+>Un{Y{fX;zSgtEiUqi0>h6^{G$|tCN-V zISkZn<UR@~5<qICj8$S3SyY)Qt}Fg#O}tV*-Nvm{>Qhci!6mu~E;SHZ0XM8y9cBO+ zD>4?}_io>uZ}7O*Ib(6iw^O;+IobMr-DP~f-`){*^MANZ9@#}7F>h%-eSWNDh)XGc zmWW^RS=v`au)+;F7d?31pFcb)MFe9CnA=wjs75TeE&9X=I>*z}vujp1Jx@b!beub{ zlw(coIIfkuw^$IUT2G7IX$n+tx!gj#5E^I_X0T5Z^Q@W-;SB2%RdcRjl$c{|HJzH= z)ta~aI&+3wiN~4w<u`kqFSgNdGr<nX<&FFGdY?Hjm0))Y`~Wr&ytPtqMk96DT<9+$ z&RNvd*9@8U6mQ(Re7QiKQwF*)b7C<QMXG_XG|e@x{;pDg3O8w2&yHBW9ENOPCfj#z zS{hn(d8)Ubae44|Z1_o3aW>V7o}VS02@?FkIkUxzl(Xuub_duRBU^DVMB4@F{11Bh zNeGw63YOgy&E3y=_@mTdmTyHlm9n47V8?D^*OEyPGWua5&K0)jbMLc>{9LHrEEGJD zP>6ZZx!I`a;esy|+%%~<_TI)0QirI;J~(~o))3OP8H@FYSnXH2c_Xben%3@`A6?v( z=U(|D=hil<a6?@*?TZ^-_I_<-|JH4CUKpcZ!I90pMKo5OXtPkT!5wTXt=Z!uTJ8T8 z!L$}9n~8C?#@DA+P@xMLK+GKn^em}*Z+LZX(gZa-;h4oT2t+bA3~cGrKY{{y{JQ2_ zcwARF+=kg5Yls`+dY7>7cX2w@kXImP;=mE!JZCDxFUp^f%NaaXAll3AoK!l0qer@^ z+&ri#YRU8dgraOOcXCqM;9*)*IVh+&-Si)*F7N0n$9j5}6EYs-DHXVS)(g1QqMU8N zf<6y`cklN#m5ZQsS*rkCz+O9Jycc+^tiK=c?6h7eXVgTuUqT4G5IgY_tL+Jttu%hT ztsB_=uIE!mT@$)CCMMK8UV0-M4^hLc2y7Osor4}K0P^xNAcf3(M~d@AxRKI%bj#-& zo5jfmiCry0CtlFqhSeT_Jo<%aiKS%@M0Bs!;v-v)-7Tjc5r}(Th4tuTAvt1fd4e;o z4(w?UJn7!axZF4y-{@(s6+2^ZQcA1dW2rFK#{4hrW@h62S9Syc+ic<b=fstRbZJLC z4tT%+80eH(Y2?oUGv>59`hl4raXJF=jeE*GeD_L3e;stt>!4YSgP>nUNiOO3)TwZ& z{ZO$HI%Dn`QEZbuX2RR@wqEhkKYOI)nNdjL2Ku!nt`~EmFnjbz>0(J~YDK%-(B&nB z_X143bKyvC0oQ{?<794wbY#RhYJ#s4t;A0dmb@QEFcMN>MfzT`btHI1on&|*QBz@9 zSXnpJi}@wNo-QQyaADq|BYxsDw2(awgzhlFT3yii*arz52V=Z_%v=*Z7}?tM<f;B) zQ(e7B%4bsV8F1*?6q(SlC7D>^`VP}Z%G^DE@c8_D2sCSB%T&p4670xfz`mP-xI~Q_ zH?)Mkha`#kNNRLAa+7#!>|k-fCQ2?!a7>w7-T<%^P)`{2O?2kW*dWTHUNY)M8Wxw_ zq9Wl`iEwfZLZO@D9%AWW@<(WBv*>dag<;1?t3bo-xK;og4oe;BAY_#pUpUw5xJRSJ zeYUm2_zYFE&>)aA4ptH!0EG@ao_ti0YE<kOj}DKyuR(n{@G8hoeHiS|MVv%B?`Nn> zYK9ogLJ`Impo6>uInWVHDw(;W>VUpnd=MKi@zc6KKUM=i?Ob6!i@siBv0hA7GS0Og zOd^u*Rv#ucA|TN<G@{<r2H(K~EI3D0Bab|N?*fo&qE*KRW3f#v5=Wr0+(&vsjtytV z$gLQwKQ@~~`u$Hq6=kjaC~-CTic3fE2*yf8M=bp3{sxbuhou}N(G}su$$ZDl+t$|e zQOwrY%iT?lWNJ%T&a{iC<z}~l`<>wA%-6eq6~ekqi@nON4$b`GAIPyBWt+*Cm+^_r z3@ydnh3g{-4z+c<))$2)hNULsUuT>8GhJn{IW1{bv@(`c`4%6y&2d8WETMhCmdec$ z_#+kPx@rm$eh0^?2_0+jNm<(XLh<-tBDZzAXHF3ndK|npl&|BHr&5fXFUEX1UUvL} zrl_ZqJAWi6&YV2Q3iFSY5hst1(g|s&x^>#i9uK4F@>S|$S(Xup3^lTJt+rSjE`3mf zHE6*~%(j0S*{P86))3Y_j%Xwu>X3bSQ<&Ch?zr*c3*cu)2_Lk%S~tgitGW!_^yWl- zQsYQcf!w%=l%KwX0lQ1H=AwUvl`pZVcvHOc;U#_2^ZiB17s|>6jq`5u`_ioQ&0YWL zfW6Ji8U7&}L0x*&hU*KnlWI}pcO<W`dul}XcP@6^8oAfP3WB+wrakM0&!!=LwwrvL zDEWm+Yg*_MsGVrA{=q-X=dDYgmr##htzrf$m`#|xF!zLgJ%lxc@ULQ9Pb^;<$<{@v z_dj}%OIuXGDaunsM~B-M#ozy!JuVfbO{y%3j|m-R!Em_~3h;n;d&f?fkIo-bh$a#_ zQ;c)QFy$8wF6){0U^gxqV$%0^-|{ZUz6|zx^xy|m&C@$=a%U8Iy|TP&yLw1=ZbQ-u zpCaFx^So8{%Y|x*$$#u{$?4oTCx`09dn*-YJSF?3-EQMdcDk`FzQS3>!U{!t!YA?e zko#NS<X4W*^T4m>(V8Ur#k-NADYFZgC0OtW!Ru|oX73k+74N-Sfi1lpQL(AY$b^+K zG&pAr^2>?<FUa`QGnNlreIo={9n-1>05=~C2Yy4+qaj?298FzZV2TdIlQYQNMOgc5 z!|RdF!{Vzm$Gu1X=a<+$4@Y{_6<4DJ6rU?6`{k0#nPrN!_fY-Z8XP2FJClt|_?pao zUwA>_flJ0u$ti}Yj4aZbdO}q~0=n)sQ4u~Kd=4J5d<?!yW^VP`IZ@iSkZ9&>ks<!& zPTraDxju)2K#adH>P}6@{O3hMBug(OusXJxPq4U}SGE5I@~li;{|b5L|AIUl`#%Th z8ySBCbgsXUf5G5xPWgfU03Hr1d0zNEYcMp6ACv3C5Xp0e(B<iiu`Cz2g2kLwhPN56 zpSdbd;s&i~hZj^;ya+>`X;ky`doZs0HEfj;3AH>??RVO%mspS_;(C3R+g}hCKV#qU z$~j1~V-wLijS(bdwI%5C0*-m5e~?ck1F4PbK`JCiG3luHSf7f7aLig65e7vsO|8jk zEb4`zkl~-~evwb{;k)|{_mPQ^Uq5Rr9JAs4)=e;8!Nuu4cF3ZjIp8j#BX2$|AbpCp zdM=dUiD5-1J6aj@3+G>FaEm9kgc0H*Sk{~$1-X_Wqc&?unTbz?5iijm-iwGU{5kwx zCj8fsW;_YawL0pzn6&S=qiZsOkSBqrwT1Iggq;N|u<3jbtMQ3`6eU01qKirc2AqVI zlt^m%#T^Mq&m39T$la1V!h6V^Sus%Pm*VD7(3VhkkLjO^Xkz#s^wRIJfzok>J?uXx z(I7zOJ4i<EN{6e0XqMcQ+}b2zzd`5={G3$2_DWo^tm0BlO;~h?#}8OF7Gu50Me#eg z6a4uIhA+z-wgNSn7dX{)uO*&kSym&5?-NZ)B!Q=8gsjiWc^e6eYcmESy1If30SF7L zQUnJCo%2sI2AvBG0I)xZmGr>4w%t$1Mb4G6V}~d32SBRA(KW~|DK**0y-^7JhYjzI zqYObp1zZdC0fo7SaXtlRNzuI^Ow*#V5+O`=TKwWTLPkJFrST?r*<adkwVCzUci+OP zY`4leEFTU}*A6p0Sd?o%U#?s~-|k|3zg{1o%J_nn9WCO$t2R4%+?`|o%u%h+(P=Qq zwfd2!X-XAsbT+4Vn`vj---Ja#V4bb|z3*JXG1#;`4-c4_J2!1usIvaZYG0IQVAmdR zZP~DC`c~DI2sw5EY4bK@jWd0;6jhsvpUlIp?&BudIzfQ7<nC2<-jSIlVB-=X2<M=_ zbF3eng3w59hV^%$5l_eCt8%ldYhBu^xqf#%s#zO49N6q=99><q1}L7@0pj3v!p#9) zjH?x=cS>1JzSO7OiLL{?R_$g>=E{(>2wrnwAJ6d30gzljmwAq<mTvA|u(^mDT=}!Q z&u;HV*j_vTsCZYdVNXiUWhhcBMx&O9xGTSF!}oAiESZ|^dp?O-KNe#|C-tRW2kbPj zwQCYMIt)?DTrL$o*qSWnOlE!0n(e?35`ae*Fb18-hH5=RE8dv1O6IE~lCHQzHM~=; zSCn(<Eqr&J={oj5yUNW--x$ijbl?=wS;}yPY_Wn!-3PeFl}<@BG?d9xR@C2F;p%{C zz#_Cu<!Nc34a|1vrebxfrU;CCR<#NEX>_V<{bmAi$#CMP>KvKis5yhGFSakL%v^UR z6~sBRb|Vg{WGQAY&>Z!d=+Y`Cq7Cd(t#<fT;V1Cn%KUzab*V$)<`Q=W;N#skzLXYq zl-~W3+bOvmpC4TuTY1%sySS6*5Rzkk4;R(D?MFMX+C!=D#G~|3Bs#0UuMVjxuQ|2s zI_xAFF)snj{TN0VP3ao?X^h2psKDT1b7lr+ZT4j!Bq#@sm@*v!6(47`IuJaXZ$;x; zMVPw|wq6C*C*Q%~a|?Y`-PK#uyb$q<DR|b&Vszkj4s!Fd^QiVDbK^C>vd+ncz(EkD zvEc!<JFAf*e2b}4dk8DNad)E?V=Or?DR5KCCUbSYckNmaz?bEOXJu@h&BqtbMC`Ap zOP1PLB8|%UAa~`ym^-<g83?Jz+h?fwKBbr(w_D9TE6z*wrH>_ai7j)q-1f7ZA)y`L zr~YL)c*|;AHgn}z84Q<;frX%Y^5bk%(=F`-NfFTy%iVlvTe<>D_0oT%3aYc^V$!fe zSG5(_=gGtt$!KPzwXJXawZS#~acE(z^|f!C`;p;Kwm%ftwH<a35f|Tinq{J6)SP{1 z<<?^>c9+?E*Rl4)CV?*e7QOf5oABS+pK}5XQ5C2ro2==Wti*6Om!&Lv=?mS@Rj;+3 zc#TU7V(x2iW4A;`ppuo;Mc{ksRF^JIxj8TAuhV93R_Nk#)0WfnY<#qb_~yHL-wL>q zR1*C!YQzp?`d2mj?=1%_E7L#QMH&B3&dv)4@1-uP&lIvc-FAN+N0lqV@@gZ9gT;&p z<3!%Y*A+ZMB&lsjtZ70h1gZyJyhztn?5u>McJqMxUOgP;_s>YmWe<Q1C%#Yuef&<= z$VkHuf+1hL49tTB`=k)xkI1{toL2l{X+Sl?pO#~0t#jmMZ@^y9&63~-@`+{iWD6?3 z)}|X4oK{#R>hkEIxSA!L2F(oi2yRZCr7{yCucze9Gpc(exG_mg+%&jtD?3j;s^>^H zxM}soNYD?8Lo3jEoPA-;Yi!nypY$;x{lniML1#quoB^rW<%sb_%BG#iGULe)`5Y*g z^py3eG5#y$aJ-P137LDqa5fsZYKpQG!79-N)LU!_crH^$2wCB55Or}?dn@+@f-p+j zI5FAb(O+&R&9D#?D=Y!l2sGQ8;cOF&M4*7=J_K}|T727Fx4<J#FbI4v14eXv30|;r z650l=a4x`EE<0qbGhhIpJ_N5+5RO+loa?pMNMRg!jk;~FU*3f7xSu43S@SKLOJN*^ z>rfEL*gWa?Ej*$!&`?)+K?um0cS`(1u>hn#EMj0GUPkw-E=t7`eeB(-o4h4PcVb41 z>CLq&RiZwh94rs+vvk*s#aWi&)eG-v7|!xPvXyool-_E^#fIfiV`JuJ!-D0=y;k-% zHseLnq;C@1u~rt}8)@&2Kvr+1Wdm)5#J2_~jKTy-TL<IpZ^S4CnPnzsF=0PxKT;8) zbiQU=93Gp-Dn%%@t=-J_e%5DrJT&}R=1Y$#a({a2?!K8K>i)Vr+S5C_S<iZNTz$Km z7>Y5wA_O&l4TjRBii>b$$W+&@B$l<f(JwfdqQHV<xNK?JG1SAGKJgc*X<2r-364l= z)D*B*X<v_UX0hu27~G*UcYbTU{9f!tPsm+%JXGD({zRrh!B@e`SV1Tzu$zRBr+_E3 z-!SgP2wegk^DuSSHO1qqCuGKpT>f3I=Sw&Saj%_g&*1v;4Tqa|+>nlB9<5i6_+I5z zCt5|}9(MHXo14e8X2%tI$CEtXx>R5vYKq*(T}f(GV>glHHw}z352YqsaSJMEBP@Fd z4+ERT+ANt*hqlS!AXk7ny|^m#qg-$M)t*3dz>@Mcf<lWo4y=$o39I0a#>K8336C#J zviSU6D8hB=s_zF1KoW^~0#g5Jd}QaRkW;{}2VHpOU&BjeCTuU*?RZ3HGy&}xq~{E* zC9yBUmYU9ZxgxJ`O1R3Un;-)8fx4Ck{R795twXH}Q6TC-@t#*|jQ15UOz(UCa2qc$ zW(sW!R*a(~)rC2!D)yvs&11BTm4}aP2~comFzC!hu`#Jzv%yjHQ9+KCFqy@53=;GR zSeJ)FegGJP0ba@X%5B+HJ!dWDWzDz3`uMZbT}X#L&|5*!+YL<Jeaq*HtdbTKH@OIK zj^l(1hUNIny(Dc)kJugCxUI$h&uC2L)KdDOvc#z=bwUJF%7nqvP92_I>rbfk>^v@5 z%yNh19e(+8ywhbE;3Cx=0UcG_k|(7#(wJ0TrpL0murAcTX6VoE$G}ASf|p@~<p}kt z0pxssX$`Xz(-R{Ne^eRJH=KAiVyHO$%y>G~Rx;b{q7Okl2w6(<)`(h7^L5$TiQmSY z2E=MwSaYA{+FE>ABIl#q&XMtk5n~$PPFAyY-^N#VF0O?xE!<3&Wi~;NAE>>+sBQL1 zOuo9NH=O?Oc{AX6IYchdwYL(x(RDS7l&tYSbh6{{(z0;>_Mptq+*3)FpheQ4bO}9e z83Nh3#e0X@?-&FB{Z5cCCT;FdCwc)RK#Z}uk<`V?ID+AU7NOAR15W<)2c?_afB_wB ziTDj<+V<0DcWyV}oz+XP(KGHXaQDIZ{VR0*zC8r>-dK3dn9{2H3t+h<arVDR0w)mo z&yw(8X`Jl9e^2Ao)RNccg7-O6+pqJ+K|NwnNz$iI#4tfgxl}!cE1C-sO$*Ox{PMW~ zWWzZ6k%RFC&f_{}F6RjF9J&1}2#6Pk#YjXMoR+8U0ihB4c_I<kYrzZxeFjFO8DtDf z6;QOX9UMPWe4_?Y8<dVJg;zgoLogiNEX;Kv**7prGfNsSp&DpUh7&LYnn+b)4+;>< zJA}X%QH6)0RD!Pne-7%wosY+|MB!|OO;&;ipZ}iMlqZ;)v8b3(9PC1aaHJrun~B9O z6~04Zk!(l|Uw}_?J&Yo8yIaMSjtZaJIK!_&#*9t#8_=sRvX~oeADvGEzh_eKVSq|O zA~o;TgRKZdThvL?I~v5QX^=$a1%!qZd^RkHm?5vjPIrh<g0oDboX9ifGuKrYj})h? zdGG_~_hO48T3`oi=a~j4<VwJmwi-wE8nBld{2>6i{|V=DEZ~~Q9~emIK`JvwWiw-f zRNAFbp*0N9T{Uj%rCKa)B%~ATOZPm2VWHgfUNtDKK*g-&dQ_|Tuwt?(3q62Ig&q`y zB3Ym|oB+d7Xdo5N{i%Leil$WQ-k4pfes_$nF=Gx-qT@(9m|;2J9xjDu-t^-abKYSB zG7Ms}jwAwl9Bh;Z1zT+TyU~HY00uQG<jDy@tg<tngQQe0emg(h{@PEWQ9@j-HFSm= zkuce5Ar?23@f=WOB?YGiNGa|pwR8I><kwHBz){6m2Zv59r9@E1uOk*Cc!a|w^5aII zuG5n$`KkYQ(9M@Fd8t1mqQdsx*2&48nIA9JAGb$P{7$vQxBLFE;t}!dtwu>o#86PU z4zki5HEzi}>HF*y8!9b1f5I|(ow#92KV;ZKqwWd1vBa(|>Kgf?``qAod5qOsT62*; z5obTU-kQnMR|mcEpXLUAEWcpMORaMz_h->vzy5A=W17F!UPw>j&k99e&o2D$w7XzZ zFVGiWK|U|)2V=DOl@E#iE|`Yhbd?8M@y$6Ll6W+bSgP^ymGJ|Xq+&_&`KywOHBso) z6cDSD{!8D(87RblC*;3Tn4}!l@hv{O&jqE)Mt4q}A>OuHw<priO(tt7G(S4_@n5a) zn@TNKDMefHi1SS~qnS3V<1y3V;q&;v#t-ps_n-;8O4B%ABtGzdx;Rh4ir^%pZm+>y z!wL3ab-nw0cW&!YH#RKXv3kW4H6*=1pQoTAufYsM?nn-<Bs52$4j_t<NG-6Zm8Xp~ zf>Ox9>Vzvb75uo%Wo1+D3UEne5*TePL@&1qDbImAwV?Sihq%CtG(SrfRDYphP4;8L zMw>=zDSCDyroLR(o9D+DuR_EcYoiFl6j)P>tP#)rB2_{~SBCIf0?eU1vuqUl26YKB z=B7|XyGc6Lq=a_dvzVdiZe~A8m^3OC`C!MhjVJEjC)rJgtErLFs>A%wSEP<BBn?d% zVQF|I6idt|Sv3F1b2af6w!Eet&|111|1N+iQlRx^QhG4+kt+mGmIwE!-&ryH=POs| z3D%WN+;<ZhA$sLn1sR>Y^0^LMpGi8t1KOp^EPi(vSfZ1aJ<lw~9N_5?;#dR`w6X`W z%!|MJ1@%>|0l{q>+-7q&$5rT+e!=@{r%QLItNO?$gZqNY<W+~Y`#tq15y5jqs7jja zO^8N$y@#+h-_F#$<5Av#D@4aAht6ikk`0{w3f1qnWUY<fi_N*;J)PpV{t?bjhusBR zpe?B>DKFu+77?}{G@sI$4cTeGo5t5L4+V~tAM9@AX4x9NhixvsTviT^HWunHvm+i- ze(oF{4K3a7<?Nb8)#$L)!+qMh4vO1m{ysclWkY%;IPjq|yCb{eG>Vopv*{X=uRJx5 zdhu|g9)XO#iZPV6qPuIe>|%c?0>1HOr*+7;Ij&7WwZhmJcqtL_-J}5siHh?)gLKE> z+?PS_J)d6TzPn6j_@wxvruHJ3v@}S0k0Q-+g=9c@*z)tAyci)Rs-60$Bk<@dk9VcM z#QFkR_AOV+r>uSN{YJwP+Vm=qBXz&jO5d(@l6IDwo*#001@`hN>6J5*Pspl9v>43q zJTz>Y**V&wTkHDLf9P13+vF*2FpSMEnV!52JH#)l?yLb5wMr-G@8i}eZ9gNPiu9I7 z>m!>q2KnpPTfN1OeEG(ECjO_2F*5=Gu?85(^xwq@oc~?~e4%A6kH>}lIazZ(RN(~L z-7TR)p*hRWy~*HT&i4R^+(L?>6g)lm@s?rVZ#8a%R)Z!HAP2#6)?{|*ZhHPutuqp= zpDD=zKL`7zNm(RF!eq_{9nVrl0UK^^t1vyT853Y6r*CwU_B8EJ`zIh?i&%m(NOWS< z&sgzyy$m%<5g;B!S=*5^QshBjSKa@$$+Xv<HJ1QQHxD8zWl_jrTL~JG9o|X#n2BRr z7H2+EDoU^&@*TJwq}6hd%2t54nTzRH+~R;%6wV_Gn>r8Pfkupj#NNYJgn;Y%i>6Pp zp+Sa=@C;M}@{G5(pX+tkzc{R27pw%8?;5din6hV<{S+?1d<aE6RwhJ3k7@imltbOL zu!oSuFQ^tAn*)*rx;nLPJ-0CJCKo_HB%^>!F=f?HLd=Po-vSYDyhuF{imn9~9cY~P zz`h7!3O2+IorZ>ZM!YT;u3nPH!n`Qd6BXs0%|+A+>Y9ZFVkJ1vM~=9N6U+JvO8HU9 z*uO6SDm>mPatYDD&XbEsJ^@OJDS=3icjX~bTsoz%NfR34=Lbnp3)Rny9X$LeN}mid z)ZGprCm<Cn#(!uYE*F<#m{!8B5aAwf*s2j!5$ci&0wRcD7;QME?_DL1G6bfQEJqN& z7IRv*g(4^-5)`oAm!}Ke6)Tjh8_I8oW=OBD%uM?08O$fjg9Jnn9<)*j;12@N;Q~-B z&>aTJvt|X61muGmqt*jb|KvgJL5q!>VG}b&KZ`n13nL-_Nmt~=Cmy86ZGCuUTRUmU zLh4H(Sz9sc-q^_5n>rYH_Hb*j`c3hU_Kx9sXL|O#W>n+ZS&!=oH^Q3EIFP({TW_x> z+V`pUIY=xAxBrp98PwtCiia+`ma~7C4^xMZU*@-m^g?^#_0A>`vqas?CkaXp-5;$2 z;)wz+lMa+h4Wv3mEQI@s8Ks;w$f61QYaF~JqUQu7u;9nWSde+RetJm&R}n3mA3dmk z4oHvF1H(X>c#2-S(K6Kuc><`KsK2KvtOsi#q3Q0eSj#)h9(Ud%lsUXS^(+)CT?)#j zf~d4Q1ij>h5VvO*^0gkXZLxwGzj?g4w9^w|gccn`Ew+(;)Ih8ac_w_B`MG=G00mpr z##B1`L6Dqv1SV6nrF0ftJs}_N1d?$IZ#Su$Ky1K`Xlq&(ukI)YXPI1f=cFuJa} z4XBdt33C%sFlW)#@fNBX!twhD#0Uad%MM;Du`LU8#|`*maW*v?<rMRDok_`KuC(ij z=c}SP9!oo?>GjWOUOdGTq8D@CgWuzKJQ@RpvA>hx`b@=ZhI6#yRXI&D<bKm5FBv^X zA9f&8O!s*`#}zMG@YAJwxXzi$Hr}N<c@^S?%y%Y)Xg7;7ED^a|OLod18kPtQuNNv4 zDwoqMTY#l;Q;=O{cwZ!d`8EwRZzS_{YOM2V!aiD5<10U)tngBNU{v}L<`mQCm@2>U zmRFUh$P`&i7kTr4i;?tXvvn?ab|n;C!pzme^P6DA%rRRoQ>sqiI*WFldsGROpZ6As z(cVhd{@NX(_Y@9l7X2kldh7kFc$~|=L(fQNW=mOGIS~|9(m)3#wqohGOnzE!t6s9u zXZ0dU9g&*I7(CMZt}IqrCTn<+dVXFqcEC{fax2PJ7O}j*n6}Z&%O)n1E^AmXZ^2zy zyqdP=n~&Zk*1w7+Wo6*fMv9tqQ+1Tc-8~VsA3^+*Bxvy^dlIWjpim-rhy%gq+8|?M zom>UvbMMm+j~h1;t+xry{Vd`O9CK<vIMwJLGP}xb+z_E%K1`Q(IV=~hxv8e`8#d8q zjJR<Xy@_S7VOVmhsrP4ENoHyV@BMY6Yio7;v}*nQ$-i;WEjzP+{>QCt2LS|sTAMf5 z@Q1S3med>4t()kqY#o6LL}OCj`@NF&oHU<_$HSL=O-hn(o3+Quz^o;sH*c2pC`l6J zsf^a?_-)x)NlJk;ewu)JkB)qnCU8M0TRau9%)2R|HDAS?Lx)}k%3;!C3<_vnwh~ch z&r0cxq?3azh7sT_m<OkrSv(ni9ObjlJJ57cE1%{f&jDGuM>HC=qFbHbr;Uzdbto^_ ze6eqw<KTdc`a6TUwY~Yhb>NvtYOBSzq}4(bCv;V{kMqmVIORR99aLjjZtiyw#G>la zN!(=LJ;pO{QF}^u2!6>CNd?CR#Jf9qmwB)nmz~=AyjUA)cg2f+9OdWF*Uf^L{d7%l zJ;LCZg3;duDn50J3-VC&xjXMCIEvR<fC(Qc%`1_47OeY`-A;$QnWci$cc&x|j+2VH zi_>W3sTa|rr3cQ3Oh&QSB7%~|yJ+Pzv1n!2pL$gZmu&~u3KV+xJo8Sr8dPcb9cT+4 zacB!0zxW0>?hB1;9=~QDE!QkC96f8AKf!Kw2ao?3A!Y{tV|6)@iRHhylbrwTFkWb_ z$>ED5dmquh&Loo_zlqh;X=vl`>(lj2!Z9{$?5bD^wr^9vy#BygUA4Y4X*1JEwI|&x zE<G75<1R5P7T?gMr7xV;bT?r8L{!KHgNq@o3ToP~>-~PqxdY~&4;{`cDH=i_g$XR8 zXNpvqRd;f)4G^dOTbUpvk4k4Ytt6~*GF`8)ao*3J*HP$!LMQzYuMkI9@+TZ|um`a) z<~VRP+=B!?Xbnu548>nfm`9xdd5+>%=pc0%ihx}BG=b@f02~2x040)%KW+*RO-7g& zx`OpJAAGEUQ8*btFD8}}Yvd?M*56B!vurpes3Fl9dtD>Mi2VOz>>Xfi>$+{xvh7_} zyKLLGZQHhO+ctLDwryAKvTffw@7+K5ocF%uek)lkeI#>c&asj?+UUKv)+V9W!@+$& zad3GsKDUk^LeULa0z^tcConWh3jAt6-z;EU0jLqi!R#oJfRh^hC?tI_b!}7_Ny1E| z8DbY8Mmzy4p9@hD*s6?7!c2hi7`T^M`Y2?OnDHodl$flYpEDhIOkgLa1f+oq)FUVf zT@4-%UAzaVeqOm8Jf@)F-J>_7k*?sNnFtfGvftd5IRhEMXj14LAK*Bd(GDLVi7^bB z5*Rqpr8pBggPebWq*1@w4QmV-ha5?Q3LnHcQTQl8SUuFEF#vfQ<OA46p#XIZSXwWL z2D3}GRqg7pQNYQfSs`swK@uoV&<hxp{49l4nDu~D><qdLMx=Ouvfjo#DB%2F<KQVi zG(83F*<c5z3{ZW)U)&jVm?!Ib=5s;*Ofr;*_IPyHqzOXEBKL^zpooR1o6C{t2FFSl zo!vYgXq=vVYcE&GUobp7a5Xi})E^5QM{RDe4(Ds^gK*yiZAtS6b=jI3)PX~7jYz)N z2Dea=-c&Ltm=KV@xCZtqx}HPb`)zMdm#j1-SBf@w5t&)sv=LLw!zQe#8=+i$7Tv6x z{_XCPSM{q})>c<z2AYBVx>&`z(RWdzxqR#<y$h>w7#!N4-f(X<*vtH&4|34llLEF< zXYx5StdTW{U#!M{hSYyw^!zC2xq#blmW_{yZduV-)nIB{_0AodDe`-U_ZZP!)x7pA zRMj>OZsV))TUsf^+tyT25#x$Y0DX?;Am_r2KfM9RUA59PKF5@8*q?!`8Ky?d;)DA$ ztz0a(Os#m0oEw?)rHObjEt`{=HK*5&a6a+|W3l^GML5ej)I=VN`Y!{BqOsPfy#5%$ zCjy7K4*^ye*zTjWDMV<o3wOZmh9GY^)MrbQwjDB$xY9%G&$e4Cr{HU6;(vzy;y4=D z&FsK*B`GaoDLo2zeDl}zno?X2G}>4<+7R`1F}UTZ>2!+HzWPgoYn`?;N!sSy2te}d zeO|6IiB)wX^PI`n_Fi<gw5{<WlUjEo<(f&el&kP7-QDqmT{J(XaMnAf+Fc{stuZ&S zN^L^rf=P41mTIKartN?=_%(HV`!2=8UDA8+(sO%)xCeP&=;ORpPi{=5Qee#+=eRrg zA-mk=+;z#kB!#B=O*Yj=IMoNKUFI7Lx?b0$67GI(is`)p7aA+|YJa>lX?&zHA@;P< z%cG5EGtCUML7oD2LxQ4tLE&_+zzG>h9m%JhK#Nki^@_5<R`Rd%y4-@S;N!Yla+pH$ ziwebU_KyH4bvv^)RjH^*i9J8rK_EA2VQ1)@(5#G#z1Sk6Y7wQQro_i9V0DnuLj0vT zLaYiUo}((P+xu*FwcS*iK!Vj`RE3invqz(QnqHO`rfo<;M1t4dIqAxEbEEx2SJ|Ol z!@e9ReuB}4Wh;Ssy2Z$Q-*f8?i$A4y*1As#VcRA%`HEuK=g4yWd$FcuyRl%~D&cLQ z0DK|vww*{lt0XzsM(b74C6qANhNa8s#MdrW_sFFRjvaW7WG~SR_ljvG&@1&kPoLL% zKxC14L-yGL)mIDP!NC5Lo-mVQufz-e62?Y5gtJ5b_hF*_;J_4c*CcM!0O>XZ%xwxo zF}h>(8Q&C54e?I>4V*hgkFMS55uNRAFKI=^G^W0VleLADuHwR7S%M{p*zq#E*t3zi z$Eu=b^{G&f=CP2DYhq(aiI#Qy=H};1+HI$4)Vm|2er#moBV0mTiJ)io>FoAf*+v$L zWAS}UVd<FGf;q#=5!2e$xNAkn5wa%qj?hHGT+`f1X}HNFLy^2ou&dC<F0g9#sZ^Gw zBZ-Zp)n_dL&z=eTt9u9Fju}lW#^Lq)eo2j1W@LfAxl*%|@SPL2dpqNSwCOh4w-$Ys zLi2eEx=^}CffR4}*?ZAD`kBz}_dh@&(@#?Qul%TfAn?bV>OY25EdO3<bNN$I-C{%d zsi?lxB~yf5H!CSukX;sNOEiTZhNGuU&}cwGNT|MFKVuP+1UZIhBg+Uxf|!Jj<fPm3 zaLO=@i&0bLM?LhDy<y#~2*@d59E-~dsHh|u;R{PAAkVKYV&M-#h#O{5XfMc>8)yX@ z1v&VOm^r;L)xil+ihGC%I2ipdX^J)4QOge`;ob)^kys%hl3lSPmMSWbT8a|@#af22 z<T~wZZDKeD-KBuv9~R#=IuujrFXyvoqs$V?i_5Zmpe-WHsxm{<g*?6{f*r$H?Ny>7 zsp$+o7z4%)O3g9pE7Bp4ASBy`WEVqAC>#w$-X_)+K-reOBUb4L4}hHGyF+6sK;#k0 z_$6J&q>mX0p<ozPMMP9DA_Im>k?;os^VI)9NK9{oLV)1=&mW=Mq+gLJ;HHb1M1*=& z+JVu0@)`h$1qF3>TtWa~;^AcUFbTm%)Z#Kihh|g`I88*{2V5D8k$MH;M!+^greg5n z5i}%Scmy;80@KFI@&bSG4ayIq@l8%6l;T}xsfo1hDjg!6;@u$A3q+2HjTnL#CC!Z$ zZiqC1Afl7-wT0;r7L<#0DWtI*#9BM|OMYCdpvFK10#C%yQQ|ay)q}zD!C)@O2_6Kz z7z5G`GSNB^NE?fzbNPuu4+cQY6Y;3i0UFeUQHbpm3&YUxH5y?U#p!{-4yc8JH8$q~ z3rO<#!6N`mg9(V`L283H7D-z!^~E&Cxb5{qh6$m7#}&iUfgmo^vEK|C^adoW#FvRj znOt6K*3lzk<<dOU3=M<do*g~OzOl2vxwyF3*(_80Oj+JuZLL=VU;g&_1WYh1Q!gE^ zH_DjjH>P;=6q>?kCSBB0Y!II!W=3DkQg9TR(p}uF*TH;>_B=<_T=Y5?r&YT~)|LFe zx?Qc=v>)gS-L!W;uKV4)@0lfYM5*@5K`GzNB>&`2GR}>+MyB{=!lu=8Q)~2`OEUS) zqupe7$S|GEFbx|z$@2Z4P0Dr*8Izfq(^+fj=JKlG^6I~q?DFT+{leqvIaMwrmQJOl z`}iU2-b)nP#joM$AOkZQrReEZ&bB^WRPrE7`72XnH`Z#x1B<$zdza5rEmqAoekjGP zhyLC*v$=-7n0fR&g`OsbfhH!|K6aWDI;GOP<oyi^rJc+$_>Y8nJeo8!HY<sAnTy*h z{fyT%#dX_$n)EXGUgog_LtA!VAYCeuuBRVSDo;JK_kr1oV$JgT(ZZbg{gv})R{4Cr zu@<U9+yv}WIM$iF!+z<edG(tpS*lh$a@&L1=p$jLjOJ63CV~$QwG^oa%u9;%_aW%` zi%uS0DOz`uqdEk!imjb!mu3n3mk-;BDBSl4|MvBp&oO1Gw4bG;YiwQvy2S6fcB^P} z@3W|<e8`Pm7|~eM^PO7L6|NHtm1@mT6?Y%jX?V`53*Ck`b5YsM%+)n69u|>hTTYuy z&oyD>%1%Apq0CHjW=_*guZ1lGpsnj6&CQk8&MDUtk5SL=X3pZ=H=q3y`uAfH1)aPK zCOPI9K2okCmbz5*dKy^u8n%N^lg*9E*J*W@V*Jdy;7*}#Yx5fyiWlA08&jL+61KJh zjj;{g`%TB<tG1XcX*K6eTlaK?Hw9d*9l9gCA}p=^#pJl%airNn1>e2JHp5KCCRWdQ zXF-cw=;1cjx{A#n;=hSoSB=pd)>F^Ct4-QhYDhv$W4y{&x`1KuT$7#Y%r^R-AK^z8 z?je6<4JkP-PB#lva=aHa9{)Bhab3=MMUCA{C%=`v-B{les!$R$*glz9Wbd%#nu2i$ zWNPW8`MA^XQ?8KkQsdNbgH~p>bP<d;tuK(;1jr-{l;%LRiw=l@CDH_o^CC)hb;V-? z2q{7p`~nVhA9C&Ldp$a}h4xORX=_%HS}8_hWS#bz*z|egYM<w7*STNq%CqwOoJ=)1 zR2>LUHK@5o_iSsv6Idzkti}C$kZ*4q-?C;7R;#Y!nsFwdnHVx>m<Eqtt`AB9^-e++ zHF0s+F-T4sbDo?-kY$og3eS>i%Y^o98L@p8s*SydG}l7KsBSu&aIStE54QR~EZVMH z*56HEKwsv_nx=%pDmm+;^@%?o(Rloe-Xna^tFaVlTj_B#p~UTF<pa8{Uxj~;>!tY_ zs9W--uZ-{d!Em)ff&amfjL-$XV=EnGTN!>cu_*M1=Y^O}Pf|avI%d^)rbK(DOg4?` zOX8iE)#*L$9}tj*{$IKX(9<#eH?1iv6WhO~nfz2^Z8umDzH)T?VyWebxVn+apirz6 zLC@C<rbAFqQdwv%YX>2-iX@-TT}f$4$I6i+VyxQfW*JP+2Rl4-LJOqA$Ndo%$iVqA zgnbL;5@3R(>5a_t1&IbA3;khet?&dT`9tRbcD?Zi!t(ThVJQvl9;6ZQN@e5$+#=CL zfIxGosQIwYCfFK*UVqW{T5wnpYvd%<;`Pc>6XN*|AfR<5DDuKkb03=3$;U%Er1hvc zE$Ww&%(lTH*GJSlxZz=N3=}$sCHaHrClm3)6eZ_lq*dpb_#K*qJJEp6%g?v*=Nq4D zNo`8)_7_A~P{8Y8$ogZG7zsFofz_)ase@Hv(2F$o%bZ68R#n7cAgYfK5&n|FCo(hl z=T=S;gzn>?fUbdHhF5TtZgS^ifUs(W(crhvGZqH8z^U?sLEOVBhfATm8Fj9ek1rMu zOYj)37GPRr48WMfqCViX$oms_qb5E`xIf1pNgwABH%j6yUPP#GL~xE|DUxWGnlgGf z$hm&NH&`f5AMQ>^geJQfh~Lj;55M3L?gb)k$Yg}8MEpCJyFeVq^8hza=BzJ%w4ekB zyBvm}IMJxYpFz|@&OQNK4#Z4FO)o!902K8O4opywX%Wz*kPHOMAE|ILo`SER3{wKo zsu(`j$uF_}Z8`q5(v}`mBGZG99e^UkgOA$}I)0X)-!GCwkLe={*!T=#)JciU0w|zZ zA59JgAq$9sUPDQ7A^sF5-K{z)!Al;)EI|U8LU1gPDm_FBoh64CU6Zh`$+6j$q**7D z6kS#KbZ7VL@OI5@!Rk%A=`<$-ot7oXYk7Ou_xqP8%c7OS{+fany9JLV;psJ{#kS&o zN>yw!u-Ob;kKBDihU;eMZlZ|vH{$!XLWA_w_Ck@wPnpWAMxvR$eEetMYUchqT&$A( zk&)tYlIekg_sE_X>wO<P^}*|~+%e@<0bj$u;+pkl(@`=)0BE#B;fKj?M$Ro}j#9Wl zF*mhX>19*KUV0Rl0o)vuQLRjDx_F`JC_F{p5mVk)bOfzA;x)_`4ATY4O;Og?Ds7ir zsQOD9qa6~r?7oWcn<vpnBc;MN<;=dJ=m?lo_49LzCKY~su&CHJL%e7Agt1YU<Cm|P zF?3?Gcyh9M>e3}2_Zh*}@@{QpuV$z>%~4R**zZtVY=g-u{9LDau)s6uKnjQuLX)o` z*&LF)yua2OTg~d1ESC0@r(2~reacpf%2uK6YzhsEx~4BU2R_!_mIJrWB7E~a1}-g4 zE|sv?84JBC-hC>OfbXJ$Mjei3D6n-`&~-T2d*jy`$K_Ca&}cV7**nc0Z;_lYDolGN zw0kCYgV&;WGX=Yi-n)&GA@_=NcJ1AE?R~o+y{gOSPk);A5OSHjVm3ycxZgi~D;Ll1 zGkj5T?G$xKX<E|>2c-?doXB6g6>cUH`z5d1uD(K!&ws<|%&e4NV)Yq-8=XuDki`Y> zwDmyq*e$*wYLGqE(LUL`ug;8e?uz!k-KE>VS_QYh@n_BcGT;qQ5Hc^RPFwd>k&;9= zlUI#y^1@Z_c0VVp<$Be*S%{|fa!T!}P(81S%$ege-mOlFdJl{J()`i}KB0<wyra|6 zHA{VAgqBLtnlw02sOkRgTGgG}#RI|ut)mIkX<UQuKM~;iqFk810_d{Q@X#9V@~LGB znsU)+%Fpw0Hi=W{w%$#k)6B_Di?tmGYD)&Kvyw)b!s-qGnIX)${0giy_Ax^BwQul( z+oTJ^{<m^dK3CNAkmoj8J=W`x!oLS6qfJneKZPR?#Mx<>%$4e>%O^iV#FP7_9z1tC zAy6j|Tja7MAJX?D-9#)=I8a?0b9sQ-vvr*+d$r!FKA@pwqJOIj;_4hQog2?Pg$_)u zxg1y1`*=ad&3-rU(_nHp;~b`15N$;tuevh*F_xx!qAO{b3T3}w={|v<+uWA#1Vi{U zhs_!2H9~N5wAm-g?tXTmdf33LW|fepv0Hz`w1+*XM!Q~Tr^Qg#&8C9?%XC_=^m61C zvWB0QVzrb#JQMN>LsLkB6=n3#Z%~K1z$ej6I1U=sU}-@|GrP@1$<aNelu6_8>l>=4 zFTu(mHRjwP>^IVEfcW@^Cv$JWx*6(oD|g2}a|3hx3wMKS!el>}vNegMwTWF5@uoBJ zCS}z+$tpX^Z6d#|qO8YuDjL_F0?XyI*TAa}Y}H45aI-o(B<D{ny9?YdzXJg0#o2v( zXm}EHLHVACS~-A5GQh?iN$a}v4YIi!g`3E0Iqs&CiD+39VHx=77EEdslTP0q*o68! z_lV?}7c`X3{~utKjs9OcHvGWoe-rnzu>Na-*rmq*X=<ue1dLo0DksbB1Ub1X_2vUV zLI>NSYm<ki>bzfb8dfJ#tr49YCsLIua89l_a5By?x^(Jfg6NnVBjq`yd|_5)J^xWV zq^sLQ0m@7(n>EcW>NRJn=gTmpv_#1>VLTUibO~(Ci-KK)OSaFr#Lgr_yMTk`onbe= zzR*&7^6e<1(#<&VZ#+<A95)C5<35k{e#6fWu@=JsKqN{o2ghO(oseg<jD3i@iuJ1_ zju2M7EvX5jh<zYKUPm(q&tpD;1ecync6l>oTr=@X;bz-GX)FP)Ej8c)@s*sMA{Rz9 zF5xbX%>)G1X*yL3$jJ6YTr$Q>Pp)r$GqOlHB4QUNM~-wV0WFTXRA3m?nTYzZxyWD` z08oi3W23k1M8W2s!Xpr?2oyDuWizA*@j}Q?1rl#to`0zK8EJnIZX@2&A>}ebBHmDB zk4yLncr2*kuV=X9-4sul;{ynlc^RD?A6U5K?7F)Ob!GVb7`GW#JwH)$nQ^j(WCN4f zU}D5i(-T;2vPwxu$&s%+%+pT_Phqp@D1qRqFD;AYR@%Zv>LU<x4HRG4VmJ;6G%%=( zp8~Kp0~)m)talxo2o+GxbPY=$hQ;BOAQ?~%2OsPdv#fs=3l*qtd>;rBCy&4oeGsrb z$F`6(VC9$0I24zei_{W;>tV1G9N(j`^Ax?mYa2`%UhjhUxWzcCSEnL%C7e33Ee^S~ z0%0XNR$L2!nK&^Tna~875;_6|kID~WGD4?YDbv&9{&VOnc-^ZoM|;O-&vzg(b8aZr zA8XJbSIw(hr)%BqX>OSBdtWqSs1BnxtiXMa3fky4zV)z&lqyCYMqR7Uja1``Ep@wv zs(btp9gUUhsfb$FN6)@*FJnlILu5Yw`tzIyX-A)k_a1Ya!HwRWx#G##O^PM2KEvb4 zSYP9&6ERvQbw170+18B9D}xCKZ62b^EU0*)b;2NYs5xvQW5eOiv>=*LjkKwS`J*I# zQ3o=xaJihNc%!jkgDU&V+uW1VrBngPbpE!=glaS5es>>pVZfpS6!Pbg=7NnU|EqK! z9O|BX1`CNYOW`t2{Cv-O7b^HJ_cOv*50!aIjD>Dx$QPgFUSy0dM)qritWXuA&?|8s zg#8(yx$?%XhkzCvFCT>ck51ppC2jT4nYxUj8;~y8wyHRHxvGYEEgvL{ki;ijqh|K_ zwWCgw)BX16FcM}=FuAy4y|dz71uvh(S_jM(=ItTdjAKUTiYzWG)*sz+FC*MT?ihF% z@`8DiYw_V94R6ETUthZc8DjT+QjZAT<;&al(s`wiPb)}ktr;|#s{KNnCF+~W=wUmR zf@U9YjK5FRoi%b^mpcmTOT97~jL+CTrwk;I^0&rxQ>_7yXKr6|FE(nnTZpYW6=%l1 zd%|DVvTVNy374oe6*H<%<(oYnCQ>%*cc^SNGg`Dox51YVT8tqYk2aEzE<Ms+0q>Dd zS&6y?oL%m;NoMt(?~kmC6BDgD*w^01%58oti)vmXRjB)wF!3#@``xd&K}Qzuj@l_& zhHji`=vDFRR+|U65-UMOJ})s(q;NeHwL@vW#21gA_Y3PcurdzMB<-30xJm2l-Zm7! ztTp|0T~z(hBKNULf9Xoq?YX7sZV_Bb6*yLf)wUJ2CJUzdgW0|fx2guEtwrMW?%+;i zxy)0LA|Wp+DQc~x9lf>jb;+8g21WV=HcfX+*i51KLuV;2jEp`k2ko|L>R-t&>7-88 z<$UqEiPXYx**eE^lD&G|j1~0G0`6<<pZ-&;)eJH|vy|=kE3kOTKBzrUCo<C0nPc1b zyZgkDT*~^4`M!%ZJf<fsc4r9Z#@*$k&b0LGU4rFk81GwEO`=(ud<`{azAJZ=9eDED zl)wvMOBd>wQx(R=ld(rlZl*pe+7)cle)$MCZA3dcVK*wF4|NnakAw&u^e@ON3`k4; zgA;iM2c=Olt06Hh5<>1(AS%NBYj!}^L;R*a{Hl!5fstXsQ<&f?w_fFYyN6XbvaHl7 zn@43S+QiVuE2k8BJ4IYe#fN;<w_2x%_ZGvq+2^r<sEmY_t3ZdA4kYj%meX~cdB}7} z--sK1QAK<2pYK;V;>G!#QkJg*aPIn?l9m$_DkoP)#5qq!L}W~fL8z!=YP|JCVR`F` z8HI}*(<8sTt0xmG`fuqWxY!aJ*6UxB-vFX<LXQ7`@MEN-|JTkI{{#FOng4YTsj*>$ z!j9lQqxynKl+^0g5)@YeqDG{KFjgQvC<!rO(-@aWRJ(WG5~IGkz$iY<lAe<j7Rt7? zWuv;pK9ch!Ea@NsMU9G%^DQnH_R}iN&{NB|u0RTkff7Mk{u{5-{{|okT|*5++WCxS z<;Fk1mlAI!+&Fa|_jH<rXhgQv5TGUX9DtW=KqpToZfB0FiN;fPWQP#Z7()$?y9|8@ zbH+ZV!pAKtFm$kD4@Cd!>{aenG16xt@yI5MB{y?lENC-tDI-Tff4#~O;_XHo#o$IL z);y2pA9Ra}2Rfi~Hv#|0fNBlOYV9G(z8+Kd7mKChkvz0$Q0ZLVA<Fw-yli1UqGCI^ zTg1@a0#Y>*H*v5O<0M3)F}zNHRuMEm$BDt3S3bZLH2<v7Lm@dL*3~-#H6h_iCp#pb zv~vV%FS<2+kr%zNLYAApIHBKv17Bmpb@q%3!1o8E9HXFQ(i~a1JH1S``=txE0yu%L z88n#S_lymKd%1prKIi4sC<c#~{1}~dV6)s1n&grNIi+^VD@9?^e`iI9vZ4W$7Rsff z@<{}W7(mvRD}p|iTs(IGmhc<GaF~jUMH}~)2;0EWADhN;K>JT2tYK05uL?j@fzHDq zOFfxH2?+oeu$)i~THsAI>4T-=cMWe_#Q~&(_LYP{tAK>YehE=Q{@fkC5EYyg-%x=b z^4njXzLHxo5>H1o?=Vk@Oq^{L=)kEs9Yb3x?2sUT|8SjrHLNTOvtSKC+fBC@IjhU? zs#4Q;Qv*xY&5oD5D+32FcL$etbC&&*Zdx4f_10$<&k^6Rs-*e6RUyQNV)@R)tC;V1 zvhMtsD1(4K?`9q;)h%KBkUfkcbd+3&B}J4}vY2}3gdMgnU*j9bTU!NTu(5(ufY^p- zlsWbYQ!<^r7s8fXjG>kE(Fq`>Ccp|!XoR84O+JgWT&=^5n^FT-<M_-|w_Kwf*@hW) z190Uqa^*1f00B9!O9aunY%K0+c%Fin`wmr4P95JM-nQ<5VulYTY99;Ym)}vSyxNhu zI*>l0hC?%pd!{MjJ2E&vJcqfxb1vGN(AmE++vlD%RH3u6egYRYUFd9G5+~XF<1=?K z`^Miaivs8&AvQn3vH*JMe+4N<3#9d0B!2I&^;owe;o2Jy0Vy$C;=UBlbGZ`H*h)(v z6_~JPHfNkpWNx@HjW%?bNB035LqX>x{kE<p4^+B7Q_|j(e|oNI1*LrAHKnS}305|F z+RA&n+hR85V}hC?IXUyRni-RD-y_{uoKg~f_S>=A#NQoYT<ar$W#=4F>>PPaN7<f{ z*eG{DI~3?L6l^(+OXHv$d8RAB)nC7J)l|9SeQS~vuMiQl<|Uc<IM|-(xo`pR%FcRg zjOE!H+_;pkc<yV>T-DJn$j2OIuxp?=lN08L$JZi>z%3`l2TF(-AQRdXM`2eJ6NV<g zi`JV1i_;{=BmUW2iMRI>>@DV!LxyK!f(Jhz7CeL~UT0BSn&rZ-#)5C!Pq5kJ|5<Yp ztyC6oZ&qLdQ}6UL+~@@F?P_hf7Gorv!@)V3;6s1TyKFtkaI>2@&~NIXcSh0D`E5!5 z)(z?1<Mc4nl6&89u7&z5IRQOmv}5b^B~v#OyebnseKOOv=-4&4Mw&a^!qT3P^K-vE z8-`Qc)vg%tD~I#RBY{0viq~_C7i)`|@f0^Pn~E(?^6sec&u@zRQZ?82H5_fktM|%t z-Gi6ud&%4h_<b4C8j1qdeJ=YLstPr^!_o*WPOUlzbmSsRqy<8r$7rPrwfTL0^I%R3 zR?|4JfSq@zuJaM?C&BDhdFhKX`r7*<UO(CoYFvVnSL67C)QHo0X{S^AS>^W9){_Pk zSV$ZbQwGRECdk3f-~LIkv92C*wbGcihO@ofHT(t6ac;FlUp^D5qMz5F_jl$;1uPN8 zml;KuS22y(XE#sCXSg4n?TH6_ZLm#$VzLg&N929`cd|<~=jOq!(Mq_+i{UBKu4b1K zv(UY%oim~CcYRJIUyPO#?I<)T@`WXdIo(A**d)(HeZ7)pC3t3<bdEu%K5dXMzTdVk ztE(=(t`D`|H`-2*7g}(SX*xB-0xkOaqp?G~J|vFqdk_$}g2Hg132fhLxh8&BXcLw| zA~vvuX%(h?1B|#)ru+k{G0^{O&ku(GPLE;y*9NQqmC|j9{TEMlHMUAAID5^tydntd zGT#zj2mvUZ7DeGV2UJ+<_T$dZq{6a`pHY`RlBj@1=$Hrh{l$G0YaKUKA0#;n0Yudc zEtH*oFGLWVLGXM?HeS;60U3EzR1DHE0H?-Ju3_KLuSPfmU2_7mh}U_{mO(Iq5ntdR zb!<)vU`Y0RG}2H6O3oh{lbDZ^$D$DcdNhY{Mr>TK699LFD$eu;CK80hpb-QYb)-Qh zuMQ>{hDT@@6^It*H(-F<qPa$?^F=&;FFSVd9b#^&9M9gpn3S+UCqAvoy^0y>{v2OU zi5x~4G3pGgP-4U}7<Cl1{Uqc*vjW_knLDI}JV0fUK76=r;Ki@I0OJ{`P=z}5(FG6% zf0St?_5<=ewt66Ht{1mO$XKy+IX(-szoSJBD<Oq(^V`E#L`^LmG3rQ?jwnbQ@4aPW zmjDTMahrf{hY=5O;|vr?TxQ}Clt>f^UYLYqfyM@?<~RXHUQQYih>Vsr#nFNOk^*;R zl{ALo<SE((`%!;777<9<T&Qb8l2g&xP$gySFzOE9?(F$fpfB`)r!;`h^obeg^>X<? zfCJ2|L68Cvl;%MJ$iWvTMO(x^$SVN@$lRJMfgCu<lSPOnV+H3k0JJN;FwHz##iw4i z<yjwuQ2^3m<nR>(NQkhMqxp@7A(LUz_fjPUf%ub}QGh$7+e+s`N<&;Iuv9r`@vSws z*eBJW_BK_8qtj^-9#FWbTT3eg4!e)h7&GELuD?GUc#|#j>R#%GKT6*oJ$+$)V`Xn= z>uSS20O<Jv->Z1N)IJ@lu}gk$)g>u3{Hpag+7p$^(RZY3I_T-Ja#{7#Z|F0Lonp!K zW)ZdLDZ}`-%wRUUKi=RfYKAD!1~ngi7R|UJpB@i7kNDfpu{pqz0^!1#-UWy8D2(8Z zIH+C*Bg`iF`*<#^97H{cK4y#{j~b#%P?_4Uf}_^W`NP0*%4G0}%6;ctk#LogrPS(b z?L$nFc5SncU3}Y}W1k_?j@hsIybO-3pGz8ppgOZrPzVqG^h8>~EtPH6;NH<nI(@bd zf@2!h1IjL;|2wf{Q<|1?%RsulJ3+QwfJX7?HbKqG`c$Q<7+p!zibpk~G2E4E>VuA( z#_iz_1US9Z5b?UzZ2NhkO?h{V1^QZaom4f%OIfJ<jQO>>d5cOh#8q;$<Gj44baI>q zO<Re|V{XWyRY5h6oM4G6W3e!qU<obW;#lU)<?V$Lv{ejnI)hhVq()QiSTl{10;VOc zKWxVgoECL>T+6FF%&_M`VM8pQHiH$5Rx9p!>TkuH{M)+<ckD_m`H)(4Y*mFlam-<e z#l1zcXBwJE?kJb^J&AEv{d$Me6z9|?>uEW^@Ldn}1SLwcs+xm)w0E{lD}r<n>&CC~ zz53$$Dx8{A$k>%5fg?NA>j|tgZ^_e&tZ0H!O_}B_MlOAS;fXeZmiGpmMQW9FYUUKl z=*X0}T2rL$mhXsf+Rp%X$)l3;6KhRK<+dP;IV7B_?x3C{ynLEeyDwR5IGt<1V{dS+ z<bj7zjE0ji;?|tbI@_>FCy}W4=R{SW<0<vnk*5q>6w#^m8Xd&wlCFgQs1~-DkB-bK zl0wp%UT#mHFYA8QQ=jZ_f{GX%%{*I(rzUkAR`OHD)}2hxh1dF>uHC$B3)+)s`paC+ znI7gHF|NxJow%yEKNY`=B5LD@U2=rB#PqutL-)sgg^w6iV}&b6bgF&QWXj*Ho*3Qb zgt^KN@9buY3^}zK4j=O(-DbIu^;5>_grk^r5)P``^AI5#+86CKQZ;b8=R+ta&!h*; zyUgA3DpT6Gsv(|)SG`+SBQt8&tu4K+yZiqfQBs+AW6FHstFJo*t5d70%{wRqxHXGZ zy6ix7*);b55&1cwks`_XqVMB?Eb&Sh`rh^N2)03^ytXL00?UNcvtS*#KpAnaB2?&@ zS#m1!&J}vclJlCP_s=jHm3h=zE%vaF@WaO)gRoZy`|X<b!t{ADle~u}QCD{9!=W`h zcWaUsVy+GO(8GE_0}wS^+R|<?@oybR@(LPE+mu#knzAjh2F%LZqPmK>PW_$hiIVP{ zY=W7~M%2TzlsS^%A!~)LvXytwo}9;7J)I5|v=&KcGD~<H>Jps@pL!43R6c@Fc;?=D znty;brXMxnzofkU50{gFZ)NpEd9l@Gh4GoGnKcAP2`3A02M`9VG4Ig3#9Xuq0dyBn zM1f8r;iviibS+9z8*{iH8RIo2m#1u&PQZIt=tT5t2CO5NAFa@j@l^@>^PUydGHPg< zRx&g4EW_Wh1ZAs+LbY|^pnkAa?toB>aN_)a@;Pr&1Y>}b8gUthV^DS>+*qV|YAm4& zWaMj50dnJbl0Tj%DhR>z_)qTnqlmA)cqjy#brD6qy;W%AW2>g(40SV*hw&pEce{l+ zzzOzL;KaFaV#4M_NNq}RW1)t8^sG9?AxTxoY+Qh@8C5qU08vb{BYxQO0Q!H+XX1?5 z!BK#OXPyGkQ5pzw@geHPr{$60bFvws%d!o_%jhKP4?s8y#0bR_*eoINtR_(d@WUO0 z{rU;mNynfqo7V8jA;7VTkyea?MiR(PwJ#ckXa;#mx$GeEf)B&lQuy2+LWl`FjaB0R zf<a!SvcV$(zv4{;Ti{4$DMGE{AR=U$Pz}1<X%UNw2+D1Wf&}?(ie?3Z$iN_-;w2l+ z2x0ou*R3?1kn4&8^A+sr5ab9=v=4HLVXb1ggPlSI9o6u?ourI{|MK$;_r|lVTd6%U zq+O{?uu5gao2zB5005XmjV%&3U=m>l(1R%ri0~Usv#kIEa4Cu(_agzVtpl+4u`>Yj zbj-K~dpgoq(z8|KK8U_S2BA@r9O5GYHws6Pi&!u##};#v_wOVh2(MQ{AR?fY6ZYE! zVDbbv4!1)Z%XEl{29#AeeweOQHRz#z+S!4z8T|5hv;Tfc{?^Xo*4oy(PUn`ZTSKkU zz3yb2o1XV|B`9Xvys!t}EPJq@M<<;Z`|=!~B4<V4+_Ybi_1<Y~J3OK&?>sybeRG?d z0%jdCS5xXfIO2NbE<z+_8c4nHz?d3h3QnbrcqN046#15+`1NOlT?3-SdL66(QLEZn z9_gxWO?KW|fnCyz`9XN!H+tPWwXs^H)$8rb@$5C_xXB+OTkAsR&vm@oa~{?D(LTZe zf6np(q}>eZ`3|X<tNE-o0}Ai<Alp%)>hD=o<Xb}>Lf0{KtgDuwGY;{6F-=0-gwqkF zL&HaV4V*i-#cVaj#8=M&X<F$PH3iZ<?Tj4J(~dHav<Kd(is37Mo08Nwo+c?)GzLcd zn`?USU~)NSa=DGn03XbGNkOpSv03G@S<Sep{mn`J4F1Pt{fY$r96<)Oa>PFp(9J2$ zIx+eXmxgEIc)pZE#+7nw3QC9*HRS2n?L?Ex{EmgQ1bMvo0qS)6-B8K2!b|x2g{|#W zeC@%9J6?fKIlP`L&w7{5zccFTGun5uyMVJ=PpO5fDa^K-hCb9JS((Qd5Pd@|{x zP)D{F+tXAd&nbBp%3q}1Z(&Pa`sj_yI3DE~mE6+eD&AiwUEIO+&zT<5ewd6MkRviq zyJss<HrvOc^?_W23kC0f5-W}~1B!6li42t$43*1iYy6n++`KD1Qmt!laO5k><SQE) z4xD#Zt8#a`Hb=MZH`1#`XLQO-`peqCt4yDtW;p+hQ&lrGgr4rl8gKp7C=Bl@`&5(z zwB3m}XFi&C*(d2$lhs?=*3XE6RbP2r#ydMEqt8uPncB5;Gv`^yhScPBk2JrmmZM)o zO2{~0uS)rF6$54xwy9zr3#@%2Uz6UuCDCD|6TVN?)VnL{KaMCYFUr{s-*%U)%b`&Q zoJD;EQG4{0Kb~4%!cyt)SF>~O$NG}$LF>PSXjVqo?%B9#+K*fyYSaFLR%_{Pf!I#y z8(kGWG`L%h$V;VGlv)<2vXAi2Fjx9SntVm`yKv6l+&F8DVtELc9B6D?T~acX{H0m? zxYmiM7p@siD^NA!DQa7^{M5nKm3&D^c$ECg^zC7XM>SAUPFt#{=jGmlraz~c^jJ&t z#@A8=W!0?QCM^n7MgvyCA3DUlR03*-D%XaaSJ=}=9lbz0q3ijJf#UI`oZ~&=*l<eo zh+V-InsR)!lB6&LDq2@QQDgP`oUKJ$dnb4f$aWVnO;L(a<}qs#o|l_O16p;?Zwl}C z<)NZP_vkj|aN|M=^=Bk<qEEBEJ)kPoLR0QrOxTO*^>K8jxK@k%kJah-yvEx%Fe1NJ z?mvJPE8~Axy#I%O$^5_d?0En8_kjk-cEI)1!3aP51dkYn)gj+$Aj*ZaV;Pv?D~Xkf zp#pz;D)bNcI#pHf8>Z_41T^RKwuw(!)Bx8Gk6Pht^S}GaaMp4VxQ96T7q;%aIi`}j zON5Ridthz#SNfr$fIpy6Op2K;qB!Ll11_%XF;yF#o?2Snt9eNkcpgP69afwalhCiY zzsH3PTH@TPK@a<V+<tP^Nlsz;CNO*b<AncvDfK@S{?B~>#e^B<#8m0z?2Z|F`GJ43 zJJ8*Kx(Mq({Hv`0(O3S9i(IZt+h)>XfZurX1jpLd9zUm^FE_0>DyC|(2*YHdRRu$d zHOBH{*E2EE!p4ax?nCPlz`VYPx+D4b{qFs167*e#h-$M?Wg~(+QV72y1t@_ykP&bT zLl)JT#7E&@gs+$7Cw@adLy@U${NniW*jDNx&bNzcv;Q>gT<k9*B5~x=4<Hd8rY}uO z6cmJjttG6CB2eLU(?xM)&rEBz@R2~wLPYSgzybSLixA&wOU-$~tKHk7-Q8jImtcY! zK)8U!*ixUFJE}rsO~E#4z>&iG4x&_E0v8`XiU13xeZsOh=lgX#iO3!>@R9-$q-Y4R z7_&hZ%YcxoQuRWp49hA4mXr1VYvay*y$58!owGaP+p?OPFV#hp`yoZ_aqQy*s<L^` z?*~GUSH#M5wfAsBO)1}EdG_f0GO|nfD07n*lT4G5s_bAG@a9@|D_xEK{?6~Zoz!+u zieFaiuIAZy45q_kcE*)u-O7nebQ=sd_0qY`q8>nyN1HpAp?4u2z@?ghCf=P?)`}*N zg*PXf7#1Z(7A0{~S}w@at;KbS<h}aCUlSO2klR>&boRX#+_FroUs^NK^|kS-q4Ua} zE70*#`L&TB>uHw``*qMgHwS*sJ%iA63gGsxAa#id-1%YYv71hIc33?Nom1zo)NeLs z2~D36P?wrFAEZ6cQPke<;s$DaTnyYT|E{Y<dlD8e!y(FMJR{^4({kS%xMLYX)I|^U zNNkOc*cEP$8#eWga=xs}9eU%ibDVvHJhPb&Kkky*xWCF}9pS=jExdjMAUii`zxD2I zen-@R7dMII8HemU+Y;%ZRS#|RvGSNWu9u2w^0F-~!Zn({4G!w;cp@CE#6e>_t;nz` z%VGWo;91{gW*rzb{T@e=;eKL;!oD8OU{TjCeZqHtG){qBoa~WaglhY|+CRQMp-uBP z$@_<A<9{~t|MLLS{Ya($pU?k&#ktJXRNNCo@!NSt{Y>L3D!on>rRmcjM?}YPZQdlO zz$(bp;6t1J{r%}8fIx@L@GA~!6q;;q`t;iC*o^cy$Q2+Eda_2%UA{P~oE$Vi|23Q# zNHPMS1rR7$7hvm;XT-baHL_k9zd++_*UN&(d&RNNWBXiP#75<ZX5SG4(2FrdaUKE8 zOX2t>D+t)pDybjd64VF!_W=Z*48G~27dOb(xGic@P!oo!M=s2&I1ur<zd;C|DwLQ% zzD9@yK1m#(6=w#%C6Z4Id40ex6`TV*N2@c&E?VR7>7ijP-@xk_3p3zkbqvy09a2EH zEdFu`yV@X$JM^PP7m)dsYtV(St;ONdI}v`~u)n-(V9s<o&!joF$VQ*YT_BDd_zLP< zuZvlUnz252{G_dsj4ZIjJ~tfZ82IiK<m!GT>Uog<n5RLEn)Wf1DG8d<dRM^%dbN4W z5GG$hMr`S!@cT?`!!lBf-oUObVKtK`mL{QvqZgue<WDteR7@0e$F0*6E3UvYk?qrt z+B<^C#{oG%!iO&R@@M}?H1jU!weg+lN9McY^A12$-s885j!~_Z2^F0zmyqrH#rIy1 zO6D$7ctP4eF5m60Tt*Se8}*XP`G+mP`+}15Tt;vBt*kvq{cQXennRwjP1-?7jYQ9* zXp#Xv_|MGB1h?UW#5{%DEx*Wuh<)s#=ebsL4&>2aD*N+iz?#y_RXHF&C$O&9n_4GG z?4txa96ksms@lOv?A@WuQy4td<MnyVhp<zuKwlQBp@OikCNIdKsM0Ttj1a@47MM4X z&*0zoMvG7Lv%d=CB-=MX_0dYyNw-&vcj+8O_)kra_B}l@plx8$h*97AE(UrdDNf0= z*5(u*u7$-a|2F@aT|7)m&kBE8GC+nY@{!X>Ua$BiPU?gz)C(rmeqFpSgc6_dA`<M= zg=DFEx5Ox&B<WXBrJ-OYJb()s`lh3)bp6yqV4q8rUEib6q$@XUeTdDy9!6b_jR^%# z*GcN^)tye*=hy5)Nt_G_(#m|gyqB!BA1tdZT6C=!&o5_In$8!ybi`xUAyXL7V>Uik z+h5W&((vsU$BteXx~;x*Dj*ADIMxi#|7@L$TvBA4`FIr5II?-YX3#i^4|b5`K_kk! zgM6{^17S7gwIH=#Emv+mERi|EG|5eZM4@5rH?TF@Zpth|({5osGkDhtbnU<xc6ys+ zyR@X+xMiH~Pm``OoSzgw6|XsQmJcy_oBFPktwY?3$|l+|x+@&0Cma@110j*CIZ+4L zgRz?){f1&Rn7k#x09Ul_*82QH)%JJOp&2QdfZfTxmW~^R8m<xiz_r11vigT*goWW> zySLH(A6hK~6YIa$RxbUR91w~k{S=Q+V#myvuFjrQRN`Gyg9Qm_fn>yEw&3+Tv7A60 z^$MhYKDn1lJh@is4ENiJ=C4}07Cx1h6qlB0aiU6zlIV1>^r?L{_&MqkKtQJiP}bcc zLW1Nsm;btmQL*Wh*ZvL8+!61$>@w_B4nSdjSmuL@A=c{{)u8HC2QDHbGq*X0NH}(p zfwra^U<W5ZD#cMbz@e$*hU4f&;xPK$=5yFw(acXYrS#Twgq6Grh2cc~3nXj+nKx_% zxh17n3DoHn@q<Fsb-0Lf{B<!9Wq&c!wZr0@gt^4ht1*I=V~U0Fgy|jT`z<nw5sDj* z#{x~KI1~a72H^fC*XCS<rdc+a^Q-SV$zMg898y3Xhvy>k8~6fux0f{>;MG<7ciw;i zh(Un=TFy_t8Ft|0b5G3X|I@|zs^d2p1j+`ibFcXD7;=pt#iO=t>4#*{4gP!1ffL}x zh|mdyOM1;CF8cif5s5%e4k#oULdP>jEGRA)h-q+;8vs@L2}vC(JROFP^(YE@8JbLR z5}1Lsy%!D7(O}dHPZ<G@6JAy-{+%Eb$yg>{TKxTEF)RqL&PdoHC7$2lE=wQqR|)~W zDot2Yy*FK8l0=(hKpE`DwWEzA4QOnUa?Gkt4ZZ`9;3Ro225y9S@db-R<}3m04MJ1B z9N2RBQ9Pit5X({XtVql~vKHUNAnYu9m%~L|Q&E#Xs+eYg{x3kib#fKNR%&?mFn|S! zjp_3h11Bnx_l3lAjLV3ctE-vU9V4!eEFDS8F$rpNAL{N`ljBPG+0gIZK!x!;;k)2< zUFUcHg9&hBRNt>i+LC6D*Y?t{#<s7<qMel|??=m~_%Et*;?LV(OOYN^m=aS3Dcs$g z_lFs@hTW4d4r8h2-g4{L%NzUa_p04e77Lr7R;Y5cP|-!s+2%MXj3Y}SRx8xH+joc0 z7OFlsB|KeK+zyF}7LWWJb(@!tSg(N&74`OOHoP<DN^>5it8U#f+%;&PaAn7}zb9sz zHfZ5v6lU<wq65l00#*qzrB9Y4UL5(Y#%Co$Xgi|ce21=WQ%Ow<x#+ds9kgJ_b$9L$ zdy*43Um|E-BlB@vEVs9ig!j*O*ZTkF@^(~$^=O>k5lD5B6uJ<KT&nz<N?eilWcq?t z^J#M8jLqStK&AwrR`#UgLaZPWt7hc0f%MT3P1nLOhIV{0-blE+DBFHrggY+cK9+4? z#;6`?yik!H?oifkU~)6M8ajJ&UFzOgKP~wlH<<J23VEzjKiRNwG#qtmYRg@Je7c*_ zkz&_@uQ`8q_}E@b|LZMX&VX>ob;GUugl^kYK9fO1%1ynDrT$0P?6zb5CNHHbkY!n4 z7JO0!E)AWdR#UU53e~NrbjXD;@)DZbM>kY;!MMlgv%27Ga{;;~9^D2@2YX4<#%^)J zpeO!^0EULE<Z(ZF>n&?IATk_+j`^<L^=T&7eQoZtIePIT(BS(=JEj61_WFJ6eu+c) zfVQj9waewfCh_;DzNc~H8q3GrUB%k!he~lJ;Bw}(^Mtb&tFr6m)Jn~U@_V^Uch!ls zoUZbECUlJvIwF+sVZ$l6WzF1lWoScjvE!##n98fycIW(ANmUu-O=(Vf8LNbFmkC9+ zM#8i9G7I+R(nA^*;_c|CN*t|<Z30KfpN0jeuBR)T#IAS!8N{}pjPxCg=ZWAdVcXIR z5t%h>_D7-C&~o!^&7~_)2}^p1h3OrWZ8qOVPH(#QbOV|SU(?6!+{T4R?h?vx)%DY9 z>F-b}$_pMd#w=%V^?tUgo)vO?A`#EjhS;dPx5w#|gXhd}j8D5K_j*PT)~+1sYE##b zLTvkm?76uE8xLR3oXsiU^@->1Y%Q&vu52H~Qm+BxKfOTTZz2pOv7Ei_pb#xBZJ&V! zDWJTcAGU}|QQMISVieXxkDp6RBlB+XKaCW<SYHm<;R72twzpju4xXIJLGq~WE#$() zvDEak&zw7wKR3f&gPEcxPQMUTW=|JHz@oObbY%fOIKB~+-N$<Jr$H+t_=IPL>4a;A z?SyZHA%w|BoAEjVE}-fuN2~uo0qtlv-h03Wbp8Jhjz?n!;?&oF{ocu)xqBX%IRCzg z+Lp1UC22`Fd$fO;nd>{*B0r?X&ZOTvO^o7qJ0xZ+)+_e!!)XX%fQ#M^8xeH;m{^;# za(I`MYc>#UWJs{1mk2$PpG`pUN)2E#Qo)p$z_MP5Vn>~(Bq};`<)M>7?iN+bzoA0+ zIM-66rtWbwNPg&NCsxG4mSxNb*9&la)e9be&`*Pm&OUD7O0&M#lmAWC2Vz?+XuuIX z2y?4WGRcyThf37LXb_kx51!9F78Gw_7)McsgAc7(vt|>*6Ss$u^WhVl8dFdUk-E?w zh{6p(Ube>38iFE<(bt^$Uqj5|NHMdCr2z=bD5*Y|I0G;|Q1bC>L}djzNyYiCqO{9I zgScYEk{}}L9`_W2iioSfgEqOyflcr|9I9;e@?$*i2H<&v=H-M^cxiDv_JZ=zi+$l( ze#nN!x_N{Bouw8Z1f(_qGGwD49QeZx$1Ok2zs~YN<Q{JsCkX}pY&CItaZKcP@!Jhj zVNn#M;66inYw8|BaU{zcIE8+IA~%rijB-)%vT*K_96A7UG)1_cs0b;1s+^{Kq=`T{ zg*|{GJmJ@+Rf&jjg-je`VmLl12}of$m>voYePpyB(*BwF25B&oO0*HCLej9?75!t; zWn#Z3Wb9{#3`XV)rhH48<rzLR0J+#)tDM=Gp;j6WH0#e0?2)=))<B2E2O7I+=(Tz* z6ijUfX_am<&Y;%8(?Wa8z}WARs^Sk*%8m(Xd2J5y1!vM(hL4#aD0M>8^La38QT05x z3GTe06?<*Pa~37$PqRdh&);!zA`Ol46`P{Wc_#nP@~V#uJ1_m?tI_+VIhwIT%;z+W zEW!I0F`jmWIv+bL$iWV2JYK5I`sasAl%WoLY|w!SdE);a;Ee=eLpxB7*5Q=~WI;Jl zjF$h804J_cK{$`#gdmMzm7ta2g&>GvkO0MqVpJ(k-1dGld?F7R7sGNDO%FBR^%1CU zpt_egeJ{4b>phuFjTm-xzX>-CN=DpBS`{Bt5BV2U?l)618OG#6xhy%R9{Mi?oG(Kt z>%arvUI;IaGER7XuvO6l9EmT<B7sQJV3}rkYTyeZ?)l`AWD#Q*|8G39d?{xcO=rqi zUieLAzkk>mva$U4jp6^!FWLUnT=^HZm#vHmhfF$@kY^t#>dRo|EksF}eiA{y0K2R) zBQEPilZB!MsZ#6h?w16aurR9<bKpO%Yj)k=S%lvS{C~ml=y0bVPPD~{<7QC<fIfe* zK}g{H?IV%V&8q%2xF`)*38x`ReFLE*!9T8ldwN=rof?auFSI4p$`%CpZVOD3LjvR3 zilL!FY^|uy1^_9i?3=kHwFTTqaS*Beq|L+V!p-+q>UiJWxv)*U-Y1gXAB5qjA+`ev zIiXhoqbEXG7+W+p!*-h}>lLb|^rOqDF^yMMdbiKtW8=;w-k8PBg`_D-8mG^aVn6PP zX7eIi_u2g`KQuIqa%t#UE!dQ801mZM4#)^?_xH7dA<KBioY?uBW|P%0mD$C{Ft&eo zl2PPD+3;En5h4;nKCP0DwO9`uRvc)A!e57pjF0GCkovESG(NS!;1WVvp<;4MyExps z_p-;lHkRd?=dH;LBV}%zx1>F6CLXlQI@5)G>L;*YOqsv61yKoxgPOr&doDsGMml<s zId)IP`z!BFkv8$_q%K-jfsuJVXMz*QH#KqXS|1f_6`lytV;PoMhs|FV<_IuLsvA0| zGS%QI+@o=57N0!xf?m)otO`S6SVw517Dbtj<nAdjw4n*!h)&T$Kx<XZYGtHC8m%KZ zZKSt=#0PZw<|m~bH+K({Y2+6Kjvxap&%L43k47#026;DGN9mZ|p@H4vk(&g#`+Aqo z$^MRC`xzB&Q&~NUNQ;^onnVx<?nPa#;-C^+-S#Vrv@v_bf%`5odnCYrt5@2%A~NA< zcB+FtaY`9!b<iUfER$I$9qo@_)23n$E9BOn_smkt7-W$hk0?4c>tJvR7Aj`d8x`u> z_ype-awkpdpin7wXB@9LWhaXAg~$cJgTq@4>(|J<bIOZ2na4K%7iDh&97mU{4JT%1 zW`;34W@cuO?HFTbW@cuFn3<V5X0~IB9Wyh>jQ_lQ_ujqr?_2fl9d*@FX>`=xHKSAN zrzM@mqABK-kefLbd@D#P=M|>r$#d0SF(n^~GsvFY98*MDW29rw<~r3wfR5Ooq0{0X z^5tpav*oNaUa|X_j*Y!JiRy+Quaf@c8(}F#vy3k_x?zqc937&A{uo<F{$PjTz`S4Z z1gjXMaGP|K%?@l`dRv1vq8-2|Q~Kz|xu(MCu~w2*{@!B~-U}h=l`hMN$DLgNLDaLc zD8Fb?Wt$e6soKk$OF{46p6_xI<Riq?5HZBAFMUg};=A9FIn|=gy?q||`Zq}sSq1;b zpShX;cN3j|`ZG84Kg&A)BY$4C%@jfjy?n#)viN4)c{s4Y0wpKr-_IkBDXzX+q+Cp; zR#*|%%Jhhm;=d#z58R?!rrLUX&j`r9CbNe|fss(<_1sm3#8?nf(ii+3k%tB*C7<`> z$A*99b=*vnl@}b2VLXa1LF>D7>fo;^8@&sB57%3p;3!>~tx{DQNKAvR-M6C?ynsx@ zO<JLNOGw|Ek3U3zfkjR3Z;*S1t>jIJR!%u1o#(KPHhFuOLM)>3bdW_qP|ih6P(;DF zv$M=Yhn<{=4j{_aP%DX{DlN=!Ql$UTkG)xRA$dQ<Y*lcH#BJ{dJJtWbD%@-q*xKp@ zi;XE?3w_jyHuMUl#L!YN%LwXt{i6Halg2-y4!lFuR;z0V_evFO#}*$G=U;aoS?}b7 zhrU{yjAT=s_e{O(4OvBXJvKys3vC&O={7$jEce_;A-nxDGjpQC9LvKHV5tGWLK~n9 z@^}o8$2Xyikc6QqJHR$=XQa{FBoQ>(RV@#FpOgdYy`Q9PwtID2E?xw3)g_fo5G|fz ze&SJqVDw8HbYTJ34*onJwEx|+F!@FisW<rM4AHZK&G;uRG|j+U&nztxf%b!uH{H~Q zE<8bK;2i20NN!g*42CQkW@*&+YH*O@aSZ*P2&3)C2YyPvEA5g3P|!)pm1m#9C4RJ8 zG^aO<?xYAW1uFhA9uJWdiYyF>JXkJNM+Cd54PGz&LzUY5;<q>sy^5+G++06l7Z#oE z$cdxBN6#kWA0ih)+oiWPTImkAdtMsp3blq2>S-*44pu#^O#1dRPH<v~PUrd&Dw)8> zeaZ?>xJ!$tN+WlNT#w49#eXaliRxW&-0l-rI;!lgxc4q9fie+vXYu+(Q2Ff2NpQ(0 zJq{YGivL(AN+cbUKHF=YW)Tj_L#NqYY#|jGTNbGGeAUwa5XUD!L?|TpX5?-070Sq< z$r|2ZmECzBm2pXzBO+_mvz@=1i#kctT*>Tl)~s5K>dIiS8;o(nen^a3+9^D5C_}!1 z%<$lpO?423R|(}AEt(ZB@lg#Z&7JnZ{-RMX7lW))vJX~<jT7lgQN71(e~{6*kOkcg z{c+IM!?AqulBquBp!v0n!|K3Q_7Q?YrOwfWU>Cu0I+6in2zN;avK6^C?y`4tLrx(a zxQmP)INZxwd-#nSBgXHohb~ZTcQx#g^!>9CDjnwEcsAGnA*-GBe|m$kvT?Kgr%-XX zwsw?GJF0K)xBQVkafU^CwDgefEsA*m`Zv?ptvikg*h%^?M$4}+-o+Q+uX$Py30g4g z))#%IpMZdrlY+~1ZKiSx+wKy;9vG$N6r_U4pF|2ZC*h<Rk1-W9*ZktygW?>^>OW5j zfO0(td`dMU%--$X3VKH63e$B;h2|v>H5I}g8c}r2PeKi1VkauHgQe7-WEs1038QU# z4opMMLv7s)Vug{ik6Kk75QLx&?Ck?w^dQSpJupSTJEyH!*h@X~xVNz-CNts`V&Me7 z!Isgb=gTIGja@SreGSU)*omNGR8x>y9I57~%_Lv?Ot%B(hNCw1Do`QK!Zl1H!{e;C zZ|rgc?Os?;j9|cbM=o2^qmZq|ijQ7Qead%<|CNLu$&ImGt<^njCx*uWp=2TWRiH|D zp5rnJ;?L9zn*ldrMtw)|^o!PsizTu<NxLtzLYjrHT(h==wzNE<KMr`s-8R)lKWv~N zX(H4VZbV5RYi=EzaT^pEHfzR%3)g%Wsx7Y3wA8j}@gyy6RvF4mBu!V@kD_<FwK5uR zs?=62D}gqE7$=ih5Z5HOXlYVM8qy<7(Z&2C)a(K(Gs7zv;qYtdw(lCEsFKUKlTgyF z)Ee?hmE$HF(~BD?B%IR3_IbBQ>tX?)F>l4_iwBNPj1-@((Ao5kpuUT*3@13%25bTh z3IpceT7;7o)6`eU5=knA*e^|R_eoJW^6t-m1LkD&eV_D5pMnpd>`r*}SJWi7E6rwV zkZM2voU#!1^!D_$_wsZ-KmK`peSbh+`sm?#wRd`%xW12(48OU*S{m3y66`7eGqJe6 zfBoj;sVX~x*pZ$ZO(+j+v?Ff(etOh){&IV!$<rkh*1Oi#BOR7ImwO@b?j2?(xTa$^ zt>*OR^nB4t_xiNE;yjjK!eaIfCNUNB0{OE4FwMmSILKH!9Hi{+s&v!`DAF{xu8Y*& z0Ptu@d=+au)7-W@khy<O)?C@2DzGu`LxKTqy4Y^RETgTD@mNmwDZWK6yo*_mQBD!J zn28xK3q$#JmS)_;d|f}a=Lfw#P%&h|i)xUss4kk|CRuYBtZ~cfirTc#x%?+oWAsEO zB+D0U3b+R>Ce<bkh}2Rt_>_rE@vTx!7tM5W9+M}n=$8e0AXd6KCHZ7WW1a{K`XHvq zIE_ny@>X#m>p>rlVS5ULL^*skn56izuw^?!Z4oqBlz<7QmOds|xr<kmjChIqZ+*;; zE;XeB)7pY^@^qteB`fl}WmVH{(AiT2CqZp3`{nDoor5$V6HV(AW<^<A`A&H*$+wzi zzQx*Ke%xIwz3kegM%BXi7pK`FYzno<R$%ZRt~LkkL29ROS5?Ioe;&|0A2UZ*Q>PKF zo1)*WlPW8i)kAZgrm|sdkMl4ltbvS_TzFtZk^ZTTM$pn!yCk1W>#PhOBBQ78SCD|M zycyn_Yt_^*1=DzdSgB$<BmGD?-K9yXm#0$w8(9bkGMgBz&1!;k=kgFRwy#zZ-ceX! zwebDz_ES`7s=l?lG<MlSJT;`c;a6xv&+|x_qD-|0NC52#t{|t7W<cx;N<r(3t9D*o zax@CYGYnaaEvM4AJQM)LwG-J4-qqQ-d5-6L)!f%Sl>|OyLnw}H;sY46M4PyT{TqOb zsF(=VfM@n}2THnmrv!X|3u!y@wd&8aLzilDqVrMmUij4+yPC^GqnWq18uq?$rt7IV zT>NK_k5Fx7CR@9WULKJMXZP#*KhEwxujc~YZ*N_CT`z~%Cs*VsaZ3+wzSajx9>*t} z>)u^HeqFrT+f$qG4zK$Ioy4}jvQEQ1O5OSXCxPJy0cS&<+Wu`wjvan@=SaIV^O_n~ zMAJDT4p?QuN}_ovJG6-?Y!LAIAt<95qXd6LXrup5c%%O!PZ3`)%~G52;eqncqV#lG zcwNiRBNAHiEBIYD62{xnzF<75x-9LCqvwck5ziM?#<1455+e;}ZcL-+qr1z=Ia12e zq#{if<}t06#&jb3Gda@rwsk3pd#<ZFYo~!{w$;Wi2XMKFm{oUy8JAbZkg!BAbh(eL z!gDgA)zmHB={4|ZUG-$L<n8gTmt$g%R;#i|TJc-eEoUioDfBQU5{N#(@1Jw9jNQd0 ze`QsR1|3{4M_zWFYsX?WnXV`kdd>&jq@W^RX}1u{Lo>i^S^7G{+Eqv~meDumvz)9Z z!GUA|8l3EQF*Syx3bnU0pD;m&@GY6TxIghy9SdBv4^=*1>iLkQI<p$+%}x)WF(=Az zR?B7sQ5elDsnK<3SJ~WE9q<gpI2mBJ=i<GxZ9+jEw72b2>-npH2I4Soe0|xjb-oOF zy@O?=;6<{)f^ZOaVxVczL}htfL{4^Gorhxz-wwR!7%LPpuQ3_f#$$rn4iu?zcO&G< z@3!S#vC>27Z*QI4nGSxttgX#Ur8Ds&*@7g^ve|nwOaSN@^(+U^5MDHq1ixr*{(LS= zB7OUHZV`eVY;P*uktmrxI78W5im8V(m@k=Q*BPR4R9JR#RSGGbB{B2virbolFIqa+ zD}(Bz{FlsA+>iBJvB>529?U(ljUv5@x)Mb+)X=vt#<xnaDKa%p>)FPz;sr{@@>nfo z6ew#lEs_qJ{Ry{ccELmaEDcPTN*1t^Ds>s%q?cd9(IeaYSJ9*BNu_CK(qMyR0PpSH zG6|IQ5tHMrZAB}P5vE>-36yNo6TT~62Z<FKs-vrFT7AinW`~lj(okB>pqmP&5Af-L z^a7s(wwPgR4yFJFmH91z+bX=%sxF9XWQ77((gTj`!pSEh6?<aT=f*O(AH&Jf{T~C# z(JCLzss(+BUr|0`LHI*{)))Tt7rPM1&quTn2-*BIP|G}E4Xho~5q=MAlp$W5q*cf^ zU=6$-+7Wq=Xp}$Ri{wG*;va$=m_5`{@_0#-I3c0{J}?gmkbotXmC|h3fl0N1E+cV^ zz>Sr%Bas$X!h%|@fUZ1IKlxsnvLhD2JuB^%fu=i_oON8(Ef-N^EEA}_BAs$1Q$c}K zoUIeVuqQJeJf~1GsIEe3CSpOYY6!CSrLZZDwmwB}EJJx^B6(S*WN(rNbZ6F-s%X)3 z3MGSBUnrB5S0q!GK~`Xjvw;!SMKTJ(b9yC%>a3J73eyT_CNe8BB@mr8ii8i$ls2TQ zf%aP;%I-|6b0CErul!ZLlA>y3nd#fT|IP3RUwweF@wWe6w8+i&H;FskpdAJO(_nD@ zyRO{|2-gAa4cHS5&+0eQE*B`OS}cu)FQcYruH9KNw_>r_6z3->Y5<UCHZD+2#P646 zIrNy}p0-*-Sp$bD2@*oy5EuKj?Vg36CkT$s6X>+%xx5W?q;1cS&<LCWR?fx<KqsSx zwGVoGz5R|03tL<TFNfZQ8tsDr{LCAQ68i(g+mk?NQ^?**fEW5FY0f9XCBG*anlFX3 zi{{__@w$kA$m=le@@?8d(Q_n#il@ln2&o|KxgEDS)K5sDd5Lgi_~F9P{fOughUQ4b zuAOmnhMrW$#6q>kfMYI4tD6u@M#Hl|abs|en6P~xG3}m1f@%@42~`>*s;h$9V-rs8 zXVyQLVCnm$Ot9T1aY^l0jn1*MOBSdZ8-_(|j+)9m|CZC3gHa6nnYebd1gF%dMiTDR zd}|^AJ6G}PEIGe71*s_m34{;)CL5g)X-jw04p`SifyQV%$p`CX-};R)s&+(|5oUsj z!q&TBVhzrWhc5i!Xy&9TCheLr+Ade|r>{J6%b064R@E3#q2j(^rHQ3kcrT8kU8jNE zM;~dde1Ik99MhR>Yq*^=s4QP2KlF!jt^Yef7@5X^s*VJ)@{Nv1?`g81P%<Ps(h^Y# z$}7doc2OvIQOY0kTm<_nRHhA!GLc!<*_$+`wst<KiMR#$+z*wR;gXSYXBFA&!r56O zeNVrpxt^uS_Y4KWkO2OhKqpmw5#>$AsFgN;>eInH#dsnfzHGQTb@yr=mbCzL9JT{b z?e!H{YX{hOOZ`8=9?H6--(RTDltkH5g0%LTC-S>GY?hEoWxfPW(bo7F`UdK*G6I9A z7y->6zI{9klm+=zHEK!Tm$AaNY_#l?M1JiXBo8JD&*H9{ce7Q*klVkvR0YRMup1$( z?%_^pm_tWC6*7WfrgBP*eA*>4!O`~DK-bk3=G4S?69zY&)kjk_I;VDFMVV_6Z(OQd zIab~(gWf8RZY=!a@bTkGd8^28s|M2hyKz7+{o-%A(-T3lNfi{AyfmBPs(6```>ZkZ z@4S~N-&17{uSKX9Z4l-%&?q??iyd)?eH%h`vf}{_dmq-@Z(ibPnQ4|ww4_k@CF2L* zJ3QpV&sQ=#&|N28AZ#6bY`r$(c$fEY7d-^W32Ygyq)Xit-DZe;HrHc^moW$8$PvPN zzvU?Q#KI7~Kl|7j1`l+WItKfF3dv)=`<sVBZqQTRzq0242j=-_sn>r5^GtwXp1)w* zNX->^#Y2Gsv;qGJ7$uy}nu1YFe9p*)B1_=i&HYeo#b;Iy6%~ArJ|qr-O+UuhA0+nh zC@|3IU)<4^ATgYS^L}_kp$St$#3KcOfjfcMgbH3<Tu3Y(fH4n}kSaV)O?`B;vGA}A zd2R}2_O*UybR+fuAQGc3g8|RIfYw-oSxbIl{1mvLymfex^x*FR$6dI83PNtX2=jFH zS9kd~E|AhMMJPW)BXI+DXh|SL&57xQaL~eO31i9)MK`l0Ax#W5q434F9nso{=I;2J zx+kfAQ{B8N23FR`8^cH%O%J&a#Q82g!$WVTI9rd-G7eVY?Yl-(V#In!PMs~cBb6v~ zRXaLSbPQMLIQ|J*b9k<aWQaI%?+77WJ?fvFUvA5<X)vPr3H!-GR>%T;Awy95q<Qii z>wOZeGOfJ{wqZ+|;umSLR?4!4KqsNVhwe0g(o6`=?RN2M!h4%(FG`3O_=IVfo}9<} zoYOV{tkDT5P<G9p4ku(#jLH+ZBRI&?l#rf?UO`xWo-xLP;Hh<_tKgZoakAFK!{%W; zZOgHjQ8NptgS7o)*>jo_QG@I#p8bbF$7UX+;)}u7#33Q&Y!E!3DzjXri;)a^Ep64u zb<zTrqOPQlIN2l&rsCTZwy6Kb&4C+Q-no1}!(uMT6)|<yS|`iXwks##Zbz`w$$P@_ zkYg#8V@lwpPJ_gqf&1$OYaMqtTX|)^XLab*C(|0@B8OKpjw8Nf8xH0uEM?Z(0a@`5 z-Onl4`d>md^*BSIFAQ9|DT38v3;HPG*I-HAWl60SSe9yf?;+)}5p}lym{s5UH#9)C zhctYXZpG~{aDQJL<z++FvLuUFOFH|VDbhW+XE6|N##hW4(@<RbXK?Bi**ARW5SB>` z3!=V{+BPdRtr4=~0qzpO%nya*hTEpHafYKmSBT&Qf93g;9n(3}>yz$Jp|5OLh0LtB zYZTzc3L|~{%3E#FTPYkGk^xEYCTrYqS@%dfWbp1drRbb`So0YycV>F~CQJgK^Q<-I z=1eCYb<KC%9oVFA=@pZnL#lY_nq)3UNt^EaGwHP!a``9TG9q)CgI3MItDiZ*Vp=rn z+4cG>36Vi+*Nz)y2~TUbhZOMbNVMAD)p@>N`M7++LoW{{mV`j`v-|e)O%ekUg!C{3 zi481@vJVP!)d=1Eoo|EC+JE^r(8Jz@gh|oRQq|c8j!A)pg&EZNRl>s2$r;4{uNHW$ zETAmfe|-MmIe}A|vQfJ2m?4LEbZl}|9V?2``gqR)NkU*H=b&9Uh{c&dYt*g(e0tE- zez>?`%g}MD(r0#YIU!=GE*#mId(vSIO;$HXU??JoQ+M~o=qj_s@T?zG#wkAS@JMZo zXVK25!lDF-kze#zQ_K-5p_$*i5HDnlx@hHZEcxh}JC082wLNv%VVG(?O!e=y*>M1@ z5jPcFl11z|fL5l+H2Ds;XuYEBERiZq1t>zWoV*qJ!4pWGthByTud!w313`s@;+i5M zMP<=SqzsnV1W8q8wXO#8&<`|s1&vH8%F)XOY*7x#n0%?UVQ{|b9_|K=zi5G9BN5~9 zs)q1kSN#3wJ@uTE;Hx{j+g2)gBVSIybA~!Yz%7QBL>2SrX7QDG=GuqQw+%YJx}!3z z<K-hF0Nt{eMlO9qb8hEK8M~DwGG&nmCRlFK3;FE{DFFj)I<#rqmDFm?h@g!VFr%{z z5WNFfG+mnIlGKbq8`xOl^bistF)KOM2(VA4Nw9F+^F}Ta1w*j!tHG+4WJvOca?kT{ z<B1R};rCn+rhCPQ?}#PvX}L_wC$g^)CH+}RIx_So{$gCfsQm5iz&z&QgbP%+s?C3B z9^>Ics70N+sF+?h$fLpDG~DA^QOJH#S;?cddqjm{#L$H6dIh8)m@spV!9;^McWnwa zfYX(uLL<JmCafL{cfr&ZV;z|jx00!poXsfe>cDVH0czwLK5f%#l*TsSs+a0%xFWMu z*)$AqV^?NIckuCf-P?QI)%ppfPNZFK@cVeTb-f<H#GO9Z+HJn=Zr?1<zYr5|_S%M{ zolou0r1k3b_{yK|Y~P&kA`?$oJyv4Pm;;S;#3eB&#T+UWB42vwXL3>|CLEvU=POGc zpGsc02NX9)1Q+~XZfh)y$D3b>C$PWqZEaHDQfP6P6yEWWL6rfk)?fJVz;j0F4Et+y zmg(lZHs>F2bKGNj3<HWvIVxB-FD;0!*ve|+%c_y8C~_W+J6Gq;q50Z@cj=1iEU}P% z6^84Zmk~(rDg!IWy`KH0<8P^t{**+`Z(-!e%@d)N-1-q(Da-Cf)V9qLo0rmp-PC7( z6_Umm;BVlHF{s=lZ#ifFr8Rfo)3u97(L^ih)-R8RFsQ{StpgyU7#fPahAwt|C7}%; zpQEezR`9szG&MO*=L2vQ<Xp~I@Ff(CHiZ^%-@90m2JO$bnWGFZ&zp_NV+nCh&)+;u zh{CrADkbn-i_oo~N;Dc?%;xz}`UofdhLz#x3C6HzKdrXC5WZ3Q3;KCJIH-9s)*IF> zS?_D>=q|-o(XDxUT)!WOrNuETGcxsf=rPt3`MrPLc)f4e^L}_337c3_^7ekX7CqbZ zT0njw&hhp97}yOv-SB(6u!|GydAq1A&7JTx%v8sXa-pFzne4;f><*J!6RdftRe15g zUvglyuAX13-qJkM#L-M|1v6nNptr}Ofd3u>EcquL0RNp*f&Wgwfd8P%n@mMsi_RDx zBa6*n$|Lmm*~LC2V{VfiIj^!e{e9Syi7&0ue}ob*=^qDAQtMmlzXo$9TGL;GOZRYA zUayG9lVMbrB&l@@ddUl-f=dqlfOYh`j!+HX?ERJn&D!;#?x3z9Ir?W0AN^R!cVwqu zq|v=q4bn`@ZCG>feSL>7ep9y!O{7sGXQX{p&B3(CuT|<?DA4VMT~94P7m792X~aN` zlaEm9n#1f|N;WW@4JD)70HxC|oyT6Tv9EdPRDGDh%$<Tj@*uPnoODgcK>+{MW=;r< z-TL`(3sDu?u&rDp?x7v6u;f|>8#*zY)`cV-AL(~JA}R$2#gm~FGskmiIk>?Z%-nS- z!FFS3pK<5K$Hkp9N%E-}R4ivvXgTH3cVJc*=o(-SRuTesDQS1x7{tT2l??H7kRY6f zVq=Xzr&PdXoe&--zMvz_2I$woeYp<Qsi$VnvPBi*yn!bS-ye@2I9tJm;ZO#Q4#;zW zOzlS!>JCT{=Ql#3D2tHU;y;BT4c>75gqsc{!x7brFKlT+MLZIs$Ie{@cj*V}xCT3~ zWGF+6JTV;wKR(~spl73G8&flfJT^@!ge&wX1<Pe#1s{DWq86jR9-CTV6d)BCSF|nR zc!Ir__D{^SK+Z$)^Mwd`{31p(NR2D=eZ?3wl8%Ek#YhFDm22uOunYAwi1uitGdZ~7 zu7%?hyDX9lQHUXEBahEd1-s4yFcO0(_Bq@$DIniGk&5>we(@)Z+<X|(CcS4CM?VQR zV#s^uNkh?(`BUQ7QGlmT_BEtZI@K8?fw)BOuK=&Vp$Fha`I>5bsiWe4&NzRH7vL`e zpNdD(jnsa^IC+XBAPz|MMk8A<rPnm2BBjueAzGH-j;Jc7Fqgb~+Nb+n#1XAj%yP)X z4ZSp;V2@VgN24rIN`SXW#4)j4hrtF7vn)##u=IfLL|lF(T*O*VMrMbO$uA8=`*Vi& z*Jzt=hF^XpU9`jU+XSQ{T~wel<Oi)Xn<TXlHRu`<nL_~>%i;LP7?I<e5Sb$e;Jj^` z0^U-nwl|d86d6({jK}bwqhj((0nzx*(J*;Iw*N880Bg=HGRu~w3mlC=O&x|5$Wn|I zJO3Invo3#aa-Wl7@<sq{g{;&5(n<X1=m>7ODmJ8umV%G6N(Jz}Ra608VN%&6$Vy|A zEbx^^xjkcr65yLyMuD_S33%s5!xWSP&doC_UnhxC%7ZRIP#QS5z^HOv=$8pH)+tr& z=POnGfj0SpSQrd({qNBZ8#Acu(!Zje|9+AIbpifQgBef)%Ktpc?1UVz;ilq1iHP|- zI-rXuEOOWa%cU2~RFYaRAJvD1h9w;FhVg?C1OL1o_9H_D@_rI#`>tMyOo}SB%y<X^ z-1G;x>EpK7v37!}(6+aE($pGj0*r7ja_1$lDxH5?TI~^J@FN_vytN8mh(pQq3q$G0 zN)N1kC_Kf7v0ZF&`ed^McV*Um$e$Oz9F5le4xU^XN8Sc&<&!niIrTY8KJU>aFI*%O z_A@~&P$*NWJjU9ZJS>`8Oo{Hw)IpjimoAt&_TXJJYeqIhsy7nua(u>8T)hgWr4(uj zT_oQmjyn1}8<KZ}6O*?&y^-4?NsWPew7&iHOhg$GNI5YM|4IetHmY3U%LzMJ10hG< zr^cwdDZ66<I3<(S)*@k{X_9blhpJ{QPFqw<3KzC@b;U>HVxri>u%%2N*5lR~Iyb|9 zVzW!*;^-<1A?l3Z)+ER#WO}k2V(=_kU7yG{&i%fOgk@?3UpAtraHE+D)T78egK;$f zL^AhzoG-oPT+4JM`fWXU*~U8HPGlkN+~Q!%AkMkfj3J&MO((kt0!S^a_pJBZGR!9P zOJj(66ZkxQ!jy4+)?-B0SP?C3vEeB9foBsL-N5~VQ@NG9#VNw-jgeNE!OOc$e1L90 z_nGDx&&YvUM8^QoWle#Lv>#_jqQpgy;mSMZ=$-_7kZ^D71pe}bKpQ2DusVih4=Vbq zC*<;^N|yjIqSw@%hw!~xxDc;SJ?NxL6s+o=GY?Nmk<$5qQQ4_3lF3+IL)Q~!SKoz$ zam<@ZbNYwtHS#%LZ*J%84bM`l%ap**9485m4DL~uUTVuC3Uzhp^rr(o6jNzO4E$Ta zBZrw^KY#z=>xrJ%#NR-5|B31ErS3nCb0EHoap4ha(n5eEQcYkICVOzi7L3v<a+GCA z+O2;K-(ib~BRNb-Xr(zIBFcSMl$0ZKgkYfA<7;CKB@Z#zh+3we^tu=(LR~CfsGxV9 zT=~JnuUVuw`@Rbe?}~S&1D)$BjitMgR<}+!3DiGC(KlwbFWes@{o(%ON0V8oF5;Er zPZvz*T(eJ5=KgsSK_sy|<FXybB!ldT-mNRBJTL^=pWMlJA4%-3ksf&lYuujFjo{Y~ z<$KPfLe_?nN}2TNizW{&>(N-X_~?lQKlIjOsh3fIrLlzm`s2y}$W8Ur)3ZmFMa1g* zXY>`5(3EK3-#Izw|L$G$-&tmytpBl-pM%iIzp~8!LL(`#uU})@DF&s>X^Qk))YU>- z*iWZGU}TZYhwrq;B8psOi%a}191JY?jMqj`Tp!FD7(~gm6z?S!5DeCbl;-C*|FAp^ zFn0kEUf}~?vo_M#EC7kXA{B1u+w#gRhhB}A%{0v|!@Egntw8FZTSG#b92_v?HoeFW z#(A&?%1L=fd)4v%gY=IArZYdtcBhLx7hvTn-&ze*di5^F%zq`BT|tDJqtk+*3Mpnn zgmU8xE_dSn!2CG~-iQ(tceJT-2euezlw3?~XWW+q#lFROmCcYK(nG`MZ6*QBx1esx z(75)%YSF3_gBH;<;cc(gt*X!7c%_9TjDM0utWwl|*Q3@)`8(prbAB=fXz(EHm?xK! z$tD2`el$$9qrd!Y8o#6OP;$VWOllIuy2E33!mLzMY}{g%iz*r}PR`c|*kQ1t#m~dC zfFItD#pi$4D0sI+1Kyl)O51a*O1l9XDe;66&Bbd1n|`X1#SW61q-~j@RgKIJF;X?i zTzvUZ^XPD8A}P`X1a1^nbVO<u8Pb$lic@ggR;Q~~&St8opzWzwi+F8%Ime>i0hFmW zDrzfI%ob0sDixcm1S}R$;z5ja^0(T=V<zMtd2?D!@jDfh`Ro-V0z#Mb*>eFOc12iI z58mw9Y5gL-<~h05wE2e{dcw-}7rs+&j%NKZi!9T9ib$)RAAI~RM_$tzggsoc<3oR1 z+^G*2E?*D>wd>SaH}Wo#ga{t^ej5t13-DRm39@s4I*A<E_qAN{v8*+zd4oEkf2-48 zP>h@F<WFv02*~H>*%Dne=!C=BC<Nz56O8BQ`AI(8_v^GgO7lB*#!7YuxkI>%fz=C@ zrhUnHePqx?1%~7N?cF+f%SNq-iT@A1Zvi$oo6>d6JqGd!u2Y@A(=vMLlJ&q%oGiId zM90RVdT8p+>Zf>@{e}SA2Xl7%{7ivE>6n_-#k!q>&B2E)8w|8N%dDh!uJ*_j%lAC3 z%{CTT<zmo0GU&Tc($CcB=`}^GzrJTAxOeZ2@nE>{tycP<s*5`!%gmX|@0o^__z$96 z*WV=kRWf7>AJV>~GI#vy`+jvj@@mRVk>f0g2;=BieLu1Zh0z|@YYQqI%HGrveMJO( z_GkYa&t+l#8=#Sk?f(KaYX9ZABb!ecz7)s?J=+uH(o!;#(ohOam4K#dO?Hd(Cd;{B zc7pRos#f-3DxF(=_LBC#hkmg>%%NLQLd<_8#=STx!NP@DCH$Y^xDX(W{ACH4Ar{!% zZb$ye4P^kJG){1o#=*+${7<d?deqFizj_Gr7b%MPzw?WP3+co4ta+wspy-@hjeLR< zgS&dUp4Ju;MGH<odb`ZK5^%RS`t{8Hz?lhsfG>LOB#Ig$OarlnU=hSoGWQ9R>jx<= zLPXv>1&@5B%BrBesYw&fI3JH@^3W`wh6xdNy(ioIarKttX#H(aA2Y(hT_`(Y{d%i2 z-yHpdnW0h4SWT<wAUM^NtdwO?)#xqH_l4`hN}O&^<nS~im{w0ACP0ilaWDcmoZaY* z_0^v*@I0bxHcyDi_L<PB84<B019p>F2Nwy1jiO)IRF5Q>V<xzwBoL4DH}`N_P%#~O zTPWGN9Pu-S@m+6NevKU8P|(R);*m*;uKP=_Zn*?~UAUuyPQO7|eT_f9o7MT9DL(S1 zKNwW~P6sTK?RDWuuG<iV(+IG@*WY8ULp?UY*I)alkHia@T=|p)4tAg&Pzh*F{Snx& z*Yd6NcgztM@9){|I{c1_?6XIu-`s0s3P|h+?bV^$SPmJ+fayjWhQhJ7_o4o*`QPfL z+2Rp^L(TFV8oCk(J=olmW&;A@mymg&ZA@ZWSz4w&6WN`@M~S12cQU=@7z6VBw=$#E zpTKi@1*>cEJ%QQ#OLp?{uZ>IN=C3_jgBH&9wD>P<a2vRZm%$6`CDJsV$lkY<n1fgw zk2*t|2}elAVRiiTp#1-p5~EyEpb)%XNK1{Sv*NcmlZnG}m%NH^2A~%07T=5TDhMo& zO`p6o<eS0)-0}+{(xF2eA${4T6;$Hl<1322Eg{C8AyIpL3bN+XZX$aha`0;`!REXz zp-pyo$aZ$=p}_|Da(m&yQ216O2OYs(h*Yj$;Kg}4mMD{Lm?M%jX$*Kd4k^5G%h8(q zifm=VSL^T8`kUG18-Iup!K|4eEzc*jsr&qxGgF;2$6@aFa9*``Y3=y9wQ}LdIbkCE z`148h!=PL6iG}3n#~=Gbo8b48>82~D6+6V7fA`NX+}!{1?!~N}|H=yc!tozB`kvC( zt;}ji>=EqkPdkqpNu<;at*aw0VrW8fb;7<U%j8d1;ws$(Z~5qn<13uE@j~akR*{-E z553+U@w}6{d5M0xRn|J5HzTbltClrrcpQwHLIU^G;X<HwQo+#*rwEm&8+@dy`s`n0 z;6dur9t8PwmRCueZg1K^dHa|4*XWF4m`dymdIJMjT&rL#j*_~nD;%pq8osfC{^Y4) z!YWNqlvD|l1qLM;iWEcofYxIKc-d<#BWWR(B^U+~o0uQkztYo$q_mi0B7m??D4!(Y zp`ryD1F#ni%j?=`B0?9VZV)i&CB(r(n#-oQ`qiCBMR3K}m%ehf-+hIiG2A<aYXWs@ z*DEz_=z^mD?l1`-mN8YwlO}8wQ^(3vi&}_)TVHTtf&-l<Fya5f3{6G+1#3Atk~6BF z<d`7VJn+=}E?3H-I30V!u~9#6%f3{fsqj%p0Fx;xRdG9U4Da-(I@SBmmts~maK-k? z*+6(5K3#B4^7PaXjM;@6q(L=Ocf%NAzJO7@V1G-VB^ogxJ{tBAiprE3GnjC}S8BOX z>50}~2KPi0Llr1>6P;M~R{SMDo+Cm>P7oSrbqp-hV^+WFr^jR%X@(2#2n6o^u&$!h zfi^YLzK#@ZL+6s}{}`PAwb+l5P1fO$d$98f=fu<sr{t)|`}{h@qMpN^EPvld$5+IB zIFLYfbg?y-cJD+78mGXCRG*_S1^$ceNc+y<uJ7QXfgy*Oc^gD5d2rb}zn80<$5UMI zX4=FOGIAX81*4$%>+yi+$6+h7UuUQHpT~>C7q?oxIkA`Pn~{lJ#?79ByMv3Hx3^5> zeax>*Fb;os?9ZQ%Fi(l}#G!j`T|DlqbbM*j1o?Wr>C-O9FE{*NY2OX5R!71BDF6+; z*O!|`4Yx<^=o~=-@2|T#<nb^5vf58Xms}g$w&8A%C;LO4Bb<V3L1OJ)j~5>8U0omh zqE9T!HK(4}&$SP3X?6kbA6MHxYp8g;LGLdkahDrwy}cU-r;WX9AFua!oN>L$&4$@p zxKR%IC+JZg*UyAP@j_cOcW?Vm59xj;lX=ao2UGEEY>2W(Mb~VWj7F3bnZg$Kc>IXc zqVsiZ5_mZhWU7BdPGtX14`LS@dmn9Wx%f?@-4b^}X_laO8Oqk<_ztUngstDgG5TW? zuHw5bDYEmc$<l1&6TyqxcG)AT`Sz6^J@>15b&%sNBk`SnsOtHMi7!;N^o{lKQ9ISP zxsEqWLgp5B+#$;Bekz`=Xdzjw+$~`rVQ<RzzX31WB9(j>sa5CaA>9QW;1?ZyR?)S( zWh1<^%A;jT;DPetp|yjSnk_T`jiTVbZO8}ch(=Vn-RC~eauL&5uO`b|5i40~yUs#Z za;#CVu1UU<Zf4;Gb#vUaRGGaCKx5^y<r8;e^C|3l43MiaWWQG@Bog7Qv`q1#&O)Ma zG+8ikhS4>3v1Y-5)%7Xt04c@F8;gI$AuL*+1*EJtBfbI^pjF!Ck`0_C*U7vLM}B)2 zx1%eAL<q?S)>56f9ry7yY6lWN*Wl$kKUb9b67`F~&*H50{Th_@4nWr4v{Q)QWcFma z;1ZgZbq)f=7$?h|^@C-xwJ&1<YaGuh9wbRdY1+F1Vv?Jz^hEP{aIG;ntjK#e7e~XC z&zO6+?yR98y@o!%`0>su%jFj5R6NB~sQyS-uoEFboUbiFFM$EFybB+W#bzPRgCymF zak*N|N0_&!g>|tg=J_vE3hHXLh_Z3I2&|a%3Q~ll`+W5&Di}B-;=kN~M#@a$Lz)te z?w<uC!q*DO(Byy@qWvkw#<7J?<klVug=8^VzKYSi>P3q~RDqu3jv_OO)gICOsvPkG zRSf<+Yj%~LnXJaieLGfU&5est>Oc+=G98=NnQm*@^0Y<xM2JI@VJH<6Q-T096ut&Z z&nIXhz*#}`m&s}5<ZsiyR0zs24k<#ZLkQMaI)zXyMdP6P0P7yT?vE&p7FK#*QWug; zbXAu)&!u1BtS3OV1E_M)NxzFtAS=?Yq{JKW$V``};jDFi%Spy>p}!rp(4t%qrzt>J zM5~P)kC`he>c3r;1`K>?tKi;eB#zH<*&%<Z(jJv#+ydb|0g#C@0Yy-x+&U^j@e3pr z>@d>C|3&h~|4y>T|3-TWqvQ#aWN~6WLqABR_i3#;DKSfu5@q<75c|AURScd5lY!|9 zG5}6OH$`Owo|3X6vDV5m=4>F)7Hz$zpx;?VxqWE9rXaBUP*{AQYW5reIGT*31)N2v z+I&+s5GX6-OITR|rXyPdqP3Nj6J6CX4}vPj(aYu4LZ0#}`UR{O-gPxWY}L(Px%_`I zVwQ^PeLtNV#^)DTlhx9Z#{n6rt|p*)4R9}Cb5<7B+K3m_-0fq&`Pz;F)<9pI2kugb zW>&yGBvrrx>PBjHIn^*P!qhOo^-irPskP-MtBJ%Q)w`%_Z2PKcNULOaz&#XpjK?gL z)bzg<)g%^ixL{sTyI>Z9#bqD;B`d3Oq-?IP9F^9kls-QJI07}=6IL+P_wwo--vS0& zYREv!0huUYS34rJ7Ss^-RzC9nQZ`ZIGy9#YwwG76(~V?p(qe+iO<OrQf5p{UPggmr zthv9^Z9M^SR8fzhW^f2K)=-}fYKR<C&Gpd~2i?SIn!s>NRY7k?mB`XO#s^j9&%4PX zvoQd9NN|E>K&jSNIhK0`WDbZ$+U8zU4ZB((<#T~i+{+mKl3+$QBbF1vhwedjBL@<A zD1_c*A?$PGjytg?9~#rlj49<L<?~UC{y)B0pB~FfR8!(qqI@vH<o8q=vLv`#OI5oq zstQb<aygp-c-|I`Gn`tV06gV14EBu0uWU~Np3g-x#4jC@MEvD}J<9i>iL{k47ktMr z4UvR=W&Mo`6e~8GLkdK|K1S(LkX>F6AS7=h7i$kg<?`47K-yA6y*?>SEpefy%209a zHP>8|p8wy&H8vKGze77gG2DNSc7lKqDG(6yMt3mR!^}I$nFcZJtc5_2pwO+%zOrsy zDD$RNDYN?ilD$l!WfbcF9imf%f~xP*Y1+$l8uxP_gFi`z?$K{MI(q*ruwmw(AD@u; z`*5~C-=rhovbTNr^ZW3<R_KL-Kts;|@xFVpOEc3n>FnZWM|F2LG1=Nmaz&g&8cdDy z+0QRaw>xNSWy1?GFAV(i`}*6yq!7(LP2c??a^CkhfuNY0H>aKr4rF@#;-e24A25CZ z#Mb1)R=4`j6VZ*5KejCWC?67M1*`h83?<bD(6m^EK~}Y_m6d&AL;BREg}m*<(!P0+ zE8Q!Kve?<r02=$*xmOc{^|0;foui?f(dVMxpSU5xz}m$3H&o%IpU!XN^c|EWq(0-r z3=xj#^D~v@{ykCVr;MUH6GfKj^EFkRTO%#LB(vjRqf-NV_WqFyu+XAMKRhti56Gf7 zC`|Os>S4*NIb`hcCpl7)N&R4(edAWT`#SEn{i9=!Es`-q%b+zUWG-V&(K5zZ7d)P- zVpqxI6EvOfh&;-xZj~zez5ulMZH~$GlS-}VD=V>SPtRrxJUl~>2j(3cE5phch#P+2 zSM2WaYdofMekJZ&=ZYQ8VDg1UZ`#>93G7JyLf&{qmNKn(L^*YOV$UdAd|qPbjBC0$ z&ha?~X}*aeqj0Nf?&spzXsecqcy(N=A(-D&@d-1Zz!_{@L~&{Y2VJIF%I}$7G4;5i zGgzD>u94^WPoV`0bQUTZl+TOG8K@r_4Z@P9;D}VTH*EAal`E#gfpUleVIl+`w0Z9k zlwVTg5Vq*l_N#DWw}BMZ{rNr=QwJ3I1Lczn1esUneWmf;-f+t>+w1I#mz{I42!oPk zZj0RcSNm^dP_VVtXJs|cJuUp-5?#KAZY#6?9(}yGdFqUq<CnNcdYozg6tgGV?bSlq z_g$Rkl8Xdo-i69K>v#MIPVtv0F0L?o*Yi6|UEb0{>F?u7QFs@z-(d@nE_A9CR8_^d zuW5!7xO{%8L&oc=^ZJ@x58a!+I)0}uK|1?NIUbuuHN_;4s-CiofdT8C_;oTM#d@M^ zqzxJI?KWbMJi>#xexPS}X1R34Hl^BLzceJGMR{cIHko{NEQ7>ea+lSc{B%by4qS5h zv#2BiPwXV|b6Vr(x@0QSJ)v+#ze|ElBR-R1v-0(I!wi=II5yXJfx`U`dxi)>AHKV_ zE3abROEBdNShfTCycf=-^e`@Rx62n489teaZqG>p2kfc6gZZf?!QOQprquALr*H5O zhl2NlBe~c()4d;U&1BoJ2ddgTeo16Mvi@epU}gRr=#-m-^Z&47tU6}${Iz0WbTlzd zVjYcALJ6C*)Fqq^Cml0`Ds)-r2b$(H)_dMkv$<kEM<nKuXy_a5erTVjH8mkXEPV<z zZc%CUGaUTv<}HJ&WcN7;sT6~G)2R%8fwC<<OuR;{W^bq16N=fDa8&p0e4x3Olaur1 z!AxXIVCvpZbZcWX*eT2lr^`dI(;c?2xaS^02>OZO)$MW5%OBPeM&kLEFuu{x>`Gzz z+(+Qs=6YR6(g}a^iQy5-^yfmYIc0iRoe?J#ktoU?cOuAD;IHo_3Q3;b+=Ax(?=Wp& zJK_u48^5B7*djNbVxE7D8hv|v);_J<;x=*v)p?%m&Y2+H{kG_`ck4PS1B~;~nCR{` zR|M(|7gQ9(HB{ls<hJ<<aR{c!TQ?M*Baa>kym|cg)^948Z{gCg(6a^hx`I8~rHom# z&fk@Qs-pa|i=Tw-?1P@$%0!gI%q%o(=Y)QdA**MYzXZN+pz^Tc_Ixf~*<(0g&VGJn zXXe4dD=3_6{yD9a=0aJdG$q9%zz=LCZnlYd3E;{`$VD<cbJ3s3miyCYJ{7g#MK<xM zWJlr@e?kIx%1qaPIBYMEg|A(QjP8SX495|ps?5GkJKz^LPs{}s9`Xfk6<BNa+|LtV zf#}(r7Xwk9AYv&z5lO-Bj_slv!<vC;_)E46Ges_{tJ@;LnJ4EQFu>txB1hqq_)?#L zaMf9;9+fxl>Vg|Q6EY_%0PlJZJ4Gl+901i5J14%H&Hr?pi-dPmH(Z&x$RhF*<4(3a zsx+}<k(uMpaWW@#e(j*_#1)VCy9{~KVQC|`LlttEL*IqSjU#P~2HI87%Sa#ni&rsp zi$aU#16jNx)rEuQumDFqky^T9K(<RGv8SS^A{N%EquO`u?qiRv)c`uw+~To}dJFb$ zgqQ9gn%6rHe*CYv`ffPPA+GwAMJretaA*cPEyF`@C;BHVk7BshD-0TYaqXW7vkYd4 z0;W8clG(c`aH;uD0yg<+A44DN5qpviNLI5c`7AHJz~>duP|M(OTd6;JS1D0P$=fWe zVV>QaRmxXcHFF3AI43JrA)oxT_@Y|h8$FMc)iQVD<*D@&Cds5=BwbkD9~tQLzM{(7 zPrm-8z~E|9-A3GkK--)5q~@z1iNgAfwaM=utGW+pXSgqal)#rG>nY+$zO;aqCVXhG z>&C^S9@yKBf*X%euaxbwL=yAOhDM0qZKEvhoeV4<YJ96<#FmY_emV_-KHRjODU1Ux z5Z`)rtzztb@AAv9{9rgyhW}<^U}62wkstPdAwR5K|8bgFx3+9lHYeKpL+wvT(?YsM zS+sN^B6m}LD7l^N>wbsteF)CTuK27Uz6!@JwlKeo0_lF1oVExOrpOd~9<3>^oD^eP zM9HM>gJEk8K+=*O1Y!*d!l;La!xzd$2Qkaqb%j;Wy<~}dS`~kZ<CP*zpMSLz;#5y- zyJZ=or1fEGFA7;XW7H(wIhdmvG-_vqr$tOtC&iDQ)6SQU=Js@RAuLwiRuE`$GGJXQ zmNhu85nk%I^s2%na)+3s;j@XmqGa=%_VzJ~`{Z9SBkb<ZmK$`{tLg*s*^&X2DP!&? z>OxcAM37;sjQS0=x}d`wBDHwHX0aVRdtM`WU)yMaU~=f$`R!{YOJ|5abJDT9^^o;y zq+~q{=LUU?`EE7q%GI3=T~JFk^V8Ngjfe>i>H!MlK&VxSE`igkOjC5TO$enNCoF|E zQ%0?nX~vu`-QzHjQ(@%haM5>VBJ03i#-zE0Im}U0mr%TzeuG1e0lvg}Y`mdGSwd53 zqFD2nB|fCU!U_kIE96C^4wKxcT2x|N`y8suP1rucElw}TAgAq!w<_VY)uvEr{Y8ER zy~yInrUP5g=Di;nKGxVl@>^hgF!q#Ov-ZIOzr#n}phJVPt)2Qm>YkcVnelZIBR?<S z+9+E?xUO?Bn(m%U`8=2Bo%>%oTRXbdMf~1MwUs;j!qNI7Agp>;!vn?#mbs!sNKn+n zK+_{+ZMv$TE-%K3V~XB}F2+UR>X7O7MB25oG}ESc4$m}nU+wa+Gqk>c_wnxajq#fx zAD_UwuJ7aP?)>}f3^MXZ`(F^yb?Hl-9bTZAm)FzFK5?4e=Iz_|Ul7ns=?&C{24*A8 zRENFLveuny9$)2jz+n#~lV0)!^8QWh$Wq+?jqcM#>5Skr^01$~cbSS;F<jh>)ze8O z@2j_PF;AWY$=5bk9i{Tcb}*h8rrIR>nsD^qqlGp@J206kh~m&+5l#-tBI%V4Y<UYZ zN-}15H14Y75`<RozQq!<N-|oQ!3HgwVUp4|&CtLTSOBUTvVuLuABZU+DYSC|s58p1 z&}dQ7it{~M7dCjBp>KM$Ifb48Quj_Wy&F7C54yZ$3K|pm)lh($(%n@|Ln)aRMDiR& zann)=L|l=EG+)Jor7oBZrI=H)cuM@~*ZP=qyhRP<qVxom>2__kA`?AzRHXPly1Q^$ zkd9WP=jZL3;J`Y2QN|LXNL<+2EYn)Os;B%vn@#aiwDE?fB5c&V0KFx&B~v2Y_-NWK zl`o_@Ni-_(kpiM5l6NAJ#suMqAQAdFub?BmFq}Ab#WoLDfvN~s=?0+C&@9+#VLx~W zX&oq38f?C?E~Io|S|*Xgt<*RfY#s|$!pKH76DkrG5RE>{{Dm~V5E9~QO5tezBvB|Z z1Ge7#BgeZjiJqc2T$FO~Mxnc4>U~IQtx|@hZ!-96EJv5;fCs`N?h{q~H+2!3+|bzK z&9h+VHTEq<I?{NrsJgwc7Lx!xDTY%GgV+7tfq9~b#5a<{4ZD3W@0%~dQeA@EvlEqZ zahHB=VQBj|C!J~gH_z{fr8oCWr=E8goBs{n-Hu&~FN}0P=Mo9}dHa1Fd#*No+}FP3 z3Us|3Tpu=QRLOR?{qf4TqJBGBm-PQ}Mq}{sXVpBH`J+eFsreprrIAGPC;2k!Fsg0g zuf`weFmEu<!9kPI8OW@}#sZ_>@lPZZ!l^;@(3(gM1jgK>j`92d5L7{HA~z5j^N)JQ z-;taO{|fqtfY7*;toN-!f%m6N?K*)j@|-`m_K`hx(er1wfq*tbO15=b@aA0^sXK7? z!sly&P(ukXH0~|fa^Jkm9IG{i#o1#h*5!t18ZNr^Dr1_DQb@o^O8k*cQ^om#0tdcU zVmL1)g=bbh&zlN1?~!qY$DLikxC2N;qmmtnD(srAASFe(`;Zp9hQ```r#!@@KtN1v zk;k6kuK-)FhplB(D*iM0$XU-UpR?Xy1y&v(qkIaMNwqgWB$04x42~uRWqh%S6#(9$ z*TYR0>Mi=Y7|pP~zc*$}mGx(hrZW2_GPn%rr^YYtKXO`vQw6M{(PC~ZFGft`6!$YE zsG!=(D(#8WV%kO|M}8YFN6#0Q3DG7iCiD3fO2#BpZm(DbRNDRZ)*XaW+|Qq&a&6Uz zS_*8VRsk$&>mq@yq0?frc`beqp~buaS*TkS{847FXbgl9)}8$<feR8wN8-!m9&f@F zf~G5@68ci&lmL}<C{zGR4o4Jn<@Pg0z+wN8on$ywvf_T<iLU-=5LYO2^pa(S$O@1H z&Bx^dAbtVJWkg3l6!0sQGgGPn=IT7~N`dLDw3zO^PuLBh&OU)!M5Sb-ZZxxnS#ZM? zj(`P+JubNlW|Ks~OtxAw&_ISl%{+hl)IbH&YK&ZsinPxhBvhbK`&m9v9aseSCs(3E zDYKVUtxPi**!Sm@vnY}fuMbH>Ka8$!0CRa8ZWweJkPhPtAi=Zz^SI#}-6e?&;zPdS z8~sBv^Z#Q`Nos?-kZyQJ|2Jc1Z26CWD}+FxaU$T|h3jM5=fAF_t8=KKun6vZ7@x|J zi%KeUd4HBv#p8LzHz0&2<^h|!c>IqwIc4<_?gTYd409?vxyrn<i9)rm0QBHsnre`8 zrTewwQA&SPB*h%yC<dxPBwam0Oe^FyG;Oyk(zpRI?)w?dOpPKz?V9NfDY%Tek}RWY zT+A-&2a2g0MUq<m8(}6FNXAqVt*7iGE{!Qop*H<6H&7I5+*7)P2n%=1Tuv5IG;Y8K z5}Edt7OXSj7ZgPvBmin=Z(GkntZ5=36utGEJVGMiyHo{<k6O#47oaMl2=2$}EvHps z)nBs$!7Sec9)Mp}H&yF(Jwr7yr@R#*`^GnC5E=pB$0~lPoXP1XtIf)(n>1+COjmrR zstla&vtt}+id+YK{`lM|52gDzu@x)(-*i#o;`q<2=l(5U#YY-O2>^$i&Zwp)zWQA) z>6b!fN%hMExdkhO(E9(!*gHnK_I2yNW!tuG+qSXFwzbMwW!tuG+qSD#*>;_J_u2RE zea`*2yWh0gl98U7<V$AH7=1kb`OP*VO?!d{4gLsLrWxsz5nF*E2B$^1?TD!SgQOs! z9>{kIDS`pAi4^p6>HFHeo?k~!gz$kwFi1p}_;q}74%6V6b*ry9^IW?*Tf2h+zL-P) z!x-ro_c1zz&hm3KV1SC`jnn6pRWC<y=G@x{G(}bm-1?vk|McaOX|EwN<tw++B*LK* zki33qa~)GCq5on*0b|l+)?10B=3s&-u65#Igyeoo1PN7tX{zygZ_78t^how09ZnSI z4vxqU^{pNMb!$0h8ucmJd@<RhLnJRnVhi+4<jq@YpsxNajbcwC$OR+hVKvAmfgsjl znVejI=R6o8nB<y7BZK0Re~w&vX~lFJtA!1K7uYV(nIY*Jr!c;hhjap*rZ!ml3p4;s z5mlmO)B;9{hcdk6AKtB7A1Dc9H9wqgpw-;o$s93{bXS=tygFDfH=@|VpsdM+i$+;l z65i6qjLz-K)XDS@9sLNhfo@BN0xXloWnl*vb5N0)YzB`WqK6Xd9d(xzf~8nOYzs88 z(bALt1J{zaJijq$G)c^AnlC4|Z-w!V!_V<MgLAV4;0tZ&@lweOh*j6&21(?a9J294 z$j8h|>pjJJ6)<9B+-F<gQt(WD`@~7KuZLDDmuGIlsH?RE-FkS^x~zCUsaJhc<q#SG zW3t}b(GMcum0$Tv$t@J@ie^6PBjigsO*zKP(?f>%`aJsjYsjk`;Hj%Hn-mrn0Ka%0 zJD@yknoP0lt6**xNaPxGT<^Rl<qSh+e+{mh8n#JCJ`<6FCmPkGGx8D`CTvmlza??q zEEvZJtHzmKs**5`wwuH-p4Kil7~>URx+s~-pUEVb!z?h&I_%|udL*6Jny1kCYGN%V z3?HVbz221wjzmle<P>}F$!<&LO!Zp>=$3lA=8fU0nw%Ub*;c7D{l<9RY%M6%sk~*3 ztEyyVoh>TK3k#d8P6g=-e?6=oY$YTUt}*0mW0I7X>A9pB{jNUhLet#<Z38DgZP2vu z@K6-khiqO)8s!MgY<PnZ<=yAvy}dK_c>j98b7Ud=5vxT0h*h?7<a?qi9It(JmjsF2 zJQiSX*=<0yMgQrt<@|^0DkBraf2vjf=f;@JbZw_~j{hxIX~b7>?%_eQC0!t;oSk%y zj~-!_>X$LB-!;y#>#2vO6vJTPz9iw0?;aC6F8Su<;)CF7fpczeT2Q<!6fPw8-_PVI zz!n!E;B*V>_aioAajo7w^6*`}iV4|%o=X#^1e8IzcYV7!c5-Z4##{O-BXmOMI%$HY z^dDS=#J5!6$zx`lnZ|(#ji2tZm;nF7w16qg)!`P>M9<oap|(78;X1dcJJr65A6 zuf!EV43HvR1ONy_LG&w2;_NBJr@~<k+Ym~A!GX@Vx2@bLOm}w)^I**%*Zq-S@4G=4 z+k7#}vd<8=o^v@4Aby-j)^g6edO^e#s(e_nPZviun|Q*BB(cUwMMYI5vBRJ`EMA)d z8=uanmL*v9o>(8RTGnFj10wZLsnTCgM<{-vqrCh<26(60CZ0^D7eFUi(<}l4*={RB zR!TA=khaTF;aP9b*@i=m!32xLrMlRwQDKaB`WUVbYgyq1itq+Bt3%R6y9}k%YB&8U zMcrFZAcec?eOru^v~MG%$<NoVL$c+A*9QwUOW(H_DX#WM{9+@UKWafcbu~zSZUpX6 z3{EA_4)ztFUYCd`#cmH>v=s$6?Wo?f!7DD=`8O#QHqW&E+upHUv!AoSu3GYW)17*h ziMx(iQm0(ZkWQ<kle0@|2m|lkP1l*8DI*&+Ur1LNyic)&aA@=OUe;yj%RF#3BVyu< zru;H!dV|q)+!rJHa4`er6DY(sW1ewycK7Am!KmV>=A0R|nmkg6A`GzTo8@pA$w3{+ zyg2kOsW2BM!4dxelZMKiF$5U^<Y}P=RU0H1rm5K%p@Pfon`C${6R1x!_K^DNFKYbp zGo-Q7WWm&lJ$rq?Q|E3}E<unWV)KCAD$b>iPDl`+bEc%+4$7!yC8pPoG7YPJ;(_bG z_~odELBa4PJG`&t5NpTaIw4}qEJ^voh76%&`8EU<r?#7R@!`RAEy^wl#(H_i;UCX8 z;aDzN$`3mC;!_v2RdkG95a;<Wa5lMWCv=mp5I=<Ea1^a4o1GJxa||JEpOUtfMgs`r zEG0GLjG`sk65Cp?sYd7&>CZ%ckdEY#ZbT|+Ej{9&$Nh_>&J)ix&+M+1GDb9Zp7{NV z4}oKi8*X1^7xKI(z@AMvK#qA~EPDrDs9&mo^CQX+{Y`e?ykQRSrRvF~X6;EkMHrdI z+V!yYOvLya6r6rA#czD~W$NCiWaUxbD=JS{hg@7!o%(NiO%5X)eUAmRFhYGeL>OA2 z#UmGP$6?+!Erym9qcwM`QwD6{hq=WKF3TIX&Pl2HVWt?$!bzs@mo;SIKsZMf4cNkY zj>~(M)R+kBLMz5<+z<7Wv@KH&;o&U2KgzlL%Uea-k#mip5p=S}(tnH^3_Sp|kvmyD zZv2pHta?z0L9bGxz+9Cl%=W->j!I?HOQ?TbGT27Quo|jijriTx_%F&JwEb&TU+(SH zsQD_Mrs!p$TgMM~Jd~&aT<_i0+aE82geimVlEW+nk*;CqciU$cFb#+9+Ls*W?osT# z+&2N#zDe4X_+3xmM7?b)%AjxeW;&ygy7)Qq2RuA+^*>-rSeTjrq4}SYmGR%tgIa5j z>k=s5$J7rLs<2txDdLm+v8g7pnd36?`4FRQs?9fk68k;!Rs$L=1Rg-ENht7s?W9>w zS8XlYTLH^WpjG$dY3d#eMDy_i4stZt<46b+)3kXEyQ6nx%jEAPEoJvZUS^6CfWuNh zcGA_)?Y|n%+Z45nPF24u2)00I8{0z?1q>~tuBmdm1+4NnwlxtDNUN?LX1F7mfG|kk zo~!<<eO33Os5@r8x_I^phNILFi=qIL6_IiPF$|O=p25e<sVbVY^R+@u<cY0Y=D<Jp z<gHw>=+-Qs!h_4UoDQuvWN77-LpWLkmyBabcekG6@9Y#E@=pb?hZou3Z9cl8N&+DI z2r1c+p2Bgnu2{j{J#ZlPfZWf4mLh=^5@awTcvBIM+R_F(aAbkXp+Z}*n;!hl!VfBV zQIG?XTy@~+DwMvSbF1hC5Iv@{jS>IianRy!b%ba%JN9|OWWr#7nTxYqsQY$Bk+J<G zfnvY4+XDY9?Dtpt39CRrA`_k15o>=kyRwyTn+9DEH_LyQjBqpEbP?RAGLHW_ur9}p zzSSKyn==cS5e%w43S!VSvc7BY4{_Ba$&{-vWA-_ksr<DpWDG%(FGvi?aWFUrkbSv} z8B6vIQy#x?XrM)(5H-mM?GOvPG7{{X1!L7pdf?th_IZ`qWxBeRPi0S)%S=WHC!{we zurnp_5Zb!5o4e~=MUS1^%zY=M=pRyIsW`%+QJrS3_AQ(54n*<%K?}@TA()2?_g&cc zz+VUT+c>Qm!Yv#;N@@reH9fecg)cV(uWY%WTA$tv8vsMO?x>`<oLZs0S|?`lF>{19 z%U5T3HlGh1FA5#2p&3ZvAe0mSEPv~&M-Erl%ZX~W1GP%pRMiP%t{^}X$QOZ1Wre6i z;Ek;{qrs>I3bxt~wVQk!CvW=>@^`0<mK~_3e#xCck}LTs_qZuyH+K2Df`Hx;pU6+> zvkv=}BERRL=I%aaJi1;QiffvU08dH-Y%A^0g|VV*Q|PptWmI_HJ@Sq5N#nHXW?F-7 zcU@%K(D}t@CG?~B%Uzn8F;%$(Mp%{~0?}#G?s~%Y&-%1JlYgoDH-QR`*>xuujMMQS zE<4^!H^1f!4V|l=+%y;YKH<Whs<sbRJZ`M@@3f!i+T9fgmlpZ$r;d09#RC&I{J4lC z#1}3kM2SEpifHEOW}w|Y#9Q%>(e)4o`~7f6DcGpFpz}qy&a*l=p(<1`z!~4^y$MTW zd0~Y(VG@=*)(Y9uCUL>krzTo?VWH|c6aq#i?D`q}6nMpg`y0`9&W8XKIL?(>gJh43 z0Rj}KPyvTD=9y)fZhctX5E{kZtV;6_5Gev!&tz*P%FJ{NBh}T|8P`As1@#Qju30e% z1t<&pM&$zAxM7FQr}ZHY!~+@Q*)<kF>S3Q6Q^p8|y7me6cX}lWV?|P}g`(IjBKzmQ zR~1bavJ{Xdi=qf<7^g}qSg&L;Hx+)om&~sf0>gCr?P2#a0@HXi<nk9_K;f7{2`H8J z)GQe1?AsgcJs)S`hMjy-;JYc>eO&1Wyvs4p+lujAa}H(m0<fkF&c(|LYr6lyA-)Of zC6=wkSY!DZutDs<&=w<=r&**@*aP72B|(q=?az50P(59%Ny!H=R8gZB_E=Jln<rXA zy)3Ja!&OeWDJ<}6fFW-fo!<!zGWCa$1cXqWfr*Xf1}@|kllHRC62&4@o+84*FXy_Z zlu#wX=#9@fL)uYHF@2t?no$~CKs8k<XMipM=<?zZ9Th*|-k*Ds1J&`uEZwpf$qY-R z_R=m{A`;hX#6&u!A(N5&I6Hazo8Qs-em2uGWj#wT!8<T$x=Y{xz?$yR%9atgW=!@M zQP%xqsDII$2O7=d_;$+Nw!HZ5H7Id{B1>S*Myw@_PX5X|69%D^UvMy;F`ilWx|S&~ z!Z(dwqk-L$vo~NN6=or@3oV1G*F)=g`m;ADrvC!AnBxL|4NIu-F6Phq3FG+F58EuK z*UKOLpJvgF|J@S!-|jzWXZX)O$^Utp{eKz_Rw?O{_-n30%K<^AHtj^>cWx7=_R3(y z7~EgqCwZ2SkX<+iY5Ui8cphcWyA>*Jbra_imXYM;g%x(_m+j*RC5tQuXQQYKVw6FW zmlYNAje<(46t=1$E8^2R5FPmdOX`%oUDL!l1Q)heqo#xxOHEx9NF`ahl@(J}wGEbO zv8IqLEf11zGM2|kC$}~RFqV>5vot*nS}RXTR31Jr$FEKz?y_ASYFWziOyU>p^An9I zeZn85Q`05yzx}pX^^JxSsN$dkUvsg<lazL#)rpUP>ynXdd$HbCR2^($AYa-m)re<v zpskebm~k+XRuf?aYcXai?#_-hIl~?^o~A5bjr@fB=+k;WFC@culB*-Da_$i(VFd?~ zR6gKLFf6lRjr8x!V9kN8bUwe&1FVladfrFmN=86J>ri%+teZW4RsOi*@h#W*ond8R zfiUHzjkWZfx3R<_n;+MrlnaR3qS5e}5>NNoc!g!yeo6z1illm0pP^`)d^oqZ@|6PY zfRZa`2up;A5Uf8_>C~y~7GE$}J{&gG*hiZh!GjJvJ4WKDb?S04JkS;+bv;ux6&<gu zjcF3TuNqf)pqGI)hbvM}Lk~Qx0%C!izSrEHYh{)Z>&gX21F~QE1r)cyA<o0!4jQXE zFX9>@8(p6z`HFyB%*cox>^C`I4O6ne`=SS}SOU|rfqr8{mD+_cQZ_ZjeV?+SI0PGz zNP!0+1H}|M7@3luqXRSP5MQgu?f%ij5&w6$Y{~WY)fK*-Tn+#C9Y@di=fPHwtsMU* z|A*)MO>?hwqFYH%_LuA1E$tLNdr6KRKTmN>Zwe{{1108Dl743zV?k{qP2@zkJpHf2 zg>&b(iO-C8=QqmF(}iQb5AYV>&Yp>Q%9TmA@67J^D=>cbK@~4LJ%RmX>>B-j*wj)0 zm`(&M(@M-v6*_C^+{3qA{j@c2;0j}oMUX$)dqd~~r(g=QcfCFba}5R~iYeAY(7D#Y z6gF!I0(Fr#(XFN)p)~rI*bJ}aAD~7PjIZ1Hn9;s~Dmwt>N>?|QG_-E++^s#8OlSg8 zu(?o)0|`vMH})+vZC1Q+<w@s(XUU-Wb<bcl(&#khbB~0YGq67fJ~YI`#M-0zHh}Z$ z-5-BHw+=e5N#n7fjH?TCZmZtdjU~QdQ?h^YZu+`=L!+ENoRy@UJ{&!@j67VOgL^%G z<+QMu;OE^wUEL-eW8V9We4l>Z5B%AXKh`n*y25Yi@%jBd@M&kkR}VLZx5%9@=*Io~ z@e5Fj2OanL{J7G)|Am>?MT42!8_5y^Cm_haZB@ve@Bv{sK|vZKuPx*VE8WVx`o9Kg z!pwh6;ihoXIa!>{k7g(H{v!Z6g_KUpB5j^LOOvN5)DUC}Ipw(gan-K2fpT=#p<P?S z+r$cwL*3ye+-b+aKGTme_J_PuR$9!o6TniqQyeL)tNb8@*WYBAZPLZ!k6q|<6$KmF zJS&Zn_~WWX1D!~nDL0P6j7A4nJwP0+-as%&y-n!Tvefc^?$7S@9}T9paKWFzs;LHZ zmZpukftgyvsu0i`n}}DUGN$T2Gez9y`p<KA5wC*ep@J^6)fX*nsl;IW9rhqETw?Y? z*5r6@OJwSSmIa_v*rAN4^oSPE-HJhNsz8MT8j@J=Kz4QEcs4KD_%6ueC`3mzA(@@s zDOH+`mR7B)Z6hVtMG9)RroN1d<7f$E)2t0rN;ecrXu@JU`(r5uUEV<kM;qW#$7#?Q z!}Z-669P2iFe5h@C~o>p#Ta_OpAcx6;7GABXPC8#`wp_`xKQjV_D355BLPWu<XdtV zrwy#hPYm-X)@ugkXtrq3=0S|{x+N5fiM`2b3H0J`CK9QkgI1qh*Ovhu-w|L4*iFXm zKoIm36PjGzovO<zA-tXZg<u)GlT^P8KMZC!%~qeMWLT)M%`Rpc6x(2^gx$$W-3LF* zOd-rr9E`xs=I#XFFDI)bkavaMh+sGj=5~dL42YqR@I1JH4q~KLR|b34374pHHi&`5 z`x|9&zx`h)+5O_qvn}&4gA3aC<ms1K+nuZ+Tw!U`7jhMEqSasDouVHcM=oalB|0wl z%S3`ryI2(=f^D7(7L<E}sVd;k2fqsFuf**6&p5X&PVJVjv~qz;>1mEi9<6D-Tw-mk zoS?jwSkFYY(Arq_C_ABj@+UZ2t|LHOPbKuOk<{BbTK>Z)Ri%O{SN&z88uaB`IX?Ss zq6+5AT#?^LY#s}WW$X{8nJb9)uOUm&&?Op65GbsHps<E{^Q?8=n$SJOlq;fPD4K91 zM*a{2ZHPIeNCcr4%-l~XUEBOBukFtfUb@%+H9$-Uzcf~*Gwt~Kb{j+0k0k~{Pysf{ zq+e>y&tytNY1#IiurAL~3&f3KDu}QBr?Jn2>YdYQYDIg>^tqYpeLi{sO@ZoyTbEl4 zwUokJUGZphXj(&EmOZJ7c^7KhfK9<_aThgqQoJ(>^hC6U-;e2Y-TH>+B*eZMP@ox{ z5gC<KzZb8u7t#G(V?h|q1Y!5RrJnCX96M&`CJ{-G!6c><H1FMvnPo%eu$~5D&mL1` z6s;;+ZHQ@^2rARQdLz628iIxPcs`0Ye<^q@7E)=#DF@e^j8P?zzx!=@u}iK=;_*eA zgA;>uo9-&r045+UUotpRu56m$EPl<?IC?(KhLpD#2rL-3;a@e5MQ71xFLYpX`k!65 z8C?zsVA|AL*D-C3m73STa!<piE$nUQ7;g!tsh|jbWk)l2%BA)8(P+e9=E@vy?x=lF zOJa!mv|>}fhQCUrT-e>G@KJ_A`F&ZUDP>n)y4^KHC&JpMzo*JRX;H!lY2Y2edyUL! zRG*;$N4Xg*YUUdTI<fFC#d+}q6<-mE4(ch(mTov&$VKla#Mo4M{(WszAPQMZ>w28e zq7;QW{f#jfEh&`BU^j{Og5)b)N)%d)7t$E`L@me4z=tY`pQBRm%nc*y8cSG;`U(1b zF}C21urmEpzhss06pl_L>!bG~7Y<3x7M7hIj<_CI24Y;~S_eI*zEogwW6&8xX`?Sl z-|@vG`sSP|`nm;I1%JQuiTQ8I<3-DP->-Jz^*MaJ3y`@X(8Yc^2>j;+6L9E!2pq>g z5#25<&gd}LSb{CiiU$6>1GDA&r~~b2wpKeNl<+Qjy|M)0Q_tTcm*$^@9#cNQr*~4Y z&i<UniY5n_QhQ;<j<MxV()lFD95QS%FrK0T4JwRzBIi4~0R>I;XE%74NY#FtETVoH z5m{C|jGX@ELFJ<9e(jr`>kh-(yJrlmDMd8>G_^Da!DPr@fAbN$m&`@@kH3aoLJbJo zAUq-S;#r(O+8l5#_BghC9Gm?Pt-%NO&?9?j(F3&q!wU?0EPoKp6jSMiB1zE+!Tv@d z6!2%MuescT3^gIEQ{#*^UUml(QA$v5yzWBsWf9kbrm$4&b#V&MH;GQnKq7IfN&VU% z^#!!Mz>)fgSuiulf0x(%XUj4pGaJXhtJM9$j{krcF}#n}593s9*1PraG$GC+i5p@a zE7VFT$VAASkaPyq9DF`qtC5gMKsHrxK!xTD-!rct+)i!HH!)^8Y(K78qT5BVkSM0Z z_H?j;fX3PgQNVC8r&n98o4t;sy{}*<>8HU1kswnO-*)C2a(2A=J9lcchWTL&?Sz3% z=;M$iWMJLqTR(uJ>U^I1{QM{^K0>wRV8$Wz6Hm^yjb>j802BO&uG6+i=r72Hha!YU zQN)B1aR5`{l7WCIVt-bs`?79_Q(W1S`u82zp1|}NZk^{h$0vKP+u3012>Th-qx#)@ zV-y%Wp2fkz);<x{F4!o0GT`PqT1vZQ479@<A46_8(n@P0440N^zypRT5Mi*;kOW~; zgvzk!4$F~%sTz8q_wU4RTxl}EH?&~$kIE9Cslawepw%sr;mRs(T-{EkHK$8f<|7ys zrAW&r!(0OCZbAwT2UFtdTMjaIBOPvLZ;)1RZce^fG|Z6%MRoy6=;WD|L^x<|!;mXE zVprDbNVwBGy)hEe*D_mw!j`{EBi#u11mh(UVgpcqgZ0Mw2(z!*u6^ct=Vg7|I8}Vk zxrUItRuo*r%6->E+sb$0m0ONdASr>pE!Mr$maO16Pfv$Dd6;3+DB8KJsTq@#L)OP< z`7fMti!xpi6LWUWDv8l)nU!QQ4N-(V>k?mJib<*V$Nd&Io{c)}LuShCt93JY?l9}( z{}Y(7VCxS;vz9IT8SebIkr=7nu<5tuBmY@U--uA<@Ext_Zc0)rjiXvQ1Kp@#ylK_A zy+k}S7g>MptNU@3%ijh*MUq4ucSAYqzwyvSq?&Y?YV)pIfj(?y)lIs}4c~4rdsFhA zbE_G&%+na&Db^w+vLsgEWC5~ObDA%_o>UG@wCV`;L3g^@h!vb3a3k^&0t1`rWA@cy zUGyLYDp`N1rISbN-w|3-Cu}5F^V;Q`%lI_qaxPDGDaJ?4HqBd2F?qAz4r&_;=<-8= z!j14~qnIEF&`zl?Q6rf@ia=GM5(h0ZHhCy6Yij|d%H1!&g?Ff5TM&!@Or<>{fM%9K zskCy@H~DzG^~~Uh07~d>;DZP}_b3U<+>`ZS2zND-C^N06uY)NcwzPe9(##`S!eG=1 zuxtcb#4mcx&@2)QCt1y?QIeEujO?<TEMl(2s`-6o+ys`7ZElk#oOR0uMpYlzASR6a z&jL7oQ-4Q^HDOcGh$=bL{|*dKF@Xlb2F7~nk)dU=bBkR@UqS^uq9L;c&g7fi-0D-7 zxfnLArz0?%?da}~DY%b5LMGDI61M>)>&^`R<%}hDJ2LI(P?`-87F8LTYeBhne&jbl zZed0tu@od?ZOjy8Ni@0t_X?q3mvC|e!OqXV)?{%1O)_%Uxb{{1cO>8$AtWzL;Q}Zc z{1p5V2>dZ4>1)+Pux-Q$0LpfQY6~k`6VqMzI4SF8yT^@M0H2*|_j0*riRc=2eGd0S zorMYR!hCvhRot*bq+@eaDcofpVM1mO1`Y*c^vyZ}j5w=q^1X6uV*qp&hraw!lByDl zhDab<<WZJTnmrmql8E)~89MW?RR<Lnbv}aH_Oo@CKO{j1<$D0PN+WTPnzejIhWu{& z&2IRe#s24qi!!#@*l3=#$%;3;95mYMi!E1dqF_Xx{Wd8ZRTzSG?Iec;mzi!0_0?Hc zi@$=7%<4orq&n})X#i9ufM#vu{X|7X>jXOKxv^N6iX0OYv*66Mblnpg_D&64;A(fB z_iDLJ{O$*f@V)%mv8NUqTJ?k_d5b$#^FDp}w#|F;T+nD@ZuGPf#R2~zQ?oGrcfY*< zCsVWhY~laM?SC#uTxLi*{ZzY0u75+}7E%2e3^*FYa2R(Q3ycj(D#B1iTf(>tkleP& zTM@4_#7E+8ycjk%7W!O&dwqH`vsA;HXEuL1YK`y`!9t=O588KQ{a2!1Y-RHGdFGjU z+wWwjC<HJn!iTlX)cM7+1#O10Y2}i&{7qYECkSk_O+*@-ij|;weg@4_{I=}{43uAZ zOH9MbOhN3Ym>**oX>gu{7HNgnW#)m~V~?<cT5=vv0U{$MY!9NZqzy%(4?sDghLWC8 z*Ky&~!oa-M_T4wHK8y@4eBZMhbKc`LqU^@${3)9zpFC?~+j(j>s$Wz>o1y=cu%j_q zVje(+WbCexd7yNhHiZXw1t2fYb*+9%hxP}9GqL@xC^AX=>r9!6bp=3}2Q~p92$7g< zLIS5dwS{(T8WIal5G)DdHS=tF3YCKs!%0;YMnDs$k>dQ7cbb>r*;^H)Nn`<3u9A2h z1Ixc9`<woN?urz?_TRAUm0a=U0x&LQSetXoGO7X>33Ngf!TSg)+tcP#s=56tCKh$C zxaGbGste{ZB3!r0JDA!`;?Ld!Lkn3!-)0F(!;)$U_vobx!4Zh`C5D%ToI{}qi)X?N zQ112%SA#yQ?VEQM^lKdj8yoI3@j=n(hH%X>)7ZtDwQq;Uro}oihhHV28kDo9F*Y4F z5D@qhle2L|uoi+_6O`jm7`_?+bATwV41nDZkxlDV3O_z_ksRu}8pZ&U(d_mxTW<;d z(PZwq*UyH5?pxi^N-^_Z4@X6VU9IGnb~qm+vtOfc8F?(p?6@@tx<&fW^LF7}wY!yr z5`d)PuHajd%M;VPZ7z`ve=R?w-FFrs7Cs<g#cjcfCwVco8-#g#^JUYZhZO)%AOAWz zJQ+8v&psu<NO{$jaF3lPfshakf7p-JD{u9fzk(C<L|Hx0@xf`#`uaOmdhPr;_g8<B zj~m;Cp3B3`u`qj)64nnguFP<I)&f4W(_e$H%)~v#1anUUbb_yG<}Hiq6k=#*g-L6z zUTKMB$aggz#-FD7=%fDrwvyY@jVo}@!|TP3k@QAA;de&qwDbqd@0Dv#QE@>Jg6MkY zOIIjrBr~BAA<teXw{tm{7F)MB;)mIHw^rK_k_;G37&EzjpGQv%LS8?}-<_CCDC>EJ z%u{eQl?$1+NH=uXsNlDt?x?<})x=9cyutWUz+Elb@>EX_qy~SmwhEP;OI`|-3f>nV zXV4cOqc*bTQm!nMWI%Q{h)~FHCQOMDP->e+NjVeM;Mi<rQ0(Tq(#|_3c(F*5)?=(| zWf<=Oh@a{44lexj=gyvt$xfet>^Wj6(5&=zSkgK-c#7?pJBcTbbb@z0>xbG`*VD^r z6OY)Os+<WW@>1AMWGZAa%^3Dj8Bb?`&4SJPE^b%dsKtP&@&g{{lF27d_J9PY@#Nt9 z1oAJG2Js{e!aL8B!llf^>W@@aM6Fa;>1$(DMo+grV;a>asIlETH`v)DByqGdhAh)! zaue!`=kKo{um@Z?MLlX8queb{#qDA&ntAc)mM6lj2-Vupu4?EC!f69hi$oPJ#M3;( z#|OeQVFb$=1x>ig&P*kOI44<ui{DNcwf2{xHTGvimBSg}s9-`Y=TeH6WidUEaayye z5ur5vj^8eR)`F%(?lNn$OR7A&XNN_GRWyOkfJ1aCM19kW3`rjnlnSJa>QddhAdlco z>T6M`juCWS2WB71-6p`2+NLPCo8Z^X1*HBM1mYVhB}@8S$@#|*fhL5RDAdmJijDPi z@lW^xD#b5}R=)c6&am~y^z{tDsf6f+z|Vd7>qR3t4r5>E%#XXg@JYIj=^2n&sKwRE zoDVNRa1DE`t9GMwG2W|u7<)YO6#I^xV%lx6M>~Q+-Fj0*`^Wn$Ep~jZERXK+9)L^6 z0l|Mr|I94^J^laxm#bO+O9#)+@Netjr+&CNxc@H~N1UpxoP+_|t51>uu;D4=HgJU- z1UVJ5yZ314_}y8|EE9WqtT~l6P(F)qtEh%QNy_E4n)Gk15Ur$8wOk&Eg-~7yRZ;*L zYmt86{mYo}f?Qs3ragudJg1d^qVnkcJ8U6LR#MM?d8PM<meA8Uq7!TzD_k0@1QiaI zb}WzB3|?WP!!Ky1F2yrJnNoQrgy#T867bU(_;?Tk5-Li-kuuB|X+}#lSW$2#3JSK^ z@IU*&NsS7gdrcqoO%8Y@l$b^^t-yeQWj9uRv8Ff$LY8SpDgf7kDMW(IkTgXgN#jPS zN~Z@H5KH}5+F(sdI(tvB#<x7MWLZXjTopn`jLfdtf$IStSO-t~vL3<3yOg(3Q>l4< zty1=w&mr26TFAq_W7UBUO8{@fO{ojZKX;2Psf%b@Y}@p<#STJNbtqb@M75J+`0+tU zou`JREFS|H1RW(zK1;Lrv({)_V<Crm>c_1LJ2sIal;?b6_b8tDGM;#@qDycKfHY?o zwYVp2Fb62Cw?SasQpHBm6rRVQ?7^$xd2on#v-$`{k$n_*hBz+k)sY1#Q)AkJHUnrD z0CII3v(VfrJZgdkdC(A*waB4=e<Snc85mNR&>0yx+%bBF$R?yjdr>#4WdgvYY7?Ee z$|^*7Rp?Uz<HZ>OG1Fm??`~V}n}Z%6r*n@DbR8KOBV<+B#BTVvWUpOjou`jd(U7b} z4}l?K)M6bTtu<sURQP^;vSoI6b##0?J9)momdGEx=j`l!ULHMceg65WMR&^GAf8U0 z#+2}9b^B(Gq+~3_v|RHAuk@m$YVa&UsAwosa$TUhVmR<~TyNZ5XmWJHl<;r%w8NL+ z_h0k*e1-Y8etmxGRw^2Xy*}?{*xBAZpA$A=_4TmEz)prPj+WKh&MAFf`_U<kJ22>n z&+Ro#YE3>E#uH~ndPLL?eveHOClgDy<<8+~=aXN?Rrk|~+ED8s3NXNn8HpOoJ5Qm3 zqQSYLFRjPV0nFxo$Vk*~h>bvY>-XFYv6inh6~fX`(zv;!#HH@~&}uGfr4S~;#_A75 zWmFjg)txmpm5L@4F8xGCVKXp(>tC$?Mv0bKK|BQ$sWr7uhY*vx2o*;$w$N&^-2i}G zmMPI_GTi1OLgE<dw%zImM5=6y>Y^G^f$>imT3@c}z=bdCPd_EDYv>QUS<|lUww3k< zCb6wp-M2a$pj}Ef)XizhWD^MB<ld(d;kRG+Gu2pmggWl(^CG5+4z)&{3M2y?L4DG# z-n9sPuVyf32Mc1bCIbkN*JQux?DHiS5lLJgNzUKYLZabGago8s;Q%^2k%_Pj54}KS z76&Omk7aYWFXWg@^EZG(6d-IJvR!}UDu$)&>@CE#aF*N!#{;y`71^$jwg`k5SHk6W zfMPW*w2){gM(X|fv`lw@Nn#<vCrr>E@IYw$BNX)Y$d8XQS3ViE63XnfvWDd^$Zqx* z0EZWw!?%2_G+wEKpT42L%_QVO`AHysyn6$&%5-xLeYg(s=Hp;irImtxg$w19E4XE0 z#`S{)a(kG9F)YTiCYba7UfA&?U=fnJqvj)^kl_FX98{N-0J70c^*&~0m;MEjQE=N9 zm`a@K1sA)eM)d%Nz<3yUB?3-_61YyFzUCT+prMgIb@amPwev4)I(Wx2r)Vph^8?2+ zADOkX0`}rX$K)W1sGL=i`68%lKiuxx<|_$XZi;zC1WrIkADw86^XSE8uZtqxqsTd< zWD^0OheXVmz9+>f?Jh8I{<ClV%;RUboMF`&2VaOss*rcYoz<qFzKUbJ0{duWylw+? z{|%3q<d>-tb_(9E7yIw4zqGX>3laF)e-<h>^!S3=zdhgSx4#~rjvjc2ySv^W;vQ}H z9y=#uo^$v+J3ig3{bP)L+df}EH?FUIAp<cku|VJ5DmbIfUxzl}6@XwQ%12%UH)1e+ zo%tZFSorWjG6LlDWb^nT(u-qD2$U(5Q`226m&-IuOtXFl&1GxFrWxrr|JNWV-P`i1 ztW9=`FPQDm4P_%|vV7i@pf{9F^p&zXa)^9h)@>)J`>RF7g|x|w?P{TsHlwbd@8!u| zk9t@c5t$%cS=b8_TuM#i_xUYj74uLx%6C_<f!4RDjJDh0O19W9SIRH$rz9O~(5dJ% zenVF30!HjL1=b5nh=gS8V%zesKnyknX{2S*y`gu@w5lu0uLiw^y&|b(34!DS$zNhB zt}HgGNss=eKxs=zT}dVqF5(Mdl0HVbKqO%x!U(hI+$1i_w>hjvZ#l_E{l)sBv5s2o zMYu!X$*X|46+0N)L}EzyCKBA?-!!#zgdX9O)`)UM3Yubz(Qa{C7F(WWbEQPTf8DKc zuUpHAU`exX%Cedp9LuA>t|{d!ioLClBJ7BYQK!d=lj#wf5A@eC7#uFI-nIGb=ZM49 zOU)$XHglmY<j$a0u1m?71mkSY<(A!qkP<`>qddk%B>w$WJxKnF90?L=en46a0byF| zjx?8cD;D1)R$iToj1hq(^7{*`=2rOz#avwmdjKfT+0fbyV=iqLg4@lP9{n4q_91+= zolbatK5g#gfRN|+T^wI4v1B`pg|yLd+$EF_0QS1|Bn!w!H;je2UU6aSD%cPR+tXqy z%vd}4>RfUk7cyVa@@u9nE@4KMmmh4E%V~i>n6l8DKTR76!Ga5XZ9&WQmg;LJ5yM<3 zXqnRZ&r&@43Hai*j*Lr5Lhl*y_2o*q=>&DJ(ukAUP<c}CN<QGEKdy1LZ#tM1hyD^u zo2&D?H(N$sE0MtgL?}7-Q4&EH>I=6y0U!D+-oCTSYn(WT&z+*y$lC-|d-c;vk-*qO zC>vxhm{j0^`8tIzsDaHP7@ngW)*p3vo&3GN_yYG9apQ?3wA&ibKaV~`{M_AI{5aI~ z&;umF8b=qI;?n&WiID@NQab|4=vxXjqUXsyky(6gbLQ43nUUQOowj<-?z3f)2P<^F z_$rRTr@?f^Ipzy_#;(A7&@Jq%%Uea%$K`z#zn%K`;P>XvNyF6q{f9-fc>5%A1Mj?9 zPtgpUbk9kfjti$pv%(t=OA+N{-8>Fa66GT035qq;&t(!^#wkDb>WF@y`MWJ*V$7+M zXM`$c;yBmjY|QC_>G2S<K<8ny&eRRg;*N(2bsQ&uwK_!UX~ge7J$haP<nu)I6oLbk zj9V&jcXBDV{Uw2*y*9{C`L#QJg#sc3ccjMts-Dp8HgkF=c_u8O^TWEgHxd51`1cbS zbY=|@r_4BV2iK=00xw&SqcOH;y)o|eRd}c}+)T;pd;WVmP2Ka-W)8?)$`(C4bP*Jr zxj>?O6lv0c9u+lf@g5Ko5VyU`dB3zt`yMM@H|gBOfwTz|9@DpHk!DM$O0trQ*Y6UT z^NK`L2JT-eLON+s70Hz}eeeb*ntBabTMKGxBr=f<8c)+|0sY$KHWRU~wS#An@8h^M znBCMnQlk^G&CVVAe7}(?{7Hi%#_^=Ib6RoflT0pjWyR6eHJ8U2ZXP{4Xg+*_4z+fs z|6%^i!p`~sHPB^bV*U5Ue(Bok8ypBDJNJ|i<~a?B?b1Gz0m7#twX&Pt0`k%980igR z17HjNEqbr(I>v?xCX(TL1g>BOuTy#jaXkNW*Ob%l@v17IQxy;thk)wDCO}jX0yssW zV7RI7D{}cg_q^H7-q_=b4`_rzRP@d9dggG4v18Nr>!+r%?1tDoM4T89&cKk}^doh$ zuj+Y+Kq!m`;zydm)Xx-}F8$&G9at_w8xKk1Gjqt`wU32Oq=8p)D2@H17m6Xrrwr`3 zHKJ)nT}9E{vB~ETp8HhXrMHfzd6}|BE~~sU#wyGK>yx#{qzSOcA*ntz0!Xo;!-ZbA znHGJE;CE8(J1kQ7x-lP0ENV0LTMh(<@P~60z?LqhjnELNED)q@mJ1kN8Ld%1BJcZj z&+FM+KBP;Z9B{e7U|a@>@t<JYr7*huFqUOnKK^oNoDtL`6zP`);_PC^=bwCtypi4f z0dpad4Jk;rm;H)AN#X40x@rxK+rW&R=5d?7r2{LFt6_J1CqIV>GX(d)0lkv~QG+u& zaRJ*d&R_intgr!4S?Zq*^fG^%m6iICi@{|LKn<m@4S>Pg8~1@4Fypkt@BHT7!p?OK z^R3~gs_)V&dFOH)#`=2z-fT;@3}XF;S)MoTHo`1R(o;15)dcNwWvM`G-(oRer4vv~ zI9Cp=(QA1jB0#ag*sj7~-RyJ`iCoNeV-ESpi+zz?%%k3#A=zM%a=825!+wrk>W+K} zZ09X<*cenV3@Xm@#ou)eE#5T4ab_4qQ{Ju5#a`KfTn^Lwm>gfOXzDHgmqnc>{(E2l zBf726TT7WHX}XKK7f{hqv~Si)PO}{J*XnZo7xx#UNCr3I;vsOLlx8w~JN#bjepzOI zrz8-n{Dp=E5(jMlft?Qq*aG$7oLIO-f9>70K*nCwCnY&JYoO*S%reKrUpNYeediui zVnNn&Y&D!C%u)9QO?&*;h7Q~pj%ZI{kk(`l4N#B()u0<~&zgRvxYezyO=iTz0QFmQ z($dbsf(C{!{;?$fES-178?|2!lHUs$;Y>fE)>S0Z?W<hF;ph8{W-=1Zw&+utl6wcT z7)cC8ruk9|(u&e(Z`>2f2jlb0m?Bak%!Wo*G_mu&4+BOx>&X-u$}n7xGeam4XA;$0 zY@2aNk<qc8Dm}swChA6GQUZ077K;)vYWiW9Tf)3UnS|ciJ)$NY6ULY;`g#A;i<lE0 zyk&SNpn>b_4{B6&O4@UbfN-gVK^2p*A?fS+Okw&7T1`VL7A(D>Vh$=*JJUEV<_Ss% zFO8PX@edD*;vbKq2yyFW{C0pfLf=@e2`L{uvzvNP)TYC{aa@@A9=5^APkPP9UzPU< zEWp9-s0or?bMwqFYZA+Mk;@VEj9zLqd3G8M4B>9hZBvg>r74k3u~JSYi&H{1mdX6m zXqD-oN*G2D-7{6=1-0`;s-^O5v`XAS$4O49)>?(leJGD`I)|PSDsHo!ZY^w*sJMjh z9+m2HfHrbFP0bX*07lA@+Z?09_nxE|512L59eGb@HXG80Q_Y?>wt)pF3<WwYyt)sK ze>AVBZ(hL?19_+ER}1;lwAS0mM9x?mk3S!QkSJG`e0dKPLanWQu!8!8Qc~B}ztweM z`2I#H>e%q|ZJi06lvC^A@AZ@&K6U;>=4563$IQvj@NXB6wRHd0F7mU*cQThvS>DZ$ z*Fah5yika}ndTY~cMu?%21{logZ{KqV|{@Vh`g~Fi}VJx8XtT$$9b%^BDRZ0V88q_ zV9{y&zj4{SF#aM6kbs3`3i`V+y-ln+8+w^;euQ9<b4Tqj7pH%N7uxOH6}1cgvV2+S zF9ZSjU<mySqx9);@CFS8yzm4^AkhT$J<L1u9~7md=bwf0mu0T8)`UaAhH-C&alWxj zek$Q;5|EO9=zJLyMP6F#)}RbD^U(c7#rEk&LPW%}N6U)$h6VSn^TIdaifmac=q1@P z(fyE{y~_7&I3+Z4++bsL+N-T0B<fPd?kEh$<#gLZ`&k$N=~r7cjL8Y7;X0>IJp^47 zRLXcDb&4d3$-Lr05priW9e39>wh=;>>oH<LS)#sppo&;1#+s}RfrfB-qI8!|X*!B9 z=_y%LDIr?Xs-v|`Y*Xtq*!HX~QduQ?!k6{MYaVtq*;jGITuOk>-#qBtX@V{xSttjh z{qA#6n+yl)TE_a#x|KIuWLwP26$7+L93Gtx7BMJE!eV^u12Eeiwudk7w;MKvWi5R4 z_^A<&aU^#0SHy6!FKHGd@KD*kJ~AoyAfdC+q@I4IWJMplRHeq_H55%sd9Tm0Es~SR zp0@7mE!ma1L5KzP^hQmwA<&mi0+A~r;YpVY67U*zRZg#ak($f2oo~YV5>?69x?*cp zR+D=q%J)fV`IPvs)TkcMKG^+}Fc5rtg^(XORwtor<inLkQi6g<SP+&dj$|EgxU+_I zr}d?)<2979M}+)@z+C!{d~riB_w&cb&5sEueU8PWW?F1Yo=>^i-^Ut*x;BvAzjH6Y zL(Na5HW5r_Ul`KG1wGwF-5LBF+&h^Pm^<-b2}!#O2R@7$AUaPMhd0Nq^h5wVZH=Hn z7Maqo5ESGHgy2D!um=_9p{pK{VyWYwEa<q6q4LO%r6@R=CG<-<^`2yo5?Wk=CX6JC zNTZ=fmyAahq>muw)bdv)YptWB(MrrNPrQ&Y${egNLYg3y?ArdUiRoFs@AAJXyJ6(i zkXll{eDRP81L#5q8V@DB*W}M~B4bArGraCmZ2q{SWc~$C52~VOyRnx9IVQ4Fnk!2? z&7FVx8hBvyE5^aitfgERTD4Gh&2XXpp-G&W%H=teno$@|<xrYc&K9t}eO%D(wYA3G z@<vwJ8@+93xqS$BPTp&6$}MVYQ2G(B{PdWD2)I4y4JLV3W>dDsXipi6)F<YuB2d~P zVAL4hQAu%_4-xIt@yCHWvO7cE7PQ?KxMzIyj?=W-%>Om!3Ln>cyx>a`@-pDB9`^Z# z7&$`^9ZAD10?F|6lg{#g<qR($=uv~M2ICq<g5W5qV~5?k_2%8c6LXsYREh#FhXM*f zHOQU%G9`xA*LpB^&0&w?l&3u?>X^x#=*lAekdTIpX*esJESRvb*ti2v8E9PAPT0B< z7GGQEE61~{OLw2HmbPztrGH<ZRjvU@L_uD8Xt8y45w`cBGg&`hYbbJQds9NHA|tIg zc^UHT2g%Eng&OKXbzun4-=GLj&R1b~2Ht=%3T7oIiI()H(uz)h2I6M-PoS!)DY09C zmMGLm<is?K#kOUF3&vy|zL~u5>V@s<V_L641V%r7M{uY!cd#-xHb1SAzx8bjwN?6u zJj(Kaw440<6<Fqfy8=6;ts8;Mj^zC>GWiy|u4+=b3J~%r__ppUDDwN%OP@oCJ`i&R zZ^%W@j&geeo>_zI;bFMHzvA;HT~;-hlDEr>7DtkbRh&rEP%haM<E%>2aBuuuYjM#q z3b4E_USM{qf{q9&qUMK0qC~jf(l}fil|wYLMGQBFTVuHc9CQ0KhQT;dNL=FJA<i*N z-3^C$m=(4XO`W0yqTJ>r19;P5);?Su$q*1Z9U|SqcDji3?zv>+U`@VcB^(W@<T)W` zf^>=lTz>e76AO+~iaQ*R7WVUg<{!gy0C#+-3Q`Nq8AVFUnB&q+m0>3p$#R@{D_Kk0 ztD%Dmcu}>|X6*qS1QQk(Nb_OggeG!m-Gh*L8CDW%Qh~7Z#DunC7lpdVTO9XAG1l1f zezk$<)+*I#PL!twwyVd*>Egxg^|fS$tQ?!LG2EkYMDmo|P6EG?L=N(?ra#6NW7@cG z<^hz@M-0+kFtS?GSv(BFztJIoFDus=v6VJpgU*YUwGg&BoNXKZO3jceb6~y+Fg!TT z<)I=HtXgKMjBbFkQl4uVgCU`zwGF%rOBKSXCPKoN2Q(-Qq^lOxfTh7}c_n~h5p!;? z5T;A{LAs`-{`tl2K5e$(ijXzae3=?GGYqO^Sc0(3i0y{GV#t<<WY1-aj5i#FCTR$2 z7`oQ0!jln@?6>iUL52no8Qe|MQ$q!sZ1~Q9KgnqH_6CX(WM4BgYOl62dxaGq(l5{q z7YP8|@N6l8T)hPS`}Ns{%iG(@$;-{f^K0)<hr`EA3p>AFR(G5C^TA_B3aFQehs)dh zDSnBa-aJPum$&cd5nUHZX{7=v9uIfx#B`hApHxn2#Oil0UXOUWnT1ok7JA!-(~gIf zXMCSf{>|^FC$g2ww1!Vs@5d$7FFJs-#?Af*S>|T6IqN?Bl?z#Z$P;1~M?o58-u3#v z6Brp<Ypd+O0?|i_V%S*AF@h+R>Bq?m>);f`Td+WfDGhIiv}28-{x%D}I*qN|Y$c}% zS_m{J4(irInoaaaWj76(P7^4)rOiFGqCn-Wf4xg&`QCn7;AqbXH&aPFq|u-#Ov%;4 zXoxd23FAff+;u~M6p;eI4sdW_LISi-CmHbcFF>D`#%X^hreJ8S2?&wj$XXjOSgx?J zhBer;`w2uu6c?><z4Un~_Y)q7kaaw<VGz5p`7?%lad^KIN>B$X70}3@IqLC>#}=DF zKay}IdsGMng_|~cv)-mTDwSaF7;Xo`P3d2yb)#KQmcbkAuio<;>-lAmE&6IAn#yPq z&^!mRR(QXVtvNj4*+oQ`5iL7-E~=ZaOK2RMw#N9_W@EvpA=odr{v+E}g7X3buErq0 zIfNE@TE+9U-&va?=qpIc>cT)n_QW`tpvnA>PvU~k=8)ge0ZqcvtkX3M887=<{cr-K z;cMO^QX~-TRJ>66!qT9M*!&_SqfT{-K7c)c=e2}LuwN}N#6n*HXPwGE6#-;P4ZL50 z<8~FPya8Lzi&#;*QQfZ&;=q_J-UIEkx3@QcHX!>wqyx95-|)n7#O-sA3nV;RH+ZNV z7LOD~9YZn>AcW*+wzs-Hd|)e2A1*pdP9OH)QaT>aR${&{9_3fmOY9h*AE&n7OP3#7 z`LpjnFaNmNRgbi}@;%p_<L`8T9X+M6pcLpb6B9m!&+=*9UOaL`gb~4J)!?^#$GnO+ z(dkDSZhhwNz+0vTddU9ejO8qK%5~Crnmy8&s#dO-8{;B9PptgE1{;ai%Js5iJ|8S4 zwVc6Il-6<vPEZ-jtC{(-oHlZEM<_N@w#ts&(mpPjw%qx2G_0UQya7lr90;|+H4E~U z&4H`fRAN=hqqlYNh)mWvR(-!_eR_Zl&}E;=(<%ONxQbo?fS|D*TIjlfPJxxoLAfGT z!u3V3LYfnaYDZQBnv3%e;@B1tb0bIa4DO0*cw^3ikz&d$)yjv8)FH<1ilSwC6RhtJ z(~J}1a(hLkvLPs`Y5!@=!!cB1-WOFHqWWW20n|Rhln?tC9Gj3PCNho%lj5p)B9zVe zJ-kq2mrDa86RbZp6z#szuaR&=eZ&;Q6}Zs+ox+gFm~<kRt#HNicXc^<FcGJvhHykv z_s>ZgOHe6lv8YR>CSFQaq3<gz8_}DJh-z*kC<IDuAVA@t^X}e5m!pd)oDhnOu>?Eu zN+h2yxbx9Z!XU4TnjO~|7L;ubRWBR3xCLqrk@0aRQGOeBLCIl_B}PG)j6#bNLSlhi zEGZ^<mll|iLZVz;VyI(JW*QHO>A1MWXE#>%O|IJ=aSSH9G@+~6(TcS8_(cQn+yQK{ zp|!y7x*?4PCWoW?226tHB&6*c0V3KdgqP-+{v)?)y(gN&ny`q~EhZw|Tw(<Egc-tQ z$$}J*GW!#Lt}N!gCgSEO2F56jplL|YCL-8GB!EdjP>ZO7is0Wqm`WY)+OSvoexfw6 zATfAon_(M909@<vc+;%g@qJ>tGrF|zKtz`(p%}>wr>m`!0FbuTRmc{?gTuMbiQ**X zGRxvfvndJ9yh}buKRjlwPtm|1p@!}<qs<K|3||XaiJhVnJ}VMP+j%VAiS)Dy@mcI7 zSK?m<G^6)qdDM4!n#(&u2vMu%F-10_mC+_&ei#exaWN3PxwV*j#RrqhXH*t$Pgr}D z!y5yQYg-p*W1ST>^$le<B6p~`8-q{*j_tk!9kiX_mR@IKDhOgQJ@B*+o#~;V1umHL zA-SV*#A;#}bIb#KZV}eTn6uIKh(aIkoRwb7?x-GJpz~iXmJep!1ip>Oc@G=ef97+p zJsLItJ{PbvKtJ>S9NIuWIy~AyKaW3$cQeSFHRJ<joBWu!)RnShPW*e~<~8Yvbk(!j zRY@qi)-^awO<G|8{Ui=bS|ArVR}H66J*T-7gBiV(QhLH&qOg+^7g<)kg;cQz;|%3V zzHV&6ARafnb+5v_nHRzLpB-$X3$U{xuNTGV0i-a~Q2J$yjcg=iBlj1Gx-3V*Q8q3j z*%ZRp;%12#pTZ{39n`o-@A~W0@YJ9!BG*JG?ZWr=5!#fP|Harj0N1j1>pHe=+jdrL z+qRRHWCbg>ZQHhO+qSV{-|T(Px#z$4?mG9c`fARe->k0ci5}hG7~_3ji3z_|_k<-; zy#ZChI9ggn27&!@q!=+#v4T0O&?b~6{VK<^5aSVPF)876TA?+0b!G%k&4C*M4M8dK z`gJqK;pm$M-pd&CCFqCQQ)+R%<osCL#Kw~#j1C3kkK0TIC!v+Us(fTh@i=-78|Xs$ zn0*t}X!E?D2w^<<T5P3JKSCZw9!}80YYFqdXAo)My`2Qs>Vg+>4fu#qjES67k<c`p z1YYaHH}7&KSp*O+B*fgW`61-mFASbMLT2+u)yRngn#QXQ!HG6!!AnPK@O9zBe}vHd zR_}aYKU=|aWXGqUvG>p^sMCh-WXKT`n}Pl2cDP^N_8Pi=Dkc*);!egu1OQ>N`91r@ z*VwIbHG7INgE+)^-P=Gs7ERe;&JAwEi!o&odm^6<l}E}&x$h4H+}{Yu4ZnV!tjDM# z7*^ZGC42Mnv@zczR#7ye3&-X2&A%%ke3S_w<F_(30AHiQVrl5vazhP`Ed1QHZ^5gc z6ZHqXGRB<)3m)%`vOMT5e7+j#@{tN2{-8I*SS|a9yJJ?ie{fJ?Wc>yK|GVvJn%@9V zaRkq0wHpW(w5&InXicqOl!q%Cp#^c0ic~}f!J3e6fHnsoubI0<zWjnGdy$zP>R@TP za!;qsyfFN~XMBEbzV_Q@>KWuh&Kts5J$4THQew=v1WJRk{;u#`qQA1eysG47=vuR5 z5zK)M=-}*XP<K7EF1Kp_v=wkeGq>jqKq%rD#+K2_?gp}<sqUQh38l^b2%#;;%3Ub{ z8UG?*%Xu(^F0dut2Z2BJ`B+d$a6v)RS0rSaDiBI7A2=XmMPyt<1AHBE@Tc~d=Vc(6 z$t+#}80J@Y`8ZjNyyzwP36xKJnb-bywda5~1)Lm9@8dVgF8O=JdAWywS~hdk5hV$~ z2*}Y3w01~3d>lh6n^A-eKozZ%-p6MF>YyTJAdo5jm!Z7R)=*4(hGHdbuEpr~%Fok% zZXv^;qF_L;dS}tpoub+&(SeRg<Pna^pgM0GMQBSh`7)GJUgo<ce-0d?vMkI60^k@W z45}Ta<Fy$;O_?gRnUYZ{M6i|0^i_wc60?EI%jSRq>!T3TNT8gQQ20r`eqnsRw)p|f zD;fv{++2^jGbV~WmD1=AS7cT1Vc~Nk+g%7xmY>paHos(jFo$E>=*r}wIX?I95DfiB zIVAx2j80gUa;Rv-NOW9El{U>!z|X=rV2KC>)f@!S;b5xNy(a+&aj#$kIG@9-TkxXI z@n7Y^Xay^n<GAu=Vmf9qeBrQ!<b}G9`|VE;u#?($7u>sN#yAz;q-6G;6oQ|9iZ(kN zC@Rl}S-m--jvrWFD3C-bbd1@bhu9l*8GhOvz4UmM5vZVmvi`7!a{hU1^g9F}Y*K=b ze9g9Mp*J@#$#OsL*I7@sWLXU9EXr>a3!@hFGnXwvl|pXFZLaVvz9=gvhX@4ayucH2 z^I2bW@U3o1fej@>6F>Gjhb@>NRsMYT`QfX^XxeV^6iM-w^O>OPtui1m<KBt49%(5h zgh5ZMAN|L+n9z7|Vo+Q1Q=sC6(!XPY4(j|g?-Ngmw#Cp#;R+;*C!M^sv*VlS*%GX* zXv#8IY5N{Vf0n6=p(ZEYHE<>77w~B28>5PdLWVH>0z>)0I0VFE@fs;j)0Dl1CWhJc zWss7n^c*IZmoTCbE%!hMd=N3?f!kn^e(n47P<*_Uk;g|hduNi5QOxU~O-FlVd)Q%C ztEcFojtrzznynFIDT|v~0zk^eczRPdf4qd1DQP&cG$2lTU&^&l)Sg8(1Zb=u!y`2` zV2ha_7;*c-{I~_5`SvVmb48{5q&W4n)n8hVN2|16rtouOAO|O#=e(m%c3+L$UTO)p z<QTd8cNw8y%XjlZ9JR8AADar*_6(b~g!p_3GL)|0=T)Mb)o@4Ilo^_PEc+eb)f-+- zO#1MKxk(nXBDl`Tk}dSnm<S@^<g6DL)tVf5Zev<*V0-T6_Jg~T+d*lfq9<}Uq@BQ- zUurX(Y3u6Yv%HTvyU%0Jd9+%3q%(j>ARcNGZmloh7Ry@?vQ2QsM)e8aX}CFxoNI!4 zPGc|_(ng4AunmK1sQ<y-YtEsiug5hLVf$YBT3WTx2mp=CDp50q5x~jr&z)_NJ7(S! zpS)bwg1C$@u;I;&>atAKdP^w?!7!(k8mp&01MVGdTdYsx^a2F=F4)=%OeK5eAzA^U zh}<lIc)%pshGP#UxwMwid3v+_7iIV3lBS|}{VBcUBBjgUuamQMAl%JGrew;{c;VGa z#0D0SekbK{n_WV~ce`kQN|^e9%aC;F^$2y1*SdX<c39o)rbkZ!duqC(k6q~%Ccw-1 zt%c33D4$U4mEa8cg!4eEl+cXVi4)pwvBXBavWbJRVx<Q>s^L;iy6&5}Hl97RQ%b1} z3RvgOQxqvCzN+QSe7Y%D1ZUbl%cF;B`l@nqOnFk9T_;X&{afo#(rm!}S(}$G7ww-l zj*iS1Te?a8;(C5XY<sE`RhO|CE16w7UiDyl3J5n#1Rf_F_jKhD0)XC#0^>uSXeW z@+>cVJZ}J5sUgg9-%s-KwJaseRo7s3`Le}<EpHxUPE?-|ho=Ib0Xb<mtngpJY0KTV z|8Tis`?k*ffBZBV8NbO$|L)}`?JwQR-wdRW6lDpyZTjenyu*b2`jkvf`=S!-5W2<< zwEZZrw@Yn)K_u~z_Pl2zusNA8@8h^1_X0a`f913XEj+jip(siMb9!1qkpxIVV$%41 zeVGB+m-hGV&A;q_{0%QlkDYxRR!f$Bn`?#Rvuem3+J?3MAqYTEt^h^V=fiHh@y@TW z|Kkk?p+M6&dp6VPFM656-4}#5yO&LlvB53RUAu9gY@KploANikOcIciK{$Mnsf56H z!q%`T(0Rks<@H$43;Dybc+-MYE%UQ^Y4AnjYt6zr!+bZ~4uoAMBBmi{^FVumzT;ly z5KyZcMG4K6L}Q-|cBTM>N<sjcIwZy&O)k<&vi5K#h2Y%c2>xBGU80~)wrHz=B^$(+ zAwzblQAzYm&Fzil0d0YD?q?v&Kxn#K6(4+O#YePEiwS}muhb}e^y#2a9!_;&LCB$6 zI^p<(_5P%Hp!YkBj_>U6BXR0ufTRPT`QT7=(6`5DwFG?2o%u4~=`i5033$z{<7lt1 zD2}nBz!A7Enb=0x@r_{S)|5Ej`=*Q%lR<@cfLUGy1SjkeU0MXmPE-VI;E?*_mj+d1 z8s-n(pW=lOU4cSRA3w!k{8##NRka~*!=_EX&*hCC!maYReGOc+B6o$~FvO@hmdFvi zE8XxL?hFk}zfXYMBCLC%0-#Ih`=T$3SQsR)Qe<A>P!mmcFf6C`ohKEW4`UB5VtxgX zRyARCwGL!3@`?UZ!k#yV`Sk<xMNI9=oWmZtyW$#u@H)}K_hbm^G3i2swEAER1O2r9 z%Tx-*q8xc4qTI7|)V0tlSOPGmB2_bgc0me9p97NO6q^epowVQvr=59uD2W{=%R2tK zGQVaoeuGJ<Mm*@|KIZ(if8)+(VscXCRR1M1m)GyD-1Xv}ThIwB>OIv8EfS9W>V?ih zPAYwy2V#wy(B~J-1qp4z1m|dd=GsmBf-I#Es(5FWCI&eY(XwMa_QoL0YQ^Ab_+V2> zQHq_yMrCEo+gaHBs<gGjMtNmRa`)<SwTY2NMT??LI{7nQDnaoHI{n8=8HJWj(q<)f zdpmvI{AVTm_|;<K=D2rQS#lC>`A0%<n28#l{9OU~?Q=yh=4<pX3sk@zSb#FLLN~b` zeUtAPsq$^Z`p59Q)SzuUsMk25pOA!Z9wtwLs>`maE^AcVG}-yZf|E{L`;fDneQPKi zOw9LLy}upQ{Oag!_^a<c8a-<JAy+%Jv^m8Wp#=8BnOeA*aMxiz6u%|tfq>KY&vj?( z%K!>#eFrjm1O_+HfLo9AY0uKEuhhtE`1xcp^bFZ#+-S{#M7Ht?fx!`e5?0>$e1}ML zh}RXGg^u?9dNR32&^v7g&iUMQHv;f#1YxsD5N+I1I{|+<<baJ3XH}2O73LZ;Q28k7 zJV)WS`96vmYC74y*#1HkW;2E};pxLC<i{+B3Y59*h$&X_UvFG-?&LdIqIWTdcfje> z<r1m9dZWXRe%JEUR}ROeFNZmqtL0NLiIp;6kiBikmJ8;diSMt911tNWu5VAL)W5ZC z#-5>HK<Zp&%l{DkSegD6eDptOqS^kt7nqIXKgo{&f33*38`{5Sq8EcDNf~@Sb~Xcb z7^1$}6*y+<6MYkg(S&c;PYFk5W=P_BQf;lhLra%e>&^vKDw$<-i(_$;bDA`<nlPGs zRg5<UV~i)IkFG(ImVV`ltgXu}f}vp%zcWJCS~QR$*I}z5w^k{xEQ#{*TnLLbAc%OD zrL>7dXjr$*NEuZ^t&&!T9EU<Pfe^WK7H^ZX0wn!m;z_jk>GVVH`3VvVqDCReYZ<ZU zNq!U=vF_I1;()|PT<_sOwotR0;xduw&IG|kV1fUzkno%s(JV8W7~uiDbcGgWGBs9b z^5Cp8FeWu!kSvqguQELF)Xp~+fn-7<{_`xlZ;Zr1wUg#9t|Va!oM>6M1eCU9oH?vT z(#RxlFc)dDVKcMHzsSN`LT>D8$tDjddgogvSlk%|Momi3yQRp<Ijl^rygO&8Q!}6& zjFv;ujKy>loxMF5=MvfI=boeN(SKuKY{0&##E$J)Udnfdq;%qW(!sid@HsHUXbijA zfS1I&Z~)q$n{sAgcf^Qk9v&9W>ae15YQqB{M7+lj13YLR;*5cN8WT=R2E`5B(-IaK zUXCEGJG@MgA_chtASZps?uw>obj4^zgLu0?)x#5t{{*%mu`!g_yA`r2q#4~QZ_ER2 zAxL}kt3$d*#1Nu4&xQxO*D#_Lvml-Y12HIu40n$)fQ1&22?pv864~!XpW|W>s-X1M zRo~jo8Use_qK^&Fhvkyz`@!11^*@Le-d~+E#npciD{N)Ay<c_>JU)+y+rKt4x>~>P z_b-c^L3Q&wxIaGbqvxCLEIe8`JG(w^VzxA=)m5ysCsq`+IfDruk2k{hORML@(NFI^ zxjrsGCq215lRy8wjKkleZ-2UaC$lzdGmq-ctLbg-T;q!cppNH~vrPgyi&tyZkZiED zKR8Rf1CTZ1aGUijYtadwr<?(%tT;krQ)gj{_O-}nE;FtIrj+zl)PO==Kt&~`GIe~n zx;F8VU9?1e1R*4|DyxwYM^p;^`5@r6<@z}W8Wq)O8~_DSpnXZ@)5OX&8gY`}x4QFE zA|WcRIlKVhQ;^HBjUv`)>Y_0;VB#_uY8(UXO5v*#3_hLt@x6ygUK(tHbgRCQ7z)eE zQd_<88orVp=g3r1^NpPIW>U)2QhL9AO3_-IiM?NWPb#%Bt;-F5Vj8z<8RtY<CGo4q zjHjFT6GPV{lC&z8x`agaZRmdd$P2Q1Cm1r9H`Q%vq@3&I>0<F4{Ps4GK3C`Kl?hj8 z>&Gc!=i5t$Ugy`-<>aZBczfsXXB;Qaqerfy$CuCXV)$kUSmB@AZ_Ag__}ku&UrJcz zfTD?*cTR;o)_03<a;}gZ?b+LmX!pzq(Ktl<ktll(KB*bto?CHu{9`yXI1_fMQv#XI zO?H!7b(?DeQ@#yuCfL##OyF#{BRCDAV#hf$`dr{PL<=?yzNa8X$m;91-xIeDm%E{2 z<Pltj%ajeW8qQrcQ`O6q<+6wm3Ipw)kzFcc9(L(^=0~e%TzUqZ>+~!&Twt|7xPw$_ zwd~XY8)%WlGlhrxdKF0&T?jgR-0=8Wu*G#ei`ebk^3FlRZ0tHUo)GVgwj`$u^+2bO zW;zdoNE(vZtT*^iV}>h?xO|?{9Ig~Bdh<m3taqHK&}R~XU5hLZBIKHkSx?46f8<=- zO6@p-x;+L#6im@U4!sfgeHx0=>Biy_@TVc%yJWJi-3Jv&<gd;5Xd}o+g2*pRB;fFS zQk&~66rtRQ*65-RR8_Q-a{9dZ(Hsn0=9+*bm--BKT!9?`R6(l7<nM97c4!I&Xt)3q z{l?~KL5(m^2y}!Tq<pR(Q$esP4|p#fiN^-04=~bn0j}fbEEP}BGU-l4xQnQU5GQsB zTk}vVfqkaw8&d(0sT^Fw4|mihajqfNGm}zu(Ia6#_&LHVpdhJ0z;e;$jw-xPW#Em; zx7xInMX#Q}d72L8`b%m~E6TFfkEv7_bh=4!MY~FlRgh#j1Rni)r0EUIz=adSBmqLy zEF8;}PECMCO#+8!J&P#RNjn*ur{^kB84#C{Ln4-f1|U`_>hA9Y-ehfyQw1I;{^-i- zpa!2|SMXD-BbQG6smD&n>(dE|q`ea7H}DWfB7%~p{RHF=@H<|yp6?t5f^etNnLei- zovzj2)T%*&M2xqZf+9~FbY^K+fS-D{2dsfEZ3Xd$jw0;@5x2jD=ApPEF2Bx6U{=`W zSaO!$_^^~i^vBFd70`)WyF8?JDN2D<XnswDF3YUDbbZYuU<o^BXWvhON#Q3FAka|k z2VtGtt&>7c{%~D`SiNZS=^LCLNeJQg@L|SuoMS*9P4RM3V>dDQ)3kjA@TSyZ#OxJQ zRb&m}b-mSBY!p6zDI~(Bph2fo2OgqjO>aG!uH!sw^P1s(3PhvxVGEi#{>FeKfUgJw zs3+f@z{{=u8%Pm-o%Iud1o)8h5QL#`OHG(1(KnmgaBSD8lP)(~hb|Hx0*VpP&1Qi6 zV)HJMhqvTOcH)=*$!0Ds2^%Z^$s+mnSJ`#u`ptv?Yuru#*uFSsUtfB?qwFgV(LG{D z7R|1EO;{|h_+j!uSw7AFba}2M%oiSVr*#ZC2{`RL;ro4_0;l_PhVMBtY)fOia+TFC z)hYt9Q*6*#Rs@QifBvYY6bCa$s8jRT)J&-JCLZ<%6N@@2^%d#Av(H$*IVm-mD#sI# zx(T6Wg1un1RY$jO1S7BPfD3(EP9b!TVwSKETloV<U)g}te;+c13dFkSUhw3gyr_Bq zrkX4kJ(JSwM;S#SCk{4A8&~V&B#hyYiG1!uLh5c6aoz=U>XT_Iz_v43DB=y8t>N%p zJ^?I3k;zpcObdYu>8wtl1GJE12{c!p<%K(K7elwgjKQ64q-yPvlFHv;X;U2;ub>sO z6l1A$#fe2ZFv2OmrLM+{z0Y)vsuU;??^~+}LyR!u93hHb@8lD%{fHewCdBq%;%M@2 z2g|99*fM%kd&f_;Y^bRb?dtj}#hE370-uS)h)Ca0CfEfq$DIf41?fP;uHtLNrt$Ep zGFt1L35j4#W5}0BC7m(X$9^a$So>aWfDW8F&9JE_f<U+MJN^{TrwB9qKunKPY8HoE zBE&`5EeOWXfmMWLueqX%el`&tV8fEI!^T2^=c}2Lj(RrnTS)u;J_BPLN7Ygoh_4>( zB+N%UC2&tJjHRp3n}>7D4Uqfk%9IM3g5XVB(!<5gx#t3)=m$Me{Yk~cX$}RXS9$Jx z6=L*s!6h3RcpL<U>05o)*3PrHz}ufA^=?ns)(|L`55{7Ni+rs^Z+baGYEq6amJZf% z>T)*d`L&T`FnEjHp+O&ozg409@P>G3NCr6mSgAeHyY5B2@I%N^xD_MmoS%7o5GTQg zapcixY!Ia1dGl-#CBTMp=+OvjDE}6bJbMb&sIO{y5M$k2gK6u0Sb>y#x$;P?(O3tj z_9G<?KMs)tZ#~Ql#e_|-_MCXBcwqy|hPB(=zek9!YPvpe`wQ@y^jPm7?s?f*|G^;Y z8+!b28~lEQDjd@}P`sY1cMwf2Ra^>&*<_e5CyLr5U5bCLt>y|(GM%rl6-0i0K>6b` z?B(qZ$<Cp#V@RC5O}W4w<M>QP0%zWBoeNwaVj@NX#5wN4baDLv@pBwb#;`wtsmi2& zI`|mexi_>w^~CFNq}T<JEHbN}-rN*XNXR(JgmeFTi220lGH(w<;MYG3h~HW?JJCLO zy#7WXqf9+LjD!kd0!AQx{JzkB{5<KkHaq1CPq*%cU)6Q+stytC39$Ew0@%1n0)nLA z*Tq*D-DHptZ|?q}l<Rg&X|=@4E`L_RD7zh&i|L)ysE+pBrHbZvxl6_iUIJj}cC300 z&_{Rm98!NBlo9K23ptF<=@Wr5ZC^bU^L~nj2Pt$TvPVYjFO~usMHWa4!Eh!L3>nUY z&=eZ@wuHJqz>JFnM)0YC(1!(q$>sv=@b!_+A}Hh$1%j&WsV3a<XiRbb2^h7rE9jev zAPfxOFE$R`v?suJGc!uaaU8twtA6W~Qw)s3@`vFDA*d>CqTSw?07Xn%lu(>NSxA&c zVVvVcbjY@V2MKlut%kD_V9HYi<g@SmEiGbhW}DYDlHk6f=u_s0az+w*n>~T{H8kL; zdRw)dK}x8E=+oHdC+zKv6gx&&cVVlwm!iRE^L)V9g91ZTmA`u9;%E4MHye^VytRQ{ z_EvtuuRld9&q>~HKeUa`_ZAXD`>paw83*l$sX{2zPZwQzpqT-M=TmmNS-BxjX;Dr% zA&>CpnDbo^PkXK{aS8UA)#L<t()+@c=**hK<=sL~dkgJ*<}YolQ&xy|yX21Peh7%0 zj!s;Q){8%Tyk|Atz2&{QS>2su_gYMW?!a^XLPLW(%1E;&57<^Y9Yoks<L_*^gf&4} znuD$b>@^MixnO8)*EM;85DqrbKNS)z7NpKbfafgA!$kgev5SC?gVAp}plXAQyu+Z? z6Enm7XQpYe1n;zldTw`?VDLd)OeZ$VtEF@uiN1NBp>)V<F`03<a}<r?-u9(SiQd-C zR1^O93hLtxhe5sjN`6(1*pak64hCCwkj<tsqd@fhi;2I|b37HS6n*t*cLg?e5e?H6 zt>H;q$VXZ|Rr6X>JUDG4B_XMgmx*T&#SQ3IU}^&>=Z3`vjUF1k7gPF>0E-HAv_<Mi z{M9uLR{8xh_ycQdC7NX!bcbTOI?q;G`6@5f%MgY*#kdoBbhW1rWw%1wTy2{yrAL0! zuAtgvn_t%OthMHpJcTEmh%NJOo-@y!_I|=S%YD_+nI<*s;cv7p*@ih_<kbV;>^okf zI7pyAaxfL6nDGrO!*x#zN|U0K(wMCtgYG!txUq+eUszSnt28PCEA){~ixjnsCAFBE zZMDhh>be`UT_iSALSaCM(=!Q_&xk&kJ6UcCt<a5==9;Yzs&=NqLtT)Y%p-X+p|~R+ z!Sy^7a9p!g5O=K#RrQzX_)e_Nf|QBVy>41Ktb^0E-6o7Po?*LNk-3vPljdKV@B#>* zOzyoWl&nQhvZ-ubO>XB-cX%|*gOtUsPx_R=8D{WVQ;BSmQTG~LpQMcEmX2RCejl4> zqQ%E+OY@t!pYYSl)f@j11^<%s{=aEYW~P5%1)=qK+SBVB*TYyE*L0mMraI%Wq=2rd zq{$^hc;B)hXiqqG(w#jONkqb*&vDWNO?WEx>aopP{FZUWf4t>8C2>gK{nJ(YKhW== zF8>?-K77r|el@T375p^$bs_)FJRWO^$i~;nc#CxGMom<~@;dy2ViK7Vn3pX8K~gH_ zuGsMKmz_@V{6#<@$;G#yCKUV^^Z4ki$3o?^w8u$bf^Yw=q2H8CnTK2Xzu52fy^1~) z*Z_BBVS>%;v-?Bv@XTu9yM<<1PHlKWSKhPHaM7XyE2rS@8*{sHmd!B&>scLCg(H`; zc9>4^iZ?za8>K`bC`P0DZvx`>-1lYb;_MvaRn%Me5-#quR(WOcq@<=b6s9EpbFHOB z;wjJ_R7O0l9fO+}LK21HDU!pCa)nBneuMz%Zb#2#sp%PfaMy;?7m(V*OE|@hfSf>$ zVmVgKNkDw+rOP>;B1EXnwt_{%vTnk<i9(6s#y_7Ku$&_Hh>jln&EN%2{JfD5qTYZr z->uHB6^MD41k|Sc2MAVw5NVycgCb%8gR1oAATTIH^lr4VwQ<jMf*iJGIVq9h^?g!M zyh2Ozfl%4Oas-D11cPRRbNIeW6?5a6aBK^P_<Kb-{4rke#KE#UN$8~`*^r=t1X7Ga z;wQe0B=gVL%wO&5;3#L6`#66r-8Nr(4>xW9^=rvCV;P#k@WnQ#Zh<Hv9;-T`?Ql8m zvtvWJ_KAo=bJ!X{gX(&DZPlVP!fb3NIF?<Gp%I}a!O(>G&l>@&j<4L{o1)c+jxmCl zcJX7=%`NA%X0~iJy4E{hw_ju^NKg5%N?p4oOML&m{^<(4@&Kk_gHkBPpeF*lW#Pme z*Useu4TM|Gw2&M%(l}FsD-{RSutkw@%Q#`mu3!eIY<#C_;f-=3WI-36d)){pxD$<W za*b!C!YsP{idkzQ<Fs%pux*Gd)Rqa@7#b!`ICI7a)tlykt2*`+6~(j`|NY?{tJK1n zfJ;vw6EOd^Rv%<sG^qNF2c%(z39e+)WKu8hB<V|<)t$YkV0WZnLGbDQ{$VzRG0Yt_ zmj>{F#cTu!V}A&6Qp|8PCIo|rLpX3K1dJQHMKQn-WSie?2?H%?Ih4YI$sAOR)09VS z<}tU4ee_wn(-rp$q?#JWp7&Ee45kM6Y!khs*(-!oa}}g$+t*TjDao4HLE|2*V>I#{ zJBd#YdUn}%GQeU>hg>oRx|bmvVU;C!{o(~f%F$^rGfE$)IZ_s*0%mnId)2uy4Udig z{35APHu<xN%%B<{nTqUtk)IOpp>d;#4I{d_P*HRYTd?D1&2xa~95H34bsozrpk%B` zkkyc)h1MV%y<hb>@dl5ErEujT#L+6g7G+0Bl3#K-%_Ldk*KS06Pr8(+TLekYY^I}% z9kU5lenB85KU6j{I1zedP5UwZ({(&}b4{5hLGl+n7OZ0LaT|>&n0)5|bVVpoo$#)6 ztQ=<bu5>i10iu>(U56&IHRal(m9Tq8Tf@m!>C$=RgRvqV(hIByl2mRrJNf+`T0mBQ z+L}0T<`u14AO#nMnmQVjsP}c<4eW7tH23T+>omaL9J3Gdz9-mip3!8zcR~ywGpz0G z0~F9+y?32{k*oLPweza30WbW{$10x`4YJ$#4>Wxs@s6otpw(t*9Q|I41dD<QAZCpe z>YbwDluTsYliE}-#mnyS_fN+mu>;$ztm}OF(U#&D!cQQq!`PmGioY!XntA;%2oDp> zznxgU)YNd?<3RY1zt6K(SSXvr`Q(JF6Gxi%GK;EAiGR3clQe;7IG9Jf^<E5ZVj^+F zQb}(52uWtQmxDDggO>b3E90lksvYg63rN4MH`KQ}NeN;yv;+-$Vh=YpmLGQy1DD%x zz^2%*!$m^B$vK@|FPASbzj-!J-7>wo#iIqGX&+<0acPx1wT>UKnl7)+^k^W$66az} zce8mB0HUFvJau51d|V9i)SG6HF*YmHB!eOnh=HLb-_9G38kGDP`aT&|c{4wpet)d{ z{`PWSYUh1$_grqj*lsg3Ywirs7ruD^syMHTSpbtwW=!h3ZQ6b|9f#c}No3n2ig!vy z{MZr!5|@;kxy3pGp1%A&zC-DM4a-WIOU7E#-DXxSMwZAtvfW&Ds<|L)L%ag?-1P0< zDX#&=D&%$r=T*IMwC=FeEJ{Ql%kg}9zk&cclQsCNPAo~|?yZ}884KOf%n5Tqr6t<G zFMffhqvPj;GQgkqV<JGm>6ifKGTFiveT!R%rofX0G7GQY;Xtf^)HRh~a8%5o>S4*M zq{@_Q8U>gy1NMFRl;XnEg`u8xbo`yF;E`|^14$yw2}`}>=Y0!4$6DN1s9qncu7z#$ z@8ROoeSE%1|AGEx?oJZx>r0u=%q7=135-Hw_80*r7I7y;E|9gCn5<CMIQby&Fo#mM zV1~+DxyW_wA3=BG@OEICj!n2VKuwUMEZxvmfa4aV+QKDN`yU11oO^-1MzL^Fh<{_w zTL=WcqfJ={%THj+3De#_8n~2!mke93T;=7NT>*gJlA)k)H;qgUba~_tX(=Pob>#yg ze0{5kLaA?9ImU<oQkryDu+0(v*LIut*h~GE)fh^RB$VuMtqke*`|QnBbXjN&P!$)P zaGjf}K5c_C!zWmijLRv&MiujorBsTyb3>33^~wagGVPv?8;IpGVxEZNd6Z~8!Ck~I z2hlT|<X5BcU@o6?j4nrnE)Fi7^(C&PfEGPJj}E~YG+2DG1_D>eX{pLo?Q?s|i@8^7 zRputYIN9wOJ{hPysLL?4JTpCo8Dd@F;{)L=bqcpN+9k~JW3f|B!JLCl){Fa{Y9avm zrQ@#jO>x}8od>f2vpqFkc+Na&oT|^a>d#71TzO?E1~eWOp@kGe89L9CO;J8d+eh3* zJvN)7!!2j<66sd}H6Z;|dRqlBA+Vt^p_k2CZ+bDVR)qgG`;O|F9{#%zajPNd>)6ol zT&9&5Lv~Q_48Cu-Qamr-nU&g~Qv9u9=6($hxIWZO{Rc*BN7yD^A-*AgfmS4^I4W~( zS1u@Gy?Bpg)bI9LhWV(0i`@m~--0o7oB1ok92R&x@tPJB53TqUWSp~H8vXkQ{b|`T zH^lK0*ozP1v9mwBhgGh>8`ZSdZ)Q(?=jkbM)R6TXihlM7L$=p~14#YpGKl9|Nu<RO zD0zZSuL`zVXeK$k6r$yJR*mKQ$-DgQgDVi_LeaQ3VCm{Bxj*j$lDp!#8Zur%qrCd$ z%Wgxm!76CtI|H@9p(AECnMH(7eB9-E;2cVB^}?S@(->XQyg2rW2m-mm+b*-4zSf^= zirj1gH=Vxt7inFv{x5D>g{dP_RDUY|q0375-rA&;?We=+&dVX87g-@|1I?~CtM5Vh zKZHy+#(!P7|IfuL_Wv$cvHzD_{QtjLHTZvmYs$hUf$D3}GeD3SthzDzTswsrd{cLz ztv@}x<~SGe;u|+Jc@2A97m63l<P=M*s4N-_;tCei%1YQd6wp}~kjmMq3hC;n#q+VT zlocy4t|77&o|1(ze2%naRb*^u;*?=^X6BTCr`u`eDIPZ`l{CFHk?%2eup))Bkw>di zZ$(QHDHZpku82ONk<!ia=O+$0*L)3yrh20A8>NbCAUB65Xc?Z%Ml#k4IHJ6(O_aWv z32#lCjfrjvnpFa`4B(Ty1Lppih5p30d7Lk3e0H6Sn-iu_LJ{s*jHh}V8xvof5bHH= zi2o{LJv9fzl7viW@ZJwlNh7fWg39J(%PW1=>M&RJz#~{_yG~7vTjTI9A3Z`>rARHy zx6GJ;dhCbN)HxoBvz|z_PJ4Bu*OJO4`yt&Z^^j=I>umEQpG~ou(~-LLsnt$(p2Bgv zMjv43jzQKx+=x*^Xu)NOC6bNNs5W@?y{|_a+4n(ND)z-aN29$PTxqfIqM+8QF~n^f zj*fbV4B<?_-jE>J&3Ae%B?4@z@?^LEWT#cqQN!Ia$fmyftIYY4l_hg}79?nGTwD5@ zo6HuVR5_@=2LOj5<Oz4`j>kj$!k*N*$Xvfy@)J(xR*29Mo!@UL1K~%B_Hh81ID-rs z_DPT8F+|Q#S(m~d?%D<=jl$sDmA_j&13JsB+CcMU%{oV`ItI%J0yg*V*>LS!n#RMO zdd8;57lTW>C!m<aPunb>R?g1n>2ACE)3^5aH+c5qV|?!yhU~A;$1A;WNch$Ehx^-A zVR-1Dv-{=wZCSpqio4yT`@73@_*0X^SXAcgB+n~j((GoQc)0u5AOESHpnsyjnm;YR zFMh)JzV&{7z5LKg;$bp-b$q>Q$9``I$}wE+>9#T6cHhhDbzSl;_ClNnX840JHviTR zf9GGk0>WnR{Js1MeTQTk&YpR=zu5dpKW@&+lAZQ)Pm`s$^?r-d_56`*R{iDn+wm2V zcx%hk_4>H+?J4T*<73#x&UQO{`r-ZZn`GYQ`SBOYTvjF6w2#J~!SPAO^YIlIOajQw z>55P7ocBa7_OhmE<Oh3+aK0$<D}tC%Uhb^<Y>oN7`M?MkEF2OJ35R&YrOM1+&Y(cJ zKN>hKoF)zl$xti-p@5*FacC^5XcC6TUmGUrA`umgbweXq#Lbr~G3LiVs;dT?k{ylL z90NT->JP7&+8<yzxaHyw+y~=PVhW6ZHDbjy?AUF?hNAHkjjj9;8<?RTN)U_R3~>d_ zBU(+3v@!N42#A=J=Wiz*eIOKgH^?^k2k``^G;Ak41rpym$~6+q+g*ZzV7v}mK;xfF z+k7;fpI9VZ>d<nOXaWtvfI>W43=-$)r&@t6rS}1`O)9--;JJV|59Jy2DrKpHm*|~b z)1gwSfKxBM*LLbwE;9in<FoK#A-K<Jc1nQ3cH%1l?bAw6hnZ&|1-es>WJ<E;E25UP zOEG3>R}saV*;Td*q67>em9mNUGuI-ehyilc-k70^ie*x@<SPQj5}|H^SOPNwhh<Aa zDuBh+zX7EJ)un$tLuN)bPx12UeOQ|y!7W3MqUW)LAafZP2p!5NSVJpq+$f5N6urK3 z*P#0V@TZ^od4sY8X3z<7M4BX#>wO5|O)u}*2dYJiP4djf16T6|#0sv*{hJ|}M$Rmg zqa08F8q_jMhlmp`D0R=vL!qVl?U0>T-f{lov1T0<x&P(brrSUQ`X0wWf6-rRhiYZB zNBw8+M-nOR3>A&7<ZCW51eSVdSU3245vXKf@7z)Brq94lkZZSf-rujio*_0s6sAzQ zOfQmU8u$a0T<CGe4|H*~b+K;x4tthp5q9x3_c2o^i~w@Eci&8qX=8RkywKn!9%G?# zWGt_O@MC1uP<Cs8xe#i9?|Q%qC7r#1s4wcpNMk3Jw*e*J5c`HtK0#{pu6*@DJcmVi z034MuW<Y0fZQKTB4y5sF%M9XP>zJcK46Q-77akiOh2{YYw9X6u6qZsg@ujR3?P<Ys z`cebg7vh0Fa6)xyA@sS~;QgHw)@^hRbsNT^Px{niz}?4{_5$V7;>=fo8Uez_)-*|2 zdVuG$868@E83SV<51kiQya&L0JA(&0gO(P6-RG&5zk9`YDMs>bV`yq0PT;5S=i0Q& z#l!K&cUvJn<689Kjl^Q~z6%nm`x7~<sIvfx!)tX8Rx61R36u6;23jagxOE^XWOyvC zXcNY&q49rgv<{E(ie54P-0m43@w5U7-O8JOl$tr?)dh{f6Ba|j6>tKXMV!Y(${zM1 z7LUNNUm25@$tWjIO&c9igAYn!d1l1B39bWIN@1h;{ToF%n~4?o2aBgB>AUWU55KjV z9;v$NRbnklbTJ?y4Rd+4--&f28~fC|Elm6IPAdt9S)tdsrH($xu4{YSTE)^)5auWx zbxBptD8WY#(L2-3hzb@<a8Jlqps8=|tbGT}`T!K69DnfsAh%4NyGcGP0irDOWB9Jy zq(>Td^#ec=>Ue-}YqR6Vnvw`BIwydI2!*G8Q|f*`rlK8aP}0Lkim^yliGdE!PgqAR zFrQzOs&M+61Qn=Mk(Uvp)p-=kn!CU$XaT$ngDld}NFx9%SY<K2-2Rcs^L{<SNJctS zDH|St?q_X9&Qs6^sv6B7wQSe9R5q)>>ok5ljT2f19hLDt+=je979z$&^Gr90&GI2D z9h6N{<uoxeKsI?l;ffaBRvX;IJg>26Z|?(FX-WNXS3k0HU4!lb3P6`%3i_;^813Pv zAsS)i43>*3AvF38m9j=L?|xSd0_W7Z_$F=48Nx%9(<}S-UM^>pZ?COITZjM^`0^Tb z2j0Rb^YpK7MxUPTVm5D@OJ3~(e$>a->7CQHat(3VK#g85g@P|(3}5;z>HKtwC?Ceg z*Y9)V&T&rG#=9elXm7@5PxKN#AA8V|IJ0j_w^7qDXXy^VrwD0M@tb7Z)PlIS&=c&u z{AG8ZhHX<|!qrmiX#cbOV&@aD$m=1~A1ihCbG-BWBMYy6M-x@ZthjAcRD0ClbFqZ! z(oaU3`n`xer1Y5x@J7E?$BhWU2`XDm)OIOhr@8ue9_k>v;|IhTDn}xB77!Dvdn6UA zJ$_Ojh6vOUar!A8ivVC#WVA6w`Dn(j{3&1iGfGm@r*YyVAzz&peN!-dvz8c+Qmx%> zsYMs)6a}FQFOM)CqW>gWFlKA+MNQPwb2UVGM-&19(YJ%!kRMe<H##dSGfj%~962#7 z#NfnY;pBeitl>0DxKsKZ|4|z-*9vx69}t&Gt@4XJ;X*s@kA|RyHDyAjgG8=6?QF?x zj=AtwktkH5s9~9CTahM<;Q<9z-G7dX+7i0D5;~^UE+|a}Q{%QsWa0d+5p!&YAJI(2 z;gY!fm59Rm6C-*5G>p^LB0MOWHDkp7PzeN)T&zVO#+u7$W5!SGB27R=2cPA}Wrtcw zOv20Eg`l2;u<<C~Gc(ebzWSmmxe$M_A>)_5rluq%d|)hmlIovv`U0EqA<xIPWdkZb z;(%Ycmt2?$YAQc5$J?6D>v73HF%!~KzWeT9vlDMPV+Wskkrj0D@9RQ&6RE#e_GJhA zG~GSw^|U~P{==;`JLkVLA^&$ag6-c&0&B@Qerql|&($Un%koA&rtOujR|_xJMm0$| zS13^h2Bazj8jxf!yu1AYL_*+w3kEd8!x?8HiuAg(yjXmCc=>ng?uM>9x^kc>%pnDQ zKTyR%5)t?{L7-qR7+YBJ@Vj4*%-(4ALj(kAJP*&FSKF=Hy=~z09W%Q&Uz+_NC_!%A z5ejpNU|Qy<F3muOUN^LS2pUnIyXrE4hA0mr&c4X?S6<5f<3b1bX|Cb{?cz$~CQA*2 z2-Kj&eF-JW#|esJ1Py=D2Ei=fqV=~PzfKi=O_FTf_}z4t%5hXl#N5i=4@0ZL6?DVc zwr4N{r@8m<M^daIx63?ka({lK9)P8?IND%oPZVJi3v$9qQNrv9MklHgHcr6FM2Gqp zw1l<D@6CKyNfj}hLRkak9O<`svs>3FAdJFk)ln6@*(D=`w*alcRGLDm2Kb&iHHScO z-N-~l$L17D1axeLC>XfiB>$wup~L&W`3El!<iC5vFVpXnZ66#xuDP8C9?PC=5JrW4 zFTzJ|)YJDaUF9FN6kt(fE6V)LQLMesXobwU_z<894;)+5VYw=gtMm`ylqBlly61*z zR5?spT9?sNfB<PrK||<{6Ocn@G<7xzgOI2j3`m_u$xCI}*+xo$I_<?NIOlZ@%^eW6 z&`>^9e2!9$L=cezx@!`1hjgV071}tg4hu_YNRZ0O6wA=zbOdQ0VWdLLn*wfrQh*5z zv@B*Z-ww;F144+ZA0kQhi(`*y)kLW$pp3G(#AnwlQKb&cM$ljjgJLJ)%Y>>*bFk23 zc>iD|PfNsEJ;1AEPo3Bxk$ER5FfJfeuq@xp;7ptMdM>zDj6pPk%o~_FQXe?tu=<g~ zOQStKpuL_%I{G?H^xl8i{=7DbE9iu#^U_HHGa*<U5BoFQT3*Jl8d}WT|DoilO-+7R zZxEbW05*(>f^_^=i*3JI<!Y~{HcFQ4GbZ(g1CO|xDwKyH(xjd$I5x>GEb*l^T9GbH zv4v6AH{uAq-M4&mMX1GkK)P}>B)Dht>cUD?mX(--?2xV+TCtFY5ad{ANy_#TWO4ag znGi$mwMYai0qWSVEU<(>iSf2uxSp|9H})&a$bMHY&TBF9i8ZaW`36V_ylF6+4!t<v z`V79)-ztC~x)f(umAAUY!SO0E3a*F4V#8I+B^R2N{oPIB8jN^I7JiSYr}Fh2GrSEQ zaY-$zJ*AM}YE%%Y+jLr*$|+7isR5TY&qD9wV%qE4)ahgQY_bQ>uogCB@OE4q)3Pqc zgn<||MPbfRHMZ4)n$ACU>=blV*9mtm+(zR1w9YR1m>m58<?LB^VxRN<PwU#A+7w@G zKYenu@GY`pJT(fc<xpP%JxfpD6gt$xBk{LzXwDB)es0f0JEOi_a1I;`VrlQ4`6Yub z4{U6zoYdXDIg&4R$)f+FjQu@dn+~Ev^W>*AsoM#NRc?7d7nTrv#oY6`lifVqG;b1c z4S|&wz&PLmCxFW5LqL<qg`{z8&vWUM*L|%^ycIuEdF61VE2R-XAIb*11BvFYBg;`4 z$cZ0zG1>`Lj)Rb>7UT@5i!AMovrp76)hnC7REc;zJ@cHL2ndN{&54ZE5avO~cbS&R zZTim~bVnd^k=#?4FuZg2+_21S{?c&q+esr%KXg;^Gk#~4)6qW!P>z3Osxy6q9{zn5 zf!&_y-ztJTbE(^l4YT(YXn_j#JR~udL>)qUX$T}n4WlLrKF?wHo@RvR&^1^df*Rh4 zXz$}aW^Zg?O#Yl@&O5Gbx>6vhHbMEFO~B9`Bp~tRZy5nQX!Fv`;><Z*r`22f6DEUX zF8{(iH|OL1z2lE)c&9eqV=?gb4~U&f8c6{Wj1(Rx+ipSz*5Mz(Af@F!*`p)if9VJY z?`V6RkDKAfXrzuI%~k{QCsgaKs7)b$7W$xIe1ky282v$zjJcH=&qdur-CjC&mU_hz zpx5Az^KJ&W4bGF(G#O0{0-1G9K6`S%wF18Wq$oq>S{n<$3J#VIxl)AhO!T>hsm={K zHTX^l{>1B$;!})yyJ=SzZ}m6(Bwz0ZuKdytstB#_uRj*g4$6&;JzPi8n9hoXtV{YJ zm}AEE62YlF7AP1}@W_%&P61pthC!4Vf&kQM9o?#im~~Pntj2Icof`INp1e48Ow$|T zlK9BTrd=(;<(=uJX=6{?m83Eh){{_Xd@-~)49y+a&~Xy18%#DB%TdukdZq}i4w1B; zoabBNY1KbdEXSnJ1tKcgf}wX_MWatFF>tbk01dTM*)y}IB3fPRm1l#vgh48DwH@MM z4N410mM4=oYSIvA`^_BWSWzCB;@O&$_LiJi$F_gUW?Y?L^Ja8Ouj*hgo777+-Z<Kc zzjVlvPu8QJPN2O@ll(M2g<2rqW%x(NxKdoFLR{oii2m9Urnku7oPw-kh?zZFL%^*t z9E3T_4)hk6r@@(TluU2(tB$eRNp}*Rt7OvAcZ;A|5kJNhp8_(GQ2r6H8P`|asy3td zZDC^kMX<PA^p%b-lxv|^IC;|a55Vs>@0EfXvStJzodZ=#v}mn_7VwUlSi23zNq7Fv zw16ffL(5O~WiZ2m6~yQ89tBpwJufoTkHPGKahwJTC!`6zRWGSPI3!b{aGQ`L+Q%0Q z7ZyD2hoNHstC8|w9Pa?CK9`1!*H!EXQ(~Ug-d<cKAh-_EE#h0NHugGB)3)x354CT( z#1WT5suMD*f=eHBxDRdpcYI?j9C5*dB^b&b(&j8}SSo&Dx&ClvL`({TOZd9FtV?e~ z2%nl{g*3O=x~XN`w8$uNct*DU(upY_UR+p@!HH+n9Go<oGILCPlH+!L&9&FG;^Y2@ z)@na~l_1?R{m$8EeUMAHm!g-o4mOAzN4O0ki|ikaacE8)sr~f&=m@*-FPGbc60cns zJr}?CE!2olD|freM}{yUa^MgYx8kXqRpj&+E_wQ92vdwD4TsjXN8P*Pv=e+L&_ufM zn)>^nRIR<_z&H7AsWCzAS>zgDoPCfL8M&1Z2-Ea0Hp=>7#aW27rXK;VPgQB|#v#3a z(NuLzUbYi3z)Ny&N$rwojlVQR0rj5|Z!fu}ue%E%(bZ1?Ro=u@Xe*s(7w*6ZOfrfn zrx9rfkt@<ZG157L=^v1r*yj#&rA&R~RQ8OY?uLf`9wB$HEK>$>Sg`uiDPIKXxaW!# zB2}IM4XQdtsOz}~SHk5pbEDcbQ6{afH`W1Bt+VgA0>!p9CAZP79@TqBj1lksrTc7v z19g{}(OL|Q`>KG4aw>G(aThgzed=cFH&9?8-*jW=n;9PQ4`Gu1+hpRuyAJ;66z;#U z$JyBb?Kt|)9xuoFW{>lA3r3HIi#jKQm>SS?K$7S$c`<w4xWo5?c=*xRyga=~I<nM{ z?g`6?X81&l@y_eKwkfN;mX&EyyHQC{FAA?2&LFvj3&>G1?!;9{z)+|V!q^*@J1{xs z`F%0O2`dZ5Jqin6!fjI;w+&S%jZjY2$CYSCU-Kx?8~LTRtfT<OJBCuWkfTN36_70H z?rTb3oZaGzHbNgEfPHg<CE^r~;ATmr2{E5Vcu2y@8KFiM<68oGEF?4`J?7$_!mUu7 z`As&!WlbaB<lhN+k5odKLak8uJk1M-y=_WF;%ngxFi!dPlO|}KOtLDHV*ExcVNLeI z&o>#tmG=sKLC0LK2&bif;?{GL4wK%Nlk?I0IsQ=<!n3VG!&A5HlZ?`1U9!}+DlNl4 zvX_fNIR-R_1;l7newzt@S_m7?G{VG=d<!fgLs|<o1mvtLiAx*jkTU@5hbt>w;yeP# z(Y2gVusWL{#4L8YB`hqq1y-RhZC}@L?u1oFfHxVyk*7h$s<B^YsP!%H4GT+(vcQTc zUQr(e8>clJYzi`{Cqz{ZamJDK9Yxd-KdDjMV<=*SQ4J~-TCLf1&<F-mKb&D9u~(px z_2)%UT5f^C&`$wa)h`ACwqOj<{<VS;6f^EXja3vlYM$XUZfuUuH53D^LG44wFpgnp zxbi!Ewa=FarUH>H$-n@13}Ay{8cd9c*2wTAGQlJRdyCA-P#v%Iw-`NAZA8pO9 zf4%*Dv);_5Sncci?OPu3w%gx-+&(`}&*zCZ?CtfnYv)pYjrZfz<LlO0AcDe9)|=<! z^!~#N3*4m`|9aa~wi=KMo5j5Ih(UpE3isD#;h`byv1fV~uhd_Dk-@=g@Td1eubaj6 ze1m-2U!S`|OVSyn^Vjq2+Z(&vu#AgY1_cnPtF#135iK=vp>`0Z3pj*}+I7SYjoQR` z_GDjNIePiCuxARBh%SZA6CvfMX_4n;UQXk2wPr!!6l4S(wV`GMtIpCLfXLFAT3|IA zsx8$D<1)*Hqn8A3(;+VQn-#T~l0oNMw;O4^kXhfYD;w4;dIfG(q=M4ZA{MywV0WtY zoUWtVZ1QQ+A3kpDlgl#wm%YD2>V`zkaHEF5fxLO7l&wbPF%WUA42q)s>ca=v46(-6 zA<2P8qXY`)F=vzLRXt8M5B0r^ez^L80vq4_UFA3yYx!Potx4Vx+hmxy)~HgOo&)t- z{fcLnnxCaf+_(%kU4Zd^DKJ+@nD~Y}q+UH;rPe(I1Y`s@inV~u1b!(uzPN#G7ac(9 zSGDcD?wJe}^4ti0p>~(QHn>|zboL76N5?){Vz79?<gr{K**FdWT7}!zFdLqz(Y!#3 zo6X|H1DQW#7>qV!@*M_02|D=6?8Y0(aV~5|A^^(GjB$?TSDhiJz@~<77zDydEO*31 zHlDjy@>qdq;cT%@VWuJxj2Q}ls76WY3^xeKp|lV2lZ?Q}Ci$I?apl1(Bc;099vRV> zj)Y-1A)S2_&lx1bc!5jVh%rOQP~1S({(O_nU9k<O38JYq2DcDV0RyCW|DGC5LS%t- z@6%fVbhNYi{_fL+K}SVEu3CQuv@R?$Hm(m#rZ}OPs?+>V4zQMmq7@l~{RGpxf^D)< zFE1f!s%XNA|FofY`@Gq`Yq@Y+P|fF8pNr<$<3Mub2{XiZ$rdAxI^*z5nGcVKzt-IX z{+4h&@49hywtXEsy5Chlz3*M>U0=&?8#TSbXY+~F+D@P}Kc4Q654${NPYrh6Zt7iq z|KlIqgZ1WSf}F>-d07uQY5T^)oAC)r!fK<B;RC(;-t+UYYeWT}9P}M`9OaL5CI!54 z?%nE=Idfj-J2u?lj6YdGUo#fyf6}SxOr^%ZW;9H-o@JCzQJ!Vw$&NaI!*_mW#+@f< z7ay>ZHdD6BjQ-8kNsn7k*eLpIDm-s0ZhK>?u9hg(o)0Gd7Y$BApqy^=CG10YSWV@P zTZ(>=6oAoaO&IC%c1^vC@I?u)<3*i1C5Hu_^Xi8)czlJzbXe9*tGFiQMnU!M8thvI zap%$ryzf`AmAhC6iOyooB|+R(><>++GNuQxh*-YI?_VZ_1P40FaTITpv*n7bARS$T z7XryQVrL#z(yv(K{I7F>q$Pc9HHp7j2ZOS?QfLhU5a+$*jP=r`1^e#r9bhq8n=(@G zxD}Cp{YK(n{(-c?AxVVV!AB5f-U?>{yvQb`ZrJun!oRQi<Sflz9gD?e<J`R<4$Enx z=8h!1Y>U*CFpC6BlLVs$wGK#Y^S>B-2N+$OW?gvfHMVWrHrLp;ZQHhO+nzPHZQC<z z_|HE3JK6jE`^`CD(s|P9<W4{7R9973U3FDiJZ6APII7bS$xosrOzO#R<Y$S}OZMO| z3`j{$pAtW`22b5sG7b-kFsTu21amoiw8)_YzdTn((P*@T07Prqksmw7$Mh*bb(^;Y zBPT0pJYxh~j2FKc3ICU-go5qNCVX7Oilu}C(f10<c}uXk1;@!sBXN0}sCMe^ZA^$v zummB$=u=o60@00_L$e8IM=3GI@91GBB_zcw2-%hx^U$2AKJmV90Ro<!a|e1rjnF3l zRtcqd?cr@v@f#7){IL~=vlt&4qqwVxaPRJ;8qbJ?&5gB#x}YF_{JX;;3l@nNWRi9f zUFh6mqj35)soSLgxFTbxTTveGL?sdC>;BCfeNt*XZ(^#_ySBx6YMniWkw|jui^4c( zYDx}8U~(Mrj1w`eunkupJ|7_<kfhF+E*=2LSEmQJ<hxq@{{8j1Yg#VMseQX47yU`2 zEC>*hfBm<DT^@f{(#}zmMh+Cg>95S_|Cqk!pbSm%W^gzeVU^(Ekk+-iNv8*o9Qe;o z0bcO{ScpYJX4MGuwVDmnV$a+XMsoU@3o(P&CWe8>#=%#1V5@ij>c?)HCc@+vtcZWc zRd4_Lo?SBk*r<^``0lP;pp!{k3p<UC4s)A-=hn;InZ>@v9>qSz){=exVWs+Eq>>eI zgv$624jhW~5~GX+cgd28|6EhNJ)$*}(*=bziR38_+-javmFMXzYr8b7;;+%}1Pd!_ z`z+RyV|`NIKLSsbzYOn*Kvh?sODWx>5+r-F4Clq90>7WhY#GFrdc+Yt5HNwV#(;<7 z{SOlLjlEf@ItVks7q=0xGiAQKVjSy0Gb2&%DH_UsJGRP}7;#%|`-tTTH||WN8JGvN z>c`qEI#p^H&)V1!NujV@6td9VIm!Mp7v!ui_TRI`yU5*18q2$vZnpUZw1!mrBU=#$ ziB=a=+8c^?4H}}ZrOR6UzpDr^*wjOtgk-|zkfWhv$<PzsK?-|d%>xHB)mk8;cybt% z=QIIRHAk8btO+89U2!ZTS|JKs8`eP@d5%b_jEBrF-`5U4#}Q|s-#JTgZfKctmECIQ zd~mZ-5Hv!ST)Q9wvm|D2`lD4zS+?hXcG`n%b3+o{wTiWpDKve>!!7$@$-%Lu6G<=E z@!XBLao%dN9bd-PW%qB49+{{&BB~FlMR7;uPxWA0^*MCC;}wZLmIS!E_@NzFGP{i> z&xJ~>ejEjK!ddu}^7T_}HN)}`el9!He{Tu@zvHR@!gk@~|G$w4Ouxld>3`duF!l-j zaQ~8n?)}py|3qZY%J#21hJRy|tM#eG40>dM+fHAR7(4t-v{7)LXG3dGt8Qy9S=9Y; zC4a!CD_>oN&6vFT=HDyUw4}SYh=2b=yb_-RA~55|Ye!O0bs96_cIQOd*l7Fn8yq|G zCt@IiNKGT8f;bAy5evI6XSPd1XRpB)&jY<*92yc$vqBWFk|d-EKscZe=2XS{RzfM` ze6)|M2-J@|HUA}mZT_YA$qxT;8&!Fxa0y)JL40ix+rA|3*YDy7?_f6Bg;^Zq=_o~# zuzIpt4J;qdQ?}o=vOxi5Uano5wvt^J(RFt8=Qs<X(Pgidt5@t#*ZG#}ji`qTUfDz5 zb~36w;z{i@>0>7e#BUXwq-?nZ1R%ITyLezA$8%*xn55~Fm-z8gfr17tUxJ`v4?4mQ z$Dm!*7B)=h!7sOqG4QUW*(D4sj7^Rtw@m}F$(VKP9yNef)2gwQnL_paL2h+pfr(#! zuOa7xN?j7ou*$R3)OX)mr;!-<yz?~T`}gOsb>mj}DU`L{iq@S&8XHOKoU|G(^GtRt z0BkaB;S%9b)n0QnV%x86!{>R)r-PJA#r>S)rSjZV(Fr9XMaL2DG-(&uW!#h$=nO%F z2;;mE&Ev9k4hk7g*xU0r2c%8LYxUQV$5=fR_gBUHkRA89rN8B?8c7Ks`rUZ?p}BL_ z_`$$4Em2yUK@v&FXd_rFaS>DA9vepb*)F#HQt0!HM;gFsjlr(9*w?|eexNuiA5O49 z1oOmuj!lQzDL5SDBn%$D<tNW+;XPwRsTSsp_I5nAaNW%6WgXX=AD86ZcJ$_M(Q(?r z5GyP$C+klNBU4L^+D_b<ykF`AMmtOhMmPc5<|pZR#?zt~#Q~Y6oMDRwyOKc!A1guL z$oNs~`ppX{o34p-bRT>ARR19J9Q3UJ?E(3(i^a(BFVy<KA@j+xJdOkOFd?qrP|?qR zl)hA!u_;uVaJJY&k}y(`VzgR&J1fLN!Qm1K)h`@8AfEVYVK2nnyfnauC;`Duf#RbC z{8cbuzsmianJp4i^a4jB+J{0$+_zRNOb92Gcd}bQ+b0fQmsr)!>F8RMUd8u`ogfiT z!80+|*jI6fJcMSGdP(5dBlc`px&0ncyBmwYgOguToqAm><fQSS?@{)RaA${hZH}k8 z9=DSt^5MZJL~I;YU)nLYe3A&<ao&Fz^%7Dqbf%ccHeov!yhYye00QOY|LLTd|Dhi* zEAziHI{(H=U8VQOEYQP;+;~IbWeaJ?B5|>bsWkbq=Wjy^+U(m9%@<kB1KGwlPD8n5 zBBLG#^rcR>Eq&B~ICC3@7HA6383^9c=yy4CHKuXv%9=c|i{L}50?j%EDo7T=i;GJN zkIyoSQF%2ky)R=IP#7XMo_^jx5oL2B42w&XTnLkAILIQdjm$*Ox9zGb+YkbLxbqvi zMcDX6kppZ?MWzvRyUa)NGlNQ=xx%?CGFLC$pqM(6#uH11wWaDM5bq-EWC)?9N@_7r zTbPc^9#2=YeZm=^Wpz!*a49yEx*oVDHOxQm<wm$%bTw-;?zYi;d)Z`EeOv6HIxlg1 z(ofl@5b}rG%yQVGA%Q^pGm9#UhwFuBx~W$&S(n>Ij6M6qYse^yGlWxvUPs-sz1bFT zCFIs?$S7y&i6231%8x$#Lh>V@@a()jXH^1tRHHy8`3k2Sh5<~xstQ1Zd+2V+5ahQl zU4+SNWx$n;Lu+R*oG5>YlK~AEN2=PRsugFGt9Um}IP#u}?dXJQ-a?ZoSQvuiqC7 zR=gEKhZmqH!8MhFSuxoUD{Zap^v#1y{o$_TX1yTCuqZ(`&M(mUb+zE4C&p@kz2WnL zxK*`%b?%>$Q9`);xB{kl8{Bv<s|`%U$WLCX3IP3h(icG%z~b>JJ~4QAydD>vd%1;8 z=oz=f#Wau5NId%_m-@%&6ty$vS{~-G4w=BcHkd76=dQx<WoBRIb9d{as<Y;G)jRFE zq((zqsqkfz8y4F)mgwbAJ+1S1Oa7+;lM6&{m{6q`=)kyK<>u*D54L%J8-&qkB1+EN zfr)K{U@9;qm0REW_tw_Y#UHeZF;&E6nt^{3>Yt3{f5ngf_w}d$--h-7ZC8J;zZ@_F zOvuYegsXH2CYe32jmT`p7W`TTY+o=`IghY%`Bg7jw*$4bbj#&R><4{|9`&NPysKkw ze0k(tVHXj@5qdnQ*j&M*nk7SKLx7stc8Los><M0{g$b>3H};!_)$EC-G!N=iv6U3V zB^~vT@ZGkkUi>Pw?L<lQO0~yK^c25E9%}UoHGL|2J?St1(hpgT`zDaBh}Vj6P)^22 z4rr3BM-ZzP!8zYMQhU$bsI;%5YyH|=a9ci^Se~T5;Ed{6@RfPTYEY0=`iCQ8|Mw|9 z=sEriCCS3^Z#U}h*1WOBYDf6I?hU}(@X2Ez+@r&1-=!5;2cm%|{%dCqkKRyCJiw7a zFxJ22yTg`LmW<?X{MQAV{jSR8iQNl(8uqW*SW+}oLOFT@NMQEf<q|#-_L3fwpnPFk zns~I8!n`I$=H=r>4vc&43pX(N1SqvFxx=S4OmWdEFFGZ$g~%Z7@(t;r()pIvYN$sm zdP>0#$}3VJE2$AXinGkB9fBa%ezfZ?Pzw4C_9E2q`>2J;L13k8;+_1@7az-}6vJq> zS72Hl1v8*mO)JYl0A6!GAj}wD`{kAlm8t^yWj<(dsYSe@MnLl3w3&U$j2~!T^4v}= zAfQw6(qZa117iS$v!airNk!g~288zASki}O)<b3mac`j$=oSYI7kWz2g9=+yW9f%l z&7;JKSH=d3ZAMLiuf)x^c5J~_qZE3?RF>#7NsZ4$TriYiTL)<CQlz$?$%_?R&i(k5 z6~Qy~*JyPhDPW*r!+Kh3H-y|yZu%&RQu8yT>4L9tsObZ4=%`pQ!txWDh^v((B|~aA zV2TQmW`PA1#e{(#4zw1IyTRC<Z#W?J4`B=x5QYv4n!*r>gfd(FwWB0KP}0Js6V39X zZV5!7z$n6Dy38S8`8(|a`7DSPGX*SA$)GTZ@;IaWbC^ftVbdU#`92ZLt0>koCqPX5 zSfm;UG>V*9>~Uh2=xBmjRCM@J>`NhcphG~Gbo4}{oq65-vx%hzI)i%MNQ<*`ROn8V z!pkY}I`mR3cl0Fzy>55=2KQgFo$2WxU24>9Xo;>bs+k_2wSV_pBgg0_mZq$p`Uxo7 zViSF(zc}3g`k(*#b9i;>VaOXt$Es&xz^h)`7@i<9i=I0q8av{{N~e=H#>Mpa{r+=a zS||O7L8<l;TsM~vO@$itqWWX$<8cAh=c`Lfo!X>0)eQL5R9`C01~0*x7W<{_fduvh z++cz<2=cU*lO=8JyiXsVy7-oy4SZS+b2?kCYJRuthXsU0tzuAw^)ca|O%s>>&ZB*G z(NxzH$Cwz-bbCMI3Ch2_d%oz}+eS4lCaSBo)4?P89EG3ER%PPCmC4PF)K;gPHSwi! zhwb=aP_{SSCr4Xar{HSMpmA9>;Q6uo*}A(+S9@l815N((a;Gu#?_=uGP02jMtnx6( zAlBe<Kuu424S)eLfz<g!XGo9ZK@#vN3Lksid?WTM>=`D_4@vU9!cG>~Ae&GILIy%+ zd`5hxyh})%3A2&;=zLr;fs{~62=y;@%m(Je**GB~*k2s~ze&t54%WlfI76ZTbFvtx zC?xxfgXQplO*9W<1CPkS&*RVH3E~@()Qh|qA+`%*IC#<6D&H@ro}5}by1FvtR#H<} zCeAE)-kEhLLnh$;8&ISR_zj+#BP;$yM7~b38t-Ise#VtoFdUAG!T=f52ex9JQ$!yA z6%JX}J<erq%)Gk9_9q@e4b~Jx<jCa6#t#Q4lW?dnS6Oq>bU2+L;fXJ_Wm~w|D;MxL zm2bW-KYKEli^j{zK(01n9CwRf{v)OEE$iUet>u;B+oLP9)HpG*#%6SZpeDH{s!hV2 zvWvr%t0xg+3Yn}a3OZ7@DUOB?`9=IqokB}@Q?k-KHLOQvK<#+BD(D@a@C>4<@75B~ z`o_5M_t?1{V-6}irabekm4kHC>&~15hy&2b?R?Z<aXLH0&fd-8_ulEf5S1;60>3qe z9QgcHD~pOsp?%;RUvi)kNNpV|d%p~34i;@o-YlVnN~(z(NLXRw;bckW9b?=G)dZeV z9&hgR;^AKT++<*TkZ;;S$4LM;%^i%5=p<LullhE%uB~Ux_$@XEHR10>hVhuH4J<Vl zDR;pS?0Ln+XOoBmdlq6vH!5Yg!X@hj9z}0l7v(~%EK1$qrumFSA2shXYWHAxGsWi< zRvt`Xay|I!rGa7Rj<pBoulMVwqUu3W$WFNdd+7O-eA=8o8Zy1pqT-TV9!;w|iG{qu zUW{QObd}!JZyEeoY1RV{%cTK&`;DU*L{wMe^DIQD7oHir+J|-#C3{j<c#J6~xD3SN zazN{dDOP0a8NS`I2O_`8QykAm&+f_(OkM}pq1VxV5fojc@2d83L!ZPk8Gz)&<Oc$r zKU5Q$zj~~D)^Fp0#O1w4$nBLyq4D#oQGy>nzAoA`d2w8&TM%@^;mf(bggTC5F!-VO zGU$0Gyk%XeVfNHL*PK!fz@ze1K)MT-@XE|@-Me&T*nXkYMTAui1u`!lsE*9sF0r5$ z@g>(bT|-m==mFjbc@N(}VA3VD?J93vu|B`8Ah39aPo<eum|5Z%R~0z??mi}#zc^dz z+_-}xoF02yG%nO>?T8-UyReYm4Q}yIa;6B7tTy6^%|#d#f2l6ZwC%oj=KiIt>L`qZ z!xH1P!QIc$5|axr=Gu7i_tB+`Ur<ZxlF_AB7e`=lWtn<3h}H(pOwG{IX_<s0F%N-= zA}+dkLcIISS(vA+MmHVqiC;RI+xK(EH+sC5A>$IFvey9hrL`3g&zrsd%}y}=<~GKA zeh}~sdYaemnZHVga`}zO;L4F?b$=fYsx0UI6$!D*MJ6_pJG|*Y@UhX8=)=%<D0?ZB z@V+~zGE}D`q|8*O1+3lVH&Yu%55|1dY}9JhVpNFquXHR%HY1zS&A4^~N1@}8$^Tr~ ziOb~H&iJR{a{o9Rajw!ztfZ095>YWR@^Wl@qRLW!NC$ijms%ZU_;z;SgPrvphXA5v zs>om9OnD}b^7|}aCTip8#D4TufXsU{bdX7a2%^{nrgZVDMq$RBr$%y{Mm6(HnMMOO z?JZJ1%{@k%^A?gMg7tiDG#gn0(K^8=--*iT*SOdQzfTB0r4TOH>H>m5prJ6-cG)~t z*mYB-{OPLu97RqCv>he48wh6rJ|#0J_Hd!@eV49ow9xQ$s8I02Liy^gP(puNlQ|t( z#poFeyNB@f#nDRbM7+ZYladU^{cT?k94)!LG8~*rY)E+sy0%Xc91jCMEZ$5Uqw(kg zpeL`32Z8%+wP`E|K{*bb(h{8*!2w1_@hUqI2A4$K4>s*N7YJ2lq|k{fD@t&LDM$k2 z9)!QJkis`8Scqr*hC5;XZnccC58aAe?B|&$^38*Vp<Hi6cC~t%h<6e5Om3A`%{m^p z|CJNjy^g*o-n-tm_2jk|^kHu{7ab~YdKSr8meOkqw$!nxG1*U~`={%}Y^i6X9yd6_ z?|k!*qml@QQu7Yeypae!;u9U+?_z^LzMF|x%NOKcS#<d0d4iugaIuK;RE%57kIGe4 zckx~=8~oV8aClW;OY;~7`Cg@?D_6B!44-6I7`$$;i#dDsq2D*2AsYwpaIR}Dp&v8b z#$1={*E7H#67P7$uwps?;Fxl-{rB>nfBEhltpEPg{Yq8Sc7qk!XQuY2CnsbXxsI?r zWe87GI&_r?XVdWW>`x>11ylxgM&gRCFK;-J@f5@n@e4vZPsp)TtzJjBR}4>0I8WQ! z+cv`Ssby;0S{=ID0#GDe34|HMeHyl$K5`jEItd0zkf#*Oo5t^w$rp_l0de#5#@(Bv zo0m%%QF4(V!9?%Z8RdvjEcMO4*rfEGx7I!FNq%<QLjIIp=3J>Lms{n*Y5tX75CwnT zMFR6DOWhVG9-kQ9uy@qhvsJ;}Rh8Kt3x41A9@S7|!kpRVTiym}Z$f1`xGA1}XO6I6 zC!`^WbQ%M+N!TR2`?s_F(}e(u20UZ@A<WN1Gg#mjjf$a>BrdE`UN75M9*0s6JpxkF zkahg?4gCv*2vC_BGmck?`ay6wzVFfp1yxez!Y1X2K{LaHqD?l9K^T!(0g!@eNQ|pB z={~*Y1*0PSwY$REqjZbx5}}r5XX^L>Us&WkQ_$&thF_1b*2A4K1o9r)pkIPintE23 z*)R?(ls8h_6!sX%vcopt<E@y-dfmj-b(OZGzS0gzgvybI%Tukqddmxv{3TztFS0hI z#R;*Z#d6`oyVevJc)!q-h6$K~TNqZve_SV~z<Pf|-U&s!?CqVtC@WX6e&a~_X^<T# z>g{B&%_8HRJFH<^74VM_$x15Ft15*v2aGtdLOHB<a;$o%^ZCNSZqoU&x??EUVBPo4 zRPoEr6M>NFoicm_`*U-(*Uh?xVNZ1VwgIWlBp&#RuP27z<wUrdj&rQ}*WK?24u2+I z+Yq-lxGf*^1MEAdkX)$kxn2%lgf=#JRc1@`mKn&jO!Ax1XY`VQsu;+=?C)^&m<Km@ zCB@jC*h?gN@0~Q*4^DxnkHJaCAjKEj5%3-dJ?a&OlW|yZp;#l;CJSF;u~I4%a)~Gf z%BpTSXSE~?I8q458*4W`o?AM$WQgot7V%|Kiw$7;fTU<ekTUsm-vn95HV;;KM&vg< z+s*FInM88>xTql_ON!?0-UveFN=jYlGBX$Xm75otN+P7#iq^TIw=rf4gfKlu4ek^m z!VQ+ITPP2GX~=;-Xd%Jh!|ewuz*SrNYUrbV8iHFd#%Jf9ISBKiBz)7)HkZW%PaCR+ z-j_qwRmFq$S&t(lN~w)D6_gu7egbxGTU6*^jqfgc2H5ivGdttW*51mav>uNxKzqz| z2yxSZDGolrW)QFKU`Sc{P={$t;M81ID}EjBu#}Xx>1xS#E_|!M#NPf<u@P;6KziZU z{jhd_`sEU2;ru`K0t-F;Kj;Mprk`TJe-k>lr1qbB;iVS7?nf_}Z3|2MVa?Ob0J;j% zmx)Vlp;roT2|nMKP-^&k$I&@dt5|4{L~xQzBEP@Y>b(hD-Edp=Y<@lRsP8fgPt8+; zIM%N1MlTeGpp&IQ9O|U)a_xcO)#`mlKY~a^Z%H4Elr|O+KN#v&*ov#nPkeqVm<rWk zrBpQDIL(esU5V^P1z|Oay*wg=lq7$-_qe+TeujE|ULOoA4tF(GS;mb;k6;fx8Sm8i zXz!Cf`D<nck8IUP7~T8}q?G)~E)1Xkq^fN_#gZhl&Nh_RwZn(Hahq3}QE#>Pm)YUO zd3v^{tF?7*9gdQvSbrRY)uNue1e`XyLWJ3PSKRL*35!@?IdkT<!*1w8@mHa>GNa;6 zva5WX1FffJ>UnS%2S=o#)tL$b*`UdhbfV`7yWfYze1}3S0=HSfO>*ng)sW=Rq0Q-u zHnf$l%71YUp^y-sbLVXvAR$f_eYfo0NjsBUY?iPZf%nmtZ<RZNiv>Uq%^TI1tQlS| zfeFdpeZCzw&H(e_ekdx!vKcWmN?+Iqx;K04+-@QZS^13Wo`V-R1aSYx02%(|ag|!) zD<#x(P;෋Qb)X$H1tBC0D%glIAgVl%Nqnmzt%$n4p&%*tYr<C4Ri?9O%7NbU7 zh7BPn6cDE${t8x7S04jX%J<uBnCWzA9k~K;02Jc2BPL7*_hr`ap>Y)$1-W}qPfY8B z)p}gvX-i9OnH#Og7%sBHLJpFb{G>W_u~5t=P2uHrKUl!RVY~#KhNiR{WtXJDIWw<Z zy#DK;&T5?OeJQ`aJmIr?wJuB3%=;T~0{Beqs)$%1>l)G)L})6Q-~@&tM=%6FNi<$t zzLf|Zb-31>pKvEg;yr3e9AGa!d1b?XFNnGqM7x;=hyDesgdg{Jb#~jryx8jYs0p<V z(i9|A<sCCsM}<cBlT9o&Crq*zFO3P|@2nwsi;%Xk9-aH(sTs!9&-?y{mq=-*QET(9 zhV12oc;*sv5@JSkZc5-YYy{S021j)-UBOn7lnt#GnQ(6(sucm4ERsyEX&_z+g6vgz z2h|(CBpIDwsN1Qjen2nK`3&Lt^7i3(h1v`VD23<^gEZuf^y`@1NJEg4(xHaSpI(w8 zNH8I#3kfdW=xHA6;}xf|f?L#`FL$8gCyy{Z<A8c=I-vNUFjwO;ak~fx1h!g{ck&fn z+1CoJiLykN5%o)UR3lJh!xi+(2|FvAoh?M_P&F+J?U|90xqVw~fcXQy`#CfIN9tZ@ z`|p(~?iFwcrbIqQu#QlX0>#AzK45gAR_ug3zJ%m1xB-$TAR>_246M?~M<q(?C>5-e z8C4c+E|{xhdC3gORmZEUB^S**G4yDKG3}2Dwg$AYlPC{NjH>JrS+fg4YO=c(r{81B zAD;V^yd}(hhZXN2j6GTc?eO2rUoJc`opv5J_dwb!N5|}*e{P}Wdg8kkhJ^2N=FvWM zekFV5e+xy(K7SV0KTE|yz`{EGzL;ig2It+|^{-KV;e%CQYVBCVL*SYT(UIjC=T}lm zu1PwdT;47vE2-2r`BhyEgg1WuhiFUu>rXWJ$(1b;Y`44Y0S3>O2fYr}V~~kZaK&eG zv@E8No&JOR*jLy03)x?x<mSs{8_n}AL#nf4lD#=WGR(sU_pDfLW>L(do}&!=E<}{D z;S6bj6T+B+u)(k(yR;|C#8n=Db=_FBybS%Xudcbc+FBtK$}ix&74hqT(z{Im)XkHH z>E9<l|L=MiBMd_U(HSEIP<^wBN(0}r>x$qPjHrQ;K}TB$^OVmgtjK)F;&j6B;By_C zCMg`;%wM<Zm$?BI3;m0y%hILG$AMqf@FG1o8kJmBedLecRAJbMNS4WJD=m?yUV9+< zI7~X#2Mw=b^@%Mgmcr^)f3tqSGtp%{rTlRO-|)Q^P1j{n#=1Cx`>>I%o1)Sg!Vcjc z`Qt+0tKOa6tue(r1rZcT)3Ct{BY*0qk~LFfTbJCosR>QQ237q&&DhEfW$#YQZMwX4 znToMYp?~=MFL|$YfWHVml-VI1(<9`7cLXls186_`hSWBF{2fSvli;iJNb>5qQm5Gz zYbn|^Jgb#}EICB^y=xD!gvk~liG7$AZ)g|a42}h`0X?z-m;NusL}x_-m_@L~^@s~~ zS{xL?4*rMWi{NJqA`2EsQ^0!EW{qvDM@+B_^%AfHq4-1Nc@q<X1f{N;BZ-_cgd^z5 z7HOJE_d%*~Kj~z6Wcln0b?CohtW?BS@P!(5V$#&~?9WRw6EMVxMH^`fnM>o(JyfaG z3p(fFnk(`<tp)N-ihBAr2pqLoDS;1Ho5d|ba6L7`8g@7(ep`w<>8D(?`fb(80!BL$ zt;WS6BtPvL&b{fGv6iz-OS^+=wvsG%Qz~uSG2DPcH=y9f7tIJMaoN^@4<k|Doa(61 zhm3oI9XnCd&2W=WJm;(yjfNwdj45iDW_TltluAU(!C9qQO9jQFn?$VhX6K4$CtJ2# z+*j{=2+Oov>$el50dG+NY>VH0;6hwP0q^sZxeAjhE8zzsH?U<bRO9yW&-ihjR1a>M z&7fH9=mHHqSdTzglD9|*Kb4GavTpM)sHu+TJ>`om)N)LRd-0x{MZC-o0M^riWKQe& zIAL)#wdu&8MnqI|Es(|xl`9~x0-3j+3D%=FquM1Ak^>0^%MO!*A^!}Hz61bbxN<v( zMN7;K$5k5`n)VIH7##G)-K8ygS&8&n#Mr9Q2rn*q`jSPkTPE6!oq-YnOW_{?jABp? z;wAkVRrLd+V+4bL&Ym@s=5`09=VJ)rtGIpMT}0ySLm*gzs}7cmM>ChyrPK(vq6;!# z$9?^z?&0!8`w)rE{j8&f%l53zD3nx}5}h}o;B#x-wo4)R!5MPv+jBe1^rk9Re}gp& z|0Iu7=Y(}2MAIuAC0G~+X&I9dljV4->|RQX$u_{^A&rmR>Y;VWG7RXn42bEDnv7=f z#cVnV$q^-`sUfJDZMB6>TF}qif}BmP?qE<UzdcGq1bIw)b0rEQTY_W0o6$AnMwGT3 zBKlHgA)Hzy5##+8o3gsaQ_6(C;|PSeQ5&@}(N0Fk0$kdxF|=s0W0I~A49m`wE~H#h z>QY%X&h^x}0Qy%i!dq_9lenk$A<?^GUR$jRY)g_3PSki)FKC`4u$zD4XlPpl|GZ}3 z9Sq3X(hWeKdA^weXjPl>Fs7p_=z6PRmBnc;tcgam8~?<;{PUN=lw|VfcZIjs608i@ zo6wT18redDPUOC<iE58l;isXc(*S<oC!);n)z1fy7~#Mo(Glg--8;h&Xqvkf-$J}_ zN-%_n+|-?_{ET&9nxWEVr}61pn+XsL87E)-CIy#I@02Cu8ARtb6^0vg{YA}p_I+^+ zEL*kW*flI{rX-Y-7!H%LEgrukqYD7{{u)jX{2FGGQBfbTd2OH?rVtN~;MUXng1!$P zzNOC^GSA;r<IGzO6D>==GvgV2X!;I820?nl9~<0BHxd?rO{Qpc)nl&n#pU!7bhNs; z**UsBngehJA<YAe+1I$`c{US_o(?-pH|kqmyI_?}pWcH492MaqUQ40JCB;|5(`ffN z{VI`#P$Cp%Up0+;d?&u;l+)4ty~riobEh4*UsJiB9Ym%kyq-ldF)FNb0f8i90E6#f z^wTLPrKYK>-z?nw(W|(#HQu%=<sY7(SuYjGDD|;f{M%J7bia8bymWUsbta&-ebcdY zd{c`-?k0pN>G<=s3&jZrdI2cMf&~7_p!`5j{zr0-fr;hc?piwa-wg_6npr{z+MpkE zO(QZ*%COE#0S%C{fl+?Lp`;S+`x94}cneCYHR{S*qPYZd??d*DmbjG>7^|%4%t_(h zB4qS`7!&jdDWd-{CPZQ6_u&k3(Qqba-Wk2j*yn`OKxw3SvIe-CtiJ>uhc8(7tfv-t zB$At?RPNJGlqpPNbSA}g#Xv|60v|6z382a?i6`bl<yOV_wxocG$e^Mv{~pcT@qoM6 z03QsbMQ=yd4Re1av%dbg@;=BASP(J44+ltj{Y}>+4n%qsARdr+kMI~us&F4RP#VKb z2_c&`9l47$i&m2eF*!nH$Rq5^P(Q@WTUo|l^*nQIk4ebBKv!ymrkqQn`BL#9Va}A9 zCcY7{8eKIbVSK?$p7^x@3TQIBvMC0)%X42zZ5PW-WR#l*5adj^-@DUazTl6&Yby3T zTRsukO#en7=_R5pbnRC8RK+W{t98K=O=EsdHsGviBh{ThH$jtvsiJ}gKtCy*suR}x zKXpyQ%8fm+*ORmM8lm=^Xg3>sB-ur#{Z*c}g%e-U#y;oBi~kMg<-W?zt?C#FAPn#= z$WebtRs~W60OuFu{-jvmfqb)17eMmqAS6ek8q26+lQ);;u0{=fk6C)zn6_hb8;8x_ zJyiK=JX6^Ct^K@7fAhIL$tC`bj0q+~-D|Cj*!Z@uU~V}^+tMsH8CgVG@m2sgYYldN za;YZ0A(wNep7=WiQblxO`#t2Q6t)gQVMIdSJ0^0i0JP#&Zn~TYPNq`>l2FUap&IX} zmxo_u3ZDS2a!{A~!Q;ow!uR;#ff{^fWyVGg6wgzZF}$*ivw3bx9~AYXh*p*gjW2-E zoDaH(eWBAuy0I3v3_tsb+~6`Qymm6#hy{M60-6=ZLBaUxA2g3tFAP(-=nfuva-KCs z2pHL%umKwUiv}1Esofx=h&v(oUpXPF>Cd*W=Is{k;+CH0zCAP7un3ay7Hw7YEzpNJ zk2Ci$CTnCD$7b662u~oqcSQJ{fLX%wyCOYCGvV+?-28rm?4nXhu=faUk$O>6kO%fU z^mCO8>>`b%<qyifAw44`=vn)OI}7Pf4v)`DRAkD^EOKeujfBV2Z2j)-%Ymk}E4P0% zi1~T_QZ1)C^Q2l~A6-fQplOTE*=0i_O&vAQDs66_k#W(dIyYknwP|#aQ!+etq*hS( zT&}guhs6fa13+;fD%@N1)ciFYemS3)Hk@0~@fRRON8P~O+|z*o5#&DGhJ|V4fZCky z^?$Cha#x6if2bf}?t-`RqoF*qb`CBWKDnHS!iQB$uk*j~w(8sGed1aP9bGc{PDquQ zD{&ZhlN=om#mx&FxZXZyd-}7i00^~N_Ku$nkbD)Gya^DT<b?P2MO1*M$`HdB*WJSf zWLU~UHE&{C2A8z`j!Eu1%3DM3A&@1DyCL|ge5|X<3e(luDpSFyK+$7XA-gU+t7M%` z&#;c5r}=5$xKqNUKGgi&)VXI45AbYuVh(V#DRiuN1JLfjKviyPF#K*A9{SrF30ywZ z=J;tWZVTtkiVLGZr}rAaxvZgThPDzlXJA5ksm`R=`8Ko(Lht^t8bxrdB2$0d*Y3)b zL`BmTY@so+@a}G{a;$^xw?Tp?PQ$)!kk$jI4X(Y5y!e+6eHqqMUce?KzqaqAGs{fs zq>WqGVr#z?sBjFIJ#%mca6(C^$EtJwRruy>+{NYf`IZ>-t#-N&51M-pbnj>=N^y9@ zj2fD>`;o(jcGCpdIV%#0XjT_E{5R+;b<g7eRLsmAKfUw*OELdns%|*g=>H25z|Q(_ zM_{Hjv~6)(5xiGwS6fNxJSC>V#|9vFiS4lRK!LbG*D*u-j%W=D%4-P51m12OLsTzb zg<4eZmE*v-vZbb`VM7Pg9aB;p-}--L8Db0DE8_&zLE7s*lNJdGu@b<IWy(4Qx=tq* z;C0RP7ty;#l%Sg54tM~CgV%=EbH9Q_;;vlg=OSKDB8Kt{*-hsp0uiGoT2W`JN`&l| z$M)0ZzM<Pd3Fz^Wh}Xv&qu>8#4LqOZt*TG-=dLl}q(^7ZT){9D+@i~*!6lpClbw1l zf?!G~x->L6q*%jYhUa*vgMoMD@rtXM;<@0L=m^T=uuWmIc?f0jA~~P&!`fdXmR3vT z@;B<|7shu+>G`^)hmrszkVaC#6}F1ca#btWb9IB0ct`IM^}<&|L{Of@TTXx`ODiG1 z=44HH_pZwwyCgD7s7IC#?8tM$6B=mPM}6wKASX70B#r`I8KEW{8uXP$UDG%0|0Q`j zsk$k^Qvs0^(SBVwjkz`qloR(R9RM@u%y)Z=4y%AoXdEdhE|fIs2G&3~tS67pHe|Kn zqPB9_fg4N^Yy&4CTXhV07uUr13qgQZF9Wv5*inYN=Cw}?RACvZf2mRZkC<pd269ML z5@R?%fjlu>x?ryyLAi{>=w`Qm2=OQHs-Ti|K*|-cID*2pq50_g$yi;<*l=9dDi5nk z&YxA&P%ecT<V#W`joea$70?z?VI6ljvqr>A)>7JRZV#sh&j!9;Ok5sJ7dd#hh*e)3 zH%_morLpVxNN?{JtzR>tTQ57j7%qI&y*j_>WN+y@Z$iI&HEv_?4;&ia!B|rsDy23c z$FBL-c(iF>YU$1$+*cXAFLNinRC>0*Ik{cY<ERV&kk{iW`uLwDL!<liJ_vl@{r!t8 znu{kH)xIP(*&L@rpbI@$9iSUr2h{`>de+Sr`IVQr)wr^t{QVW%_>e2>qI*Mkd{pp$ zu5<a-^KSDp<+#(k`bY_M033^p(T|`g9vI7*;4R}rtWd^t9q-M0`PK5R&v)5_)6>?~ z;ig?{p-w9+SK8>{?xFE=wC`YUdNN@yP;KO*IHnj;BO>G93<X*u;(+osk9yoz!xSw5 zD#8|p(LNDiDgJWnont_&s8)CPz<s0uH07vP(lPmiyWlOj$r<ru3^L%Llngw9*a2^$ zXn$|Z2_#hyLUnHb>nEA6p&0?DZIX)S>a{}gXYRa_3`b%PuMUHKfyYa1S~@cKzTtP; z$ubb7e#SzOL7`S8x8F?x(Ycpgy5DCQSv1A*dy%wI*22DbwsVY+D4vGb(^O#*3mae1 z4MA-E0mLDc20h8dmuDNTgjTX(ne-_7y_N)}`%-xk>&a1J&CVfJ-Q4cZD<)yT7}z*O z;YHhcw8~LjYN3MHoynW`bLU7b?i1N1?n-6j=ilqKYhAhC#$Gxd9qsP73maD#pJ&H( z+L4a$o$LFjO4aws%50g_%a4&Q-5zcofpDS%|4~w8K4z?NA`MkLgv|Tnp_~ai)6~+l zqr1wC5{7~~PYEJghG=U01Hzv#ELA7GPIXE_>+mZr9~4-ce>-R(|E5i4&Bt+^w0-}& zy6p-yxS;R!{XXdpJZ8vuBsmcaY&@y;{rdYyEV=Mv-0Zk;FI#4ObO7P@@U>$*7ACD- zV(oqb_{3TfbttG+gOqu`x?XRDh;^6MID(rq@6LKWYCo!=UV;Pv``4z8!gEXW!|>!S z<ddFZ+8j7SRP^|A<Z1U=Hz;&r{{XPxI?tSJ_U04Yjzn7T7b*<@JeCX*<5}Y_u~|R3 zU4vrqOmO0^B{+AQYS4cSca-hZs#T`i|26RHOiRsI{w23vQ1|fo%!E?PRWyb-1}KE< z%w=<*<2j|687B$YKe0ka5`8N`+M4j?)7Z82hcXD6M{{PNoGP`z;e7cA8gF3jRnRt0 z^L%!iUqubHjP8W^X0Z832kquQ#t#>}q~Ta7b$=CYwlR%{;!BSgw3OW_8G_EK+v=Co zEFeeV8cduB@ga#Q`EBNc<qg_MM%BI;lS9f=C|1%76WN>7Gm%w=W5Z&m=sb@cuSfwE z^8WbDPiY2jGBW%=&!P%N4ZxRLuac4?2`uvh!m|ai0EkCG5spVH*z7D>Qa#)|RsTNZ zmqAud`n1d=l?PlLz=K)rb3qWi%|rhc+xUt=?QtOa&6o;xkE$+Wpdq=hz|`8_f_*%0 zJd9iM2p}6MT{Qh7u&r>C?FZrNfayqEl&BE-aQOi;AdLvM6s|}S&qqWx)@A5<bShf^ zq7JgkU#13O9mnUc5Rx>q<2YZJB=rS1Em6x%>CxS)Vx$J;H3_}b(c|p9J?-P=El(X+ zS~@}JhgWKRuV#^ibLUL4kR^a!5!-&4p?F8Y=l2~nOxI?@Z#|G4U*dm#=35rLxrsVl zQi1C!dA@J1lG=2nQDXQO+hAS_OdH#;bKwVR41i&&qq!ZudD+_nl@>Bi-wqi~%qEi* z<fVfx?g>2-%cs}T9sOKZYjEQah&<pOIKycwGGnm-LXB#mbB`^2OkEKD%JaMyOWe{h z<C?7cT&^!oh?OiM3h7hGh#n4LY^$IG%2OC^1L1Xy%ti^FWUCj>M(GIDD1+rJV3mC@ zYU~hV)<U5;;PZ?{6FSswW~~SYUDCxc2}nLUF>LmFC^mvcc3MwLi1h%$W3`FN(G;7+ zH*UGZdF_^3-7{m<%DC&<s5Oq)pcRoj=J5V^&EGC0*&R$BR6Dp0${a;SR*I^$IC)`y z+}ylby3&}Fu~cMYDiG>P2ojFcQmjS=b!cZ35*GBa%?}_t^fKueh3O4w01J5=iCLY# zkPIL4-GXZISJUpB1BKfz!W!bHyrZe}%=UrV`sH>sjp<WMky^G~2S5y#tiI9KA>t7x zn!w54L1;P?KOUzE#Pj`Jj7=hozvt9Jn!M<{)0yiHx^**N@y<@?P9Zh~F(NsS9PwDP zQgHuwdZ{pyKO#0#_9KmPD9du=3XRC!!OaPtft0pk5r4ZYZtbq`b0&;vdCG?4v)`NC z%=E@r(_(sg{jd?=Oqe?uaF#>${;_$)?(>KfR`<-dtUKHKUXMJGAR1JEH0Gg=O{yRR zTRAdisJh9$Bk0L!y@<oB8-S>vO_j@fm=9h<whuw+0?t+rPTY4=c5DrE>Isk&=M>Zc z&N0O#oL$ewA6aUHlQqE4u`mp~0i47lY9#P9>6#V}$A&4AcGgra%O}8?#VbsI@2>2~ zhU~kDY=h0ID<xD~oe~UJI>$u%k@L)^!%S#r4}kTsH&j2cOC`4aNH_4C2b{nuA6nQ) zJNad(o(T$R=!!$)3W}m<05Wg;rX3&mJ95*pn709KrXghkNy}g4<S03GG(@Kb?)pw$ z;k@|jN!R=h+bTUrVK<`2!VZf`KdCV6D^sh?q<Yd*hz9v|_sNE(2DYQ<6!|`}<mh~& zx+?eu6=Sx7Y#YT8Wv7B@UU0zHljym=nt=P^qn1=ww#4qtB>Uth`+%H5bk-j~Ju0V# zg3K<VDcYo4s(71={$prvzw;61PQSzDaJz`=KD6lKHn4t%P`indN_{M$%1A<`ftc!7 zBHQ@SPjbkZ<e*cre#bn$HqC{Fy6QxS#`01_O^S1~*JogRAs$~vcjc8###|Rs2AkjI zmLx-c3nrO)dzht#Z4dT^R#-*mDS=MPy1Pyt9$~Ew_&d!SPQJWKUtV5&NJuXxy8(el zW@@=eNjVN4<{Bi%MlDzUiwBnQ+Nf*LjC_j3MilCA)IqH1lGCzd&g8L?$K$C}TWR3v z{Qv2tvoO&A6C*SO`@ijlU#ZF19<ai9zpFx=iU3)J6bVOYAoDayw2W3;7Osl0LZGMD z2ahID&5f1x_6*XAxZseT9V_I83NPBRXSp*y470|hAjI&>`lQRrPAeinD%s_TK5USW zh}+>Ffr?}aKZrPCl!_B8W<<6nRdlK#ejyI*doG!g<(}DSzCDpSXToDw%CZzo)*PeB zr$7#+`Mp;)4?vKaK8)oe0Wo67@5vIx<*6&xkfo}!YxHf41j%cJo%UPQ6h;+?8B<hU zn6du#4)Dfy!-m5dA#xZ}$2`iy#|C<nq-fL$GMqa~V!&06CjHQOr#Vn>eWdkikR<K< z<IPw3#RyO~!zKEhOLmeKK$M2oZXcu|9Lb!4Xa@m(GJ1x`6uNHu61P*aUCp`F`lO<2 z9q2;47HPw&W*kTR)wAdQcV!R7bI;rT2bhpvZ;3nXlpzLEn1!+_nvM#ApJ@VukP%ui zi6Bt|Vu+nfNmHpo)5nT(yPT@s%rG1)5DLg00+j&U^HTuqm7jn-@}gW`l3h{Uk|LnP z(rQw8wVV9MlH=7jD!nh?t-AiNq`Q=LyS7lSnlhOOBOsjz3j7&M7{F70Jgzis(T;Y7 zsB=kePFDNXx-)&jaLGjnix^&o$=Q%DLrL>nohD*Xq1K_FKfq+<LGVM6nD4#SQ`$Hn z$ecy11uSt2(0S0>5Eva}Oqm{0N4-1F!!JlLAu%r@oSj3W4vZDD7$|YJBZ4i^{Y}%; z&<cu+s{vdN4l<)6NaRE`VC~OCW*4g?@|lP{fUownm&rbBK^PMsADMJC5Mzo5XIyeY zi!(x=TBYt&xaUJ1bGY^+apbeRO&fm{g*QSfbh@6z%js*R(+qtx^hEOX5_Pb6=kC<) zG6fq?-I=Ru&-K8D8n2_;V$0-C*W%$+f!QUECyg2;MB8nQC_RrKZRW#75|MAeos2jG zGi~1Q$B$0C;h;<fDP<6(e#x#MHgLK|S)WP7y5TZ@Ln$OIbEM`tE^xJiT2^o2QEC^a zlg;sB)am+cW4mTi{n2wE+<5QfR-0X=rJM;jmUPr^zP=rI7z^x)q(m>re<aBoUC}+j zEc4JNzfsfdqkubMqK`U>P^qGQqf;D>jO?-HVgblt5-`$eu}1C-FfL8g%?tPDr+|kH z1~A#fV5_-pbC$fghpm*?E7@xEGTfVqHEEA+%UK+_CbCqnuo6ozU<W~=<qYBH(hc}% zThTEe>w~H6air30m7>|M<c-eD$n12HBXa>tl|CCsOSZ<^EjAdf7#Y&~^N#@Sx!_uh zd+8_ppbf9aiZ-*mE_*rL|JduS)4UQ5qCs)$vwy{$O#p`@&&cjvL{rQ7xt@Oud^`(C z$Ci3%g@}#BO-#VPC#;r$X&g*{D86|V9|}5q^70zmy`0*H%J%#%{GJW%Be|IM^CUXR zb@kk~!%cJW`SdfriJ(>LK3c8stsQW%6})mcV5aSdLx)zKS)93u-@*$?q2d}*HkqjZ zqzww~acRWvaqc~ma($fxP$Ocq=Ke5?6Ci9miH{9o%VmEUCSILMSXgd*xw1D81IyZZ zx%~-)LBai#)?@mIG9?C<e;@sEr7mT=$qL_d^MeYD3^FlSutgE^UyfM-Gg}zm(7Ei( zBe{+U!^H}ZIQV*l6;Yt7ZkEkrImh*=Z}Wl)-I?@aDyna;uY0n%Td=Tqxc;LOl|cVk zwX_~VA2B!^fru77q+z^VEK~Pj^R#}ig{P0$-_i3D1$9onMczUuyii<VnfB(cQmQ>h zDF9ka)$VZT(EM75Uk9&gw2B`ifBB}OK})-%PZe0df-0(msM-2CIe!lf2igOEHPE5< zQQxOw9<|BOdNhJf&;TJS9~X4M6a=F02mwbD#x51W&@z*j*QJMXdJ)i5C4<$2)5Nlo zmDOpeSJw;zFo3UeuQNZa{>I)?Yv;GXIR!16FQG){$Zh58wAlxSue6d<5)*m#au2uQ ztsa|i)eJNg-^a@TTzCm(*!tr(A5s&|wCZA}_j2*JkRfWelQ)#B%S38|gD8}bX;;2U zW}MC0RQ5b+c#G74&v#G*hH)epBLP4K<q<=mKyd(vM<eOI2Qz+Y*r=k3(7b?w>gkt= z+7u;mE%glOF#De-4d`fXjsdb5Gj2+n1Nfi7!2@XB>k*zTiB^xAS7H_{b6JEQCciBw zUyENz-pZ)DdI*e-YfNDM@b#ZRnz6eD3Er-L?N(|{jFWEj4&=>^A8Oq&GS;8}ex57D zQt3|zpreE_xG15GhGzx8v2!{j1AVvI??Hu>M;7Z|@vzTZ>~YxA<GgUd0NKM`C-aDa zSurU*c&^T}Vp`Y4IzpmY2vgcSEeML^7oDCr+b1Evmu3g5EHjg)u&hZJ3j0K0?M;yd z5A~cGYHmV0LQLiTjWSdAtl8p1cnhRbY(-}wWJLnsY-3iyD%wNpZ|jzfs=Zvx{-aNs z5!y(BuICP)yEA@(75SrblOVH*%-k$cl-$q4h|+#SKL9Lp9@D&a1~h)qQ2<x}%0hex zG9~B{-jk})b&BT)Cl)n4x6M%wBX1qZnQm0@Y9Bs))6<jI8YhS$EvCw?QEpnZ@Im4P zjQ|&${r-A?b?<5thz@;D4`QAt`QerB3#q_JjDX+T8{UG<{j}Ce`Jt=c9A-dn{^=)o z8K7c><le7<Hec#<ho&O!@{j6SFTcoV+#vIjL!Uc=W9-o#aM1WzBRsNjKrs(nS=_)a zpUa%_iJ|^Rpz2!1=M4Aa!}w9yRR!t|q043V!v%VE5aGf#)JQJmoNP%ge4aAPfb$!n zc_~U99o7ZeE&!8*{%)+WoC+e)9<>+m)f6XT>+-WI8@6p9Rj$liDk;QTuE-@Ug|`>9 zl%F{|sX!&=7*8xms?4deXini|dtRP1@4A}T!cx=xYS!vS68xTtD6DGZ+2sLrPmq@2 z&7^R~dCrwetjNfkitzz?;&az>7=pYXc-57QA@)*o(BcqI>Ck)zNslW(-7P0jCpdbp z)}78WE9>lx@I75kD#Bn9;2xah;<yJ|U}UYBq{6Vzj%nCFV_Y6Vzk;&oK?HjQ_8}K( zcF6Dg<`zi#wAiKd1Gub_=*4w&K!0tyCgFqO0auukwpgU7D_2~O8ACDY`xI(GT3~j~ zTmk<p+o;9tN#r3|g{KavbK6@CCHDS`Z>r!7quPuy!?MERoR56DmanGW1=y=ut4SIo zauA*1Kt9(j*v+|W0EJd<GV5^%pyd&jk(KEvgfgf@!a~KP%CY;4ZL?ph1w?ziIzP<9 z<3I(ny|UqiEz*a^&+Oqbb0~iE_P9sbd*;+ApIh_tCuV5eGzL=zoagw_HMokk&HH5q zu7ZvLmNjoTyd9EXdo=(j?#+9VHBWQ8#rKAd#oRkD*M(h5o!xuAMfig5RExOfo0sY4 zLS<35nVW8QIEBv7wI5OKt)@)gOy7RR;Af4synV1ADxZWB(!qkP^?uVj__iksXeg({ z&yBd-You|L%so%ii@eLD6f^7zwY}Nti9c~Y($$gaix4y#E!bPT2~6G#jMqaB^Ca?+ zOs(Z2GVxmfQk7Er=F}SBiq5{;6Y&kei3sTX5B7up|6nftzs9!zTLWvhAFK0kq6@n< zv}18ve|hidGQ?g*)`-g|fuIB41Ga){;G5mgF4Lo8MlYgExCB0Nihp~<oxBa(H`F_~ zx<aG(VE-b)kw<nfTRSbJ_6g@54tAgyNX@el)F?nkx=#Q~|DB@62=WB|*J>*X)u7pD z96DT0j61=hCx93|sjAZ8Rbhx&JB>X(2^F>}HUTZ=V56aqG?VC0uw&C-BoAa;TO^Mp z93&<51N|7Kl-<B)z~8rPkBl__ZnlQvW4HSD{$rvclI#Z4_K^KpDN)LyqogF_#<mku z@OxCdFaaiG&$I)`kOw11mQ!ikYbt78Yg6k`+a=yhppB(%t@_WG)in7unc1U;(+Nw< zyJ-0aVe}0_MvZ9N#OJ(FCCd%534r^r&sW2G$mnqZz=%nJi^SB#A=(2!;3Klj6+|Y| zP>>@*^x(-?P%LoG%9nR2CgN2<73EBH&L;BkC!&y~mzFwmaGi$F5~pCFS-7Z_Al*iw zcxp-$P{Jr$d)oz(!hYh|mNremV<nz_!PtFQ9=9yGcWGk@Y@pjl-Gs}?;C4l3TLS5{ z`I-^HxWO-#6sy=cLV$$mk&Z*N3D%JbbFn^mz;o?d>OVKEQ2G>EM*XlUe&r;Fs#1Pf zscp#rA7$qhq+8cz>9jLX+O}<-v~8ZWZQHhO+qP}nwoa<^uc(gd>iDAi?})W;-iv*) zW509Fz2+FtSQCYCjWulmx1jRK5a7QBA{y#^8GwLN-tf&YTirFI2z!afh`+{}BS>h1 zBprVbhH6LMU~Ay?^t2fuHv*?(E#7%i$q#cjrC9YF+^^2&>EQJI%)$F>|N3}*{QPx( zyOi<d?eld}kzrE<m$S8P^?4mMlJ-LP%ZK;l==KeI9j_YB=jO`W%`eKqQnUCFF?m#= zTK8?02;9VXyJVulWMZ%4=(c2|#wKL|Z36Gl&Q6!vOVxA7#YNTE>-p2uQ$>cIhqi;2 zSH<RruVUcla#LWEnW9y<<fV@m@7p2NH!TF0kO^%cc2=+D56werCZH>5TH3uTRJ}kY zRTI7?epw3&wgxS5YM*@LPI1H*ZhrUDlCo?;VLD)|{KxYJVMQ+<70xcg19Asq;nK~0 znOcv8U59j;+Av{~zsz24N(~e0_m@@orIE#YifP4Jd{HS=gD?!YC)w*ZQVl>>blesG zskLI~<>CWY*EozBAl@^=Nf^xB4BG5!y|np|4m@Fq3p$f5k)*HqD1hE)heU&x!F5eU zf`pVVlOqYmn!1TlRO<^s#5g6kbTt7fVt{~M#uN84kbTbJiKm)~jW`QcU(>CyKVSis z?ibeM07{_s_`acRT__&rbih=VVtg`q4N)Se{#J9ODVftn!Sg*xEz2Ihzot=1s59Sn ztm+K6Z&dpsxpHBcJvPwEF?A-Tp*s*B0yeiCac{IQ^ftlJo@*AkhxQ11_u~2w#$?&B z@ee2Z>}|eNl`KHUsPHVw^L``@wAL0l&o5RC1Ad^xO;rq>&cdYX(Ks0M#%RYe{46bU zk!+&Mh)u)<;0!)yzD1AKRnfw?j0qDc1w*hzh;wbAF=Apk`jME7>yZ^*^WUNkmj|Yu z1e~X=y9^o6@vPz;iPCiEWvd#DouNY_2l9fw26q<x9Ajy%PKD7-B!0s4DvESU=Mv4R z(hR==a{$y`V9Y~p4_npZhS|-Iq&6!o>rN=AIu%#K70h8vQ(IkP3Z6mq*ee?D{o>~c zW)1B)vLVy4qF0yse9~oEUZR?D!!7Z5S^P>r5FgPdpcl0O<-WSHzwTyy@&N2G9txBk zKv`y|GH$v(-a5v|ZpOveg2WQW`LmXq9ma7>K#ool8OMz?Yt@e+82J;Rg{nfP(iWn0 zsdy(T2R0)Ktz|I8f#VEh(5`Ko9uw>Fj}m08A)(YQn`I~+oaISdhz*_X5J6A&x$i#< z>%o)K8nNFG=PQpOMwCq$H2(s=XDS&RKqMH8oJDkgP%-`P>1x|47<NFOARysz_K5zV zA<4;J-41FI<Q3h5m|941UwE|1=^ecjDj@?5>+5|Eg#4wmz13X93AASadLMBzv3K#c z@Ogj#x%z7K>C(gL38(dW{MDrGN_=5MaQk$X(Xp(9M<?>!-1Bs${CW9YVic2(K#{2z z9jWhGQ`24Pf<8zqwjEsuzP*y_(<9BO_HHyU4*=;(RhSSfE5HHe9P_A>o6t+PXBwB1 zA}ufGDLNdrE)V|~3Ef|Wm#wM3_Lt^-vkFbyFZSBM+#(xbMF?~`8c3okm%I;wT)7In zo}|~<E%Wexs#h5|xm6;~s*xf2j)RwUvcLxNCNBCAPScs#N%Wp)de47RFO0%;?F?5k zM!B8eCH$|N1&tza4?4ChK3|A3zuHl0hHCy;lpqLDv5>%4#9+5ATUn;;I1mid9;yhm zp~xHe6)HSZ&$h8BpOw9w1J?i@%VMRDhj&I{x@jRg+8Vx`mKsKxOA5IUFp*P#!+|pA zqHS3Uyc!D`1CjM%=xuoFGLqfC9VkD|8L#|ae6||7VZ#A^+yb>xTc!0L=W@j;1jVq& z{PPJrtg#%tE0|%^_F4xTX7r<gO2vt(*WPZ$I6-fWWNgMF9xv~N4E~0D2Sot%U%&cB zK+w$U+zHDGJI!M8g4`EYDRh~MH;tqznK$RZiei|k5%2VpN+Z3yp~xw91|l#{Q$pQZ zxJ#@zj_n<F7$*nI^0G)*6tN>Cn4#DJMdML&<t~M>$X(7>f(t#wK28(_I-*M$$FBOy zSVVDt4ziL+ldI3mPE~4tSIbg<o(qz4(0cTGe&c1zI?9hR&hhh^;0^fJSu61x;;I)J zC)*QZc>CXrBl9Q0BASd}R)7<-B(6;>IrZ92kqJV=Gli|mRVesdahuyqHOv`nDzwmf z%P{EPdwymr1GYn3XKPp5%HT=b6Fra3OhW*B(L8eMMXkMYq6*NCbPbe~J-&r%d$-fe z0dmamo~PB{`Tg^yh3#E6`Lso?ZK*g+QbRM0VxCh;bO!T+#AX(d8nc#21`MYuh8EA4 z!^HGaL|%byHDx7PKekHTTr8$3Jlfta8*TiK))y+5$UKyec78y$LbNmIJMx*rbH%lI z{Y}2G9t01JgFF*=<gNNbLU%gOJVx`LScwgiVgghCbg4FoOwG49b{Eze@+@jv$VvUR z4w^4&g`B81CCYS5<=UX){9rVf^(mj$O9Nm{I_(M|Ka>Wbk#$&<PB-e=g*QW%*un}@ zI8#Z(Ehxa^@(6OAhEi+>6ngYhLLAydWJ)YX`zP1fpmNdmN;9Th6Gu=Wl-v*DXr<(J z9T0U_o{kXx@23N}^ZuNuuA#WMkWN8<f6#{G6uZ&lia=TQ0pu+aOnuBdm{=cObl~yG zK3ZP&E|nI~zCJV{HSY;clwZ_z8_&?muMVZ!8;D!aL??XPm@3Yz8h#OZLxTD0Q5mtE zB3EP&FJhgIXAp371V#UAgvQ)j;5wQZ-mZ;WXa;MB7MhAr6kj~6p+Crng-K6rNlLj) zlw~@UK8^A2eCmph&nZ3*<K}E?oF&+CJ1jxsM}{spW(w;5lG!JTeG6HqhogC`I}(TD zMiUi63F9Euxe4PiF%O7jNlqpN4($Z_A{m=VgAgU&_J%-azZ&St`|b7S(QVmN`VX^x z!^5P!LtT4%-<2s|{bYajP$T`;`uIefaeTl3hwhkx^`BB+*;(oT-R^fu{o==S2mgKD zBhcF|##be0Q-%)aShY}vwM@$pY-oiri)aO%L?RoXVeIpH?OKT2{IH5>xrG+NnSFhC zuocJ6WMD*p@O1e8c6hiL5w$AQKg)D1Nu=+L9W0XA>U@g+FzIUJ-h7~;$QC}881dI! z{UNFqF&QZ}M|f?1(oOS5frS@Iazd}TR5%UF;+)}kwDd?F@AQt8@xvG%61XGNz?tJv z9ZpAgoHgmqZ$_ekHa4(^E@IYdl9S<E;2Aj2U&BFmyl+nZiJz0sz}WkO9!MB)4F&j+ zA=iP?Q(#~0%?8pq!>Ml)jofrXV8tB_oh)WqHXA=#uWcGLV`W?*VHk=lEd%(Zeho9p zSgF24ToWdwvNS1aIk%#Xr{1R3pff^I2fdT76JhI(d_c&6t=cq;m9M?2n#ZPoR?=Q< zj3*X(uMfWw9K$}C@Hwi-B8v0Hp9nbpYuv=||8%EjX-|1)d@}a9zw95$HoPtUYCx;; zb^bcIX)rk@;skaj<`<i`w7qhMtuDIp^S4kMp@~UjgPr$uATXt^8ZSOFf_8S#7Ih}n z_K4_oD{y1O>Q#!~2tRg}C-0w9AzxdH7Xv~uS2Hu`0#X?}GGbM6G^HOUoA4x&qYZQu zbO_bhB1gfhQ;$8u)nF7N!*^u=3;zoK4Ep{|Fr^p~)!-2UO9ZKDntejmW<HvjQl%Ew zp2ud*K{^Z??GkmYo_}0kjOOb!vEdnq=H?+-c+shyaPOZ|fujRSQmyS^WTrCLP??x! z@ssVxC84txt1U`jDgiIf5PG(KInNU1DmcSNUWGPxB_m-N5__ru6$EW-qTId#5UypM zMf}9uFWE7jv<Vn2lv||IKqcS5&VPHaq90^`Ze9=+ns=ICdb@DZsfB<skPAN}DsID` zhckq5*lsdHP0;YW)tdg;{Wq+?EjIjAn0_CnYK>AGm!NSH<g+`mq1H%gXq)psJ797~ z8S9|rCH`HAvifqZow~E5x-+=ZT2VdrSvfbYH31VMxwUm^gr?<txte!Eido&nAsSgp zG?Q*%IyQfl@!%_sU8In(^C4L}Kc<-X4dguzSMredy_e`P4u2ut#cm5Y76|_S2CvlE zFCF=MzlxHdLpI~c+q)lIbDagawc`uo4L%RgOL>=*l@aj~NzkhN74WEbt$&bspo*_E z+g&f!E$P~hQe~W4+Uv1#EH$25@AUSU7+sTEU*Py;Bc&r^k;R|neDvchT@?`@Ds%WF zU3Gs2*K|eYz@Ns9V-e3YtdtKpj<I7@x!8)m=$P!i+RI^`1Io5x*SZxi(0N0v4>u5n zhhc-H=v(B&;8GbRQ!=hLg$kr`p(GhEH7g$O^P#0AG_#!fO~h9`qv}X6>bqqQ-l%!d z>mV#PHEAsXKh;YZ{t=KM;y%S{X*c<O)U%U@)L7#SAKN%)q~E9BRt}#}jvEpV9KjBv z_mTp@HC&fmsLgx@Ek@cO+Ntv`{}&;#Dw?so^#dJ5V|m?oSV2mR)8l=G3$lRpb`*X( z9WK@w_{2Ko4WT*?(ivw3fx0t_?pkPb%%dpq;cptglo-&{dkbLl)^FeAz!$<ri=70& zhMPTfB=F-Aa2$cBI!{}OA%nLBR<vif%~hUO&*A89)BZzmRsQMd4yZryy-$*~l%4=9 zuC?`+p-Hq7e8;yubfK;jdq}OP9IuuftjahtIS47d_W8?Qz-7!JCNWy<AtQ>1uzQs3 zy}r!(WqPYNY*Fqtr(rAVQwuOH_O2zQ0-?6XLUA5g+=|`G<j<C$m#40I9}r6{=*1LN zP(@0LkQ8#ufG~r0B4QknMbM0hF-Y?caV;Z!lpRYHN;wdk{JMSH^Lna~(;|z?{$^SP zq#NROW8|uFlMR)q(t>nt-s9B@0=)Qobe|;R#lNE!ijZrL0GX1a2}|I{)b=;3$aTIg zk?I<%0)*F;78EoWyD>CWZnfH=QPa4L_^T!p=%AH694e2N>e?9g0A02<ZiCx_`8smJ zQ3Y@UZrjT_!In&Y=km=p%{hsYJ@_mtuCD6oM(U5AsLnbB7_gj!V&me|&ywZ1we-pY z+U}nvN#zzyUbQuGpmTy|S=yCh>#b<oMI@3}2(2Qpd~?p;4@$)wc0&7)rK)A&21F7s zhi+9`yidiW$k8uZ@_px7@;NV5+zaxW_w<M;+dB}PWR*=s&)cjUN4xzgj|-}oc)Bt* zBe=wGo+GS*6DXsboU(t9WQNu%M7orNUy<DW^|UXrrORnAQZ6FRS0Dl(P=<K-U0e+r zsrV%`ip@^Sh_vBMQ=r`vU0|Df8v+)89h{wb%U<p*p`SA>pWEQ&L&!bJpR0{s0X1Mb z@~pqa0{z~spL11r&#bamJuPY=eRnG+y!O>|8HxLjMizRx`pNaZclw<zfR)^f_o03O z?u=e8>>5@4V*FAOjzQkClYv6|%W~@-^$V1Wq*C>tc4hW|a$YgA{@Z6#OKOrf8zS)C z7pm~5K_K~0yseV;<WP-uS%f9a%Xwiq5X?>S5D$CtN*}LJS!>$k`Gg}fN3D0l#4aw~ zX>Z5E;qK5e?l&SmvLfIkgwOi%<RqPAn-Sz;N%#4INJE`tlUxrNzj&p$J^Vug>md#& z&-K=e`cg&feAZbiDm7Wwd2yH5$`_SWoZYnZ4o^)P|C$W)#kyNo;YW*43er)Dn&gzS z1$4dOk`RV<Svb@`3Q&Z?fNr8~pPkkqIEgGsAG{Uc*$E{g|0zVz>v}rLlr#{gJI;zK zQtF2LIl~3l`m1Z<u^XKmG}WKx?jQ2$hD3i}QUsU!IA-rF44L8@k>Vm|bjTosI82<* zWE?JJcNiteZyK-W0is8U&LmNmQ`DX|jpdsS#QyL*fMlV9Sx`8o9hlQ?rn>9*+ynl- zQ$dB)uS<4zl|@Nk@M<}Rr(te_L{XI^S+^vViZlccc4Nx}VmWNUBiiDgRV3ibP$9i} zJo;e`xMp7g5q%^ohig@fEjVZLFvEOmE+xLsuDVb$#Cv`fznYOYTH~wOtEQHK(idt$ zZ_-2`o^z`efVX*33B2&uF@2;A{%9%SV*^|EC%QXPmxUr3llHaxJHXz&Q@jr1mM$gi z&O*wtS;=Wg*}yRhTEUAW!!vW*iV4K<sm))JaL%XA7Sqn+UiXQ*kfSB8=v0%2{aUnm z=d@GMJPmzZi&o2rsuys#e24V1Bztl7z9anPpH5AF)pVH%T$z1MY2sK2B(%MGJ1)dp z8D|a>Zb=0k#OM|Dk1_6(zXRYGtq7Y@8LcuQ&FrE;)AC7LtQ$bCsh`iss}~(Su99Uc ze~k%}?mT=CH>&RXGsKIXQNk`Q3CkB;TO5M4p-?{4!5^XCAbn?soAS+VAUhsy(O9n@ z4Dgz`qssxHi2}|BMLSJ&YN*W`t!vCxH$$VX^PVJiEhjZ&scSpE=_}V{@|8`j?{SDX zHkDSr$lT~{n_8NZ#~P<uYkDl3H^5xu8&1U3!9xy?8cXgn_bXgCmt!jPS=O94PgUWp zTdSL6z1L<r)HWtCj1l=D()*UtSSO>dm5XtaftX8qua&s-+B7A30aGE~*ExY(`2+N# z)p1ST{DeZTLc-7;&4Ol`ERh0~V;e8QO*flwS`LIB+E;i@f)Q;{SBdYFmc^-bZd~RV z_bmr+XrD@G(sC_8!k3gy;0oCYyp&nZ!==ov34C*3u3v0d=eA7XIp>FDAo0-s0Nbxa z{{CVgd$2EZhO;M_dS7dSxhEzhK%(OsRdri}<n=NPKS`2q_5#0}v(0|4Rl`LL_QRqE z0-LbgZoFO$npRMJ-kbvO#LR6R)pkoPt16MaZ{pzivw@6QjjMMoKIrIHrWp$VFj4U> z6}>4Q9RQ|9@Ok0@y&h1yAiCM_rXXeW{B+6|c*eEXPIA1YLiE1zXFj9z=8?3J(`s+Y zfE8JTjYAv>vEe?K2Rvmj?voCA>sk{*w(xY|qUiKGsQ&c8qR`ZCWAS}uO?-<-)eG>~ zV{cbw7dMhe$^wy;=j*mq=!yRRH5b#}9m}Cm$xBZ8vjMR0UpW7q2HCq;n(lNMob4y@ z%t*1xo}-(VuO5LQyvw||8PQ-NflUGNMEjlFn_Hyaucw}GwI&~!d?U6NXixRvmmn*o zZ_rBW%fx@EpNtIuR6kk%Khnz7tp4>?^L4F5psQn;YfP??U#N#(TP3~%1l&9fJYO8t zHyTN!M3?<1-L=PC6sHVr<cyK{N<~+PI*xlA2XA}J0o92W&gsvjx7M`GwCkY|F{(e; zgauh4F=9WYfk@y9^~!Y7L>Ss68g=BRP`P>1v4hB#O6B4v^kz)CsR~!xY1^-I{<eo= zbEJna4ec48^KuE4uzAHlliD#eJ9IizGARwejd5KCaB5nxg^BgM6Al|DUKZ5{)~P}e zaYd)4$<nyId&PGhTxT*L)@+!}WdtFiA1l098-k)m#nA`#J=ymVI61RqJKy>X65D5# zi58@)`eaf2N@dC&R|<{h+AOXzGwT=(7uD%=Lh%KH=zQLAn%}djQ16|m_fA=&lW;vV z8+t(}ZOv)0%63XM*-&2LTYWV(DH_VR<;TO7xcH8tr_(w%i$ydQP<Ji#L>R@Dipv>Q zqsrw9sFz!t*Hn$N61fVTDh@emSev@LOx!8$UDPcenJIVtfLiI--T)bea<uX0AH=XB zxDV~2*VzxQhnPMex7gS(BhT+NnXVCL6Y3c|C?TMDbd<+O*+{CHOIJhGCZdR1YbOl# zKGa|1PX6pVY7i&IH#OOc!se%2H%B=qVu^aWC<1|zZ(K*ZoN|foaB0^*iF}WmYagsn zp%S|Ji}{A;3jcOyDxwPlt~85c;;LQp<+$aB0D5s+8>KC7AA$?5@5kwipUXPaGiN3> z((DDLi?1Av>=3sgB5bJVnpKMcBx{1cXKh-U7G`ImX@Fs4*^r>1va!CAK~ELTF)Ffj zJQX^&f0EQVHQDXv=E?H7rhx13)uERlLjFM^mt85i%wWhoP4jsl*3aG1rg~&shtuNl zgZh@TmUA+%ER)l#00L)mQfgwI8B<{`&fhHL&A-ieY!$(kt}4e0i=1#)Da{*tgbG2m z;`Hg(mQxv~-R#=e%u`!EvpXfQYI+7hY&Y63ECtZl^Y(4D51PoQhgB`ML^J`Jtmik& z^^WrCJzlz$&lsbxSn0z^7@Q?7vz8_fXa@`NRpBULc8RZJOC&-n@UU<g1h9x{VumMk zSfo%JI~71_N>uKw$mLZcvZ!PkrCMs2o|}1jrTukQaKVv{rH9Jf1Phc8w(c>YPL<FW zNDeb=s*;TiB~3RsKtE|hb@rR#o-#4yl4l}8GDH;7pMiFq(os`&mC_#`7Ft6HGm?On z8A;skO{5Qz8WWKki=_~hOjPVfSOnzqhn!$TxP$fa0v6A1y09J@OFM}I@go(?l@9mc z$r}_>78Cg03}j}_&pta45X~C3`f|E~;0l(nJxIVl3W%E%*iSs}K+MH{roL`;403(2 zxxT|rBu~!kb?|f4e$yPnYK(|SMXuBwHut++-7G!uHtVlzO#j((PRtcIcag5G1m(V5 z4x-G6J|8q^+$b9O83YMQi<|4Jz-FD*IJi5!T;=+UU&rYcP&=THgrk*$nQn>9Z-`m5 zd))Q{6575rvDTX#$o!B24_&AWV<XOA(sJ5IWWONYOF@~_hdXH@a|${P!M8|yHni(I z@&NUl4-7>)Wt=MyxSKeCAVbCWm2+yz&MlL*UoN$2L)e4}s!kb2CgT>^M8Lh0c)PW( zD@Ls0$0j2ha}<7#-z+d2T4ppJ6J*?(e2)nrntb!_d#1#?6=PmI0=k%}xxXb9G$oy) z2yUs2-Y{~E=ExWveKVRZr-HSPissnvmz<rxA0AHjP3!`54*YVy6AH0?rV2L&D#q8& zZP<xu=qGU{(@PYs8_nN+P>L)0Wpav?w^j?K4K*`tZ_1Il>*S{u642WQrT*SJ2L8p@ zO=nhR*^E6o?jQpjDFy4|cJ1c{gaQuv9hAeX^3ta7^uCJp>8rz28~ijhi@MVtsEw|I z_w}g{ne3zq`&}v}-*`lm%MjN2QRqDa5|H;&!`JvN0N?fIPVn~un*Z_HB2dgn)ZH^1 zR;Lm-OUD<O2ZNW~OOH6ZWT9?mmS2qUS(aB|L-x$SR_?W+X3Co{ke;u5mS$zvItpv? zq^P)j<5R?iT&{>L+dsqy@TOy8=bttk=6@hgGq5oKCv*1yjhy{&cp8jUjBsROGxX<L z(leFZ-eq^bjmH1bW&Vp#gY>d;b89Rau1IXE;Ye5P%JnfFbi&09w+slEJ>#wOv(uPi z7LrRMVp7)tN6V)Z1I|E5<m<LU(e{&P`>1t8kcS~evtKe5ln8{q`QI{oR;}}@dQn-u zG>*MXEK8K;mpx6dt=T`{Q2R%*hdzTBQb>qnA1+<)1H-A%zYz9@8k^Y~sHpHylIt@B z-7vcHyn6)WoSIoAib0V3B}7_~5N7642MfkS3}<52V1ke3QfpPP!aZwlgl^<#h*E#7 zIa5(^&RVi;KV}oZ4pIw>@W&h;X2Mvt;e*6Qf<=(ChNGk3K<X7p_YL{i5qrikSOwZE zt}9%vr(Gtg7ykNlvwnR4VEW#em8$=XfIpJ-SN&jzjaAqyBz2x))29X(^$9{B0Yv;2 zcYhu|!v}m+&J@MhcJ)k#xrf_(6J-zbg+_UCJd`7={SNo^hUFPA!$1;(%Aq&N!q>8Q zjo}uGIe0|=4K~`aR7VNh!Uo=mlq{-rPR_Q}O?ONhydGweHM86}!4c7P{h(TeF+|C1 zA$cEdF*(rYoF{@_<bYzCkUS<k$g702o2KQ9rBlo=dRM<ZbPy~*pY9Lv<`MZ+n!zd= z@cIU?GOnECz@T0~XH%mx#$mmZUK!mK9-VV_$oBa5S%6tjehSExjDGP6Ed2R=XP&r| z`oyd4U3~dPDz1{Uyorpeg!VXn<;9CGw0-8y<gSE*=p*i_yIe!$yhw(MLKGQSwJ01| zqAR{`5m-S<L42W-#L-Og%O=0Fu3VRDANsUw3`O+372{5;E(aw86Kak=QCiB7&F7Y) z(j$ODEH14@4*bgxNEIn}c!MpuN;V1LqD^3Jw%kPq#YfH97{v<6p|oY87k);F_PO8r z+D^{5#zajL#@<9%e-)Okn{BU9rxk3m@na~kYU{I^gH1I$Rv^VgWN;<MGrGZMsPF5? zPWa65Y{I8;sK&vNF$KiC?5^h=9bMi4A@(4}sIEfR8x`6aZX{0vQ-e=Ph;yf}Tc(4Y zp4Z9ta!gE2o+BDu`RQe>Zpur8=GZpn^+VuHm>~F#3P<)Xfc))_f+*XPtxj@Z8~#qy zq4%C}mcgr6bJhgNC3x*l<q2!0cf|ABrQL%2ZJ=8FOPW;VC$&+!z$dPfb@r99uK1hO zgd@hM;<QsN4tw*zR(sU3`k9B*M?em;HdkS>)gr7nu{Ny6;m+r?37<>v9bPuur}}m9 zx`0ESq@Zc6^B3}YOmRqrN@hsvAXSS9e`@0-O{x7Y6byH0Pw&_>Ua5Z$8#(9>_GB&N zt2(W3bdek>I{{G`*BLGZcgrflj%N}@Xw><MD73zoxh@*5EoC0&70h4|#@)m5uP4_J zcHvG;CA`+b;p5(%lc6>AC?g55tCtkhkbi}=)v^|@9^sWRN=WpQUAs|@Mc^P7Qa`cp zmw|-aO-hIzY)}j)OkPv;@u&LpOx197$Q=$wwI@Hc7kBi>u4f&ENFDo*{Q)|BTvLxQ zgz+KTVZz%3g3bhc2muGF!9&Eq{3NI?eMBN266HpF8a^tXuEP^OTBka+(M1H%9+J7( zs{pC|EACvOfpYK${eTB(MDv@y`QeTZ)khG&MCprAhANuNq~k*mp|-@cjeENNO9gfc zhP8TW0EV->OOf4u2-H_R;dX$B|IzkACb~YX!O1Dam^|UKCm;Q2Cm)?8K|gVuMr3Sj z*4L<;k3<wo$-a`0=YjD%{Q}dGd@hUn!&+Vgh~C&C0YxZ3Ysn}H*R0xVM*+a|5*VBG zMu0THlvkrI8bj!PYGEoVx&9$g;B8cB1|-uc8#56v3Pk5%a2uprAMopey6H}<1Umq4 z9DIZI=?hWtv*kLY`(dWA-0mJs%}bh%)b#nA`1Ejuz_h+6@+>yDMVdkb!Vj4L+qd$P zAJ@n@nP9qP@)7{|ohsQbF@EF&;o_S`27Ym}j+fDx50yF?l_c!p&H+a}gdB6bV?pHo z&ADYc7+h7B;0qkPIko&Bwikx~22J>%^h@lF|K-hPW&5|2nU{XNxg<aOrI(u2k!Pc7 z^0-70YM?{l4OCM<{I!tgh#&&9LQ=71IBc7^uXo((r`5H}fXS<E&BkBPN2cua2*L{7 z=?DsJZQ`K^hvL#=im^>3vWVzF)r2HSrsLBYyJYrbjU-Zs1!d5(gZ1YVLYVU?#98ET zPmqo`nLK&8z(s*@vxkDI>_*IQp``g^;CND0d<s}fZue3a8GP|g(qweBx*)=2{T7=3 ziK<=PZjrwrdpk)jB2GE}nj(Tlyov^1BML*z%9@iCiA?nhZ-d;if^JT(;es6VQL*bn z@GnmrLS<V0l`qLPW(>E33L7InJu)Q?bJN$z5wqThm!g{++_#E6B#V}*oSKY-aql;< zX0hytrDLsD&kVqr3s#~=vkbv1H>{u+*P_W}aMntJ4^B!w3I|F@<XRBzfz(#uYgxmB zzu1RBVq2P9CyjNqS`Z(rvO<_|@8{qj2V*)B=P@9uZI6X%cVRZ`?H9O@-RH#No-pRF z{4CTDzNeMKTqqB*V_M_Z3p#~~7*Wb!X`+!qz|}P<q$qdG1<ysF;^OJ!VoF9plpZs> zNc%{vZ6*z(sH;A>PfT1QPD8X7yoZB}s)m4$&$>mqB#NDdv`b~Ii`w0LPOQ{vwST@S zO_lhgjcS)LWpr04;Ez_VSMOf=0wca0H+ywnw=HP(q}Iw^*m+(=QG<I?hp(P6MGvrX zUWXfzGG*Y0ElV7sFxZ#KRAUv&AbNq{*Uw0=-Q{ZM<oZ;D_t){Y{-Zz#hxbQmal`iV zTf-K<|FfcEK=pHE!^Nda6U)=n>RnQ&n<i)Li@EEMgFy1yK-J!a!?;cL><SL2AFpoZ z-<<8u&HROxkw?ED-<vD^eE_~Sk}1*$X`uA3bgcBOH2d?%@p*!*H*1a4X~n?G&H1PM z=ZTF?_m7;)*`wvL1EtHu;q_ooHe^O;!Ceo@`enfa<Q4{8HOyi79N%Y>wwF!WWD2NB zwgio?cwl8=?^jEWb;$tQ!p-{CMoSCZ%2~#atgkI8vRiW^ao-H8kyxe!eU5Kg-SJHS z>)qG2c85*Tj<!xr$9=Po&Wn#ePqn0B$Zr9|B_)lqIj57-Iyyq;VRka>>=n;Lkk&Xy z{q!G$F@x<xSgW>lz2mTsOZ{L_VRACGLS_X?ySw)$OefrSbZ69&=(03I>t|SN$O(6B zk^8B<z)6r+g8c5OH)MnjS}%=tbF8R94k$<D(p2qRSnI-QA<=MN(P6o5sywQdliXbP z2IvO}241T?VIj9DvD>9*uQb^{twQ6Qd|g6gzt!t3(9#gyyn$&^CZ5YECz3P0VV=6B zi}S0~o6=?%+O#Bw75kOA`EAs`ue`*($_J<|)jd>m1guLaMyu=;+0s%`#j{awyJS>% zaM3_Z#KS1{1n53vZI1l4`da9#5DCex16j#1Nxb$$QTPl|1$DGsoD*^q#h@^yHUOJm z1k6X^2DEKXx-3+A_9j!*s#lGZE@9;#kqGX>VcRb+aHsW76==lcK>e{3<{WdYd`#x~ zd@rS3)YVLjOYs!$`T6aKYr5hUdtyu->5!hUtDDm2<3K`Qj&vsTgAA7)pYLPUqyo(( zgTghvneC#=+uYD7uN=lrx&p9`qDVpymBjS-M2?xrc>A3C5jqv46vh*P$#zAIBk64m zPB^zM>=z0oDN!y}dg8Q&>F5CB*5hdwNI>tvaF3Mw819CRwFZ<>T?ekDJ<<5zB5x#6 zPb^?M{;+}QF-8p4`PxAtR5maD&OzNAB_V)+`kCy6H+XDRNB+<c?oD)TJUfY!0x-Sq zA33@%`Lur<nSBBpiM<K_uz5ul!PZg*HqF0&LQw1sknZG743NzJuXVw31}Y|mY*=U5 zK~wHRpIT}rvhBtigX?gj&H-}7fe%=^q-JYk)3#L#Yfc^gH)HK1b-2cd{Hh~*$Hu+S z_awl?c5&D8R?eKO_Mq!_d&817QCRL3qc0CNrASGsuI)lj9_;f}kK;t8t(t)<74G2x z)1eVZ@k`U<qgDs}Jt)V9n*oGa^y>=eeWT^((QE)0xYM>Z7c=1nc!PQ0$<+8Kmc#bz ze)NQ$jHBLC?sIouifeV*qm&<9`>sjSi6_9qOtZXQfth7FXhwa}Z*YArRup~X3^cq} zUAuNcfGS=laEry@FKi{rQ#PT!X7H7=mIXby4uG?qW%VOS#=+%77;ikK!=75jgD!b| z@7VjiAf!@o!YLiV#?V@{KAv8}G{f<NE_836?X+7N4CRKRW@!j^a$do}(9Ew58TiY} zm;nT@`L&Cm+vrF0j`gq6g&{%k4m3qU6k@Z}qVYw2=!ss$)W$9Cm$?ZQftwM@tCZLs zUK0`sbp-N4)!&2a9;`%L<LLz$yXD9PWXZ3vrZ#~DuW3@yaP1!sCP}otJPgRZ^6!D6 zhI=v^WgnEO4^H3oo&d&(o)xKx+>fqroWfFXdG*#QaQYd1YPlV#36M)Tl`xif#y+2w z-)E*dQ$ExguNF~5K6o}i`-r50t{I&?qGO1=nv4MU9J-b;mT(Ma4MPN8ncT$VXH5<x zJyS#&1!T2v3)q^Bfas9*G?*wvBxeodE5)R{q^Due3rD`AFTZD=dv!aR1s|OW{#*qZ z$z8gdXE9wm9`J@pj!65Yh0?CM8qda8{JGM%8MRMRnlr>HuF?bC(8iMcCMGo~B)MN+ zU)&DTnJM^cx;OMr-o$GA@^z*kIs|Glx400?e_Vg>nBu-AB_}G-U<wwH#NGrzw-rSf z8RwX@_c&pkabfSkhc*~gaW`Z)Hsv5FIyZO~-uglku$z46@VPUd>LXVq=1FL{CqOkX zJ?!(D+S3S`kX7=>p<h-+hQ!uIiTfNaZN3Q_bLqgXUR`0ufOnrGj8Ha?1isb1?#=C@ za4ZRNS3=BFPV#ey9}4mO@vY&^TKjX3_jWEJtR^dTB}t8V4#Y@Q${^n(uBCNbBso!} z?H`Wsn0;C<9G_x~c^;3tC<lqMB~Y-u82a8nX&_c{SJ}KRS1|8*2FbFi5-2NJ<>v$$ zT1)NUNm3nbyyO3<lIq_B;>RdE_65m$9!G4CY1zjrqJY7riEcpQrM^omuT9&SOV0J% z5*ZfpE$nySjJS;BC1p`-CIyGcn6%gHc_;HbUufH3JMYENe&izrCn+W=XG~K|gDxb| zJ(UMOaWXp)<FX=7`kN0)AR`^JD^j@|itlB~@{>ds-2k`itJ#L}?fvx|MO23G#jJ6D z<86-LmvaqXt&NgvyowNM&lKQw<IX1^{&q|~NDVDa8;uUqon7pUjf!gl{BzTgi23wa z+DP-v9bGs~lbu+gZi!J`KP@-Kqt9*lc!RfCZtCxJzPaJ}ei6_Ay~_Fv?nTP_|6{op zC`p+VN&doMB2*6d;UpK_&KN6Nus41#Xz|mgd@Y`sFLx-gkPZqIT!OwVN8qJ+&faxZ zK$Rck%#odZ+~t7;jgZ5x3YU}=d?W9=FdgE_lK8@+A7{1thZdKS^`DHbOh3}3e^Y{g z^)v4LF}8O9%h(zOv<!onk1ISUm?0gW%h!U1r$Nl$`*T_^l&mGb&HUXh2xlZ2jYM1( zah*pNE;v0ove!wDN)3dXDeIjoEi-M1S;!n=fH8R;5ID#DvpFC!ANN_}Y9WZbp~?uy z$7^LAJ8P%3Q?!?8BH0Ufr<QkUUvMKwa;L(*Xgg1lzU<^odHn<rM3vbC6DJvm+oEhw z(vsqtB>X1Dj;-~zVJV@I7Dhg-7+ZpcKCX2}pr>qLc6H=Z<u4>wjtjhDY|Z@O)ca!o ziN^kYHJd{N$zBjPzQ4DpFQe|$uDE69OQK+}l4`%rsjC_0&CP)%NOYG<YKAB!EQAsx zH{AqpK8U3yofJM+T*^sd&DCQpyH5QP_q#)TS;8S=KlT{MUkv~V)g(+99|R>0rdVr^ z8Yy)5AVrQG=mo)Ac;1$>077QDG27k5zRL_&=G+4tr+_wsLq@e7lAqBnmq^S*B-NTh ztT(pXI*1J;k4mNZ>e1ZGQ1bFnLii(1q`LlwOfgM9xj$BpVvrR|VZ4tvlEL1bQ#;W( zI@-Z}y^~^DTVAyWBhqgS`DmPLyF`vb-(YMF6A0>NJTN{E#~VZ35w2y`xfLtlVgbF! zycz>ZS#N2;t0FXEt==?_poWT1<L$@U%Z>T!6gIdc<NY%D*2!RHp@Fr6=Zo5qO+<Ks zpg=FsBj~XfLpwe(KY?ix8H(I$tIAGRJG`4|ERo0XEK4)^RV7_O>=%Hc)oC2g5Wy$W zuiGDY8KX-U&yEF9SK8T|-Bx)8iC}vme%vis-Dz!^OsL#r7+^REmtrM#l$0_QAni3= z@mTJyo^k$R5}q)jFR!l3Po1TnI!v@+8v-5)cxT2#6*1by5&;Z?<S|7n*e3;qy+yDk zVTY$3b&!>#Y4i*qS&6lfCv}^W&)}wNO($=7rY8HRX1Sf}I((j^h=d1q3$aa7n}*e0 zPou^@LjO8RwTX<ni3Mhx;@-M^IU`>byqMk4_u8!MNdT+&id1Jm<%x>xkJ=g+Xu9<f zF*E9)$OqIEs0+^qppki6AsjOo{S17qPIl=I0Kxu(pg9X|^b3?-R?I51Bj%@aH2vUw z$r~f#CcgTv?s-qH>F5m!#07T5nv+@i$VM`{<9XmZiIjsxcl>wAbh~P;=L>#ee-Uw3 zOCYU#k7dwXZ8Y7A;0vI^Txj@JP+~76`sp|ZXvWbv!fOX&Ln%`E3pU}Tl#Dh54vquQ zS|oR0kaD<zsGYs&xXM6M`DL5ayL^&oBO_+<eea7Gn=*JU+frD2EuychKl-OxH7W`& z!bCo8upDO_%qg|)8%1*tkv)LJXduz*KAeMZ&y-Uy{YZ$@<uMao0=HUh^W4s*xi_cs z^#&R(zv@GEkzw?D#tIK?x4{ivwESL~N!jRH=QdzFOQ4v{0@5aF--z#CxC$=Wv*KLa zm=r$LV{%`aR$_ZkJ4n>LmT3U3dNjj_sx?25MRa5H22s--XR0JC!KY2V?Lf0b)7dNv zTcZI*F41=jTx>heI1G7jkAH=X@3rQ(HV>)ha8VtV)zC3wq@9Yww)eU_@8#mzuBfhE zPi6pQ1d)-4c+F`%7tK7OUVr);>>V^!H}h*b4e2Y|a1V@En$y|%HdWp|9=PLt>eR&O z)PQ0wU!Y>1&0m&3sjB58?DqlTkT9csc!8!HDGi^+K{x)L!F&Ipa=kPe@wgP!y#KZR z{xNmqMRz%iM`o0D!SkK*x5t<PMI0N}n_4)0n4Vqgg!Sd}ewtn}XPK4h<E^n45UTbC z;R_VuVdkG)RE!+|lvm2k@^33re%J#JKNHoi3su`<G;>maeqZ8InGz-|?2-gUtoLJA zZe~#NOu0e{f4k3{h6zye_+;%8JDavpVqRxF)YX^T{q5z0?f0P@)rbb@G*?K;12uP5 zELpqc!MYNKzWv?~4UZLXcsiSEURQ;{NN}j*r>c{*v1F<|#P4}#ZR>WCg%h_d7Z2^U zNo1!WCbXMsR3AE^)X^?o+gM_1guIj+v=z2ZO~D=T7^XDRZLi<<H$icR^5lD6kF;n$ zG_9ahX`#0$c-D~P(Cmuxm@zBx;E^4|Vx;WQ$rZj1*EtpmC`EsObpd^yGT4Und@nvS zwL|R;TU-1g3db=&u0Cj_WQ%r;-vz@gWP@r_;@@?W3GWF27Q2es`AsY^Z}Hv)Yim_~ z_O+BiIZY;#q!7QYVC$&LlSz%3r@65!Bl0!SIEIql&7lSH>WwjMe=|8Bwy#>k$5?~W zqc+}RWmR2FH%j(CfMq1+sK>mR3Z)qJoYkJ<>zX0Y<=aIjLdlD#%}O-XFD$NmRABw3 z@0gs;cmlOHB>uSOb3kBw4v)=t2{J1ynX}S%W+jY+_?Xbw+%wiQk;mv-iW-<xThYD% zlj760b!xLdiM{M33g@x_pE}UG#>2GgJ!Xes0M*lG=43kp9t?ZwQzWW+jazvKzMR#T zM?LmSzlLroXkn~q)^1*+@j@i^)LeP2G~cM5Nbb)fH9sp~4hHJ6B(KC_#~-lnciA{v z)-&eu;<FG<z`$BAR)a}ft+_HU!AZA6{r#t44Q2WIRBfY)5az_Gg6b-|XsFBVyo)J+ zq<Er!xa>u^smOS<Tj85~OoA>nO#+$N00tx$@lsYmXhD9Zf;_zBZ8dw1KumCI`F>6m z`!XKAvtes+HqkQF3`8;jUqD8UgI=$fFbPKKAe3~*(Lu7=rq6xX2N1g@gj!TKr-=ZF z5UA)S#=SwwYy8-KScKt4L6-=Di&Y{OG2Zh_Ny%-k>Yc&_jh`M9lDgbina1i{fQYmi zSyAsC3|=F=e^Q~;w;q`7R@L8ykXMv6n7mMGIIJa}0a}<o4o>Y#c+TX6c(-KDWz`8X zj68ei=`PIEe1t;Y&V$tC&>7>kl_!=Y=T0<Z17{Wudyit63`VBp%g+4RGpWv3`JP?5 zRe}J0mN}3{pF!4`0<y8*rHvgeU9_7f2;M*R{gT5>6V{ug)cYfS&ME9j_TZ!5R%XEk z4op-FIFb0-CYxP=?$`As3WJH@WRUjY^CgMNpW?_4B)aIt+rKR_a;1CE2;rh3KpDp& zKqa$LARZ@d@!c-&MDn&4t|yjXZ7>Ab1`#wE<CxF{RC*Qs00LM|$&uH4=<@)HK9*%{ zk6V%e-K`5zSxk#$w1gu8pT~**kE-ZYY%ZopeURZw3FKW<y=bM(&Y9d0r4Y7w5Q1o+ z?Ks@NUmQv6992vzeK(CrrtZs2v3*Gt&DvXQkRDw%Rb2?n^~Foy@TV)Nr;ei{3<#$I z(-D>2l#eeH^{!6pq>*G!ZszAk?J&gT1E%8&J5>{X4;fp1QOe;PK5<dm*<TgL>p0$Q zNg~W<4X^p88VB>tGr88a9PN1}G-gm4Q16lUCl73=CXb%Te~>{GFP)(6AU;0#k^=Ok z1GF)`I&yI)%<jtloyAYy!#1SP$4#Hq8vkyqW8jGJB@X(S&9pb?@+xRRaT;@;z*qIu zO<nQDD}gCeT?VqS+2$iJ0wi4|)SC2N$Nh}k0?TnCHsB%K(3G>+_fa#zf=7-G>>{+4 z#PqqQ28z?OU6!W{_M30AQX2HgMZ9%;D>H>9m8SJiN;8MxB7mkePP{lGv=i)~h15R_ zT0eIh9V&5R&<_`T91v98ckXvG--!@(E7&h1hR6-&k^2*d>bCY@&}$4ThuIn)FjXIB z22eRbQJMXq;Cq0KNGNUop+RS&|3CSV|C!9g{{ImbTcx6DlR=N{eWI$i4lOoN7ez-e z?Xf!Vc)qZFOjAV&CgVR$LR6^z{b^|lF<W?1*ab2%a&qr=!sQIV3ItM}H6v-#3?TsD zANl}5&Blk1ZVx9Ugg>I2=AVSchv>?Ske4x7{|E1xactj{hG%k9RGsz0E7KLE?YEIZ z^cKq#L*0dD+a0~V5zT~9IZZT!OWiGQGTZdh{M(VPG6YboEOszGF*0#bgF7F-ax<2% zE_~2#8IL-^IMAqR?lMQKLpRr`KYuKJ*J2J_IzVbKgaPZ|FoTeREjqy?5Dssiq8KbE zBcCV?=bYa{Y`carbTnU~8i|&PNG}<|4+F2GQtIAd-F*@j{TCdisQ|z5@vf+YKC%QK zf5EkH73%dD=6M2zjZoYkIDcRM@_;ILpD*JsIC8KQ`i$G=AlMaQf}1<~9`_!JAc`KG zFgdcRaCa{0G!KF0A+!pw!6pxLlR1C`OWAPck(^Bxt@TDg*WW@k{FgbR$)&El+Kn*T z?@{Bf1Ut$L@hCK)XziZths^v#p*$gOM9d-q(R{u+5j`QA@gtda^|J7M$|-lHMi<hS zwT339!~U>Tk;A`Ue}-s@z7w=7$b>IaPh0Ld>^Y<==EzjalVdx6p)o%?JCl{IcePeO zDI-}dG-y0AchmmG_b11e{G$T}zhR+Ao54O|WNxfW`%66QDnsh&ISKd7uOzl%6r{7E z^DiKgBFkx28Rp}k_35lXu<ovvMNQ)#fnsTA0=Xwl(_0m^$80f_n866YhAFN)4?e_q z%!138L$?INX4GOl9;#T6H!dsl79NY@Wr4hF#^$JXE1Ab(ps}*5#~&n4yv=ih78|ca zqVFx2U&!H!!n+44RhPLf2G*`COvC+s=c9pyQ^1xl>+LN>shSDRC^P1uC>n?~l0G++ zrJH$FL@(q<^Xu=xnvRqBe|cmA*)uAeX^@NvB%!z1o3+4zH_;fUtWggzSg}d@R60>f znl)}YMp~VhpZbsLoknltwl9m*{*D}}>&eA1MDX~8!f4>>aE*%8DL^~$x^6NN;CcSO zUv}|PV<+}s=qr%HI6PkfYFl>9D#Z-9_+v)jlhfkfijpl~RNns^AC=AQpZ=T-{{Tq& zmjdqJ{d)e1ytV27$#Hi14#&FkyLj7Br_vy14P+aPB?VJ9_s8S_`r;uqYj-?%%(?M+ zfzR~Q9r#1!;kE(@q%v(5N_HFA$8nn^Kt|APyUQ4Au<5S?CjK`+qy2(&MZd^%_nkXZ z8aISF<wBClxopPitMgHo#3SM|V~mhEwg+6GHy4H(hYK5WopA#wuNp|JWC|{F$ux@g z4efF*dTwSx^5ekFtL`J_!2d?h%_RGE7_)IXF|?XprZ8i%ByYMb>y0;%&|60>h}63y zXGj83mg)Llr_UQetXu)-pB~mv(fTja?SED>R%YgZ`(aHbYRBZ$BM0AnqD)P~YN>4i z6>0qqnjoD<=RYtu7DO+l3Jc#GF#P^R<tIzOo=n%at6Arpam#V|`;31Jj8AW#cK{V8 zZ#`kOc<xpeU6lsFWU7V?Yy&9;f>Gql2vR2Qi{^(`)C1+rA-lv%AT_siv%M0*9YP$) z2g{&9%Aae6E@$G@iBsc-!Y$UXKhWY9J2IvcFBYxNfM}{`xp-Cv<|J4#e*s@%6$!6E zSgl`qc@S%oMPB-hp{2ZjgRI!CBpp=ZiFFT^pM1573<#}}II9stUwYw$5p&0?g(grS z9keVM*VVTqh@pc!h^_&agd12p@REO8*&w;hk9qQ&?jTZjzaHn;fv%U;DkCiG$9k@- z;w-0#J1j(cKb4b*BNR<TwLAPF|B?=yYy>@>LUxwZOV>moAZfc)6C-T#tYNWf6WAQX z3KhYyI<+f8biPC~G@8C3!r8?Rgl=rI$@tWxZEUI(ByjfMejtz})Z2qAg{9bdF*mp> zgnf{2$-5Tz(GRaeeG-U_WY`1+)~Q!20mF%m<QWwK-ap6O<MD)Dt_FA><z9{f#t@C+ zme_%1lo0V3SBBnN8wQTsc{@tWH*h6iy6i501?5wJpHAbfw4fa_8o8n7_<RhIe&d9a z0u!`=lqJ6FWR8UeoR(4@@YzRW=|5ujpmB(P`?R7;rNRhWpbIXPE#kO8U@Lf_!#c>} zjM1Am#29hLvkqAPt->!8Re#uy<yEf$j6NaTK)@&R;nvh*5VjehPwjZY%p(iF9_-Th z+y?2xn7L-*l!X}xI^mW!-tIC!fh;_6-12~(MjG5}+s5kuJm!>remFUJZ-whxrc39F zS@?&ynvv!Ilpy_2Gh#Nj|C$jqGqe4>CE{QFX089=H}4v}_aDV#Ps7vy%!sX_8-3$m z^Q!b9UK$Yg#e#{!$9irsuD6>|CK!q;{n3MYeuVhAa3M@4v?&G>wCvFoT=S+t9ZL0( zLw2Z0gDCPyi)Q9DOY))1i2+22788f$Nu*%~S{E3^PJ?S;6Q_L|1PtzphE|cd!Wx>6 z#0U_n1c~SMDlqwm(x+vcjqwGT8nTTmmP~3P8V#^#`eIcj0tyz0XcQW<e4)h44ajJU zwV)@bzD0Y&D+(K}r+MZ!>e^6Bmci$UkeWNY3Wy$>qa<p5g{Sec>OcVT_8CMSmU8%I z6Aba<e8ve5g8&?HO_2Qio+8qvuv}k#cqT~4o0lYWM%K^qAZ2UNl4C=cK_yz2m*Ff% z3?3AXg=-VTv$1tx6tVUeNEt)VZM#-h9cDj3-3qe+v;kugu_cu%*TZI7hhJv6ejKZp zFcck#lzMPRs`{4hLrK_{<UuF44VEOYa*aGJCiN^!zN93~Yg{zJki8OC9tudr)>f%` zDjY<)aj}{+5aLxPP6B0Sdq>;9EbI^sERe*GL2fa`7u`w4Hj{H@81ZfEThus{eNn{C zL|Xh%wkM9M%o_v<OAI5#Q*{!WTZYOwfUw~N%%t}l<rpEYf;2UqC<(Iqa0o6(q+`p= z`p_B`SSUCur;Kv}%G9umtC82%>nqw|MK8_!7GuLJ`l~`(H3G7EJe-?7-X=DNuDUxr zJKK3Syk4w3t!BPETR-+JUzV1hI<<PB*dO<vu5UVgF1x*juYP{MV%%z16<QOO@|(K5 zCC)Uug9%8K=w@8(cAUv>+j6mfX{kt2wSI|upP0IO>Ns=8Oul${h``%fdU!Z0Il6!L zL?7WCV?LBWPzx>Q4(2RYwukH#%l<y^e%*)hkqu1`kiGRII!EjrACOByR|z{PU0@#q z&0vBHQZF980KqyT<C9+6FvgW1IWL+Y(2Y1}lwIIN(fw11?>*&|YM_1`G@v8{!9^;I zT0W?mdvppcBYM1FH}>Lh&G+=Kr~!u>0V?0_&h>zRDu|`;^rXdmQ~bX;d*>L@o;GW= zZQHhO+qP}nwr$&ePP_ZGt<$z`+kN|;neWa_^2>MM++?RxyLRfYT~AeIt@S+1J3F@r zw+tWc<NK4zpntxPnPcdOg;Vhn@Hq*6-W|3h2q*oE80ZJbNWeBFg<Q&sz9_iFrO4am zT3jKYHjVl#m{!<#3A~S=umWqx{92H()Y~LR+`!9TX{-rsF-C;ZI8Yf*s%dXB<j34S zJUJh8d=~v6;&KKdS-z+%{0RFQDkPNg?x)b)_4fz5;wrUAC>V%&$@PT0{Z{8!Nkd2( z4XGEX^O>^T0Vqh3JSPYZ(-UQIo5x^<++oOHFx^unv%h+RIvpv3U7e1le1{cyAEok~ zhW5-Wruj@nV8LeYl*A>ySnbN3<R!gw+XX4Uqq$|w`D`6t;;*lZhqlg##}(*F0o5&b z)6s|wn|VcD*3IF(hQ@{Mynz<N%s6?y@i!uukjfW&I{LEPv>b|d&wJU&cF#_)uS;Fs z-V*vS-`Z1d`oNHK@3DzmzrWnj?CZ94<tP5;0k*dI)7}r=EG|yh;p*32#4=cu)uSHY z4LQUL#^9do^@s*wPi{v+1TR`eboDksc0fK7r2K+xg4BL)aHaQt@8naR6jTy%C0tpE zi7lu}E9~<@-Z;L0*t=ZJ-hJD9N`Ib|Af3}d%Tsr-afkv%&7iXs%@o`3FNaBAExrma zC&g(qS<Dd!gy^`o_5*R!bHW*BnqeUq1H*L^O=JbB)ex90Cl}9I1s8z=0z^$AqA23I z{~V3C$PXek4I&=EW)BOAT2Q9(M+<WaaW|0Yy7B887)jw<hJwOf4nWECltq4UoTHd- zDhh~_?-f*}q%0`LdsIs<iy|fQJVBBhOEJ&}b^<^v_NbP`hr9p=!<r{D6mSgbut;Gn zEltZD&r+J>$@xMNO~H85wc-|ysPF#u5m<hLAXKZAtOk26TrpIhv1cyp$^7y1^w;U< z(5j-CYCGbQ+fN8f0Qy@4>dJR)`nMduAS!^;Gddr&;yzeW8N(E!rYPc_&`P5MhKHUR zh+LispHamj*e~p@@NSqGw2%3LidjRVyb2MmjPH=>pmLDU6pSBMhbz?)uhNamoMxKO z@R2gOHn`7)D!6ug`teFp4zn-rXGH}mE1%-5G6nkTo-2`+%r2Z`rX*d9$n0SD|BfHu zDy?>}ywJ^h2T^GWi?6IXyDn>Jm{r-dsIp^GWzVX@mgTLf_kHArFhxFSf@vuYR9Z1- zLW_u^GQ*J-3w(|gX^GdB7c9l#(Nf}7svN!z`p~RcK->zHdhGv$eHlN-XPq0)a4sWd zpuEpDMexh?hnF>;JV#z(4<KGA1$&YHB~4*OpM}>FFh57Zh5@c2R@|@|!V9+K{f7uI zVUj1Y07O%5k;MY@n4?BmFx1rxDV3xsY;XTmatCD4e`S}Gf#L?P-YpCshRR9A<*gHO zn{IyS=4e!u46n>`k|#z`Lt}vCJgBOUW`0x{rrca1k*Ffy28F7>g77{#Fy1nk5}pYa zVU0DO!W8&aN3i&gLGFC471yD<Of2_rw5XsjpW!v|f_FEol`lZ@yTa?}!RUIfS~^ok zS1ZkWISl_e<rC$AGS7&f=@j3>LM4oG`Aj4xYGo_TYH3cwgV32O7(LZ9Qjd2^;w)k> z7o)gH>|hr$xk|>ICD#G!bo+eb&QRsE^1l6DqdZf?pN-4kA2gs}5&5gO*Vl*UuJ3so z@FIWf%HV-)g?K2RxlBx}gRQ*$htzg>DI~sVYK|eUd%e7NKdJb7<fl_S0bg~OI_e_T zaLFL4CrWrqCH7A(<;ULbuT&P-YyAa31Y_@eQFD@>DVW4~_o9Bk#K_!n=-}(LP|o*5 z6T8Eoa}-5kloK8qRuaQT&z$!3DLrwHGJ-nUJPW~32BK~Lao)i_oIdRJPL1r`P*2$| z*Ri@Gbt-rIeT`YFjEVDHY!B>v`_xKwQEq)GKB66kKcWp4AJvM#7E)n9f89D(te!kS zQa$$I-5CDqVUbT1!Cq(+WD{i9pJurCACJ*SNE77xs3SI~9r1|mL0c?NYvMec)0&vv z`lux~r!8^0?Lkv)&H*KoE|~&nOa6>!4r+Sr$^7v|r{~M*-qFX$o>P}s(0Vq&7V;%~ z0)?2+kTa<3`^V#`2P43|{5=EjkZ-uhyQ?+~C}^TCHA)Wj*&vH9>@xd=mt#8*U;}VZ zT*z9%74>G^cFkqrrjP&cExP-!4cnD3cx3Yyk$<=VvM~M63*i3&XjuR2en;^CtwH~r zB`?3ufDwNEijwAL32zdY%W*nuyJ?h0rn`rNK@dF)Lnt^)Ru*f|&uu$`Kcp#G)g@ht z#qRaiIYoaPP1pv8Ak$TN!zbqegyb&(0k(%7QJ9Yav<G-62{4G1^N4VvA3+?jNQi^< z*mX2N_SbfkU%+t=dt3jrvsxWK9iIJ}ns>pt|NRQoiUg!@o0%*!zW_mJ)6*OsfoAbH zalsUaL~p&>0WJjbg*c(wwY}h}@6%2g5?{IKv}N)NIU*P%q)*!ruQ-JjMT<VLIk=*T z7k=6!XNZNWJ)Bhw{xbGx5$4hdR>w{$&f#jvbMTgm+TqRP>cg+T33x&dhy;A{cf$-- z@`j2AHn^3kz^7rtmzdO`sUxzY-j+;rks6btSjg2Dma%BW<YHmIbYVH^F(xh<O>C@| zT5FvHXHLBors)z23pF_n!qgrX+X3j@o!QqokHpJ<HV+@Q%P{er6=U)s^Lwd_VT^T^ zieufeo(gGV`D#tIZo;{sPaxD+$5WoEtcivl8e|m*Ro*;Vr(@5uLKw|>+lj(rd8bJw zud4Gyo_al`+VZCRlr^DB6a&pl^F%>Z$HKG7@tO%QB3$KeV-2#FTv-n)lmx0mAQ^d5 z?Ft8qT>eBW7Ts~8;>r>z1zaT2tuvZ{mUGXFytbo{kWy^lT9v?JrMkX?(<+!6^LJ{x zdsj?@@^PTzh8afn@P<)K)<i{2$0`_C%IMr8!{UZPOG?M|hCpT0LP^XZxzteH@r3o4 z_?Yno<2pFg6-(Ag#mw~=a^3NbVSgKyBet)7I@6_neSTWF#WfSH164M)YLq^7og6nF zZX)&8Ahby}KK18dwpc4i8VhT6G;U1{2(_q3CMh}1VJND*B_iW<_XxIzx~bob+M#x1 z-Hp!SPtXtgE>~G`kMG>>@4-rkN{ypArYmlLVQL3wS~8CEMbA>>a$7H0rmlD?jMh`+ z{#s_iTT)F7NMVpE*<hb<OGG~MAT=RmhosDSre8ryKEoHjALW1<o$VG(C>ZdzvL<TI zObptsuOSR|-#v!K!mit*4~jEFK8l4gKz&j`E$Zi2FthczXw{$Lr^7!wb^YD5#_!wO zcbgE!AK1DcIsXy_@P0gF-NV1IIvDteP-SKL2PTb^@!v-vhO)H(6{=y^@6<GxWnBau zQ@_*69ECEnLDqK(1kj2D2?6H~)`olXlT#vtu@|D(&~1syUGaLhkC(wQgRlVv`BssW zHz%V7FD3_OfcLOOW+Dd=M4S&o=n$kG*dB4+TY`%`I&94C7(RWy7x^yf=)=#+kKY}b z|8!Z0Q!nXF>u}iOuZLH=xe>wzTzktQc%G&DhK^oJk&DRq$?2#<1ipWFIbIBof~!9# zH$p?CooxXI#IeWs<$sNN?|@e^^;BQL-Hh#m)U5&Ow?cN=DdTV&?gUb};J(aNIEMt~ z?H$_h*pNf?pQf97!x4H}sIzmojAWydoa3LbW$YCPO_WeI8Xd_wM_SX3N$TE)B|a~@ zP5;?iSAuZUIS{#hvS12B7by$bQ>IO*2N%)?HVQ!|TohO65(%`7Op0QQc7mZ~p;L0@ z8Ai@btFWQK1&)#hzBHzT$IhWDg`%C^a2ajumFYZ4sx}syX_5j~PM7f_SZ<Oikr^Qs zDkD9MSb{!Sja-o;DlxsgG;t$O!lU?w*r*sOq^(&p5?SMwSZ*41>6wUUVK*DyB!btJ zD(Z!^Jd7bN2VzKChEyJz29*h?Ev}l9uYmb{8J0X<Imykgw~$iN+3)=pnQgxDM_uCl zI4RHZUX8lMOC!y~Gv<%`^uTlV6y35C=Cgh3f)WDVL6OvBV75JO<e|3`;G+R>szKWU zrXg1WfE}+Bejvv5+~XK-8yd^FXKtNr34kU7<uR{(808|9r<w{9xpklqwZN*x3edi> zWM%g=HLa|TOO*-@)>xJjIFM}BoFl}XXLGM<NBOosGcAl9lF&#*f@RT1imI_d-f70H z7Fl`ZR)O#Q8AXQiM=DEmOL}&i87sH320|v9xM&r=rtmyfsi+<VYh#&}tBUcIshUEe zdGy6YTg^71>@U7rqxrxK?oE#QjS>YbT+I|$Vy^u(N<<Pw)b-xJRvA_VNwu3Il_5*H z7cjfHm|oZ9WJN9$<&KU*o%q95l-iLbS5Zdl!AjSW<$Xn^BP0J{K!XW~O*CmasiLqz zE97tS_0~AWn$ajNYLdBYKvG!rMWH()dd6lxBp;KHPX5WuC=P%pZA)=4(9KrikgFE~ z1Wu`0SUC7joB#-1l+dqgU<ALNkh5}o?=8Nj`1GE&Lx=9&b(p@>dxzYw3{Qu*=U20q zd0bBq5BV2(KJ9kNe~5ABA7tgfQO5rZ9>d7M^xuFC3p4A#E!uC^)~=>wck<=$DZ)=q z-=dN%tpZ|ZK+gd|Vqm^!h-3_|iyYfQ_JK_H&sXh=ZyA9vbl+iF*?Rl%)z#IdQmrMe zJreN>2}WKO6lI9mm5B5e01rP1_CO)TFA+|DBfv)yx<$knN%B>Jlj3}nfHQ)^XHa7I z(gnQF`iw$}!x*iXa1l{r&)Gv%X2UNfX437M5T`kN4rf<f&6PQn2;7(;0q2o#6Q8<a zr<U2BFgYC!lcyY*J(*5g^d0vhiL*nOBk9H?pHGb1rrxJa3OR@KIuP*_Z6G#(EFaw+ zC4E;$@u^OC2i?wkQ-+`;exlYhK2QU}Z+t@y0;jl8_efyTQzz&!TSh$$0QQ4VEcR$) zm@78<Q}?SlWl!CL0|BZBXg8?X51uDY;dYx)VsE#f0>6Lv4HsYO;7ykkq%q990tYLI z8*=#u1J9mS=G1hxKak)ZRV=)F3tjH)+!s;3d4hT(T=CYEk#CY5yVwb%Kh8S?M{Om4 z;DMow$j&XJkH<WtT;R(!3?HQqXTl*vD2yC~3<f$Ho_7R=IhZhs21BP8K~qfS1UO8B z`EIZu!BcFtZX&?~B3fUp4clpuo_K>+&v7C{N2sn1KID(6JQa*%>u4K!SerJ@GKx_Z zr4`c#tfn|6NDrtQ3~AB?-BlWoYJ%_=Fr1&UK3*iR@$C%;ntW8uw?Z7=-<XlI3&%c$ zE0d?x@N0&Y!M5zT8J|bfNlM3?jqwZ>lQmcNNh)2!-kEf4Zza!hMCoq2f!Nhidf}5q zlf869tIENPbVIw!9YcPf+oAAu{;z5Ozx#*F+rH1YBk=V8FO{DjzF)`oJ@3=-^gXXH zpBdZ!xC&(b?DXF+ck=W-pILSA_<DZ)@9`tc5X+|%Jc^u%i5agV0PrZ`%AC9AJ$ygV zjK}N1?HxS+_sgxv>*lR{@z--J|A*%H{<JC>S((-0uazb?R7z`FtT8Ly#P6?{#d^M- z{OJ=jiE{Jr?0gh?lh@dMGE=qKt{OdS{7T8VXypnOa|}{nKmOv-<j#gtA1Wu-tX=xe zA?8yZ4Uf4$gc-F)P#t0mfjPo|<zFbBkmkPs%F~vw<mQi#YA8gu)hU*yBp%T?O2ylz z3GM^(OY>2-<@=DKBvG8Av^zRK1~xDDN7(qz?Il?}saT!i3>1KGm~a6vxyPJYLbeW2 zuG)Rnv;akAh9#2oS%@n_);g=6Q50MP@+aq2Eb_~Hrzsb0y^J->r_^9!bDc6B1|rdw zXq*m@=74{QU_uE%+WYO*hy3w`Hy+n0hKUB`^?E=nen>Do^94JDe~Dy5nE~E9;+@lM z+DI)mX$+?UFtn~*<m4Ehr4ChGH2V1PLmF3rh+COEXM*wqD&KgCgj2bLiMBCncZbb% z2EDs+T1#wzf2s5V3hW$8j+st+9hP@d!#r8B5UxJ&2QJcSQZk1YDdbPcC%J7BvNw%n z$vc^Kca?N*P06;xrZ!8dELy8n1}3TI<k=x#hr9t-@a1w51Lu`)JHKL_it#AZDFt)` zl#azxMLdjK%EUVnOPR2Y6OzF7?Y(pY^4OMrzu*d!Q3dv~W`royvmT5B=l*eH^xPR% zmZj$h6buBHr*oHW3^#Cq+KN-rzUCe2mkz|`MzGR`Z;Lz~)^hL)b>R91OTJBNZd)A3 zhh~)!T1Kd9Y)0d?u(f&zoB`*HdsT>GisJ5;L_oeR`-XC}m3lrz(fQ6IAe0c^7dQie zry(4MmNMQPmO{VgY}TmFE{qkJxqwE%hK?;8bSh$1l*Km_l`=#5dM2Rpd&k>6?a#1X z<06NXcu^Chqh>3VLB5HFUBzww_C!%Y=GOA%Ao(owy{@|X@0BwKhw~Pdqh25R2WRF3 z(*u2yqwBc(Rd$yC+xPuL`R_M-a40+vMh=!-Ft*1{dH>f5_V43(QXPIYzzkq~pXGQ= zTxi&x#&0%f9%sMfctIWconQK2FB9?GpB|x)(%T-04%_Dq^wKxB2{)(8AgxIcZ@6?m zuV?S^pYX`cZk;}lf9T`W`KNlmJbdmaNM5SG-al^cv{&-CKVO0yclMUwb-r(I%dg)* zc2gDfzpwR=URu76_Vwebc>yq{DKZjbSRO?mR6p^=;NptvdwQ5Iz&F0vRvcUFd~=rt z;qt*u{Z*gT8+wq|g4@6?;qUNn@KSgacvsR)wU=x)TTM5AQm_AaXFbhUyTx|3#q@u4 zE|X2Sn_pQ9cq6<Mo(Qf1uLW0uSAjQ!Z8KX;*U~Jt%l=o#tNG*aF)d3!6v-=d34%)A zk8kA~2HMg^KhqgY6qY((AsPxoU(&}1s3L%G5webb(CVkz!xgs-;M*cq6#h=zPNfl0 z3dY751^vw*@GMrV!P9ddPzJmd0>CFouVpYnW5ho>LIPr8NkM^URcZ}P2<zYlB?YqR z+niv`#s`G}?*OP<w!H-(7{&DQf@;*N=heoF$17fu=YT4NaDGyEU3Mr!+y_AX?lCmz zmarG=tr)hJn6T4WM+*gAEWQT7Wd#P{3)~B$E;fVA9(h}g4eb%AztqtKbQ5W4GYsa0 zV{B)bdx?zlPVbnDa?k(>sND<PH6$S`c#ayxb^}2OX7ju*XzQPP;bZ`b3{!Y&)~WME zFG{qlkkuI#F@bGe$8!|L<B`A(NHIkG3HSju<!_TwC*1|1sY`P#$lPyrp!w%GNPe*> zIJ)I2V-~^$NAc~DpCxccGB_|kZ1kUkFt$aT1GQf2&dx~-meJ|<J|vNYMmu}}@+0Sh ztN`8wznR=%&(LlzmQKasKep5?1EM8iNsHJ^?Zovz34GGX*#>eV&8C)<o?+TCzU5em za?0@(hORWZSFQ@7C5*5v0dq5uG8}Oh*_SaheUN~sxw}TXETl<^xE3T@ngt9dv>oPA zWi0}`M*fATI^pUy80HfCo^(@BpPLC<TvpQz?MQT92YW*%lA`iD2KKWO&==Pg`VR4b zfe90H*A{Iu0RgW6iyYc`!-S{%>n(a|{50@wOmqt3;Tl}^2;5IYKJDsk&PEnHwx}SH z6&15oq-;jn5Gc*d06vT}-)|DU!>tJScfRq)m2n*82@k4t7j=Dt*~NyisO%zxw_mUH z3`2?)f<yrc|A!e@U+oo!XZk`q$vElbu)$$*xT+XN;j|+DiC7Gki9rhFS7pbXpyH){ zwNk{IB>+_am=-{mmvk)B4CL8d7W~U;d8NQeg;)7K(bN8dL-<(;wFEdumQkVkAZsiU zqk0;{`2qOTD&`^uYQ0nhF)=UYYud=>tCXGctd{`Kc|dmYGOKp~0Xv)I&mn*p<jJQq z)lZm1@#GF_IT<#Yqlze?*ZyGTx)?(r=HgjEV4A2b(2J}zhr>{r^XjJD)=^VHdsLNK zr2^d`G6;3XQ!K!{V-A==-fomRB)F*ypCvrIVq3@zmR0&-iMVS6;M~RI__pt@H~T2W zoifB8dG#wt!P<zrMX7TznD94i7K{o0?i26`0Ox8ZXHOUtaL>Fh>0H_#k?kCI78(av z>68}t()KSM{0foRw`{*SQz~<*R`O(OaYz<`=y!&y3|pNQ6_v5xO}v}r4~bAcV@zD) zO;^e5t*D{N0bWrO#9q<W`-M<`cmr7ltjXKy!V-t54b`HJ-zLK;H3AqX90omzi#$V~ zl1g|Gq*yPfYgF*0QV*7H;?$JDos|7*WZeBYweP=60*dKHPknmDcas}ChnOf0-Y+4w zYNO}J8-qfp)&%K)P(c^jfZbOBXdqFJA@(KS6re%8OSIqa027cNKjx5aq=fqBM~xOI z4*+CR6+Cq2KG3At8Hc*6@rCht&=IC1J%x{yrD(nEr_kS?L}`!_yd}#TM|<FCKl$4L zjD6HJ3!G;7i56noIFhqOX}mkeAX@I<ZZyh#!CR_DBnzP3OQf{z0p+kN(*XXt>Qmru zh&ie0%frD(Ze{C@ABU#kz3eb{u<aCN%t+IAwsoBO30E2RZR^v8E)kg5REPmxk!rGI zLU9Jtj)QY%0#0%T?cfku)LTK}C?L8zbv8ay-KxEXNUY5;3512T3e0Q{g{vPq1vI`w zmFZI!6rw{@2jHDhLSycS5M7E<0n%{*c_0`pigbYMB}rsAALJ=s0cSr>s!gLq;7D>E zyn%4c^xHnC%w)Y2L&d)o?NGp1spJpJrMHmA6)EeJXw#54@2(6YCZM(^g{{G6@P1D+ z3vqj4cGB<=E>2{a*EqWl73+bE9J)ap7F@;5^$l~B%ixOEI17%DAQ05aOF$V9^2|2_ zVo#QO(FwE_CsAB$Y!)QdDLlIa3V0BYJqUj(-UEZ%G8%lo1QrAoy@xTbV%oujOc*Id zVyefoLZepOq5^@A*8+L-5iJgE-)Nl)yHx6N?q3EPob+N;Wmsi9TgFZdIWR#q(W@ns zmv{kOUF8GfymJF&d}|L`XLp5bYU;EW123>2VNsdsJ5`S5DV!0;V45=b5OFC5Jg?vP z>J(kWqDj}5RcM^Bg$<ch$U)^igeb{RM=ZgCIVVx$Lj(AvXw#`Qr6rQo82ko3JGoQ@ znePcW%TwSp<NJKX5zjvf{=yoNY&{O_X15_ovLxwGMQoD`RpfD{qkD)@fxo{z4n(BT z{Md~3C|kc5z&<jcXQ_^nY%nr^0Dn128ePnbARkX4%+WZ!IAdy?$g*Q+bH>XWQ9zKv zlNJb4oR(t5hUC1BQH!Tz0q1wVdv=xU;)N4|*1DlIoGtE}&|of@2IdVU0vtFaHtHG# zz&{gOc8YxL*Nt7q5)uqnVQ>Z{7;6VanA~V&vsJ>MJ$s$t4{$B-*$;-ovX2KEfp9jd zq(<u3;AE2?cxE?7J*SzreEbMmL&d*FJU67B5MXLybpl^3K~s|~KAft$Oh+<TZ+x}( zxkftwjLrJ%{*w*V&KK_&t8Z%BGgI$4_nrQ)zNde+{(b9+9;uw8bm?B2)DUgzTx;Kw zj4i0<7F0tgs);A{=$%@^VJ*RgwqROo5RLsmeHhjj{Qvnh(Ow7K!*TpaGh)kWH{qxq zx9+r&w%?M|a@a&$Zu_cy$6Klo{5gQ!Bi{`ck)?pj@*37gf*GbX3*8A1s;C7&zWn3E zz0ZAUZQ=D56!*xMJ%#9nJ?NQvotydrg0phh4AF9Zo!q6|O@^qWNk!edP$MS13|b@; zDuyj@6W%kntN<+RS?@y|mntS6?b@wmx~LYY7ocAwI<o|RXsvkvh`0NGVEtw1P^#ey z&{(JOVH$A=TQot{eCK@EToF(ixkafj&64JAMm%K|5MN8B<QjA#FAhCDwoHeKeD?4& z7vu>h4&EjqIC!bf2KUl=cm=rpqrm498O|r)$5sNQSv`|>fwe>uuGW=d11XJAGC#TA zmf(f&RZDJm+YeB|wbDo-tuH_~>@f7S{!#LEjT+@=Vr>jihdu70F4SI@IIY^+2_=o3 z{6*F$jlMT%@O5&%Y|W!6K#fjx93U2GL7-EhR8<$B;_>!@H8=k@ss6yYT5K-XIOb7T zZO9?A!n3ixR3Lsz{pE*Gy3gOC)aFOlEYJ}7;sqktgQgsqn%f+oOWJ?UQ?9w4gWjRL zR{^aAOQzEhrU2rZUw3@|2I?r|YyAhzg^m56a8<T{Uj{dnHQ_Y>qwIS2g!=nS5{<Fr zrNe-5y@6Q4)|j&}H|<scTM844P8rO@+oU`Yi6m>1WQlC-g~<1N)<2GP2tfxJ;!bfR zCeMrnq!9U)5AZKHf&lr0FM`O*EuuwT?<>as*!dAB!5NC9udBX4%b(Y_92rN1xOw^X zZM*d9KkV-8`D&Y`#7i;VF$o<=Ko5V07+i!df+p5yU#%hP7TS*mnlVCmy!{Vp9eDRV z=oEYSfjGT5gPv1v2x<K!u)*T45fNTS1F<)tW4iK;oUu9bz4G||oSHiW5bD#O$+=tV zm!A_{{Wa^u=-O<O8%AG1V(-&(**YtZWV0KC7Ml!hS<#c4gHS!0*RLw90SkNLg&0Iv zB1aux4l)l!)mn-sJ?H2&XgxJgeih`MRVa+bsME@8&fdf{YGKo2_ere=k=Ljm%T?Gs z7_4kjkQK@3on%D7l4X5`kK)d#I%Bpz`rtbk7dtX&MK`t-jX^I_a6@{vWVbu+v=w?I z&<rgk6M}{g)P@bC&jhDm+w<M4d<vaQZQ{=3`aju}1GtQJUMa5QauuPnY5ksq0$+^U z#nYPY8|p}at5VzE4shBJJREjABm<t1r6H?>c1N|gxtI5jClBL#XA!20Sa3mn-*iE& zK9dfzU=IDf>6@8;qL~lmSlM_0AlSktxWhpK2|xQry#C;BP!{U9)AEPmuD(^R4i=0~ zE$k6&aHnO*)3CEqw`2OHqdjC*`{XcW6+Xye_j|3c>L(`Rz0Gfo4zIshxI(fYH(^u% zxbj()&bgawz~DO6RxFX$Dy`Qq+_4?0v@|6h1}$b%=tH&`^iS<6!lx-%nv08sCzG-M z6omLGDvQnpkch?3jZKI}q)4VRcu%urCm6z(K$T@yir`f=3Z^*DEF6H)v{Tf;(5o@l zFo%I{GsOFmf({Lwn2J(;);2fShSsUP$i%$k!4_0JUP#H)jf<C+c3)N<;Z@Z;7u-x& zN;xgWE#FYWQwby3pj4WyBtf<?po&jsV=9$0H+VuCLj#keU}*IMc`j2IpPbqttC@=B z5kZ>w`cukSM_a%gj9@w_-eW1<?lVD?a+Al}jEsO<_0PM)SpMmEG^v^mN$HZ%U|49$ z0vy_H{40Dhm|558F{gb6M`pgzr-|E1^9&m5oU-UZ+&UV{(sV=NrUD}G;x^(!*YrN9 zT*R|yw)uTs;`L6i`=45&WoO)J=f&3jYBcY@SEuHWw<9~x<}FVz?mmYP=li_bklx$) z{N-fIp#4KD>|69taPwdPur;v$5TXAj9Lvn||LWsdnA!hrXVork-FVUw+aC|8+4wPO z`QM{PzXAFJYy~9&z!6AzSI|I;`H%^R?S5%tPW4P1PCwLqE<7801#aecG;UrvN7oDt zP`M@bYp*1stV;X^w=`D6-^uUg8_hPm3$z^`0yiy2xcR0GiKU2+w;)FQ*=8t0@917H zOE_Pz4YopjQ(7=i+T>a#R((=hN1aw0Y00?isI^t@&nawX2kQrHaYpNl+ZbW?FxxUX zMZa@xaw=XRwgvy@M@O$FtrvGnMuhXOhg`JP+4NHyqYRKyzTvisG`-+5+8IfChz*V) ze8xr8OC7cWqc^^>$HPV73J&_4$Uuq(So7sWwp#A&C;hT~z?7BAc7mI3rJUTsoXj}f zQDca-I-53FZ`!FQQ`Mk6`krVwJU-{JUCpaKF$;|6zB6Owpn4fy*(?JHp$y<h;p>N8 z^+#uCeunvFOWJ0R(wZtUf@?{g6CLkDEg8psr^bZqzM?i6#~sHZ5m4ZOWatGe9|#F` zF<;*+N7(L;;#ZU~Cflcoa`74z@&Y-HP7%h4H_Q}fb0j>#K>BEStKqC~fW_DZv`z6L z%1F|K1{VzI9==BvrL#e&BZjEq8&N)Vp{JxHIvZu&Yra<yuFDfk{EpLWKd9q_w8ODi zf+=qte>drets}0pfef{s2;v^v&r34vTi6yQvVjQ&o>($~{X(BK`7=>As-AeryarQW zg31GHZ?XrQC@=}6N6kmE^uleIMoJSWc*n9bfgd9uQtr;PSBl8TwiS9AaT3SvmPNL^ zNF}OX+VPJA9^vrapZadE=ZAss&+CmmzxS`taQW-J?(b$_F23*G<LB@Dt5bJ;zPQ)h z5r7s5e%{abd4HbIFL5ruPVYCnC;9bw6jya{14DQQJm*zL^cS5cnV56GKfaHPPY<6@ z5BB(eFTZ$wyFMo>{NG>Gdsh6vOT!A8YGXL}af(GTgZ#(D%KN*<d+d5%|8jqL3g=|G zE5J~QJ|9pMoa<%KIZXB1whUEPG%>_fr2aaCVufqdw(rd}K?fE!!h4KBTcy<PJ+NrQ zn@#hgR5mb=P(mKUk*`U_Hh{WZUF|x-yA!PE)_4IjuYrXNf94G1R0AuAv1F1)Z6<mI z%b9%wQu2V6Z{gMKcJj_7#x_euNNb;}sZ=gkRnD6mz~zvH_ZfBOj=+XAZ!J(~$acXs zl_hbWBxGz;5y(<RrLKO)HUJCDPRyXZ6t^SW5>A26aTU`OwFZuyMzYo%byQ0u?ET$# zap@Rjv3oSlAiPqnlc;3HqK?J+w@d}v73A!!znSzZb{v+$dCS>R2`JKN)_C_?qYa%y zTMBoqMwm#TR}l1X5J(wu=n`kBBe2|~CkQ2K4c=%4&HJHNzNh9h59I8s^0hOqglq+w zO!ecEoj~RuUZPJSzPpKELD{BMdoN{ES|Axl(C?!pGuyQ&v(Y#tt2SWrbX}weYnVUM zj))G(x{gX=2`!lFVI_sXmo&s2(-sS5rCMBpr}oKF+#|S|5`SIY?0`-xA*Qb)MOcb} zPR;CT7!oe5!;o$QAme}-2|CQ-`EU_mQ|gvZvT7eHW|Nqd&Oq&N{~{PCthmErSLg&; z%eTgwBr{N2aqiwDv4DjuxT|YFZfAO-EM0^y0ywB-SKvu`iHqP`>M(bs^Q0%$+l{F< z5)#fbVVou?Ah(UUnk8Q1+YVqZ-;73u^MvotqPe_{;<AiU0XeOJi+IjZ3n99;j1>G6 z3}hEj={S8>V)6%_HD{mhHY&x5a!zb#Yl6aem?;}nhKfGaiL3*VT%rOa1Ze}-Hf9g& zO}S2jFECC`Y!e3|!+{MdW0q?WXK*v)6Kr=31~;AwEp@Z5?pV})o?6X{4O~YSZLr|Y z(?kq&qriX=LcL8e&><vFJT__#&K2AMn&|_TGB)ncQ-cN(Gtxxysv`aOM&G0JBDVoj z-`|^#0bq-Y7l$FqWGSqTtjC1}F771H*pzgU1fQ(iOGPepO(!|3ov9F3cwD4<4oj-q zIGS#cq6p~#Opq}rB9tX6(v5)mPAsR+owA(xe1!vaj@|R7CK3b%0ND~Yb4uu;^{5@W zuD)}|d$^%CQIsJo4H>lOq&f-814zr9_Zo_DA$`CDJg`$H6x=4e9gl;y&F5#LC|6!K z%znAos1z$x3gUC9SG~drPtBN$gWmy7aX!I(VmsHFg((WQLe%z*hq#{iRaWXi%1)TS zog&vXhixi?1Rt-SuqF6{LZza>Ez!1pQ6XL@HbIj?Px~^YaxGmz0W~n36*5xJaK|Wy zA^5#BPY+3tk_!)Bt0rkcbQf8belM*dB-#KEA*zE;ufvYv9yBx(R_>Qy5AV&+5UF>X z1cxfiJEJU2p(vmkTZY0Mf}m-zTX0dmc;0Xm^ChMPT~!d(EqM#fDhi%Nl9#o($QpV{ zZe$%O*zJ%qNqA1DY4E3^v;{s#{oH_>GJ_7zvTG2;S&J7+0#f4_O4wC!ApYVS!K}$C zAfon$rNFB<sT729n}9!<XHhTmWO@k`QMsnju+NZ_20z^hF<+A6k1%^jsyCI`4r-*) zMZAVdVR*rf(-CBvLCm=fFcC@q!LX40o#O+}Uy9rF2WlG0#O+GeRx-RGpSdK*iXbg2 zp$m{)cmjMTNr-Ih_j3<1SlyoUQW`Yv5Ih1|g&tCqZZHtwhwBIv5G<;U`C$A3IFSMQ zpC1)LvD(2H*BS;zos$e;BIV4us?wiA0x}i5LAuj{EAk`|Qv5oJN?~P53qlzWBgnFC zs5{>A_9i84b`RXSm3UavQ8_qd{sB`?os2~zRAI*h>Tb5t{m6!5p^H%LGa_ONIR&H? zona-a3a%BpX91sM1V|W9<OZywHpVkH)0!u)3$VhHmSZCDaSQD*EvZ*0;W3EUW*0yO zs_Hbeie#a~U8L810l%)#h@iTi*=<{S|Bv~6b_A%X0a!y&Ae!}e{qMKs{Hf@k*PE~T z+YNgjFz2-6_3p^8$k&$;>HO}`mqLI3Thf+t`<^c|?>ED*&-tf${^^O<$DX4<<=X>$ zKHsP4{5E%EFF%X~J-*-PO8Gb3;@Rz=@0|VPw?FXy+i{rE6^I4)>?U=aJj=e?{QVL5 zAVbIJ@si)5)BIDxxJ!;WA51gO3Ho4%ukZNcee}Rw;I}w8oC(eeQ-OKGK5!Q}IccX& zGUcXRwDXpkauY6EW%EqA|1osvp%qvDPmL)b?Y(8D{DhAdU%C49>7ujOV~!sGh%aVN z+F=t-xhW^@gr%n3gp*d<e8YbZ9lB`AmH$&?%1e9Rc$mNCmTOKCzt_(J&5_$0^OMEh z?-9~sHbxjvBXNjyE(IBhtQ;$3yrp1af+DobLBSQb$rK{qy&)1~1$oy{EO$L4VvXp@ zN@6N1SG<`pBPc!+8J3TMG7$iq)-yMRkQT5MC}mqjk+-obB=(6$UVPLBNVenI0|Q)_ zp2^AesYgnv>z5aJ&Y2DESw;qWDEeEj{rKmQvj?3y)+M1?gxOW3Yc-Mm6RWWM%7Z5L zIO}BhyFdczq}^knF1_P!$K}F{uo!^7tXU@wvnwed#!^_4i7<9w=%-k7f02HfJBjOB z*F7oJHKXTsQoe)E6HpU_vCZfijGmUl7$}E#E9B|w94?2TP|~4i`fw-kL;*kj<4C|! zji4A!G5jczm6qVzQn_nIGPXn1wNq*_7Tu8dFwp3ILn#<h*JPAYmnftwqRU(oAmTQt zdynBN8tWxgs^gx?qg5{cpymV=$Sfw9isKLwIz;pmvWXt}`L@Frl<F_>-_!SFm^A*O z$Op)Z(13_mPX}`0A?ZrhXAk=q*hlxE$LBtLA<8oM1`v5U>a9b7LX?1)Hh~GHR~q6V zdUtia)FUlGAearahjr>1Jgx+Ysf=nedKO|rIZD4+_pz_MhGhQug^giqLRdX8W@OsZ zMQ3@B0FBr7BX1(qCpZ+mVY^upOuM)EXUGW=I;?^y0T(eyYS$`EDWeyaWesg0%c9)a z^XJkt=$GFUW>gRnku;Wei2bb!K3?E(j)(0NU{A>y>#Ta{8u$g>;6s&A<kQZ+Tt#== zU5}__OLx{b3ZPg0kcKPeXD4}c2Z=1wwr)(Ij!$u`jUmzCJ9npK=C(A>JH%j@Ffy~F zAa<L|nS2VD*Un}0msVg%n8Z~x0eAJ>ZTPz6K=U0NY8qnI?hR@_{x`(qj4?wG4x!@% z7?$7AX)RRFg<y`pU8%GT!tg6<xdx{eHQvDM;nK`;-c}p=c9OT@R0`(3k7tbLs92Qa zElfM0%Wmd)jwU&LMIyWT6!OtnPJEwCv;1$ETpF=z4XmwW(J%?oT9ej?hcw+s{4(X> z>uJ5*hG`{bEgh#&44lFg6<umV9_ZR%TYg;n2HkSU!VCi$73&Bwq+q1DU7|Gwy%kaK zFfQWtH0O>KA6XHD-0F1jp{3b}rm&bu^Xg#nK?|$d*W}``>?TF%IrNz)geemx=xJt4 z0=YqxC1zVhn;b_}yK!Q6Ta`X^QAp&+Z`HV@rHJ6J)NGcMqXWYioFgF@oK@YvR9=Cv zSy6aFuZI+;tf*Z(KC+_lyB|*0pa0_}`o#I04^6&odiOL}r6|1wg{*JW?`(;ANG<$v z?7;kjnBMmt>weI4DI<QDM#l_3iE=_q?d-t-w@V3QaU9oMe^0mk>xcd}A)gM&PtT=d z79!b?m!j1aC(x_dD-{u;Jmd0`zJmex%;Vt14^M~RBY~x2rU_E3YS&I6N#&%PanE#T z!8f-TrV)QPQKTsk@FLc;^L3ppZJiY@PSm#C8b~OihgR$FEDqgvGqYEi;0CO#xZJ&y zX{)M>vUpg<f!)RIQk&M%g0^u#aJ!8QO~}{ZaLA#&OqXO{P7*670Bw+?(G01>{`;08 z;<<TOCb&U*ZcX0`(J+VVd1Rv6RELH%R|@;RzHp!H^}J1s`(Y|yG-5;Me_bFDq|@>_ znuFl1Ronln99{ULupo>$%cb639H`%=ePxkG>Q5Nd8GWYY0frzS=0Lwh<=VF`s$A=K zXVA9W1xxp{Uc}RnZ;4of_v(X^Wmpmp_p+g+_wUq7X-4zA4|`AJ&|&-Y66cEd8uPK* z<+^=f!>Fi;?S@e}oWkW!f-vF6q}U6&^;m9HFuV41+_<<v-P(B;qf!Wf(;i#Y&~=fU z#i?2<2%&!E*ac*oh|}?<l;=}=JFh)jGa%qlK@6Y?Pxf<_C;&1Z+DP14Z`~FF5(3X2 zMUi;P8wshpzd{*CNNW}(ca2!b{rVtjbm`5dD!PpW^P`X}JKi#W6qXgv(A%}Ceq$jk z8?}v{X`}O3C3j6&v~cgN-?xwJCYdarr$0ZmGp}ZYHYKI#2-C7CSxOJe;PT_NPZ)uL zyYra}DHzo1f4Fd~<R=>Z<zT<_v_>eFb7CA%4RY{Y=FZ|299(n`?_b+~uz%95<K`Vn z-G)Ok4YSBMLetpbRBz_`<T?V4=)fL+j86PP>+gSCpu_g?H2bcFWtL4;O*l>E7#9t+ z0yT4Ov6GG);>jW*EC<kfvD@G!E!s6+@q6bTkx_7tkzLew<00)?x>wL3@i_fzOc|+y zkLM-{jcFfbqS1a*)IZt5z>t<7cgauO<8A%Cdy?|HFEt_~zgKTp2T{u(RppYE)?~~i zCSyn`38`xH77xaPLX)dsrE42U)w|Ota}ptn!pm6Rlr^?Ah-00?ruwfAKl{TM|HSwm z#y@~D?Ck#&jQKxOb;kcvzWqB=^-SF#{p(K#?!WY}WbGCX7lV>?n?9@*gPMF$5DG&U z1`@q2Y_|K`^pX<`zxQQ@t*7g(4hK9x^7fbO;7Qp-l3bXq$-p6>Bke(j9OiV8<F&dG z2B9-ZZRTo5Gj}ywI8F2HYq;j!V(DAeH_L+;4?8}`yn4DbH?~~Q)fRQL*;qS9u6C=K z>9d6QI5wPkxBQ(h5^i_TNbJb)$=&=Dk={q#eYfv2h3l@!&Cye8-n_#@w0LgDmT$+r z_u72Tr)E}hE6MH2U6|22c*$CL$+jCqCL+mgqWR#@av0r9Jp5vFWOdas?A10oOD_u7 zH*i+)?Aa0)Usf1~CFmN~%)XddY=u!J)93~~)#ywKom26e$sbIQ2ejGD`Sr_8teB}C zf<FaT8BoMSjTlmb0a+(ZYT@&si6V26R2^~I3nv>j5nEHK44485)tt44hwx{4V44)0 z$?CG1xFel0CdJ3z+NexQ;{-{<jR=}uX;jyHMcBX;v#K*E(;qu8jWzlVD8#fzJaO18 zN#%tX(X?9hKT|x@us?*^#9CLumbJzk)S}y@oLqB8pgB(6^Ys}tD6ADIQF171_Du3h zogpH32@ii!-{{hF0nAwB2aA-}^o>HoWO~IKV8I8IsejI~TPI_-UA<yRl*S;X9y2Hg z2%?xqiV<KBMXMAR3jQW4MGYsEdGo7IL4}4z5Fb0XQtPLtfs@U(@X#UQUN{XlnPxhB zP7EgPSHYXRDpqQ?%X^iW@U4iGij@NFUw~KLvbTMQg`hzezCDu&ThlS3@XLMXVqI0_ zG2x^^nR;TRBZh?+-?NlwadiF_Ajc{|v6M?%>^Z=Q3;~uv`d4RUf0u^r^rjjzEB@&j zcqyV7<A6dTo8*QOL_E{V6;>?f4+n!o(_r4T`EX+~g><9X(c1iB7x^PJRU2C`kPels zW5Ax0W5)P!ftT)(<V84S?al)?MN<$mz++a>d|cvJdK7ZNQ&tqRim4m#gt@=6v0q&> zbhKyxYE?3K9qFJMQ|YGgv&U<@cJ0K@wTxJ7xhwaZfs>VwcL!s+u<6Gx>8^V&4BbCj zi*a!LQz;MT|ML6%cfxP=Uzs8(05{%zp{2TO!ptLbIR_^ta#$!yG;;qDe_;s)7Rd9% zt@+3lK}%>rv)#G?to|>LuZOEs11C_1DO!rgzOohpK-?xVMMvOwzi}DDJ`z?Y1^*)D z#zk=R*~1~IhF451xDJ$$J<77@A@F0!Ueoz+yH&qOzn}k6^{*nuIxj!0U}kj6yT$-< z6VP$-w9d^lZc-V6OXx7hDBvH+Y#n{9xNKMX^bIa~{M#=t^`RuKX9c`%h9}DBY}0v^ zhqwnD^=NwHvgc{@V7i)XD5JJH-?#O2eg>%tUk<w+Hq9*Q@GD|us)8noMt88WMr%PR zstmEAvcWjf{ww%PDjckyf7oIVfxF~SsG}l!CtZ9K3HrGtH)^xeO@r+N0XUJErJfj% z{-|bk*srAl2oRYlok3Zx`{Xto=;GL)->7vn5H+pbH3>XgFRqc|s2MFH#T(NXDib9H z)in-|Gpa<EsE68HX{O0l-DZg}K#Or}%l<O?;B*VEk*^$WnMR^m2)w&FVwtUs<`n}R z#26ZO(Ftc`>_KWwCyIJ5fI`IMdq$z8Vj)QfA_-b~mG5&|;fYYx8RLo942A?OLDF0@ z5!Jr6FC0=)RV)<_X~00`+mwS~P_vL?4-p5fl-FKS76t^XRCwPunSG&90ooQQ8qmLh zhdmrCG>JRzY;+T_a7tro)@(S)^W%74aViQ^f^ci8bkrVrFi;~f-d>U1$umBrlVL$% z`scgQY<2KgISiqUl2txOkRiicYE9#@?8q<dEHlfcn~z_-!*4}h*EnkmoL;IB)kJTv zAlI!ZHU$-UhXNr{=sfhw#%hW{QFG*|r2qrZHcTZc(1;b?GMOV&!341NeT!eT(NMEX zrGDMTFhNT>Dn%a2N5CY@{&U<bVPjH*nA6~DI%u-GSS|#vU&6Vun@N0gYb%r|#<{VE zg8P1WF&!7RrHqsBD!epDcewT{?$w#YR@sX^p#CG;s^;(|I^P>zdD*V9deg1IcX@2r z9gu%*_Ly7k&pYz0z4NO5)@3#wUm7f1&-`>Z+$ToL?w=X^io;!jy<~1rt_K!9_I4Co z*GRsAN#!9={^>aUU)4MQuTpVl=Ktm<SXlpUdy!_HA8vx(&Np9Q@rRpWrBp%!#elx3 z+a(bI!m#GIF~WfMB@;tq?wjOT`FO|KvUBx*E{!pPVzAljR;5alz{Qg~<|-Qn$7LLH za2U56B`mVr(MQ>c5Fd}Xo-;JEI|x2~<>t;%cC5ys*&`<T@uThz9^$Lm&N9p-`9^ck zxJ7i915Zc!wBLnbd~=nIOIXcMe1I^Ex8ElOX*DPn7BXmM>TJ5BJ1Phl;Q)bNeihef zo04*%#+Pz{NW;bI-|uj$K#9o-g^L}lN9J4T2|$Hw-dl#mlce0k<iqddH|w*Ny6WnY z8Jy@Hr^j!Umn$4`J(M`G&r6L%!AqyWmmJHl-tEPCbEV4ACgl-+lnBLJ9wJuu(@BTx zoZ0X2+41wQTT3){lW)dZ?TNrtPKSQSjVMce#U?C3Tc{sc$aLywMo@}A+9xbKYV8wJ zh@R#U<AuuX0WZ=D8sR6d0-XngPS&__vb$CMK+@QyXq%zEjiCq%CvcD<Y_E^NNe&w+ zg<u=nD<+@D>wzIl0(9rC6aDIaS{}<&A#Bgj05c<uF(|V$!-qkh&>>Qy@iqd5i}w+N z3OD!~&(Ma0sLgJpB>=(@{Lqp~$@Zh&8j;nZzQ{C;V3xjFU;xPyo!@6`qmz8Wm1(1E zZ{v<&mF~0d3ptO%HY8fB>C;D6hEx7zg}pV4d29oapV#^5i{P-n6*Y(86n{Ek8q6t1 zFq=crjyuydiQpPJcr}fn6u;+bIH9gJ!DoL{3Kq6|Q$mv`6+YptG|wW;i4i@dkKb`- z^3sVeFHO4tPk!R_`(v5sKlzF2AAaJ!-Ph0O>o|Yw`}hYR@_per8o`G!5aj3k+@Jp; zDZaq{d_0~X!dLn6`3=&hLv9GL%7eujI1`fzLzFr88@BQEeO-Bc-FZF-!ms&p<n{6W z+0XpHA5P_;@cpYiE+tfU-3dxgMp?4KI^|vPonPPg*?T<0{kwCrb;dIj(bi?D$~8J1 zoMUH{YzkpRBpPdHjOtuVDr<Kpus51qj`r+^nE^KfGRTqM`==?WWv3*v1#ryllGI`} z{3JR`8|-eFf0WGo?Kxx2*z;Jzoj1&`;{l;9T=i>e`;<7=nN}o9Ra-meMe~5<DLzP2 zAm&`gv(WsFQ;Qw6T2jV<h$W(xUFcV?M+){g$kcoy++BMPljLbvq47Lq>~Y1ab!phz z`l8$osHP#>-Nfvqc>$RS6ObFOO~HShcFlBY)pCg)6HHMjDikq&n?d}|uh`opUt=n) zg?z;7g>&RphN1b_A&Q|@7fcQfV+_LAw3Q;eWYXxb&1dJ^m#VW%0H&zf_hn!%FbSws ztSX3jQ|*{MRIuEFvxkp^t-9JYG1@HElTT4wM$pjfH|8-aqfIrL8Kgw*^|vNMN|hfL zCu{`%P7sB71*0YlrCE}}l5#UyUnIBFy;CoIyuASKqw&1MkIdtLKW+<b1^DkMc^Cll zdVk;Ne}C+EzhuK-^YiDu!&0?zka})B$==BC;7{jk^hrAg`uE4mZ~J}B^kjRK@1L&M z_i*NQ=lj3<e7r2rKiGagzh0d_WB7M}e~g{VJ-z#~@%g^I8t3QdNiOW$e>089Kf2?8 zIq{G&q<MfjI3T3X^Zf0u#b<=jpgkGie-nq{+kJ%(yRzejc#AIlaT}6YADs?MzC|at zBevat#99~gWDIHPTZdRru)Rn$ji>Q8StXvp(|j835MSbLxJq=5ukkk7BtFN}eEyFi zrw!r}-hXV?h|78J;zYN8k8-1Vju2gI94u>;@ZL$!eZ812WApGsx3S-RfK2n>@Dyma zRcSWMNkbF`J;gRfl!Qa2^)rKw?@#Ol6?qm3d%H3RsijV2v4Xv%vp!TnhIl)u(>C;$ zI056f6`B#wD{8&|m4~gURsTu!)XD1LoSOpGptBra>IDI?w4B2JfN^1Zn=^P7xeuK- zSbU9oI;6UhuKhbZpt0d8hk#1AAywco;u8eSkX8b5!dyV)%oSVzL86eYMZ9=sTGhnZ zph#ul+unk(4{Hid5)j?_Dp|0Y?!xa%TTOys37s*|3U!=R8)k%T3%RYR_X-1G*kn!q z`&y?UOlMKuz^EFK&aqg;HbBr^kC(Ts&84GHwm?DP6*^<dVpoDQ_*4Hk>ZQePd(o#3 zX%Qo)XW$)WN2l7_q<aW114#~^ZXP|cin=+Xx=$%B&C~4cd_qB?eKV1&D#iwVvkUOE zbO52??<9b4fy%%ea^1j>10&YL8R91pIo^QGcI}H{=n|UE9Wn(8s11-6={|Ex@`U#& zDdtu#=+MF+TZ(8s?gLR?uZ4455>%7f=OB@Uv<%rJ<@rUIqZ!}t@))dh3xmZDv3zPb z7yl{cp3dyq3l>ppc$mkoEhF=ii7ZS6YZd8&cO2kZJxVv4S|N-4ecUm~IhVJo1_TC5 zUboh%3U$_bE4Ir`_AQ81rcefIG%olin*WEkcMP(n>$Y{vT4md|?OJ8qwaT__+qP}n zwrv}$tXrFR-`H=&{mzdwBO_zXjKoBY(KCA+?dgIoFKPYi{x$;W=AAaGV7?2=G(fcl zcnAbcjd|zVQ049;=D%lhGPZV0Pz_1UN#Bg_y`28Op4m%|7}8pBuGA`P;sjooS&-~d z-vBIOeGHxh0ub_@NhR;GePvghA4?grPV7n^11vd+s@7s6C}%|20K7uX5-*8*zddn~ z<C=~suR<D{5&TsX1U}Mgbq4lC1ci^Y7n%Zr&NiH3NucPn;+(tFTAEa$fuup$8OCUB zYed$_(XA4GgIQFp^VB7}v}eqR4Nkc#Hw>QTDkxmpTg7+)P}fj#tjmAEdIe+aDlGW* z3o=JO0eQh(bypodur!JB03z2Z8#vQnUj+Dzh%J#26e17&VWA~q%Yv8YkMblwk`yic zDt@wO8HU^r6{=!>w&8Yc=DA1I55{0m>U5;eeWqWPL~%~j@dvl|+b|GtvJmkBJA7=? z<<=Dx>{VV#?2e%d%3qasLr+^bGdxIXR!2;eSp(Xkk<f@5hE2B<C~z=ufdFX%()(wh zJros@rMRVzdCM{unF)tvjc{tVL@7`($n`xFD4-hoJ-UuP4g>XH%G}Y{UF}kb#gmot z3dOd-@(Q}K^{P^hSOTz*<8E6pSaaB>5rjZlDImbY*{5HNmcdQ~l!&_U#(?lSGJN*R zK#LE`L)Z}21YEOn)uFY(38b9Ty}!|Au75^+a*$3>`l8dxYJg1I7CY4olImk(4!0h4 zdtiZa9<>ta#P&YfT)Ds2sk0`nzJvwLC>@*Dthuy)UbJ<y4mj!ZX|p8Yf_d!(e4ymW zT{x`t9Kk)&GAUQKROFEkNjeIkp)!?4zQygoPD>-utZ$L%6KkjOCKHH0MC{rvLrQ=G z$AKmmK_ym}CBl_*)j$KLuwaouy^16Bu#-I_v}R2tTDbw3gf=u?8Q-;3r~+xdnQh;h z=V9>St^v;V-b*!aP1-Jlfg>p8Or@|a{5;-*O+?6~COOt%v^(G->JnAi)MdIhwM?0* z0w(f+`+JzBG|2VcSaG%-w`-Hop<Zgca7Vc^RJ%wWiKgj=@MwDhomr7zQNhAZ2)hGZ z+-24`+&XP$%e9jxtr0z-n~?DH6Swt+bwtY+Gi<`Qc8!5>WVWH-<6T<19CcnXDCUqg zPuW-H4mvKDO%sFO)_`{q9!E{`ZZk8Xd=l`ehb8&?g2={=u>ko|N9YUk@w0!2O~7C^ z_&zk0cAjJLC(ry=Ez*X!kPKLc8g7!h?a&a|MN-VnvL;U>@P&Ubo{tzN5OWmt5snqT zP#OjiI5*1Wj`UYfnrB9SR=8FZ;U|E)Q$F0aFLrd>jshbWd&>42Vh2y+HP(sKPhcOr z$KlL#HGc^j&HL?mmqNlMI;1}W0+sA$;V{qdhi9fT6?YA9kUOKKYGcheH+qNSu5q(0 zp)j{(9&bE_8l+B^VY9YLU?tF6=en~gb#yr4-O30zAxI+$r=2+0?)T#_$B7a><T4aI zi`3Zuh&<(@d)K430E?5P)tIP|wmpL9EC5Zds<Mqx5}ST;=A5J?8y{D;0-uags~ZJ& zm$|4~o)4~WjNhwayY#1jn<Tawsg4w3(kdU2b2Glki*7Gen_i?s^|3KJgg0OIAeKHu z8yTQALu^ypU`g(_Pt?nG(6GqiHUNc+Wj(y4i6?aosVNzN6JIdmo1}p|jwWGK#?TTE zkh_iIENUEY7oA7mfz_TfIyYjAv{zTeD?m$Ttt$3yrGqE8?!L>qNnpMz*!x3dCV|pb z2*an;;`iICQ9~%}iUTfj?zJVJ6z#}|L44s`dGN6Qy9b3KZR}h1r+H@rDYdPT-dV)# zCTXUlb4Y;d!_d!ah*h&PXjN!+Xtm0!6Uf~>B>I12Nq+i?@XZE#|GuiJ8}&F$x$Kne z_)Bg4;xu0bZ(?bn0#A~cR(q(-CD$ki%medEdZy5*$`D|YV&8g5Jmp$QpR^=Wzcx!4 z(qAzMOAq52<2>dgTQ>v^cQsFf1j<&;l&IV*sJ|@IXueXO{)sX!JzsQRY-D>je*_0G zYoI2Mv006!2=vR2132}|(f}X$TAmj4dv75kxi3kQL`%A)u-X7D9rV*AjU<MH+A;Pm z=??Y)_Xv?3Vmu+2HYvouOzYZ@6gGhLkyT7%0k(UQ-BcCQVY&2~JSFjO-LI$E+T3-; z_Dx{vM#Q7W;{0V*L0MJR>WRjx!og>;6z2CYL`=6_mwO(gw(@7}iol>IBuhdvgH#@1 z(YAzS@`f!U?QlvPZ(f;B+O-8}n6tBUOxvU3-SKgt5v(Nt<3rpth5LrIT~V!>`6AmX zVId`@zFe@IehrcW$!lrj6i(AE0Ld^MmI>Zv8U7NjY8L@4W#JU;U|)Z8MdbWIf978W zR_z8D^0!3MD+X38v};GjjOd@3iVkvr?c+?8{U&ywns;5sT})G;cA0J*e)iDLwrQq! zwUt$43i!2AkBhF%<OE_ghch1wZ42%Ko!j7AiBwdPHB{6fBSh-(Qw_L~@@-}jGNSyn zQ>gjy{q78{p2RL~X(^9DMWUFcwHgzXUmr}wDZBv#rCUe|jR=ta;9}2Ms`OzcL~APp z9afvZK}~A@GsQH#+S;^Vp+~eC*@pmJVewUxL(U2`0z9ZB{}o#833zJ@q`hDOm~)P& zoP>{RGdzMEYP0i$LYnC5-~zN8QdXXg=3O@J0uwl_<2sIpggH#p4gol4S1JW77sUu6 z3%z$lM5``WQN}15;VqnHn@IB>FT`?8nE2;HB<?fHmC976K!wyw_uIQ<j7)Iw3HCA8 zWBnP2K%<2zgu-Q=hPI^CPTxc0`I}V$`<h6_T+>`yErvmVVsuf=!jHcxFKM}lD{Cb7 zIbWOhHBd<liVJ?<@$?tnJLgx8H6^MBiAj}~;bFXquizIi1<NA~U}#fp=4skjom^m4 ziqu^1seW*(Y-AF#LAD{F*TWK<ki`kSMz4WD_>p(Fm)Rd%?EU4(AVi*E7oo9GzzBxU zsv`cbyTh>t3SeKmAgH`ZmZBApA5lN3TqIoA{Y7A5<HvstruKld&!-#v%}4o^)_jp% z4dpQn;Bd}d{M!O!vATxC!JI?2>xgU)2qGRF&<(Y?-MmZ-5uSc;snHgDR1t9VnX~s~ z_R&RYCiO;+CP<NSxg7~XbuH00Uh7p|;bEQ0?-=EAeq&z_s$K6T3iHpk98HoUOE)gc zulmHZdV><<eOLAJUnPn<-QrBWjp$h?od&#sf^j?1;h;3&e;DC!7RP&`ou|f1hvij3 zmIoyB@0^uBdW71qc>W=~!@=<nY*zOF6WGW96g!IlOYB$_50KhCDnJG-M~8ui<b)}< z`gkX?O7q3BFi_xNlTW1M<K^|fN=S*f5EN%cUkM0E6eYGdAYd=65fj@IgFqafM8Pdn zJ#;+n$Y#>lW7cYlMuYCz(Q1YRuZXyM4S09+VCrhKYB4eLIC6Dd-EO&<SmvmK3%hY( zgK%3pJPx2ft$|hIdEvZmk4SXw*@z-!)8}pL#LCQ8tUtfTK|H@_C*)(5-A3R$<vo7J z>mXU$J@CDL6U=!I<GE2pZYSI&M$VSZ;dB~yMwYFKTabqj-3w9n5TVd)>B!*O_<V$| z-{f9?wj(@o8}h1?!nQFDXP!wu&{C1)5I0v|`l&mUR<;83*XE6mPJ!`06$|`Mr>;@F z5SQ(&)i;(9x-c!XP{bmYd>B9du#AKs7u0P~$4*Mm?~dNzpt4Snd@X_QUf-HvpZxcc zE7<%CJF~L+9wfc1MAG^`k*(|DAhQ!)7`<{R{lQTsrL<9o2|49fl}Q*!y1IWL;X>G4 z()>F1fSo?F(N%01OA30p?gg!klXu}8bqH_};ikeADJpLC-~u)E!LflU|A>SBo`C!{ z_m(Lew;@nSY4*CWAaw56?9`W15<HUV8h{c?st|XtAE0Q&cN#CXV}Pp-{TOqO)5ZsN zO%bm-D)RPB_p{)8_;^5>z7{3eO(O*@N=O+uG^M(j6{CfQ-BWkPm?SBC8M`P<B1wrS zbg53sr2(2Qep0!D6QL6?t&$?9WEB<t?0G^O<ySarzHrqyINJo8#DFe26rHmA=sflS zA0)XyCv#G~wi^I&o~dc^l-juwi&Z-TwH|#i;IeWiWm$tlHgPdUr6sxhI+=%R$-wWg z?H0BElHM3-CRL+#lrxQ~J@wY_EMVy5QK(2{sA=M}@CvhR={|ihIPn3-p}5dl8WezE z8w!B2UjqsV9-!_G1@$KY1R9j^F!@D5MsU?dKnR~1ML@5k0;eLEG_>~#NVHn0P~T}t z*WlIg9cJ-O7f)aNnjPzyTRGSwAu$^dV`w1@dov>zCW{_B7b}5100q*dj{m#=u`<yA zgDHfa;Xmhf{|joz(AvMjc8~#fpTD3aJ<RaZIh-$vW2~)VpzM+*DS(t1)(MEoG4<D9 zo*mkq1Flo8=EvRgLbYDpJw5eL<m{!%$G{StZ+VXZAv5J9WY%Q|OJwj#?u3rTQW_=g zSq<$S=Wr3MVeMqoFIat~ZLC!b7#;%jJbfOIted<$Jv-a}JeR=6JKwtPrZZ94`D`;l zWcs=to?F{G3yjTUa}gd#>+yG6Pj?b!??&IYzJ4Y%2fzWhE6<;3JZWLQL?dUu%sZV% zdrYUUk~^owHPpe|zgV|%mLyiG{y@U7_S_>X*-EUsqtcI}{+<$Iwh3t$yEUgCma8i{ zCCHS2Vm+(2dVEL6*G*)~1%f{=ifd?cBaRg4Z#5-MqmtkW6_pn+8}CZQBKs1%smWst zzqQtbPz*vS6h@FzKzRX$gvmoIRT5gzGN1`5rLs4@+RdAAV3P;O?~9{oa$}DzOwk-1 z>-ovh;QPq|-a9IG>=6i+ZMm(>Sm7tuZ++7@@JXAG4$9A$n)M>@1Azlaqki*vrQU?z z>ZY2et46TT+^e9BY-Rexv7mO^g+3|KRzle+Lo3;ZSM1l056P7&pl~)6qnMPEvsbYD zY><shCXkeHNAf>9jq^GK1t^h8&x@3gk{Qh}VQwSah6z~6Rup~^O^HTmWH4JL%_IN? z=P9`+Ef$qOLW<qXL7A-(k6*&+#zn|s)(gri)tMG&Vf14<=Pk-N97yG}RxFtncFda} zkSEL$cdV5R5W?x`gMP~@nIr@O3e)Wv{4V$7|2r!VYWkPj;TKHs$?gE?kJ74#p6NX8 zKF18MdWxQ38CeEr#tj{nrv3?%ah9*F4paw%IB_{q;>H>zh8UyNE6a|jx8L)0PS_hd zOJzeV2rZj8g<0)m14*|_9$cniS02$XC|I^?Op=zu6ai86d)Un!i#d_7Ofo`5m;0uw zPJkjpIcixSh-G;gUqaloh#^z~QQ2zwrAO!VOF0J89RJr2<Z4f2jLVeO8T}u3uZ~ru zY@$FDUL1-RMN-YGA5dFN#Zip$(+EPrK#8`2$KcuR#=@iN<@}y`m+S{@8UQ}b|L%h< z96#OdUv*#n4~2v2UoW6O^y9w3X|wZMsW}}vEDEXASB~rL_q`e-1;f_e+X5$x2<n?L zL=a*muG;%iIG(hoD?jIffBy#28|2!r;!P1&$r>o9lE1VK`5hLr!VZ3>3yV(fePs&! zk;i&MjuUr+eKf#D=70=)6Llg6JJUB4hpVII9un7Ay7qxHIbz#Igmd`O_$%Y^fZ6g3 zA9kUBPT>Bd$1_$Vy}(uunp4!i_Tj;-7~CUcCY19|W+IM3qBbR-kNwnWEqb^5yU7*A z-P?u}=uh(9Exz7<#23Wz$w;(g;Hwa#LHI9M5h!|L+=uxOUu>gjdf~tm2)@Y@j&^9R zheJ8C6>gry({z&%-h%;A<-Tx(pTe+(uEDKB2L67;U-TiuBcZTF=?}N~2ZcW$9;xei zOmFz-5bEMEfbB>bGN9C$!Ie(O!Ci=%-uT`fB*007ppv7r#lvDFR~C+p8{ePgA~2~d zO3tf$2yQJe&46cpTQQ{0kj9^f`Avic0?4PXg0mWs9(T0kdQ$dfuD0c+<7<XAkvry_ z`KJ2Ys^@DB4fYj}_GMJKzr3?7Xqux2ZYT6p+GPGEeL>q~>CSsXvb57iy$;-QQXQ)( zxH(3c5w4hHECf?K>qq#mgNlx7-XSD|w;H*wRwouf&Z#CO*|Nac%_pJ&uq7v=yH<e7 zdVqLXwt6^1lQ4R?xZpnTxrxWN(@lmB9=m;d)%3x>wAm+GFPp!LUSNfM6Mch5;Ae&R zrY%(UFg96SvK!l;(5DN)EFIWm7&|6tvy1ykv0t_;f?rv6`_)|@tZutisbBtE;wZwC z?eYHp8aQ#0-TBnw{Zr%fz3~3+{roor4o~y@B|xaw_DABlSh)F7LIQepek>S5H90YO z+-GIBh~T`S6*BSDZEor>g}SNF7Y7wJ(Iq$0B|fjWpCJcl7Y8{SUl+1DU&!AVvg!!> zjV*#h%#Vz%26T~>@eMGdXE`x{KF@K!yah6KWcd!pDAe>xIiz2~im(bitP-bo{p0LV zk<}ck2B@R!0gDchaNUQ_&LXAQ*gql0^a`eT4_lcUqLCd+3(m>AyxlSrH^s64*eXbv z*tf7dM6s3<Af8y$3~pyYR|m_PC$qU`P0Bd;^kO{z&TJo07qO!DX0C=vo{mwl2sjBr zTQ0=1HD|||i_vC3VIUpo*}I1CTPlc2h7VV_9Ml-?NOxy><gr}M7F#Cs-=vayBqMx- znP#-N0KTD1MgX#l<OD*El39;C9{|h5mc9GA%s%9oZ9qecn0h6fb*KOYdU&Uj!$cF& z{0YuQ7(EDVu$37ZBf9M`f0NFQ?D#m`j<@t!8Vi_F!#JuAnM|BE7<PnUWN}EpBj`wj z-;VyVTf5kR6==Q-l`LrOh9NYwg&gNUrDfeRarH(+|Jb!V+Am^d=E;u@IXM78x2G^x zhz^?=8iXh|1CsT}`mxftA(d^B^(JwpQU)QSOpB$zBskGKmpY11#k2MR7T<9g0gQ6y zzXwKX$=U}fhMSBNk6w2jWi#o#z(Y>LPi#JbWu8xia0*joCOEn~klF9S$cV55$xpL5 z4!#_wFKZ$1b^VmowGO>k1I2b~i*85b5}387Cv+aZ7CjE$T4iKB?VU@3S6mTbu<i|o zKa33}&qPCk-DB=1l4uf*lOxiv#>@UCUQ#RobHcYwiKWXKP*H;3$RrJ@2a)Lls1vuu z0agqWy`&K$;sDFhB@i}A{CK3NFC_S;%{=%gAJS}lr_Yj?P*wy_Ad-cnbXciTpj%Gx zHWCZg{Vzm@q7@M~pz(cZx{JElo0g<y|14Oco_OdDO$n@(GUnB&ASMDcu#DRvtn_Rz zM7j${X<}|($TY`cUw7|~+^g7?;o9Sq3+?xhO61S9yXM25{q=J5ZD-1P@(8xL!XbS6 z{v#5d;H@0m@OFNC@;qmV2TbAGyc<j4W2auA6!Ut$-wAzIA1Gq~=tQ4WcYnRUH%<;l zdj6!^Jor4h$o2#ceSJNYP$-yn`*?rJ;(33my_cBmxqn{oxW7|;9}nzATa4vC%li9A z_vP4GSK2&?qI1|{<FQsNe+QoYSs_ANcH+86FC4*dXSucDp9yedxaWqjhWWs(<nUX; zuk@?*tM;oB&<Ze8PyWZnNqyN!J;g{n`Tx^c`@!NQTd6l2{bxg`TWkW&?3Iw_PvKF- z-~EVIYQE;Pm_JW}0>{}8-Us1d;;;j8ifsu_@aepo(*^DD@S05AMAORksT7egalQW8 z(KW6lNKKjP*Y=47CW08?DORpAIZ9C6NeKAZ%4__R@L=$z*=AubP>X?D?kV@b6pm{Z z!XxGv#B#}!Bt=+9CyQ)!r@&Cpd2Ic!-3BCMO*;(SijsJ17O`2$VBgWj!HD~n9;NNK z@ROk_c8F+W_nm-bYE1sRu$L_Bn#eiN%``znhEqrs;Df9+0hY+P1Z*Y<V9T!J&$S%l zUJvOnF9XH`$CuNsChS82r6l1PD#iUhiDD2o?Qm1i!e$KJ(g_1ZXbcwych*<2YVC#8 z;B8<31S>8H6<9U3<zmG79qKPh(rrLC{g}-|^bmoxQ}!mHkqB0crs`aa^qb&mHZyo- z6bt`3fn~F<bXgRqOVm=a(6#oHH`LQ&PywNab@w;2zTu>a4AiRQw$5ghAp7BJ7<WFj zs+ztZrF<q);CwBCGo?TLL2N@vVL-mBOm49YnhX2FDs6ry%r~s~sF)0v7BB@+c@JPo z4jasaAToy8_QS#R_SRk|XcB+~r#dFTe>jk(Z)d<YGWOTc@Dc=sK1@6Vq?3nR$2<GU z(uFSr{YL||a-GprK{Ii4OnkeR3sfG0Asc6trXkjE5!pu3Lzmh#OumSdScYW>u?f-k zKFDha04YS2pMs)Tu||;aFWFYnQy~o2yvGzSpaZ=}Wl14e9ZD@E>mi{4JWyBK(!zop z;I%Db>^9D`$auB<-XJRxSybdzn)%eKXghF;D=|U0KVl<>t&o3vN1^y?D4^T?QT1qQ zSxF-Je7s>fM;nabk3Qq7(m@yvm&`PnU=yK@2$b(W+Ben-lF(1%veIS|s#}jW&cryO ziL9f`sG!)HG~R?kgrq({?|^;YD@3k8fm!Ia#m_wy0AHcyq7T)oYe<&uhIOckU$RCG zQ&}ltqwR1Cn${>3=ING6P{h=pwr;m>vV=EBajI=zB7hw?8%M8Bku0&)cU4A;xos+R z3ylzot`v<Z<3YH)tZ3~Z@4)&=y`;!m+i|_Rq8D%1uCW=*G|;IM-H?u)7XniIny8rx z$k0$?tn7ugny1jdtkvZ=t9xTTnx>~irRYv!6>_2RN^2r>rxG#JRvcgEL^hPE8V#dC z{DNa0GHvKxW+xaR)VXssDUc*6<!yV9Ybg_(<&P+C3*+O`8#rm`QPl_T41eds(GZn5 z7=dC2J+1Cx19(~8j4Ca-wxqF6kGMUxlzB;0Y!(TR$2*&6!rvSz(7>1~^34e&e z$uvs$ah=Q6wQXONZF{U3AmyaYRBvL28rpO;*|`UsNx+=f{wKU{)mBWxWsThMI+LiL zIF<B(Nf1h?+SwwR^AQFpnt(aT$8Ukq@k5*Syg_EwD_%oHs(`SR<G0Ld${g0<Jy<4u zy8YuYkFAWJCtYaYeq$tQ9&oW86MI(wr9TurZ6hGreyohZ2e~y<BIy>?z8n~8{a=Xg zw75`-dUPv%(2i<e8(jkEvNHI=3e(Bh^cEVnrHfuWQEsN#8TEUAUAR0sI1~kIMc{<u z7bv8j6HVdDAdd%mbqCozdBU<>=|!i&z0cK!e#1-^s|*6>fh*8}3XF|~AE#enYE_Yj zJx*J4a6nVQ*bHp(Mb1h5U8e->9<7-@4$4Nu3E~o5NoXOCD8dFldoxamDHLI^rt*PX zvS4SGrKH2kmXw{G0E=U&>#Yir^f}2B&!=RAgKJWh$#?wb`5q@C{?eqJ2n^QJ53<xA zat?IxyR*cPLYfEL)>WYsGxbmf?&LSg)3udry_PoEPy++zC=P)_6c3D4Ln$k0X1o@R zlzT-;g_=ErM8nW2!fD3aBL7vZVL`VM509feL<O|$q3p@Eg8UKguhl=n?s)5zPJD)j zBSb1YWml)a{AFTloLuei99z6p8Wds$co8_w_+6n>YH3EqG$JUjOk4XH;0o!2TxY`< zh8#CW_aj2oWHCG&3~&OPjDeaC2^kYM=Fma%s-G0XpW|eFJS0_F-Zm>!7%fBsG^eWh z2L#3)w&r2M_DCDvALOS4FJyf-KGpSchd5?o|CDFUM>WEsTI(|ZObLDS&s`AGc$A`Z zkMCJZn}Vn>bO?f#dBE&0ocE%b9pRlwUdBKD`&VK5ub*uE#xnlZYGidfRhJ8vU=v5k z0UoiKH5V*bXvn=J$AXaYycJVw#cp30w4fTEHNUe8Edj%C#=(u~ji9x@!UoO{a+7IP z(qqlEGzd%c)zfsOe53tkmepF+gk+qmvD;<=7{2l}Rq%x>^yz(IWb9MpvC%jR|1R)@ zJxPGg_Obx+m!ee2FpTRWTh;^1Xot{C_}!tlO3H_F3O}5i3tjg_#+}8!!t7SiWAogL zT&V#eNL{Bfr+$p{@6|r$9@xk4t-iwTHlIsf|M|%871-ieo-EPtiSvT6iWt&r-t?DE zQ3o%s6NXxrP>b4QZqAtMn?r7}MzBsWJs3ln{|?#zD?tBy$o?Mz`oAM}vk?dFgq?cy zguPbsK|OZLQ7iSxzip!XiQqrBupEy~XD9k9$`35ARBGcu%FMd8!S&x_qUWJyJR@%3 zwN(LU@_{~@;0xq5lIX_<i86x^7M2`O>tKhFy4M%F8p<y%PV|r4_`<~IRB?iKM8Yvv z1r&v90pr84#iA%*Ry0!FH`eg-9X7&wyAHv`zoX})XV4ASSNs2#_V-i;Q9z$?#Ed;@ zxroWGw?*~KvETq282nnG9O$VEp*V(?po<;DKJE%2F%uxj!X&teYHSEOYlHr7#wD#| zT{SNU+;)bZLY}ZRMdX)GKIq0RRu1;jgj0;JCKQXXIK0cB@%MK~qG}DZd?g&RfLn0D z__E@WBB3NCx7T}Um;nQ_`HN_GzA)+5WOJ$KUTxD;76M5)@eYsUR%#gP9`J$<RTJWe z^ylAB9CR;DBV`~(!dHWyz#vXC2wiAU7OL3CvGrfy#B7^VV7^EJTQGs+yo*_UF^FH% zg_)(Zk)Egg*2Y55e}!YR=Bf2(c5K;Vfv^fV!9I1&&yQ09@!gDCjM&F&5B@rfiD>U` z^zm1Uwl-0Lt@%F>q}*Cz=TvB$qE#-O4pclmepV=LYOV`1Q{LNI?k8@@b53-lQ23NP zc3W8Fu)Ak5g5lB#*tL1qh)$x%IMtrET!&QWX&&7|3+|O%laNGo^?p@z`3p8xgBqfm zx$7Fr;L--+U$`6Ekq%OVZKvP7(L|5riM#fb6}UfHM5kl#ySsdvc5ZeF@HMnt&|3fS zZ$!zg4Cc1sZEGyxAkY44Z}8d$8EM$y+Bl?K3hYv6zc>_EA0yCm&Blq;Y*#mi6#vts zADzT$GoZjsjfds0DBA_O^2+1tzhN~zgOd{3ciN8S<_8&$W^-dHprVCW<XXv_1hCEw zzyebdCFot{`bnp)ax(nC^DV55^#5S6U|?kZm)XKYX___#?8v@54^**FpoK6785X!t zegJt&%!YoB8&;y^LYv4G1Y5C=F3juS-K;5;W0>oa>9>fq(J?&^cXxeYoBqI=3s@pu zbVTAOj&`}_h-f@^nD9=@M~#4p%A>*#*M2F&<bUIe9~`LpgM6fsGJVo!#^1F(X|Y7l z5K~+Ly%F(u@4!qTQM*M}GN~o=^TiEE1@Y%kH?naazs?2j5p8d+w6xKjh#khtpKnoY z9p;^<0Oc`HH+P2kR5L5#^%zl_5Bs-oc;wE2o}2{VInUBdDG^J`<UpDfVjw6$g}0(S zPN~Aje<qg20OUfeMkQJ`l;Q{M+bD@nv^ov+VhjTvO8aozXStqY>RE#L+1<QGTfmkS z#Nj}Xj0DVXL*R6SYT*&eugt2ii3FbrUq@~A5<B%Fx8`ZnOQ%XPW}J2MLR${pmmt{v zpt<LRiXz3)U-nA-+|0?ulFi=O62Pd;wDHx0*Dl$*ei6?6jZhaQ3P0n5bVN7|=BdMU z)g`Mllr46#>=7@e%6$jRl~Ex1q(DO<P1pogM6ZV_bVQif8;w5sJ`pJllf%pWHQZ@W zR(Hf{ZRpCjz}4&Tk0vW3suU~Da+(aqP?pYkSX4^PiqdHti>5TZihpEepr*~OiYr)G zaK8U~4_{7DdPtjVns4r$JrAm&n}E2<%<aP7T;j)PTu`PB;^D|wH*%A2mZeTpKVZ7Q zy@rcbnSgAw+P4bv!Ivs#PnPD0xei9*v-Z38SN`miC6oPVOZ%DZ2tr4pfBmBPY(g&K z9~H}dnfPQqZP|g*9;e)shPp(VIyt1|bsQDP5c0L83DOGt<WS^wK|0v2umyIA-_jVR zjvM80%JK^=)pTQr8Uh<>xpy5X+mp>_oD*<`D=P(8H5$-_?Qn_CTXrHX*UlBrO9>d; zgFEx;xF<7b3(4pJGY^l}3A?VJ{%lGheG{m6<~$?Rz#pb5csgwbqs{xXIbg+8h_{+; zOAy{xXpTq2KFy9HH;yq{KnSmPx~)19=t??YpJkSJ-9sc0F*IMs*Q$UNAMWDZwOKT_ zorC@$FZ(1qxG^F}AEsDfcYA|G`J3d<k)y_sWS9$*8CxVEFS9sY+0qiGJLX6W#y*g+ zt`j-18$+{OM%sa)tC-=y!d0xPaM<&_W3kk*y>rA^SM`U~3sgJSfxJpD+V!8k&>1rz z`V%Y6F$<SroX%c@1DBO3Syk;dnodr)$te9X{D4v9MTLyT^B{kw>R;nIa&jV22`^5% z!<@~UgUmkwGoZ(if4GL`7{vh%oJ+f;Q!))M3_Ut04S^)l-6aKVRAIae&nUm-A0bY> z9^f~mK+;x?64)@0r}lFSHq2m|SCnW3*(8`eN!ds(ID7jzz44oWAWSLF<_Z=wzVE(g z=9fs?AM##&PQ}5$7wp@hB96|bx_Q+Q)$Jd=LM7k1d`MMHfjoBt-%rWjI)$&0pk&Xk zkW;gPg#Z9-_O7V4_c<`Y;snu8#z?*LejNj@%yB}7H>oK9RnU>=Rn4Sh7eBKUJ6D@J zUC>umjsI=y1fV^g*6B$cA>*b<7c<CKc&~o-xcabSE%X+rc?S^h1W{#5SOy})?q3}< zr;K1$-suuaOO;=)A}o&ZL3~SfY~$$lrL(PR5&k{%4BA9j1rY=B4UA{v`S4EzDBC|2 zQ{iC!*DW$vYMM41tjONaHTbn?kf~<d!bejpi`pB8b#X9aP(sNVnx!;u?Tr&Xcog$t zo$Z>~mQ?ho1dzh_nGabvx1Rcey_op6YZ#MUU64uq{c;dc$8h-ka!`Q&vHX60o}ky< zgr6}FExzX@<AKc;CS+qOuiA)WHi<(^GDSv8r0V9)&chGWHaL|oguXf45|AW%_}fm` zyo9y$Kl=I;y2NeKb{lY{;wZ+_0Zpot_ceY9qCo%D><5P~EPx38Zl0+>DtbP!IT!=6 zHyTl3=d*m~d#Xnom=v?FQw+R#0%lFtD`n6^-9_(=A;ByOG!!is0fDoCkJ=jjcrg0Y z2wTM5&x9mwI+4$fGfRfoq*W46<T^Hj``?kX!{`(_gf|X|T=x?rU07Ao4f9NJ#umvN zA;i+#!V~>TlK{0sQTZK_P)+qQ6V&6XK?E0~Ty@gCuOM#adSd9|?h`uDG}k?Pp@?F( ztA?SSnFQu3qmt<H-<U#wwSqx}=*U8t+ww}<%DVIk(FQ8u63&kF>91x`Kj&;+AHUpf zucGB$!6a9Bg>(u#1i!b-6wF}B`*j*Mj>^d=f!&NpDlhAmjX1X>W%Jr<S*^!LvKx`^ zNY^wgjPk`R!vefh^p0Wv25ux4k#0B{0j>dIWX$mH=`>a;?a8G+mXliu&r|3@3r$-| zNUHiZNhCcul&UKepRMDBL~S(BG<4Y)`IOGDf><R#PLPJNIinw)?}uvof<hbSQjo~m ztM+;bzSKD{zNOS;!Ec*(bkLskM-U}t9NLI}?im4B8DHVr75<Rs1TwswG@`0-FcQ*B zEHy<elr=XJ*6}|^vj}7ar`Ig};GE!)&EpHl`$oXNBI-t(+@8;TJBarwXPO{#;sCs? zfEuLlb7e=UE0|B*D$|u;j4@m15Rda}W!i;Rj+)j_+X{qaAn%OFt2T)+*;AgDULdhW z_|A+`AOhRf#Xkj!{Dq=d_q01GCO(C0N<hskK%s`$s#TTVy^>RSkYsbNbOzqXo^B9v z`6<&ZF!XTnl#No3WChhl#+t=H{*0y0CBdH==K>l^F)u}Cl^C-fjAfi1WjwHae-|3> zb5&qiFI{q#VOT6(I++iDW3e2VRIGJW{JF$+A4civN^eqaSlO}EV6Ygv#L`D)9+Ju= zGCsJN+YRVQo_p$<R2g6QP^U8b?o8w;DdEMl=!wsKxO=%Z)8t2lFz#iTKG$c24YEb+ zXeXS(>14*c$A!yjg1OwmTM;4WN&3Rr|4|cWVE<u6U|?kamnAI5|JS6$#Q2|M#=lU1 z>E8fiEp|U9ojIGjKX3KnLxdRA(4(k{=wbi@3IJsOwYw!Op^QYAlbAmQv9j)kgCrvx zs#~kI)ud#XV!C(ciwo>}jjXpJnsX)8dBcEO*BaJY5_X$_R#RfELXy|3^v+lZXL-k8 z^2k_of;y`ropSgtA#o#xbKQQD<YP}!wY3FTSnc#hS6Fs>bZa7Jdp}j7-SngZ3l33b z`eKPSIt>E+YuqF-p2cuo1H6dF_JM77dYMd{(-LTT%XoCdBiLD~DQE=UI%w(kmyD;a z<94l%r6Nq5FX;V<lekEJrbn^<@<zBsNW6RT8#EsChO`rkHG*^#s+H~`7<Dz>hBwqA z4E6=`#=1m9zU?W+eXfP9C&-OWKDBR_*CE`vM<NZ~4~Q}iGj}F9A`xMN-b2u5oq(TA z9i<kkHPBB5BGQg`twgb`(`9Jh=}%;^Za5?{0_63lVdBUDO)!pj#vvUg)F<jOB<aAi zOf%T5{v|nGuU&ErLFfUGo=`ixkpwBk@N+AkBHuvWmklDcQP>(@s}hWeN<#P(3@Aj* zI#9iZ>~X-LA2|oN$csWd_L#a2xBc*RNA)t$Tny@rNY#?ntg;}BhZ?QlDXxdzGyzg$ zxZQvu-{YP)fckuGPplY!v<=SwEnUI;x&6Rh$d`Fz#MSV@Oh_HS4#<cWf@@NJs$p1{ z1YODDT5R#Z`a+x13fr{3hJ8U+!JWczo6%!y@Dn4{tm7Mv0H~{xQ**)Db?(@f{;`+- zx=4e&)z;v6^};5tFjfTq1hc#KS3tky@?4*fr?!qNzCXRGQ)F>*adU2H|8&>PY@GOX z_`KY7Ow{1*Jl<VfglO$`w|!h3wWRELN^gX8OrRC;(ETxpQ;l$fbTbl%P*T4N`@N7J zX17H)k-;``G;wrK7xRaQHbpk&&)@ry_mY;gjTVxV)GREHz;w~PWwNEyrjB&Ui+G>5 zk8@R*7Z0J#e5wKC+XfVC;7z?CGTdD$PUev~y_?)T+3dVub#Qqp>YAK@CC?Qt*d<i< zD7p{n4Sc>Bo~h*qKXoi}P_hd)TMa3Tiq20#QZH3vI`6_4I+olxde_Pvk)w)3`K_$! zp@gS+WYkENaL9HY?SlGH;W|U*UcSOTy#XA^>qT-D>>sB>(uq+{0$Q*4AXzqXi)ZTd z@o6G`fE5bx(_=rQI~!Uticb!Ig(R08CZ|d!WP4H>W&1MCQHo`d&uSv;@u(Q)6qv?v z0Fw1_;dG#K`b!`=S=E`(y93D>=J{4$s4rU<;uoV(e2_=xTa<beu~%#G!^B!PP&vI| z*eme>lGVe<Kkvt7d9rTm3D@)Ws*8)l)j41}5mR5Fv#g|RhycOt1zv{bYWLyjy7c5H zqu*(890O-+07YGcP^E&>?)G1Dr(&roU_J(3LgERf1}OE*q8P1R!pU;=hT)gzH{b)^ zl@xgPX<EQd%hPsc@8v|x)4-6`3{&#VVZPRyLuq!ITmwfUD3i~mk+ynTFgj({W{*x( z*e&3YoivK@407z-isiQzf}u&1m|ELS(}OMXzJO%P`@!A9%jDW8XUB7urw5KRL3J`M zGsn@lMJBrAaU20g*$JkD18PQr1dLY=Uka?Q5Q{1^1q{UeR2i$1*i~acn@nrB8<m$W zz1EGO(sV!R6vWwc&{5>1%*X>jPaBCWvWHR77rHEnM5z*Y-~cR%sfg1c$^qP)7Ar`L z880p=V{xwH?D%^vc$*L+OL4TWc|*4Q8xv@l<}x73Ew-~#)TlumX|XUp%y>W*8KZ2P zV4Nw4^AIFcOh|`1dXwccP30tdT>g1F>9WGsu>l$!<_832QfZTPY8``A<oP(ZziEnS z+tJ9$(a)hiGKy=aQ^t9AjvnO5k1z-%=p(4%AF3VKpy!fE5-K@5iPC>pYU$s`Z-?YK zOFg^WMLa!_<TsDZpD5cK#!Zab@)uXCP_vy+A}1Uw3`9vA5||T~G=@V~Sd1hbb03mE zF4$kP1~Zzu205m@!+x1ntQ2-ckJxY;J3Io(KiY%KZwX;ujvfb(NG;UN&2&ac8v5*F zb<hU%nSAMpK!K%0WE1KRk~%Op*uRfhQ>6EaDuk#(NKZoW31b>AvFH+65|S0uU6y3X z8A!^M?Qx~N3{`kG9bQ6oiASl7v5{4f#fGTXp-Vn%^v7e1RL?D7u|7>PK;yKr6CQiN z7fW0sqQNt8sd6U2sM(7-1IEa80%;sF92q+}9EX6?Yy?i>1Cr1iTEcJRewGxPcL+L= z2aCuRf)tLhD_oHzazt>H%X}n<U{a;jlmgL>u}36#jUqM3Qj2l*8K@RA8wo#Hnr`9j z<~N;az;hWO!v~Iv^y*;fiJIsrYM?@W4c9EdtKF?aHDvv&-}Z6M_if?lK(ev#)F`M* z2Y1u+ex32TKZA>x-SX~zoX4P_c(KB3@P7FD1ev14>+`(YjqMtKbpKkCLz7Z7jF*#Q z<K0T1ld==jF=0c0;OgpKpEYW_({keD?)hCERdR8C_|)Ko_u2jNb{8|zY?!-SaYaU! z=TzaGlj4#JvVx>tv!n6}`MlG-0JGej@x=)7&i^d%<F6+BG|GM7eN;8WJ52Fw_u_x| zefHY{uZMd|bIMVF{*ToGufwKE^!ub;4#zdqh}UuJ4EA%{zi*UzpES$ixMC{tI&PfF zd`es3byzp~kBv7>Ctk;$Go2Z}&PcP?K<m={HKe2OlXNm|R{lNErg*o!x9_{04{R+k z-RSdBP0d!KuJ4hiiv!ZyMju6Tg>3L!+4hd-36i`pBq=hpiU@%KO90%nRe-!mLTU#H z+DUyRq;k}#Gs5vBgeuWQWs?{ikQqf{2vjzdc-+6XF|8h6W50-6D3@WwW737nDLLz% z^HH;M7P4X;4w_#tuf%MpY$sc-c=3$3ph&oc<-mHY^2{NqNdqDLI0Yv@p&J6=dp&&^ zxgY=$rvRr@!<#ugD!c9M>p0=&x$-KZ2E921WGK-4it~AtBmgV{dpHmMgfxW@;m=cT zod2%7n&088ckg3NlQ#`R%r}d7<Md#V>=M1<DaYa|!oV_Ii)P0H1ode&C2k)>dMd{S z#anR-@kH!_Q21iAk4ub0y4nY^73@dpv`Z#=9VG@&khPWwCa=zYG`E@X0AOC8i2kOJ zN+zvO0G71!a#WJq!*ErCk(Sx5fYKIh?f_mZq3)fsun!3#qFGju_mVzVzO@wr6NZ=z z%%!~gdGIKfjQqY~_tJUTOH)hZ@Jp4-?n<we;C_qjcC=a}N|)(1YX@1{2oMBo@(yZk z|M^QyJLWAYx&z`Jt;t1Epe!PzkB;m_H0rf^qBp9`vJ$AqBt-RoBX$%AFJaBipli#V zi#mknBVS;czyg|$V!}cjJ1zqYR`3m$!KQ^d2<NhaxMq_4LbM&L>?_%o?JcXfy2tOT z%rzhwmt8&RyC*P34)cNy<U&5bRm|u|S{Ea;6b|CwK>dnVFgvn!#aGc1mYX^35SZ2r zj)iz#L~=os2_;xHjk^4!7j7knTU6**c@)cclDka0b{3C?ufeP7qQvJn2MTKe^%rU( zgk@G<#5~EktiTP8q@9(YO)+H=NSV0IdDt8=v^Xn#t*i>%ym_GmIJK0|E)ipddeMj( zmsh2fPiC|z_nxd5B&H#{Of{3X=Faw;L3o~WDxjYW(&6{158AJ1e_4X;+AC^u{>w*{ z62l-^zHu=cNnt&>0ixq~U7Q4B7&9d%MV>reD1}&6F6-J<)m^Z<10q~HQ2E2WU4C8? z{~@B_adZ%pk-jm=G{wbs+}?wss%1LU_o6-W)wI57-~fWS;>pWjNg7!Dkla*5wjvQo zi*yTAQlSPiA$`-#l!D^;rTo=xMe9@+(*?%#9ZZ$c#K<HzCJ(jjy5JUb9Qk*+M*IQH zs-rUq$IHrc?X?zFPi{XaF)eN?7li51rICTg^jQr%(v+epky2AKXC~l?53sF>&AN&l zX7zt@(&H+JgC7ud3j*R`^r#3h>FYtFrC5#<O~lq}l1VAZoZAPvv&gdQ(^Ib+5?@J; z@$U-ghlBG}=nIi&SB&P7&e}#RjAGIdiw&$aK@7Cx0)AYpNsIaIF~=$J1`w-ve%Z?J z><*bHML5T#Q5PHJx&6eSdBwnw-7zqbQ69~7GCBxU1u24Ov9d`736W)C;>ex{CjW*c z6KcSDIV$g`Ya&4sD<Ns?n{4<dPE;n;%~vo0xvwh6#ADyZPz<kf6Kzgv!ndKaf;37B z)ZNgu1$z%m!n?)jp`pgLHh6@3<vgqFK`@*CMeYXnLiAb=3T-Ae8qF#wOs`@=vF|oe zY3RYEuNkVEs=1TZgEHxFj@ig*r`HZSt%X$$g3*h2LDr?m3PAFwE9TunZO62+V19#p z1o;{fW4|NB^1V%5pr^A!q@{3cwySFOIQHp;9xOt_z2d}n5h?MP8;tfQwRQ1gZW|_q z!Aiz8WbfxyA!fRh#j{{-`OX`k?fU?xLN2_?p_aL|nk$-qmbNi@HAokM#D;i73!rl* zE~VYYa~tGz{wSN9yC<fVd1QR=ga=k_ykq;(SuxzL3semp;cVQR&TiXOz~EZL1z={D z0|cWenMWDfs|rTaX|SE;p}izO9UP+N%>?JI^#lIwaye)|EqDqc7zDK#*)W=f9h+6B zD1d7)Xr@*MekIb12E-U=-M4*~ySw*uH%|-Wc9)ljS82;L+{0aPZsqqlf2Z$0zD2Wl zUySb?e{V_e^ofR`6EeC!Z7}EV0^youcODu)XXTUoZ1jRh57c|i4|-9lhPSt&zV+JF zGApw0**qybA>^|4%1)~LX^$UvB#?Lt-d0U1q|km-F&B3{KK*DnPOHgSQ?;DVXi!b0 z?MVN;y({7`&_XoF<y210-p4G`g_j@ES6+(q`ze2D#^0@v`Rz)7(tDpGn@2~n-rV3l zsIhea%ca&Bfj8Y4V8njTj=JXCdhQ`47Rd9fN~<?l|An$@h~XemZYH26|7N^w!1gg6 z=3r)iy+*q*gnSo##boAn8Y+w5KScFC9bI=6kEzQ7b|1^VC$(*!D7SBV8QZR1)e8*0 zQ;iKrB4K~jH!ea0@M#k<omjW~SY|xYr#(roQu6^AT$t{O*wBXKI03;#l(i!eG~|nm zUz#m#8l@nyO9h>11@$$HyTQx!IP-%A5@zxX%Vo}z_TbZ&bfw+Bf5lamYGe97>audW zyK-g<{&1Db*a}9|1<_dDn8n3dyiwiod|K|hS}eq>+UB}rNq(WX!ad8&8wNpvzSzb5 z+?6+qPQhc4GJSQbPj4@NiBH+{wX?Th=~o`4>z?E|GDP5KeK%T!RraWSebacnXgBVB zM!|Tld^O;)-fG`Gw=mz{ZM%+m9N^qUxpcB^|0{1k>N(lY=^Jp@(9vu^oIGN<2jU>^ z2{bC-eb8x}2LiM5uiAaX>vkKuvRzz3J|C2Ca7f>+Sk{0^>ruvunIp54_P!BmTY6LR zMzutYJcm$XX>C*BY`eJ6o^n%Uw>#IYZC?v{cKCR;x;sBc(0ZD_z3;9b9-hBF+cx<& zeN@jE)^Wd2?*D$h-{9@={Go2x=KJ`%m+k4i(}#kz#QvkLh|b5yefYkny+D+-N-!Q_ zvR=(6*&1i^g*T1h*z*r56()Ly|B+JpFANy-zm5UBO53tor-$#|dHunF4aK1vaMc;S zfzc>!mCv(OZY-)Or=y30K~9YDe!Z{No%Jt@7r<#&90S^MyidEB?7$%#)B>PmKZ`Wz z`0PXC&-yyRO&;U-irK>Y0}5yQssmN$#)KZs^Y{Md4D72hqn_|a#Ay31$;2+MIxmK1 ze+>_9M9`qd$=1Nu`^+;4Bulf#UI<)u6=l*z$CICk9{cVT#P9!xuk&1OO)s{%isc)} z2EVJx<N)JYocX%G1{K)l!ei;s7s^O;USnn42b^Z-Z%f7UTYk3{!~psa$vvh)`Wbhr zujs%;Ladyf2RlzjCiYIWOz_^7t>@R*!Rh8?u6M#HtN&MEvt*c`q}N~?y+sxmZ?Jrx zBvO?T$*++|dO!Ji<a+8y;2?*Q0s0oA3+^%}>81}kYVhG<SPl@Vg3y$+VYRIyc?!uc z`B6Ks{ed`zRdKgs2kk}DT*@gXgNLO&XpstyWL791ofPGUI7$-1Szo(^`K+zGpvl5V zBBX-y31&_7I*oO+48on$#wPBX1~t0%-_Pr(-82iU*~O)?;9O0hfd%{^<%P&@0=mmR z#fevwj3#Ajt3pnBm(^Os?2$z3r-yVg!6746rpimz3<Kvv&M6&?^48Bne5RU2W(mbI zujS#W^>x-@>!3S!CBMjGMR9Rn^l(v%G7Hlh_mFVD{*2(V9bbRmHH!~A<+V4i69Im$ zg7h14s+JH<S|~pdCSPg47+@AIA-?4?%WN{%B>gJb;5fuBqEB=_#PslUGNXUMuq<jR zSLXl&UaCyIFfPg@2>ztWPgZW?IDKBA))sal34d_vsbtIOEPZq5acX|2xq)l$kyQ8P z-rGpl8@`*au6z)*p3@LME7yL(N&gIHoJs;zncB4*YQ#wn<57P)%Qm_Us*n6MNe(+1 zXZ+e!M|Gt3n5V|N9H@V|wM9>dEF@AFt&cXu8Ow$qgV=^MT9~*SI&^&7bM)lkWl^*P zZ-O<)S>!C`!6}XV%ynjfAuC{dN0WABzu3;~DrGalnf^kUu3QMIMoau7@Z6@gsuOGb z8~D1V8o@J|y@juCD)_^Emn%g7WnfgaE&A;}CP;)NaqR}-3&e-SMDm|HC*wat!Wi)X z<Msca&b(6J`mxQx``rA|GouS@Z2giM$D)Cu6zVk{!3D@;cG@ttnm;m#{PuRftVLxo zJJJJ=3n@l>zy9dp+Nm*%>;=NN-8_@!+=>Om_vIlVPo4CO(ZvV3^#Fl_CS|g{k~`d% zkpWOvOoTL2jroB*wd39apO8mXG)YaAO4Tb>I0q+8Kf|h|L+pyi2mk>0^LJir?GVx{ zI*{?ZU4rg*FKYo0QyfN8x`7U7&EOcy6N<H>KB@++`G7U_!n5RJ494<HX~7W%X2LPK z1;C5580O>S=|l~ug17`cG}t<NuHfNBUr2sSqQlZfAsRW+!-QLlH6sQ2ilQTP(_d(} zLUYJp>pN*rC>&RdA~@%-QKty!*@QB=P}nnaHB1{PP3I=(1UTqgUM5Cl^+FF$7#dU- ziz|)x4{iEYkI*~3nfFo}mBG5mWAHoanP=e9?#VQk8|ulQzLt|;Kvl%j2lLQMi79IC z1W6S=5}6p6QpP*#4ceP6vAQ+S=~=kx6xHc8iagInZqX&UnhlbtfOEBhs`2yPDoa2X zcH1oX5Cq<srhO*TT@JS^Ij`WJ^oJ3pUF_CG!-9`!nkp|_!;78=xTJKjl4rP|Vp&-b zTPd7SXeP}GE-yb0I`_M5o(+P=?xO+Y8OrO7(u)@b#jt$z4CAgGZy&(62n;G`S9EU@ z0o=_43{MzVJCCqeC`~`8S*z~F=<QY|&$0#C?W3p{X{FX>Ny|Xm4bM++;-71#1e<sJ ziM$o2E91{9PDun>s}QmuhO%rnQBO<>v}6>HQKqBPPcLufuUpo4UY<WLZeLrw`80p> z^m~Z`8*2t*jc_Teo3zmkOC`(KugiSE7VzXTO;Pa_ru#t+S#)@cJnuI2y`H(cy1Rch z`4~4sxR(SDe>3HQ+9b^mYLYSckTkAHn_9vNDq?By<UG<*XY3_UX|P(XRT?#{3>bUj zv0?@3Js1XWkToPvXwX`;U82~ftp-ep>>bf}dVb_k{OtQDv#SElgeK#Yh_yi`hf7b+ z8@PVvRnXy$0RIkjVHe#b)}gpN5B`a)xq9>lHoF~!18!<8B>3||@Bg9fEr8<avwmUR z-QC^Y3GVK}U4s)`5&{HwcXxMphXI0naCax@H+i1jySw+xeQRI(UtK-j15C}-nbYSd z=j4{o#2%@Ibb}a48yNg4Ac1C>e|c#BnJwA>`{71ssfND;vS;I&_OEQY=w>p!7l}1C zhO=(9RY-z?)*QJ&rT^CRcwfI$Acq>SNyLTXS>p9~vaHsK=mj%!oH<hBU(Y4~Dl9lj z$dU<;Oy0|T>4o70Rz#X2f{i*}l=U^Y0Vd!<g{0p85T92Jm@FeSe<w?OR0MOn9bp~r zS+&hJB$KTCBnCo0@lX82vy;(CDzXS8Zu+D#IZQAMnahY!xp@4LIJ|<OL}RI+Hre(7 z^OKrJGrtykHJETziX>h&EcXTDaj9XrRmCt+r|MvbaQtBQIEOeELX|<Ik*X!pMF-D} zd_E9luH8!o17&!QPe*xQ>@Ae50R>38`~?#_CPr%5PE-IBLq=>dq4~zEMYiNpbN&=z zAq2Hl^C$nl);*&Xb@CGmhR-UEFM7aaS%g;ygCU8^kRMsw7XBh{;Z+=C-aZiITUbIx zSv%>flJfPMCNy%QQv&x^D+o|VbL$bix2IT^03#weq#)})pTum&Krh6`QAQTN9fW!V zv{uGb;b%4_9Y_!yN{k<Vz+3NUgDczFExtA?Zu;uD3#*ivKsI~>cv?)T%hcXyDGWbW z*QaSuoxln9XI9I6nV;U;EI_R+Tj8|$=sR-m%#Lo}N&F<TiYJqv;3})x+8tBq%KL-i zF^XTG$DiPOy9YWn+rk-VunsQ!@baDSK8K^ZdAMDcj7D|7=ob;}Wil0uwxo+IAC*k5 zO%_yLEBqJv01h2dA+w>-Ov)f<<InuTYq=PTW}MEEnQbD7mR$ilPZep2roW@K)n0Q9 z*JP;@w-Imyj8go;>9Ou{<(P_g?b>Au>!0%{rS<D}9>6HI8xz=tX|}<&Ah<Xk<C8I; zSXhhJoanpQJcS+S(DM4o8PJb8=VnZG|8;rU$cKy2mzT&8IM62l0>k=Lh+LsVqu{C; zh@48SoJi_85En#32V1_58&9xLZ&wUzhu33SRzq20T=>^tIm)rkys>{$S;(u9Sf&@n zU4}M4(2a{tGCTWJ?|!#ZLAfkMroDIDIu5y~^~1Lc>-YpUs$_V5i1OPw%E5f~r&iK# z{Kv^WoDX=vXr@)(ee|qkMRA29FR=*<ETH}nm~6lqLH`QO|Dk;!FE7{sAqH8wIsa>7 z@JxHvhCm9%ccc2Sd5KwYeSW@~1fgqlAm(c<fwW1WcBN!fNd2b*4e7TJ#a>MmxEFb$ z%vL1u_hm)x`=4F!j#g8}LnGNkRXIMGv&O-ahQum-t}IL8P}fic>mQl)SUj%d{<(ws z(d^~Y1Zl{Hk^LiXPAGy3>j!=iC@lIsnjWD=P4!4-1_@Y6TB@+}Y7lZsIZiEfHFL43 z%YKsrJ~0)J-A)Wl98`m4Z;t)TJPwhJLKr1=8L)s)!sN6hZri!^^CU*d<vBoye-d{u zr6e?5s<4=yuuhp-ZVfE!Xgg(EOh7>{iM4sj#CQETjvR7%F*{CzGKx~Z{@Qs>2Oc#E ze3-~_W&D^cirBn*RFQDZSkjjsS*oF2%{B=%+P+B0>RhQ3N7nou;cE|3pfmA6AU}{q zAWdYb;0UCe^i4Am8(anzL@WuLkYp(zMk!RSUvwic9!XOiGe0@`Yb=gFj5N<sF=Z0s zP!1%9LegoUEY*#2x`Lts-sizxfjP~1`uu=iel?%+K^m+vG-M)p7jb+L#!<QUL#<IU zJC4F{$Te}LekBt{a92i{0b`oF3KFUm7M3>ljk^k!46$e_haKR?;Qs!KZ3@~9pkjPs zDWW@M9hQr5<tcq^m!L@zGG*JiL1Ts5g;&Vz@DaksiQiQx*)iaJijtm5iU7G>yn3;< zv8W<nRL9w6J74<5%Tsi>K`cfA=)olMD6r`03Xgm|Ajv+?^#K9e569Waokv8>$>nzy z{B3;N%?H_&$zK3%)aBu`Z`+Oie4A12#O>JYvx{AVfVO_WTCQq(T^XH`<+w{S4>^j2 zDJ~7<=HdO#p3hQ6&&GE)=53byy+<$AH{;xU>*=18IcuSY5Q;aD%qG13qWw1#iXY__ zm0rYd4yO^`Kft=^>K!&*Ejk5BW2Mfuuz+Ayu7!P?on4qdzv>nFl;hp;F}pfxUFBhX z3;x&p=DOGG)^ioVVODo`w%*F%@znYCaewgqU>iSgwqX|YhTDeV8tUEw75dEtTFJNR zI!JZM4Li~<@>I?siR>4X^GR95wNdR;Z*C#j8_(>Uj_eEheaqm{c?$+XaU7SVn#{qn zFH$M+?vgm61ae<ARdrB4qP*k@?Flfy_W8cD08wOQ+!C2nMyyKj;-aC#xsK3JeRH?s znoZz^R9M8i+jA+QoVe)Ut5QRQrcL5A@Yv;STh&b#tk`EeZ=BH+XRi6m9QwyB_c;}H zP*n)i&KEcQhOK+aeiiXJ?0s(T@OppqD0Xq1;I(wv1L2wE{YJoZ<|A>SJSv%y>DVPw zCpqNLPKT!8E^=U`&;OD2=NNgeSZ!`Z1bLf@3vQ}40ZT<Sd8`vl9~r6?A3K*I-a&YM zIN_?`8bS?JL2SR^%de4#UpB4w=+~Y!&RLsVl?S<*UVZza1x$zNQS&YPE%y*9=X--T zPIIPFspot32SwiV@10!3#8b1$H_fjV-eC(*drzuS-E~$3W2YT@`uYq{<69x?V}9pK zQwK_#U(&g9^Oa$TXTC8Or~~GcZ{WZ7Y&fv2kU56luQp2d*)*p`Zq1W$e#5JfR3|Tu zou{#(an{%^8_|d@C)1Ls3e&@ErE?~XiS9lwORsU|r4VUm$yj7W8dqEGR|Unsxx@M{ zMxSJwwSx7Xz9W)V@4{FniJtDEE7V%AEqr}|bE{ut057`_k=?Yfp=gwq{ks{j9y_~p z-TYuFEBlj)guSwbBpp}MvnBAO1N{Ez0A?38XB#Z>qgwzLUJEFOxDeIU(WNI|g{V~L zf_|^ha`e5aVdD@DaimrFmEt>T4VvGcWh$B*;sQ5cZyVwwUJoVdLLpbDcT;548Fe~h zWknm8*M-<Qt3H+P@>R*mQS#LO@{*(L-QKkd(~)`R$WxW+apT~%FrghwbdaM=IL}T_ zFR_=Q6jR?&q>G(W%P)+J&bWw^ZQ`X~8$~aSofK(;$2%Y(%ovw8V`5wH=Q%*x0+7do zkH<ucQxRAC)Z!hSUM5SDDapF!Jcgc<5a)F%yTu^;pQ$o$fO7xyJ+`HQ`~}v++JRT_ zoy=R}KI{~8nZ8cTta_vXxQTl&8#D8tng@5D)+7_&*Yz8?EsZ1n>*Qs3B4NmTz^UWv zFU4i!@EiMO<Mf+<9{u(3|2p^A)zut%8Mn=+($k(_;pWgY;X+4)*|*!oe=l`a7&=;r zM2v5;a3YjJIU^#m0c7?6wz;hQ>jjjKBE5qh!4RJOA&;_i|GUEGpEtNb+0B1lasGRw z6slOP#SNL(PyTsq5D{1$r6d@tvyz|UnTSnafM5_f;&DM@IHEYy3SZOIm3NeHmMkln z%hw(iOO~V0!5ko<r?4WuyF`yLP@*8+QaL?FY~X6aXb%?72qk!V@-*#b?l{baC#XV> zNHZmRqXjVGJPNmSlUoHh`2q9t5SQ`8Bws;|NpxI`xM2WuORUO7-k=^O7F8fS7|xO! z-mpWN)r4jmz>?GcI9sQ_TLM^e&gcCuIYs{}IhEKwBT-};%<?E6swGY3zpcL3&u$$a zy0IKbJ4`)8_t(eA_m-y4mW!5hehxNcSAg*d6zK)8UuhkWLAPMi+@RMU0o>8_De|P7 zvrXNBJDux?Wz0oY%xIV16tAuhoZ{m1@0w7v5KfaB;Fq`a0L;%#&V?6EQ+UDWjj0Pm zk=zXMMCO~+xrFrlG99(Y*2;eDm>Z}+my7n{+_$iht}m}=j*IIEIa{=i2`KItX)~NQ zxF%J(F17g@0((|Bs6H&;3Nmb48K)UjJ>dOk*+~`1ZIL>gFmYDfrtGE`?Xo4F3;2Ag z1^xP(kJw1}X)%QSu6JUuNb>I++O#CD((44Ka7QNk6B{G;Ekt)dC(we&`M!r)mhn9n z#e&4>#+U8|B8~l@v%i`|#LbgR%hpIiu2w*X!XFJXqnvcgGAv`))`En-`*X{R3hfSs zCKnev8$aO%XP|9I6cV;d&NVY3T6G1q-AQ1U3+EJvCBo=eh&zs;mX9{lgxwi5<5OR; zb&MM)RJD1w8Wd|!|8+yVe%aOd@^{%O2P``y^|cFA*CSFH`aD`wAEBlUdgNUSgVkA; zb4wNqaMyz@@*VPL%keBy{FKwK-sS5zJ7?rO+|zzBPW<GWSYqO6$H~x*t4%Uv9My?y zr10ja*x`@074R{^b<kd@t1#CduWRmSs|6otLVAX_Opfo}W1oIWvO3ePN4{IApj;6m zOLJ{Ia~Ao9IKrd_e>WKXbpTsF+%!XEGW97)bg6sUMk<T`aguVxvw~T$;nXnNB~ng` zikb2a%8XFo^G}h;`-he(tSrFkx_|xr7uZkAvi+(ga6ZEw2KcQ7jC#Iy%afur!(i#B z_PjW(8gPFyDGZe`^%jbWRd=p2lf1m701)e3crnYSdcey~Dg_j6j}cc215`fkjej)Q zqPbBm6p>`t2^e$E2&GZ%S7<A86U5Sk{y^OUf8zR-#e9kxw@5B8$Fw~?U6-yVnC~6i z5`fBwaPFQaTwupoQM%xW(VxBZCYQ#-;?z)P#ETEHN_Hp?(8w38(gQ$X78Ty-Qf6We zY!!9V_J{#`YqJ@YtI<fD(0VMpitR$$oJr&{heI6ou7b1|r#~C*ErgZPjC3xzdg!7` zO!RecZ~g4nt0_Y-x_|G*hA(^V1a?3p=re9a(XAsrD~_t}K!a<A_xKP?+3te4?$66H zJT`fw1PaXRPs=%ucB}|;>~)Osn&+hr(S^>riz%ex!iMex>9)mMm31ZijRG`gh;}CZ zp@%H-W1>lEO?<gj^zfbg`4WUUdyLfzSk4`l_^vT|6r#$TJZ%MuyjKa>YmZx@=Qbx5 z(v8cufChbybF<|cgJubafU;A+1>bBgZQD5vjhDRU=C3UyH-fc=OnvgfUkc`q6lPS* zRP#$)Ki;!^Ccqv-tu{NmFo<NfgdPo3@E$<I`cgoACPKYT7;HPzxDqEf$Cc=bUZ_{8 z2_F2s?m}JoHI`carEh?Fyrk?G2Yri7_Q-8^rgudW^20Wl#DE<oleLQ|=ubI#817}A z5ON0H+5-&$veFjuI0-bjD3{Hd*~jEc$J}QxJj;Z>nDkgFfWVHb+P=~c?e38FV-u8+ zc3FK-t<n<`=vBg8E`|DboX9$|@qCTQZD;<n)%B{1wAcvh0ztk@zuSA{(jC(M)%~HC z6{idJCi6l5IxdwYVtXHC3&R+B6Uv@#rloKC>#;Zqzo>H<5FGAk_+3r`wd})_1kdhK zyc?0Ge$l4AG6d{XrT|Z*;idOz)ALkQ%cxA=`yHo<tplgi>$|&GXCKaP!l?^CZsugJ zH?Fkh1i@)}uKU3;Nhx+~;_>}Fp#ohz^RcHit?dp$=C9$1)sY(|+frmM%a3xgQoBAF zW_{jjiLEFx#62a_4Jr;}T*+=<jdMFnbgM@gzf->MI_SF83&-lpM{%pfx@FqMe(HjM z4!vMg%+uB#Sc8yx9LxLGWL>sNOMRwuw*hiKMxEH61&xh`%0Axj;pLxK$zkEy8g^|O zoxN3Lhu0<5uZ91~v18m*{RZh^NcmtkbM^6q-lY9G)lRzk<I|am6X#-lU7o#1f`Hf< z8T(KS@oiT$i*s0r!!Wmdz2U~2e`Ex%;P@lM4zbA4EhQUOX2f!HC;2<J`Dupv%euMk z?dMa|77wGVBiih~_NiY?d07eDZ~4t<B#WHNs!Co;%uqH;Lg}}1l;5XHJ7{9C4J{tI zTScgj{`md#2ke=fo%4TjC!p()&H}VA{lZMTHz^owjAX6ho{3AKldBUgmet3c-lU3! zF#~P7+nCx%<J2cglAW!K!uA31e!zZ?ccu8v3n4W6m1H6!;4h7At$}Qj*Ra&_LMMr# zQj<jV5^|*Y5gUMtl_3o6wH;p=CBk${G2$DT-8eJOkkM&sm&tQ7&vn^|>zD|;5!vA{ zC;0!;X>T7UNou1f5#-}~G|;XBWk)n)6B~ntX;8wmuNw$SlT{Z>uXiP}R7A0lw+JB# zLlC<_jbQb`4rj)hRWFn`A3L`cBALs|R2l;R!o%NvTg>i$8b#F~&E4F<MdrHI&M^sf z`%BUIM?Qjf$^vLHUq8#rvAEx29*S<~a0zHW&(AP{YU=1Vf8zzK1#P`DM)m7lpAV<y z$ICvgD;%mxK!U}bQ1wi3#ye@R$C37W$e{rfnhc)vS8b{4Kuw9FmZlhtvwVG(q!)9O zcHRTRs=o@}qG%UjOnemSyY=2)x}rh}0qtEt$uJxC1Q@0Y?o_f$o7I;jYt^%mICoDC zr|mKQgh>f>3M^#4!5TdV&7(Z7m4q?8euboPJ!+~14VUq6xrznm_W}l;IUl+DSVoER zc9k1@>ln(=)p&@PmL3`{;zMX0a+q~<`LgfV)~s3Zqo{n{IpCQb`hK)mMQU0bgwRNG zDtYsC8);iu;J~bUW7Lz=oIl%>;0`hNTMRo6Uv3zCywh<-e|_vDe#+(d8mbLE;O3zs z93~w8l4ANs7bP=Zd-LuD;Ez(OF0L^Mx~k$F($}3f_5s6Lt?pa0Vx=M+A{;9Ip}`~N z_#)>M#Fnog@Y1BR|2_~2xJ0Ee^!CTjYA5d&y0@>Q-nrM=*N<P*AE)kN<4xN80pC~p z<s?!k?yRcUBc9?S>h_0jur+Bqu&d8>SHGh;<0J+iz-)vgl>qf%Vx0w}bV)L(Oukls z{%)?TR~`DgLAggXwoCqsdds`}`cDDF`R`2X{{%ttu>Kna#r0ngkT}z^bHLz6dGqV; z+ki9d@XN&2LPcYi4WE+@Q7&Z+`>|i=Uvi5?DJAjln|(FtF0w|O4maW#BF<HRf4Xz^ zSS!fxZz4a08^(&SQ~;KWlMiRBN=p}#>#D_y1|GO8U#dTfe?eQ05fObdY2`!57Lb5Z ze-EagrxhB(EHPcj-iuD;0pDvLzr4ekBglsdmnO~c+Hr^mp~843KRuC$4x`r?2Foiv z4h^H8z65d2*I1yc7{im+qa8T_9>Nzypb$t%M+wlgap3ZxPZ9mjy>x=XmQHhGz&c8) zQksHc!@M7xcL*_>p74noGJff#1w$du)q!ofmqeO{?J<ybbCp1Xk&=tI+FN2hcU*YT zth6&CSk8tPoX%r#r^8P?Q{)@;CQ$=*j#P)rz5REpluTDu(1n<Cot~lsg|@arF3|Aa zfVK#RM%X8`V;n1V)nHhnpgC!({w@f4|K*w|$T%F27QS|zqC82kFv=6`OaGP?c%?AI z2g#Z;Kl;&;C*6vAJzqIV3i|Xw1*dte&ls<otvX;tjvD?Dx3UvBHu1tHcCtkj)e0c= zp$)LU%hu=>47|^&Y<XreR3`v<AM4Lo@S#-@G4NV$JB=(SdT>UCPs9X_kcPDI9cuVj z63VfSsO>$*$wq|V?!7rdPEPb4`SdR7=t#A@VI`mu=#Dj2sl~p{PKRXfp>b7sVW54= zr-}1YSceW>KixE1=zMzUH)<OWA9UtC$zotu3=UsJ;$J6p7jmC!FZSqd8LmIyV=+u! zOzG0V_N*mp=)bRR({Mq7zZW?>+!=+7S!X^7?`|80hIajWe&yrZrT1BC-GMp#WGcYD zd_I`C{oKdttxKr2;bw1ReQy|<I0?J_e7B=pz_8=Y&*Sko@YGdvZ3Ck=ykyr<%{*}! zSHUE4J-IDE?J@|bNx0f$GMIC}L_m;oKJr<J(U4K$0U*G0_RibwLw@n|HfY<2MCf8Y z6=7R(@|vaPjpF{bXASvP>?Uyn!mct)tyecghe!0=AXjJaSSx@3l~jf~4|<;GVQPLh za&f3P?*93S?&x$}Ry?YO39-M%0(EPzyan9Vz?89#kkSo<Wfsq!3svaR?Z5@63kQ3; zeq^d{I~71)k3Z=qDb*i#NGU2cCx7tlM+$D;M*?XzQz|g9a8zypLhVO4_bGsdmg)XN z6)gL#X=VNf+iZVni+=Ht{F+ZoG#6lCKJdiK88DzSU@ixUv&(5e*h|!iOu{ekLZr`5 zT`Vw8WM@`*cqaZrCfVTlp-&J6-hXU+=lNmSJ8@aV+`@rVfS^!bhM{+TCn4Ve+c<-b z?DL5^g)`dvxl;xk8`QWp1zQ~z!?Ltl0V!8o>`3pHJ5H$2-3j}8|DK7)sBg$F%JdhV zFRnP8Uwark{oq%ySJR86@hDI5joPrW$A3+ObfujS){D({;(e$DTpeV5neHaESXYbS zV$e)ZQ=f}XI7%Lm#=hBd&P<zYG7O%*c^kcsFHI+>-_maOZ&vMj#(sqqUI<m2uf{({ z+gbdqJW;m1nHZB6lP;{VNhOUwmMB~W+Xai5ipR!jW-~GuQ%b5PR`eZ!n7TMJY<LGD z24+X-Pz~-jh^D}#ObUwa=|V^%HZYx3<VJ`B8K}03f@e&x*x25UlBRzqxwOK$B}{o> z7HjN~l8UNo`dT~$AQ&anbpQZDQ51oH!1~D7bf2rUTi4=eGU53+(t~;Mb6vmh@>bWW zqoG?1GyhuM=?}C?74zVeG43QnH<}9|4x{>0*KH}cqx-Z*%=62#aq#t9T|d)ar+F~p z*z-72d%^?oiHu_jV@QL(+HNSV8q1_fmlDhVy4zEXR|iRtE^;r0ly5V#aR0Glg1Ti| zh2v{J&405U930hv=UMKU7?rMbogE*gkt(-cSBIxrX7PW_TW&1HvOP_6ZUnLRSP+VD zwgDBDzp!$i2g^vyV>PG8hJZNauKML(Y|+Q%9^14Bc6xLAnyFU5+(?TJ{52L%r=gwe z9Yjv2FH5^)yJL{J{8aXzDq@#rB0s&oo<J@gKD|$K-F*|kv}t?x>P^&7_v#(0a=>|) zZIyWO*8es1=pM{w{QX04>=@BL2@P&xMva&%QMo)(@AU|*Bs10;L1_hMo%1XNx&>B- z!K$NFuG5d+dPdgh!21?|m)o5j-?<hSit7fGlNWPa{q6U#%Ic~10$tlM;QMP2+~G%i z#ZW~CQW2OGj!0XDA?@zP{`hb{I_xHLpk9$LfP|+$pun;~+JaE=X6}Z;Az&$YNuC?K z_c6|CBo^X93^)8VkC6?H55{D|!%qJV{3=w1`VXm<<3ENo{R5R^W#Rcp|Iq)U7S{ex zCumrKy=Oh)u+za{R^exwxV{+5AuKAnET*%ki{W&%*1Iq>@Fs{Gu}!h8XI^4taVURA zVWSoNpw3>*tFO?$!=xlWAWYw~c0d+~f7A-6eB}=i9X~Z)WJj~mX}Y3~)aH~XlhAT3 zPSLU+!e}%>E($`>tP`-<AHF2aNf2J8Tr1>|wyj-F5A59V#@Z0?@wz?n{Lzmw@ceUK z3Ic7?8ybb83;KiHs9+8kw`5Q)0z{{wS4lejhs1DGkvS^#)3i2=!Y~e|Ywy6zCR&Le zl}xN((P1tlAJvb1(vn&Ty0RfpuD17Wxb%^ed%gG!Bfj6bI{M;&k55FCy(zO$0W%MS zG0_dA_AAPpv!@n-c!Cg<%^pMeg_iCMPipoO!-A^I<YRia+GlX$=Od_F6)@_<hE!a> z6@0aQFB#Nh&M2GUuAf>x*7s@xN4ToymrS+SS`K%bT7ft?5E55lrcsE6OeG?j%lk}b zEnW@jOIHzYnxr$>ew$P35RNp_b@C+HVw%{5pLiN*Nrm-=z$|2>gtEzlD+$tfRdd<# z#8unOBHN=2buW~xOn=(!+kI@T9DTODEq-5&kwePUUgiQ^Up`8dyGoZGce+44ChD!J z-i#92gapCGicB9Dm84|-deJXUSVBC~$Oti&T3G_3tj3)-Nh=+_y2B?mxI0Dk*@`9c zWtFDMa)}$%lu`H|0>6)n_Cx)@Y(KNN>NDDNB!xZ`Fg#l_bZaxLI+(G|Vt@U`m4blX zY|I~B`Mx3GHi_dGgwxa=U>reY%$|lAaChk}VDQpGz{nZ)`UT45TLm==dLTdJP6pP% zw-1;TK{L|~vupy5xsD7CT-LX9(l#ol1KbTinlqL8;Hb3w=?H^1x#vf%JEnbC>N2eP z!Su_5(KNm#ki-fyg^Ps;22(``so`c0^&IHqohVuQwJ=55z%xL%WsS?p=A5AKy%U)} zOUwH5B<sFHc5ZvQ`>wi0@R$@zzrF4`3Y>|Lm%ByV4!lPlplZddG`*t0=a$ptlAWlV zxi*-q>aw*#3b9ec9f$><0Xf%}kg+iRLf+XeU9uO;VIsM^H}W1=G$*xddYM-T3Y60s z=%}b1E02ls6xa64Wb2Qa<fK@MY%|qi-_w=7rAVl8@IhxYyl)>13(nQM{ga+Ti8Y}? zvxzlNL;AxA@mE5c9%}XViJ71RIF#zG)OuT%kjwTRX~w)rUYu-^`4*Ij-aj<yOAC1U zm_@bKG0QIeBtM~<XbXD(NrLV&DD}dEQteHN3G9fn%%Q7LRb@H*i863%_EcbE^7qbQ zg2Tm7U}8VqFcE<lx&GZOWxAOUaOjzm8N6KoJ(bJrxHfC`?oux6c=Zc64@x`InZUFf zK3|j{YYd_%U(fZ=HwnX7_+Ois=JZsBz1P*`FX)`T>R5mJMq>YiH=T!#>wi%lZ~T@` z4*w;ar2H+LYy!$AG0NODRxyXTrpw@Zg*l`@`c<5K5#r|}RF}u|UDDx1W{mQ6fBU)o zAVLNM00pCtoUEBXeFlSB+Fpb1$Av+`$Oy=hAQ?8|fixXHI6u2Yc(fTU*88PV|LQ@j z9}UsRtC;Uh8BfNr%`sgR`LpJ#(?5|C?2$DOMHvMyPs7wFyhpt<6BM(Svd7oF6)fRb zjEZ4oveA#nC1Fj<Z-Ga-Z%bB4_g4Ejd68CdtQ0YDi~TU92kYuTNyO0@Q)x!erjNdo zI4yQ|9A;;&xhk#(w7Xp#x40N1gcwrRsr)#NKO-aEM1|u;x2UF1CZh)ERlHT3k+Lt| zpt|)Pam0I85r?q5`0f_CnI|gB=?e<}q~05OT%yG0?~@k~_ps}ra!MIr8wB`QNwK=} z+4SKRhAO)LM#*#4KM3jdW&Dkjp8!$v;&RnKoF*J@T7}c)Npmtg0$xrvb0TUNb_T2k z+swjGnN37fV-z##n#VuWTc0He7y&GR-DyQT(0vvZe>z%!Ka`YL2N+|1&3z_w7w^)l z#Em7>2!0hB_RN>VmUY2p)$%g8036jX9`5b6Dy_W8uQ|RG((UT5vdI!W$%*cbHTsvC zj%|)$Pmjxe?ba!Kb;Q&&W5YUchM%J8+%K-&Rw?q>#?_UGVnDtCTkuN=s5P6$B$e%J zQ#31WMO*(CXCb%3Ztq!_il($?%AKQcBNXVjiuf6c;Q@TW)2E^5D+v6PfU{Oz>(M4j z#6I^|N~lysr%mvLCT~#$tF+nd?|EffNT^*DpS!uxKmELafPv3pF0sS40K3Q-qnkK2 zmN!Qo8b9m1_;Ct5#-XJn%^5I-IqRmqz!zbj-SxSO0dR;Pg!??jf?kbj@zU7OP-1+a zXFT-7pXK=phF!D2;=49tJ)Q+Kw8bMziaui7nLld}=a@~xJWaXEy|c0;lGyTIiTk=x z_lwU@{JY6W+Ok~Dcjx;eKi=}(`{*2tfOGH8oNYMgk@293a%3c#o>D9++@J`RJ6PW4 zjfVNqm-Ed~xtN<8&$C?fcb}9`CVXt3bXVB0<py|vibY^ch<|B6{>fQ!{P)ep|18P^ z6S0NCIcf^V%8hBUYv4M%w#456>Lf+OQX0;U!5NY5n42zq+`FDRWm!IgASgobj2hv1 zfx&QWuYt$&!myxa1Q>~<QX9p6qrF9S(!+yEkqu^fWRx@Gls6^Uva+V?x225y%y@v* ztDMB9RN%ty3GK5X#&9{8R4KyzBR?R1bo1nEi3q|-f0rnUh;K{<^ejGtD(3@|(QYKf z<IgHR@N8PsF0Ll9>CJwS)sHNB^5IXG_}Z89W*H=Fu!t%H0>hLzrjJyK>=D*g;JIK# z#D09?G+512$=F-VM`w?xENy}vVO7lejy}c<DAPlAt|mA$_FSxvrO`a-7VY%I!z@g$ zZrhC&=0`0=R4j_Ks+x&iIgaNZI9P5L`UR1S<w@B$`#pzCw86s0P;ur>tUB)6dZV)0 zn9h3HkB${kr+H+H(@c0f%9)t0)4%qWp>{OL=}&^P9Lm}R<uK7mtp-|Pk0yzpME7S_ zVoPyt$`}lBY7JJ*)9aQFYZ?U{uEiZzydD-Jd<`u^8B1Ccev2mqfg)zQ!rvn1`)rjl zH_cRMI_##Zs>Gjj<`MlANrgynvsYWw*2B7qjktfwvfR{m_U;94gBCdBG_7ycD~>%# zb<f=L(k}^J_?*BzccTe~=(g+PjFaR}K1`p#H(kh-pMSt;K_s)5oiDi~0=*PMB+;>O z(I8ZrF3Cs^J<aN4?kCAi`hlIux~(aZFAo$?l0DD_#Wt|B+ZyK!&iMI)>K=94Xh!u) zbJFj%Y13MU7=Mu~HP?4Q`rgklrFo?v6lWq>kv368bCUa0Y5u;(^mX~(ofbZZ+Gmvw zfb)|#(N$%PQU8QT*A=}Ryn&iyRu9*B9)U>f<LV%A*yZHy;-e`}mR`C<)_eAK#H(pm z=;9dr+lnXFt$_EkfT{Q8>EX2iA1^TUIyyzvaE|;Jz$>A3kQ=bUIl7>KsEd?8*Iy+T z;vQKq%vKa@E7d29)f*9~Wd=n@Pd@S2zfCW{-yK$1E*qMp0(<4rLzx5BSq3b&hH<}z z%<cx1j|fio?}n@3p0>Y*%pMNAJEGpNJAS#mu;y=b{n^5hmLY$NP@X@s%Kw`Po%-GW zfB51RXflWc_D<uk-Eqzjs$rAl)@i{A6t!9TEo2_Xd4D}!qWw)P_d}5db48s!y!cM} zWoyFzrj=!ig^oUhCxat-N3<F_Bl|$`n)Y0vj<BQvdgh#4ec5>-s|cJ0sm{uNk{H0P zl74880@BK%f6>ZwbCXxUY2`g2tvp125QB~^UOssX<)2Ex4>@BR9T04@59cu#H0NUe zn^txJc4H-zF0m<-t6bj51&#={nI;0#%42rW<bf5)>`p*hIl+vKlGp%o7~*QR_fP;Q zYwbQbcxTnv(TPCscIpnJuT0qnas8`pF)V1XM~q69*0YWG2pl{9_(dX(xCK8`pC*u1 zCYzc^tUb5G)-J`>F05DGQ)+Y%<^92BF*1a;_?uP!^qW<dus5|4S-q;UyfY6@O`xJ% z@+^haSXEtqX@G6)GpBXV7mZBzR5`0gfHhspmk<7I>E_OaX8aP8dQNx4lX_xN%QCy5 z-KJ?=e(#$qZZj>rF17wp6Otcf|2>t*Y8T50%J+Oc0qyXq%iui?WhJFhNsWtp_*isB zflxLTGl)#B*N~79NwH~etU{kWY!{k4Io&4l&aVXDyj*vzU`(xzp|7>1qTK&1kbA9k z!0B)s8=knpI4PV&F)%hd@o!dna^EMN1eh<)G|o{$ysbfYBz%~ahItsxC+nqcFZzi4 zdvqyt?VZmCMrT#qe)vX;ouipV2I00!RypX|{P2NxJ*j8V{4T77MQ>d85jH=DteR>u zk7faS-9BSr{E`WnFOUDums*w7Q*Q3#&y&~gFn77*f@*B){Pw57d<n1si2u%)1Kb|> z2o_=Vf)wGs=5aO(X?OQ|%e%AafERZ-_NQ#)p$$5~l5TM7M&GGMe?+dJksB9Irowl_ zD5>Ol#2M-E1}tmF8J&VoqJk~o7%n`5tUKm_G|P^^m6ME<2FQ~mL_GMA_;FkJ+1k&$ zr@n%`pH%Lnl`S&Py?RMro$IDff}ZxE0|qR!&<<3PRgXvM%>XZ5n*7)5z3yBh3#PBz zVxw<&JX#qI;@5iH4$6)OzJG{DcHVz)O!q$m)!hFAs(JqVIRIzc`q8@0sK7Y@o4WDX z2F~C6qfJnIWHzaU!62I88}xDfHNCmD=Mp3Id8OZdC)dhjxoXu7`|(d9%b-oAcGvnz zJ$VR-<VsJ!?da%_Dav9l=Iux_IXk7|w|^Yn!^qFiXoSpi^q<yC3adiVqf{YpTd)EJ z&mOKt-ndyx)g$;IFQT{Rn~Et|s-b6V>fqY&+{9~w2W2S*n@jqk0X7)286h8mlv-S} z*O~yv$%-yYc8<!Q)T#{UtIZE8k~!n56bg+9-X3nEw7D{;SQ94#X`z7uUW`bDuMyV0 zCQkB?aCW1$IpA0;&a^h>6_$8j@I(0CwKk|*eKt%^CKYi*3^34G-$ulki_&doc+vS` zO&y%k!lS~2Fo?WS(;)OI=@hS*bW!bRq+zpzlv$xnFF$?`(tfZ#GzXFXA&o1tpXbrG zj479syQ`D0NN^U}0J~X<pl~W1vNC71+tL#z5u7NAUL%`O5{_fUX-8M3JcGQYTyhM- z+uDbxfo5a{uqv-g@TZ7qTH(lnP=%bP1<9HD5uU0=B>io^k}ZaUQfpi|m!fK+mb)EG zoH`}!6UV*gV#`rWX)BdjHN+y^ktWHxX0QRMs~8HRM$fu%0X{8>!)94KsgXm>H0Uj& zxe?8!Nr{Gv3&byQ6i(-lc19{exacWCEXMQx@hj35Sqhavo%QG#4584q@L^Gw7gVsn z2_6mNxqp<1CBq7{40h?U*2mGo!NI)e75(iTs*FqQs^?*$cStlYC7uNFUD(*ljZV)S zud6}q;ZC_r%pEo9E|c8%=6aD~44<J5nI9=#(I0O%c!f49n$NfUT&H>wn9LuRT`pm} zJs!dvqK6G1Yo534>%Ep8)(cPk9-mrI4DPz^*NJZCziiweeter_Zma&fQQiFDg(uT( z_?h|Xd7>RS(OxL)Cim?5?aA%e-oBQ5DdNn)3DQ>JuN4E+jy*zQ4%Bm&tjb0FuLe;v zs{MFzyGB;dE4b4LYylI}79qIH5hjwHrs8k?5WzTD>*MZPt6LB5%_m=&+nBlC7hl&| zA}`yXi=LaFkJ*rfKJU|4Xv=kxc#^(9mhg6SR%b|53Agv0E!U7T>pwJ4lt=da`MGtz z?A^Z&Kix!+Cwa~vwCH?KUs-f?CHEyx((2H=FJyS$J7^P%#<SQoW)8`t&TukwG^Fq& z0cf<4N@gXlY<%^m*ZC&zG;dg3SMf?G;FZz>Dd4}xvz-+qqrFP|g#@6=cBP?5I=4qx zS@3f}Z^l_8CTI3eLjZTbw&j}`(#r7Qx3h`o77FfY6{3O0^dpw(^X0)o7U2im#?JMM z_T=>qL!a{Z56_<MzR!zQ?fM&C+6L>-^ZP>UukFna-0rLA$8Mfq+TTi_#}A@AQq*H; z9kp;dOOLaPTUFx47d7wa3L@OH@YzFS0ghKV?6jfGB3T)!Sjnt6D2oxPxU`;?J`t(0 zuH&Be0C9zHjSAitc}6`eO|2^R7D~`2O{XpjN|WQPG^TqWN`!(Fbm*-so2wI9Di&lp z#W!TVyK9~@>l2MBrJ~VZ!GE^1RZvXmpvSr(8l0@kjPUN1DWb<hQqxeReP_U=WKfcb znupE`BS`Q;rygm2`d((6#%>?{gX+6Th<-N4Y=%?YT`Hel`>;@a*m<z|J+a(n1h#GY z)~u}K<VEsk#)n3T#pGWfX{6|j@-b(p!;Y*5KR2*tR>)J+&yJ3Lu4BtYNd4D_m<rrH zo7<vw$1DZqMzGxIN#~z4cGm1E6{zSIPninW$W(39Rtpo@J$t>^stO}aIFx;_y+^m} z(vN`e%n79k+Cc0&yIP%9TP8kxP`y%zWl=$d0JDo}k%28MQ3|bk=UlO6(V#g%V1U!q zq6kOeqi2i|&7-R2u)JiPc!KvGd5n^$8$f)1Gd3FOSZa`+R#1?gv8wZ_Hu}@#F|@N; zEI7Lg6zStKEBfbK<UwSSd4+mYDiwUgz9K)ze!0h^RBNZR`DkCgdQBna+QEC_S7B#3 z4xzh%&Nt$HgBK$`Dd5vpRji>+j=iac1ex7c&i0VQkChUHK7J5=^Ek9+UPFuZoZ&dg zD4R;4=Bqcr=9th1%Qz9=RljSw;jqNwDGnXU_&iQUriL+POvVQJQW!cyOwOP2*4-r) zN9gQf=oa%dS_i(`pMAEKefrNOuPRMNOA(I|Cj&Q15o9(p8Z-DGTVaNIaQ&%c65(WB zzqT9CIFjY^76bpkoqVr6B{?HE3l5$nP9Tip$xb4S;?4f&(O(b$uXBH0wHwPY3r+(P z5_G<Gr!l}6^zTbSb%cu6EFL3F25yid$Yf+NCY%&ojOn``LMx6l>#ofRCy`n321p}o ze(@htH7Cm-{YL*AckX}sjfVg78})^a74=yKQK<xqZZ}P@6pRz&{4Q<lF#cfyEW^$Q zmbUk=c=I?6AW+nuy$uJ5zMv4tF6RM91c5lPlOjvSA?Pd$J(vh6z|s~jMLL+pBYCLq zHg05uQU`C3MPG(of2386B_Rl4a-^rEB!co764a$r=XCgRXLT{#@Q^PxM*_9$^xJR* z8nW0~{s{rC5NJ61<qLYAp85%eWsl*<Z^O~^N<SBN1kG&T+lmF&hu?;yW>qmdl?|ug zh9l`+1fV-tyyWX}aB@EE;P(EZtpLz)gdiClpI(1uWIGqgVQstk@V!A_8bJ?_WHM0u zXbqMn0!}~0ijiKMrz#pYBCa6Dyp)(G1L)Xoov*klSiqdWcJU{`!7q1)!LT4PD8e^& zO_wZWxZ@%nMwAADw&_tEW6wOy;{w&N&caRS4`#!uw9#InY3O1qx4_qs4b1tlLsh8T zz5$;qb0S4$QNlE9Ydm0MU2GTTlRvv~-7#s>X@$Nn#qQQEZ|a?tCrWfWhlLU)idq(@ zx*MFU{Y8>?HPu{EwYEm;SaeyxHNpu;s_w_AArUcAW<#EaM!NC$c}sWtL~ZmvH=)~r zCeAo6>*Iv#GAmO26Uk|&zs*KIK(kTwbqUQL%R~X<-)5s0R(Im5CIzx8`1$<#f0&Jm zew&RvD{Tx0>N<a$jT(SvqlBSQ-Tg*q;~_VsRwddD>GD)#p#~;Iv#x;3TWwDI;hgHU zMCbL21oi>P8pyf2GA`(>WQ!xZHb#|<>dv~Kw%2*rw_eA#-i#Mhzn!@uKB!Coa_08_ z!<m~T2%5StOI&Vo*-Ey;H2O_Y+Re{HK;Ze>JiPvmzYvH!aiBXSTD(-wGMrl7w^<L} z=Pn<vTKW8XwBL8<II&uouE<|L$;I6Ww!jW>k*mx3r)$>$d9<%nnhW<sU4$#c$s4P; z)_aO8!?P3v&;{78uIvZ7ejsb?&De*E==q~f04BvNvc9_-Xv($U)CHPyjdpkRq<(t< zfwk;CN1q{cgX#XCLX!PYwJa<5e~<hExhSA6%I`qy;|jcVe=Q=H;znFk=!%S;)=U?L zhD49d544e%ij(f_NK$wWDn=min;0AzFg3WrJA4oh2EzafW@^gA>O~$5j`SSCYg7k9 z^euyR^A6SwN1lv@Q{PNbp2?qFBWk?Bu#qopv9B(4c%q(zft!r>8<`@yxlM*r#06AR z63nK)_#`Pc6AbszEvUcrF_VA9(!pkF-5N+TUrbw6!eS417hZ{EC`qoYdNNeKI|zF} z%9*ejf;rq;9joZb3q~leD1}N)XrMq#_a*Fhbn&8Ae)!eSrOBqy&n)E0stc<A_UTK> zbmMB-;@)Ze*jH6jBXn%GvAZblq;LR9ea*|y5K*(FGZI@Um4r|ME$#umk4S8@I`uO7 zs`JXD!62Dd**fON@h3r!m=2AL0!YrWx+!Tt>hw?3#9Ec{3qxf+v~7enKG9_pW93@Z zFi9BXD?hO@ml2I8uzdF&`z(9Y)-M+u!WR{CtC~7Isv166#<gm3q*++GE0G##GYhwF z*?Hd()}M$KAfM4-1J4pb^k60f`&mHgLWn%Dsp2+tEa`5#EzwUcUDe{d|A_kagJr<% z6_Jj1BW|9wpQCqsspRsl*gB0NBW-e-;!zt+Qr>kH#xtZtkXq2rkKSr1zceUqCP^nU zo5zp6@1IVM_v|kwJu<~VTBK$G$kB|d6?zN@;XV0Y8WK3CL~A#Kgo^whBt_SE`9d;_ z3lVY`b%NJO2W}-QQ%Q?)l@+))gvotl`^QiY$BilF5$TOFRCl>f8|lK%WU8^LulQ09 zSme1oJJ#%HD-KIvcbCu4B!qb0xN?a;x9CPA%=_!=FBfR9M@VCcbo^xY37<7UN!w2R z5ZAxSGHPolc|tsBmA^`uT#Gzrek<gH`=wfM=qG=&Ct-4@HPg)xC%ye=oeNj_1y=20 zGs5^zLaP2@w&hD%U7iy1`X~S&+sVl3Sqv_37+~ml<z<|rBftJUbUE0|WMO()D6gLH zFgF>Vjfr}=L&wU%hecXopU#oVm9(&`Lv-kPW2ub1o7%%3)$9W|vmnN4_LSUUVv)3g z=nEtaxxUq(LJ(-%`~LyHKxy=U-C6xC<u@IS^Bo8$!JK{vvq&qLY;{pxl}V<|Dr^G( zO$Y0sQOQ*y{icKC3EEw2c_jSpFN3zCi!X$`d>G&ZFpOC6^}Yv8&)t3v_8DdsX@O#r z{7nZJkC2kc_kcH`uzsJrGwMSy>5ujVq^Y3Mwu_|VW$Z($Eqtp){6<=?jmy5{`-t~3 zDb#jxmo!m~%nLf+5vYvz04k%g7jI&u7*QOcek-FNmp*-sJ@Vd+&u9frn#k1d(+2(4 zOAKD|sW)V$55v&c{5*Dy;M=8vbqLua$9G`QiZ3!t<U<V@LCVNoc-@__H1|nb5AL(+ z%h%Ty1Ps{mMrZ~bfU1KX66G5LZN=<iE7=Ebi~!O`4>LK541BEbDvVq-D>X^;Lq7%} zBxO|Vi%=2a7QcrY7fNwy%!FoQ-q!{)&EW}}p&XV*@r*ay%+p2VErjfd4*ej*>ewap zQq>6iHmgWEx35vU;KNaZn4f1FIVl?9u0S6hpDYe@ZKs>qFmsSq7iTTRprWrIpIpke zDzCJ<Ft3@wc<QP(L{<Vg*P4Hz9XG8kEwR9c_J$7$(3{%RJtna&yNpg)fsRkeIaa6t z)SE1bV7Kb;G+?9hysEWRzHCtEGfPw(`74+}(py>PewY-`q_S=RtyMu|T9P)te6Q!t zkGKV0wP$2c$Ip0MOGBO8HZ57cSV{b8YEm$1JeWW9glxNNU#n3t7v!N35<<Ice;cMO z>cW$-{#EVK0@v(9GDI>z10lU^he>_IA808y?ztTy=h8n@t=(t-q1%1cer&XP(=JQs zq*ZE4j;||NT-UU25FzQAialK>;?#)Cx$dSre<nS!GedOdDdhDWJm(gBr2RC+Gj`Qm zYFn0e=VO=Ov9$3BUf|oy?vF`)({7|9{!BhCT(1bCgR)kta`U%38Yq+A;I(*XiSmRd zs8`xv(sKd$Aq@lGiH9?Oi>HB?sdrOu1fulyHvq{yqucf!EnkX@P~g81PcYbgn3m^o z8w`_FVmAiLqk+998!^TT?l`L-J=?30`y)749MtQ{V^ghO7)SeEKESb^cUG2vgCDsu zR;L=Xsw<-pJTv_$%Y3~c=X_%<B6PLRDbF0UyC1*9KsVb}PY*xnZZCADKOlqgX*}hK z1XdR}VU|mQQed#aj`|DYW|Nm{>rNXB2TZp1*{~Wsg<TLUeVK+jf%gkSU6tK35~879 z#n4rgkxIW;#wW2Xr7!k7o;4ZkKMkWCl6&vcSuz;r3Oa0cuqdZu*ros+u?NImluk;h zSL=`We)rGmLbXY?GE;0H#vd(XY9G*W;|+%PA6}*2n8%iY=Yq#So*XUFJH7R6PpcV( zJTTu8itCdOu9rKEOGf4AQe@v|z2S@qzE;du7vOv--p&)&^h@0m6856m_`_Ea2hYFr zzyAY<2Aq7$@-GmLllLD^s{cZ=qGR_7Ukc@|%CL4L&8KxWb$QVQO!3>QFg%rFZYArM z&j;$fQZt6uhWD<iHS4_;>5o)Mnn(VIL}w8emit-j?Y=FWVECWD!JE*CLr#W-fH`!W zDfB|Ty4Do;Cdf}}i*Si|GU|wtRfHh4W>5=9q`-g&9$MG%iSbfP{A58~F!~sXA<=JN zL)8!33S!=0+D!F{$5MeU78NdnH%_XJAOao-4RD5TJQ9mU3-cPoxm}554icT40*>-# zWsjEOm8%0Q6Py=I!{LwpVmb$gjxQ78=aC*^HbbGt5hWuhJ<5}UX};5;_NggkPM00m z!wNQadajplh@CefCi9Bz<FxZdgD}NDx%ID-#o~fRk!KTVdao&pG<bx#rwWvw_8b`N zf!;77+HF-MMf5YHJ1Vx?JR`C&a8d6(_cRJnicI|3Ard}__peAff-KwRl5*loPo!L| zs0s~fDLz6F30q~M!>3QAfg{>C^+qw64FdsEp$YOttrXNcV9tsk9$<OnSvtuaRI$R* z93|=}bigFyJ!`&&MAhfn)?HM#Nb*84qO|U>>Eg;aaGeYw(CHAJZsxgWV0Z~<3+{ua zjtu1-IYR&f#K2}5nJ{zWvb>=S6m~zVNmhsWEVR(X(AaQSAldBvfGAdeHlELLR$>m) z{;V9ZKNpW#&!)<;f|BDuHxgF65OFbq;e|v_RX<-=+XB+rG);;T9tQ~b8<$EYAdo+H zf7f#@`j9cPKQ80z?9z2A^v;p_%35kTS<T#bq88rSlQl22;Bc%}JohDK&Y|7STCu)7 zFOKqH%tXcnRSWhknoElmWesVf*S}Or{<Z&QeQmCKqCR}T`e@tt>9K26WQ9q2b!mK# z(%bK-eUj^7hC@F>VNrma*+BmC#>1LQ*VvU!ZLrOZO=EjaP`l|K%@_V7=(;&v?jDs1 zwpBYkcKTf7{Z&1Jo+tCtYYY{WM~JGn;zL1b<FK<LqpF?G;?w8Q%vDZ11evu#UONRB zH3O2GTvvnb*1Vd@@!*Ii->k*5nXVsCmzz1+IUj73XMa_EDE;F3EcqqdSC6T>tNP@~ z_NkQDQ2p#>%FD^cm9yJm;b7K+HPg4G+xu-~Vqj7mvemo@nMh%s-@-&eQ*i+>kfd*Z z@(`K2q)nfvYhm(U?uhT@Y?0If$L?^mVrs!xhxxJ9qR3QttEtriFd(K7!~oBpxd#`m z{5&KtkfN~^y#PqqrE^xA0>o(<@7o!81LTK@a9@EPuAwNp-2o7UPC`2D@xFa$Ru?Iw z8T5b_3*fCpp0C%x{>3(GGg_NDRc`6>br)-V#in0_1(m%*3*i|ddoAXXb}kD0PA`ps zAhVV>rcPD;6IX?gouU&Dw%OgnT=&~O|0D!vTJ#M~ND%nM>HchSedXlz{Uj@z8&PvQ zJ5>2sw~KuSulCLL45y50nll{SVOIwC<q2(pjP<D4!6V95R<`)+fpeTx#<!cOSgrT- zN1_SK@vJqeIQ3qq{^lrgVv=pTA=Gk(v0|gh@zMKil%fw^S<Tdhk2c3Ui&8~?i?5v= zmhQY?)_e}B?&tvv6G`wIJavACsa+`>dd=%5%7Ra|+3n%hH_mU(N7%tyeNy^R>V*hD ziMbbH@^qjO-(J7z7`+)-&op@DT0>sLndyRH_CQL5R)H7_)8vRxQaT$*XgXO#mVht` z!#P4ef_)#cjP_O~G7na9!})*h9+^jwo`!mWzz*TTvstjhq^@~z<mBo<j{bW1f1Ug5 zY9zLKwi&dO;TTe%AwB<LJ8pk&)|hAZ-%Av<_N%(E3R(*dtX={HQ*5jFK3b}r+5b79 zjSZ4qHclY?f9~Fz>jDHe?SlCyAI6Zbzcv$c@i`<C?t(h-+dBVb;vWJ3>9%y(q2U$- z-Emek?OA?G;{DbX&<uPvOumh$Bzv38|6CViy&IS^z5l)vN0|K3TZNI0vr8enWHpJb zvEQ)^3bH=@Az5*9{?W?wzoB1sfnue<CK3JaTJ!xAf9TFBV}pN@Nl)76vN;VJN+yz^ zz*sX~Apfd|a^``PSX9fz{K#|gsCTNgfI4IZ%7SC_s?3j%L*Tf}V)6A7bqU95=<AvC z01S+&BeX)<MzB^-3|+sOv;LiHjcnl0e6C>Z<qo~@hLA9gBs#ST_{M6y*d&~oOsPrK zVycwt#&&N6lhSsunf(6VhcRbF`ElVSYiV9k|9csrn*~QjF4V@#r3rZ#0MplAfGUEq z9QBhND28CdGGr+#l}#N>SfBC}X3hSyljpm(#%z%jSI#qkkVtge$WQ|k&%6Rcex>5> zg${;E`GdSo4^31v+0@BszP(WjXPPTkvJHHq4^1}ml*XNHm!2ISt(=BLcpXydJ<*Zi zs+&;@hUX6VN*H)-P}<9qI<3h^^<w&RQV8B84K4Cc>{W(oZ>ax|vbPLwYs<E_6WcK} zGcz+o%#1NJGcz+YGcz-D%*+roGqWAX_N$!kzTNlxQnyaaD%Gx~QtcnEsiiU3n9p$0 zO&n^9rE6f6uMf~ucY7)R21O|<@rHj|HzC~cRakN8&M1*~HO44ikt=^+OIs<k)gG<L zVHPB8FhGWZ8ZAPpy)=rosD8*c;ec>C?2FOjM6+Hgl3Cita0MFjxClDwieMskIjd^2 zu#-OI5ir(k_mU+d!U4>^5tZW6e0ByGjB)>L;Z?Np_XBBk_vNNp%1J1M!P3JMj43+R z<TMP>KF=Ke=$PErs}4Uy^cH9hoPL~spO76B6$UcVubw+_Z!<Um-sQ`ctrTZ8SM&${ z@VydtLbAcp$6l%vc8<2JUMJ+9mPKSobAJCb2tBJ#P~EJ)6lWwCAmgK=HhTLx<r(te zr%rk`zjp_DgU_Cbv1qL4#TRYY%jjS4KRVj7BiAg_oTTktXmUP{Kh{x)Xv53AY1k~p zPjrCpNym3`%?aAzBuBCH92OOLh3JK@PAHnDCWldvClcvbwqXSmqO6t5B~dh2v}dof zrJjDxMuk)*pG%>52LTuF`T571`9tTGjrqSoucgWZ+C0Ave#n1~zp;Quu3(LVizkt& z;U|?>hnw0ah=J69+W2`9!eD5Y5^{rT#clT-{knz2M{Nkr`UzO}1Z-?l&cv4>Ljeb5 zy0<S>9+El(zuXTW2yW(U`YI7>0D=k&Qup~1cSo3jnTaV?R=?InQPcKxc`yOrt>NV2 z@HQ%XaI};p9f^^ERwbo%uBS?)Jp%AW;W)bfz^AjW+v`w%#h=!nMcOBOV<_$6pc|x& zLk$_OlWHJ&uYxpBgUrF%CZE>`r(fii+hr1L&=aKXkiUey&`R@4OcNaHDL;K<9x^$y zKCc07II%si%53YoC2i<tQhO;df^UVwXq2qa3_&PY9|%p&=eD~UD6ML^r9VDFW?18m z!ax{EU7e>Nx)vM|whEgeZDRdi8HX1+beD7`v(7(*$MxQa^Rqj00h+SutgRDEqD(@{ zQ0`m#lv2UD=3~#%q9JsCKYe&K_xS!~L%BifQnnW+%C0ojtAc#aX8Znzdk5FTQVx-* z`E<P{x}}@)5lqZ4e?~MmJ~*W?^g|RiBewKl%ZAJ1iEO-i)r*sfU_C@}qP1dSYD=vC z!m-<YM5J(`zPEvcCQrcVzJNSPO^aT=8EOP^H7ViwH?1TY#Ud!lRg1V#zA})0{e~41 zEDT3-A?Dx^=DoCM$Fb@%qwilA$42foWqD(5EczqnOX#~7E*2XsTZ~sU*q;Jc>?tKn zO_x6S(#=Hg9%e1~mY8FPHcc;oZKhsW8(hkDgC;gDkx!ev*KXNP{H~`OKZCjKy`VGC zG%gqI{`!?SZAWSy;Bj}0WG|P~4wzx(7BUxX9pGURsOW&#HZC0Y1UsKoTC@f;n1;>o zzhe5OYEX?IL5&-}Oh|4y8IR|##5VQlr8+~qVA)dzTV&JXWM`o27f#N)IsB4Es4KN| zHndI+WwmtY-WjGx`-ZZp$mCTuE=z^3&9+PB$L*%GLnkz@RsE;3VgJt|xPN)^=>H3T z1R%2su+?}^*VHzq2&qS2{E(Sr%awDgP*+xMDN|Ge2hEQQJgBb*APY0;OJ|sirO%qV zzgp((?Okd9IvM%h9W@cL(RU1v2ID?<xbz(bY6W-C1YRbKHK0!m&`3}?v%ZC7SJ;=M zeNw9EH>IJ@Xw7y@4>qEXCnV2jmM<UD)%RqqT@d<YL*tHn5B^2Za($D4KBZpetNK09 zwVc_IFC!S^>BtRcWE2}{Ie=K0idilju)^b;W)Rw(OAst%uF5I`o<?`59}X{$Y)DAp zVly=ynE(2|cyRseyxV0HXUhewV1BbmxwqB6kbedveghxS7zM>iIcX3<6*i7lQ+*%K zhfg!&3e5QKnGI-+A}#-;F^X7nrywi~0n5)ZYaT_eDU4Oc9RUQD(KbReA!WL<AZknp zX<vm`9A<B?W=^ieS#Fg>(>I~36|T;pd<*D{c1oDg2lG~Br7fyyg$pe>4`|XQxg}CR z)T%C;XHajDhb+3vljd<Y3Op&)@Kom87KQMW$~@*n(uY(Zjp??-8&pr{Aoe{rI-(ej zw`W!#bZcZVoLJ*C9(eM>)N4W)2xXd0sOn`C2JhSO#n_vCX%r7m4_tKi(7?49zknI1 zP7u~gD@8RrZ}Hn|C@berO8;npjZ~Qx0CmeuW^7aY(dyTI21?3hJtAHm^}|hF0?FM9 ztzL?oVK_foDsFFy^nvFMJbl(e?E?F=j=NB6xpN<eVJIt_j}mf5f()5Nz7zepUg}U* z=ep%w<#FkqVVI+HC0-}r?PKfA&9V2vg%OEN11E-qJjkp&+qH+|bs&_bKwgZYv^=QS zsAY%YHm)eB&DN6$3l=+HA84adfX*=J<<=Ca_BiNt223Z>%65M;jOiLyV;BD#)~|1t z+j#w;1$I4LxRF2Ak3KA5T_wS+9Ii!=eLq+^ZCy^jDtx!|v~^-?#nsmA>OfzIrfrS^ z*IpxUoS0#SoUWHIjly*=Pju$7pAa;<iyR}c<51crFNkHJ?1{Z=C$EU~>;Pwqz`v_= z6Huz{;ig47OC@xJyrD{p@~Zno)v?n5p&`l+7@GOV<8L$@RJVR_R^CT|szZwnu8U%r zX(6Ri;w-xmXih0C2WN*+2g2Z6edx)-5kxIFRR>fZD{eaO<I81t$6ZMRf+`S5b>nxT z2B0-y+<T0M?}nc>L3oCI&yWE2I%3`OZ=o;=t=ZYOz+68KFz@Ch2uV_Gi&z63CzF^D zp@509(6}So?D*P16IW;KtacPI9QVteIc9k+RH+GlpS*eC+ynhx3#6|Q#0EB5zRo=I zTsO|Ie>w#>P{h;-kn^a?1BLP*h|B-AOz04UZve<lGmZTk3Gy`(er}7{GZ=o97;*Om z?FdhlAn#bu)dMNA8W*(S?t14JE%sLM_id3Aa%wAh<*%>}VZP$nrXA7tE+%q?qCpcf zjXNlG(DS5HG4X}lMihLSUV1;orZcjnvlkev?DtgZO(d!|!c|U`DW<>4<8|#9RU$G= zof3J)iWJSo+)4FmE>R`|0KQJ=v-r`tRTi7%*8ARC${m!D^yq?HX1x;`_H=GTSX|ul zl1^#Hk|fF%B32sv8W5^u5u6c4^IDEJi>vdLQ5nkNklst9l)cdH*;Mf-0+DIAd_;vA z9*bgw^(Uou>})JJqP<bB1mEHAO3B?~jekiDMjA~p?c?8sbl{dy&NQRn5^dtJJ;4wr z@2|Ad3YDmEA$17Hy?X6(u^O?#&tkn#1A(iY2oQ5jSjevvTI=Or_4V$53VtR}LTH$< z&=aV_38sdWy^m$%VlwQA5_eMK^HX*wYtJIsh7t-KwI-YJgU!ES(NS7_oT#6p))Ku# z9C{g|JiB0}qm=xKM5B+R%IEGgaAB8sF>8I~R9-&{wK?|<rRc1Gzy*Eh3r=dF0A5&j zKJ5LMFV4@tnZ01QCf5Yuw8Ih*uY7&rjV6IQ!{C5I1lOJhugOF>M?&AxM?N10UWfsE zbDfC+`#{B*K^oO1Ck@QVQ^^0=aO`y#I4%j`697MNLGWKA0XYH@K>xBguDd=3mI~O* zr@`KQuPMO-hmPw)B=nYvO1Qr@%T_@nrpyL_iGL@HWZ`L}8fo#MX9J(hN%D*vFYV!` zBUwD=_Q2RtA$Sc!`$P4yurU6|am4@83*=yB{&y>ojqRT(g}+gqfD=Q_76k7to$oEA zbllk5#=$}Gy<t17U!l+eema)OZBwU2a3>cSGp)i8-Yq$g=%s7Wd`&X-TvTGyWNdGy zOsLVcgZP0j!z5)y#zf_k6n-P$57eXZhpi|@OIp5-%7Zskn~1iY+1oYhj6_R-Q_1P) z`qv3WTUv#Qgtq51u$RvU*Vfm=$U6ZBWiaF|#TJDj(ffAA+GwbA&DGOR83c5o8OSH6 z9HS_{VD%ZsTmJk+m~c^Ohz7;tRqJcuSnSM<QuoPHfE8p%!7+#+w+w;~zPe33JeQIf zWqWy@Sg+pPE@-qUb|jdQTn`#0g?v>GCih3M?zY(Mb`+3I97sk6w$f*#4rHS8GPo6r zlH%@m#r(9?&qK43@(knpk_4I~ij^XE!JoiY7*VJKC<n<?%uRpl*7qq5!kb62B5T3Y zo0kCzz#wB9`r{9!OVOLitFnpCp@4yYX9Zcv1X2vF&D1?m2=F)G34k&F<*P7(3d|&F zBoBojJdr+00_`R=WRhCT1q6O57}})PfZf!U@x3sw_Y(@NVFLw{=dkc6%(Y5<ONR^; zDcx1_Pob)<>V^xM_=4d`j0ZdLWV58XLBtJ4gTcggFl7nYtMGn(xHO&vj360bQi_0x zU<WOsX>;v?cqd3KKkEQL7q!V!mL{XA(vC@sJ4?{8?zlJUf)>d*FbwWMAFxJ1?8`El z*j?+ZW@S|ct9*E|we5@=H*8b|r(8|DT-@nYvwo<<Y+2XP6`w7CcEjC-_QCDO>-Lbo z=r?y|sB*b<n$*TmBJqg07voKzZF+`>Y|U<MU}EcZ?9XYgX|{Gf?QTc^aB#W{c)#y& zg-u~F8fq?)G}0cH*X?+4j5As=!|8V3@@(k4I-0L1rgO$5E`<nSGQkVjEFe9{ndhj= zJ8hjh%TEcsh_=v^e%a0RR+=<$-`TfsJPyjdABfNf7lESybH8v|W##1N;IaS;COg|$ zbY|+ret+Ecczr!B*|^-m3)wMucyQ+KxjDP&3CVc6+O(>1>3>;tb!d9Ad+uM(SxF_S zYat3Ue+Wk(j=P|^<{7HYTtb?6hfd)%WACA!M;^Lkj!qb1kILCN3JMR&NuHsO^J-r{ z>hUl=438A=3^axq+>`RSpUHek7rc|HL4utm-n~H05o9WJ&+IKhO)tYYSe4voWwyie z=>F?tq{N)K$daZ4?3L+wJj^Cthclh?XDtwuC6_E~P;{+m*3Yke?_nywA;6iSw<u4y zhi_{wHr`2U0tToAc-KQ``o`z666c1br2!FL5gbH<_9sThw}n|)QiZs6E2G%?(+}M+ zyI-QuW~!}Hfv;w1kHvN^D6?h)v0As^Hoi!gxn|OOjl8np(etfYJJUF2=Q;Q3CE29# zNM0OEyvoiV&ix9jDxRC+{cP;&-KEu&84F|W`hK5=r7g{OwVnaTbo%nV*NE92&}i1s zQ3vK!_mC{gw)V7qc5>J(W@_M*MO!^&)56!0>|V5ri?E*7xjOpd*$E2%9ESO^(=F-! zRRNoED+4)XB0?B~KY=UnM&YT+oQyep9bEe)usARU#6^IJ-E(^mEK2TPS>m35kMUYu zACH;($f8ijG|@Y|367&~*SoZ9gy5w-YexQNNoo!P$Kbxsp3HGX+o7h60&Mzu>x(pl zm!~Hm_Y)t_+F6`s$_LNd1HnqQC?fikxNduh2QQYwgZ+ItJE)aYY3V(`#)=V77VojY zsA1j@Fs;~lh7xU4%>V{7JjbPNDho14k(X~APyA%q$?Wu8dEYA8vCPRFdyzVqBWg24 zcD+WDFA^omm{&47=CPfpE97hx`L^>vuFd(R-ehH*i((SAPRU4KFC>3~-fDDAE|_mL z^TZhwP79?$WJ9DuWQDbp5l;+6QZv<0j4%?7)7)lEuYD<BvdSwukJsHm<!v)Y0g`ym zRV#YV*}ut9^5{x7Ud&&nV5_Ld;RDmk%@2J`I0H&jRaa|v^s@z8yg#PRSyWH|+MrH$ zeiQjbf<T8m?OK)M?mmgKe)zbtFsE7Osyp=jJeky`E$Lu1dlu-0Yu9E`8Zlj<M4T=& zc@!HQZ(!#(F-S%kb9vjP-Y|T%z^NC5B&^f7p(W!At<2HZp;<u(w#6k6&Ko$~GxlUY ziQDt-jLkClQbW~iagX4xt1F*qBGN0kAj{Waf?`KY^Jl80E^>MnrwIzO-rR7e9F9qm z%po?9%OxG6$184kL|XZ?W8;J81R2@F-ab4pZD2WXDf})xA7!9nwbehKj@24}JwqL} zi|#13lqXT-v#9bpRfL?XLr)_$?@|PgB?<0};D3Hl1bTlqsm?q4!v@RB_y<wR#_?ZJ zw*jJZ9v~{OYH9~02@#f^Ey-5a)R$%%lvSCuSIs1lTB1x7;-L&aaJgh8n507q;el^w zhHf}`-=_w1WFmVZ@ohJ;p1a;hoc*A9rmVK<`~q^vIc&LsI6%EYj6n|$t9(9NQq)tV zoRzQ0cOn!EV=ucV1s^CA3(F0d<tuuacwc>klavOz-poG}NRflL_Gr)mA*AT|G?#zm z|0>}CMczPA(2Q-<+xXNSVx9<&SR8yhtLvQIJHa62F#|6M#IRc&gdi{!AvS?P7}h66 zd^iucN0E1I&EAF?HGKuTH-EC>y5G}{t7!%^L8*cX{f58+jRb_MH{+bTd66X^hhRvW z{GlNqI?-s^7lj|r7<Y6!$dFtd71@|<IbW)H^Uc4cHq*381i5-IOIdrsFDy!PpVSzX zndX$h03NJu32t7<t&Nf;k&<AsewtKIq?SUss#WQ?tep5QD{(8b)E3;d!T_>TsIUaU zBUE-*t+Z&;O1@0&H}9lQkh4<H^C&yIT()an>c>YSt11PW$lK#&OobgtJ$pL}Y&57j zBiC5`;zYANNj+59;Wv_a*Uvm+&k&AeSIuA$<Q9z{&$qs5SM0|+Do3Z+w7$9=lBr<P z4;TtjQz0!E$9VPH)?ig)fmg%YoaUt08kWS^H&Y+mH`dz&{aKBbirq?}V{bJuHm{IA z;}8;Sv>V2N(qtHIS;AT-dn!5;xjABf1nxRV)Th*h1Q@7n<oJ1(|0C=E)eh0dUl_LE zacz2hgLX2!dsQ}B?4$Q*!jWh;F4!uqm5MeM)f#g}0zw#JC|ii14MHCgYb|&XZafQs zLQdS$bll6~4@(=8AnEh#(b9hJO5E=kIK@mfvNsL|yAKydD-H#>gMw`gLD1;+y}d1y zIl7;VmcTNJqgG#!F!&}yAU(!K+xBm9Is8QnATC=0;*!=@UDJ1#LDRPBL+*IhKN_;V zd0VadOVex#Ek%)53buprie|387`6-w`xv=l<QUn0C+!#|(H3l9A2A@`l~xwzoDPmk zm?>BcSMV34@qkCrp9+roPkNI6zhHj>^dw-q`5$^xR2_TGF0;_4$cnPP?BbJBLT<T$ zK0YQf^<RQA3Q2^LIm&Flodynk*rmJU>hjl#AvEfzfN^b~^}ht=El10DS6IzR?kT^s zZvznM!@58igu&uka6^6gu%1$c@~U>F%U{&Z^<panwP6O=@zKLI3*+c7hgEzTusEt| zw9EslS1+_8J#svRtN}PMfS`0s^fTSaST}%|TtVp_`7J0HHGvPs45TnL{N%3$;g$jO zl+o(tJ)mhGp8%%QD}Dgwp71jw00xE>K{3RvBvuMGEqet@G<My;GU-I$>Uj(&BMR42 za`b)j_36!`N{~5~6p||U^<<#85Vl@R^tFQpJy@@L4yjt0!oI(eB18}SD4%>G1nMX_ zN>5o5Km#l5r2L*|D$}S=6rMaPLN$%3hOZhbkOYB2ddF~1rkD3nK&`}%mIPY_$ko8} zU@isjS0XVVY>HPAZlfsx5d^=@!knnAeiA6mZzj_3QbG}LpBcATtFXGYEcjIM&?!N5 z;E1)M(e>0QmEWGyr<vJU4+$;`=<FD_*Q;y3<|v#tHae0WM6?$L->wfhVneVYw*mPi z2e}dW6QiVX8t3b0>w}HsnR#R$f6dS@jWP9DUv~;!S1>7{OsUegmbPRwx^xM%Sy9~h zYGm`w2c_F6b;vkcP#HfsSpW+9P75vYq&pHLfW;6|8Bcn@={-_^jT|jRlcwKsV(X>C z=V$yN<IFYOn-WT{vLVwJfIX4!(G5tP2s0uvtA{lC5?<e=q?jR{oRWM?rZKSE;C=l* zvbIOKW^gfOp=6YGkiS#HD5d-wW+UGR#Y;~i$eYYFh`lcfYl#5F6ATZE2e#}2gZB#_ zr#2ea8waP=hYQCQ2dC4Xvo<C#K<`62qRX1`m^8qe@wuhc7f1L@K`sICM^6Tnt0?G( z=C$YupzauL*9^C@`9b?5blEWA*P}pjupA4%S75`K7ldS!6=}ub-m$N6*V+qdO+984 zkYw0uKkYZ;Z(V+$$VKNpdvGhxf4}XN69N|g$=FxZJ?~%q$FgJl4<Y$4%n1Y2-$#C` zX*d-86?m^(Oh@04OyUQ!KPiq>(_(!NYSY0q8Xe-R&osDge`5Xa6+_GJe0oBBV)<Ij zO^hurdX(?b4F~;0UE@bO^i)c~Y!a60XGjj0s)K+717ut47Xsl-)$xV)rmo(X&R@E1 zwfpYak7X+r)M!(&KmFbe(i%17ne7sif)sHyX~BG;!A<oe&S^kDLzbG5tbM;Qu`H^6 z{0<bMr|Tu3t}$*vtDg;JZ!H|41NuWK48cetF@@InLueuszY`7<K?s3h9Ro44?oE*L zlD;@7GEHD&Pp1Uo;rdkH+lwWua;jv{6h(O1Jqa;M<jBWS7%m1}L-3Sf3h2UY$Mr`v zRY>ngm8sAHwAR=KyEK*jvi<fNTy(_6T&3lBW0DCOn#`bG@nU<CVZue@trsfSK(+7% zyfKl<anKLm>0R|RG9v;e%@$5%CFrIL*$_sqDGfd37W=L$EF~qeV0dK4>V!5n7Oe;Y zbS}chZ&q0-7Bs9_1<e&>SyHNFa8_|*C6w(h?w8}FlC0{HRCdme<)}L&aGvZ^X#59F zA6ybEamkl?=2qz^ppP4{7y*t3@}v87W3A<bO3I;O(P<;8SM>eYE}Ei0%78Ay3BbZu zdDovnrAE8NHI!!N#sbp=8@BL%#YwyQ&a6y$SOCqEdiV-PkD-QZkZ55(<IUsW<HMjY ztd7*uYS8B$!3qZVed9tjK7j4$W+;>Y*|8|j$KT>$88mZ|IBs16h*;`^eat9c$%+zD zi#xdSii-aqkmo%Z4I^i*HzJ?lnCCud_6c_}3?M{aL%A5e%ygHUkNcU3(RBy}F_j=V z+a6e`&w%t=XAlIcAEed9KO4fG^jS95*N2J}JX@asnvt^Al~1d3D1~i#FXP2VJ;?PV z9-jM@7r`I<ydfzd8otnzGQDAsglDcXx3C8o5AyOguWLPY^+yzyU0*|NKn-Lc{GGVS zr!#4#!x?^l(_!KAAop+0ZHa#VkVe9Fk%WAz$;^Z`Rx}f!!rr-=mb>~J(#^uv6o~s| z;fdY~((1y5kqL_HT*#&tUCPwNNzPRZLyy&-<_?#yk8=dMYPdh=v5>9A_2N^W?7S1J z+VF%knrD$^`o4j^$`C?m9uX#!Q8lf~$UU5#vT6%ej9Pm0W>@7u;iZg^V^t-hI1%kC z*0VibxY^aBNO)Ld3vQX_1WU;Zxz}423?2+Ra%)KOX-(;RyD{Zpq(?yY8{`|@MK5P4 z=m;ZJ5MAP4KM`+%x2l-7Pj`<|hIJM=;uL0jfI#$s<i`d}#=ZUu<MD)HuNiK5**}WO zsr4(7?BR2*zk<x}3_1FMkaflP2IdwAlWhqx@p(GmdAZmY-vp9f{XXvj!QGFW&BN{C z+6|F?k8+)8;|q&trS>u20A>O=h2}rsyT4FEepuk!eJH5-lom;J>LA-UX@ILg5kR%O z?pWro^>m-CNOJqbi}0KDdu#G_2z5@#Gnyp_8rGk_yXcwz<GbtsYJ#yd{ksXq!tu`@ z_1|cM{VzY<%39X{_~C|r`{DSLlZ2R)B1uvnx1Q3Hl$%F!coPb{`}}AoFL>FwY+ATt zroWfuMndum8wny4P#BX5C~uA^4vD6XDU%o@h#h1K=^9yG6LJ`((Zm9}m-eY3rgfWY zL9al>)X405D7m?vl_3P8V<L!&>*xW{pR+C75Pl}0y@{+qThN1eI(z$*<WU36*(2nP zWvRy~3?^~@gf{+S^75h7#T>%o#sN3sQ4^q^^w97WeGbut1fZL(5QUZOLU!YrgJlza zj3&8|h!iFTfndR$#&q%Drm$vBy6g#v>)=|g_UY5~5ltHG)6lJn!SkRQfUE~){C(|& zAUJA8f`LF(g0J=Be0`mGzT*cD@JkqpZ>J5=xSrsIL4kME#lfO(?+axFDGi111WIZc zL*Uw_6(L?Ds-}hRQhvYNCx%Z{WG-$^Qfic6(k&oNQ6pw^C(_ebU`XukyK9Bvk|4w& z(gR{on&I~#41|1-KsF@Lo07t~jqOYWaRq}hA}`&?mJ<(D49=Ip9Rg7_zm*G(HB2JL z<d>k``IbBY!+=bb$Lhd9LtaQ20VQt~f0__JQ9VJ3xneTAn>ogS+>d0A_YSJ)IVHa& zs#(QAY#?5UA0Ve2B^+5m5&wk5%_bvc8fn{)Y40!8O3?QR&RjofBzMR$n!CPd8^y0S zl80T86x2z~oUpzxSf|3A7fl8RmT-8%r{b`PO`B3NS;*1V_9O8u2X&l}baH(0;o#TL ziS1doqsf@bjKjq=8nlE%L*BL0hI7YAgrF%**;c~(bnI#x3wG!qd7SKWlV#@Ks$E)T zhfVIz9B&qN-YLA@8B-G;`e^yGcTeE&k;M%4S(9{HnZ+*?+$w*0;ua@_avQmE2k4RV zb}gB++rcIx5e|IxOz53B9hh=94J7U7)u6*R4uUS28zyND`B%EM&c%r=7isb8hbUdn zSKZXHtzh9`$ABhxEE`m5GUg9c64-8E&-aWS9=ztMlOts3Bbu_S-Yu8dR8%U?q#f!~ ztI@{cCS9g`?CD2Ev#y_)Grx&pt{u+UM=v_szb5Xf%~`%Blz5sbPd-<v0Z+9y724gO zGg*f*H+SS2aT{IOB`-u8lq?PnkWD{NRi@u)G;~W3=~Oh}hs4X1mA^c+Y}uWf2I7HL z2+!54Z+iZ8+=PfO_BCk49G2y?_00i&Q{<y>AjJlF4NYeprFg7FjtZGDXSH=<l{*YQ z{BcfZ=K1RR3r<eJnmNoB#iuhZdoJ~2l*gqhE{X0Lu<NYb&cHVyt6g1$8HXPrX%fdr z6RAqgqH9zd<~dH4ScYq26z`nhpG2~@YF_qELS72pf))?QC)M4#+<;^Y=awrn&Q?6T zE@;PpOy7+U-XEOWDB;51uZy)Z8z`4V*7Id+3x+k$HV&qMnMXZH`p_CDJ$jN2RN+s) z$XqLdEB!D~K)IEvErx7{RQyscuxQzmKHYO#jm&6q?(sUwgjq5QZG8u#GsCccnN6^h zk>mYT>AZMxw^aQZFLjdy#<^*_?FphOCpg(bR-5bUiR0<q>5xp;jisX4(`Lz+i5D?1 z4m?W8lvscW0TUS^p6~6ERN$!>4k3@#mJGrCi_1SRfL##(wE~~VY6*Dj_sUWxbQn0t z9S6eheUXsZJ7v!vanjn4F{{#B)bh?CN}_ysw8ain9~C1ZO$-DTk%1%xyTu9XzwQ+_ zBNiw^$oxOI|8O82h;b!yg!_e$uq)d6`__mA-UC>GyR!Xj0pZ^Zemw~GHx7jRztE5f zs@H?5T6V^)G!JO1Z&9DDTqOlW9a36|FB0%@ZAQ~QTl+QY0U77l$yHh{okgoGhMPbJ zFy$`O8ry*_Znm9+1sW4AjU>5h(6U>z=M$^*$z5t&*PaeL2uEvL*8xWwQ0M`rW|t7o z3S4=3s^r<yb!4f~&pW`XWJj3JVj)E17+bOpz;}^VA$l3+sBmRD#>R8ETU~F=275F0 zcTWn^uwIEp+2vNcI9(SdtL>#U4^2ON_)<Q;Jgyp{{As89U!2~5SrnN53ujN7)^CeK z@D%`T?Yt*8=!88i?hM8}qgY8V1^`<J0oi?~kVY48f83hJ6aRvO23)qfa7a0f$1!}x z;k_?3qzgfh-q@~p)@jq$D~xM^3XbO+5I2r)%k7^E(TBdyA1+lO4M4xI(_1|^YG422 zj&95<NWwj@L8`8T@S&H2en~EYvR)5S@l}9Yi6#*+56M2adeJ*m8Ar}SPpz@jLTd~3 zA2c|-#0^l5)cPDrJ^iI;aYFQ~)lQ^@2}EjhcZ+S&7b1PhZ@lJ4Q=g3{gj_{22}g*N zXIUABt|cdY^raNa0$Z>1?}$<n!%ezoo%qlv+*7{0IwL^)*E0Qbc8GYOPH2^o?TWqQ zU6~{YwGu#R(895|lml4gCgko%pt@OB6IJQM_h_aaHeBhcp&QKi86qUp)XnhJXO`ax zHq<MZGRDRfD9qGOV+T1U<7S<);ex5MRlEym_~6sVhwemZ5c&m@6iOMS_gADU5H=&M zlF_Zk9{?7))e#l7G_kdQdL`{_XnnyGG1%!g?_`b|?O23^{Xt5J6ep83Qc9vZZ>^MY zBr2D<AKFT>snan2dTpB3^F`T>6bF{jY-&>uZ7M<LhwSvsQVdLMQ6)O$%1I1j^=^sh zWlc@1C*{<NgVgg}i9eVa1cZ(QMHw6HmDRAyd7U;m_f9P7v7Na3SMF~~q2I!?8)feN zMe9^4jbO2hxN5@ZoGW_uw~kXKmRItUaM#=B>$adc`|WJc;DmkHF<@BgBFGnqIt5f! zMAU_gbGV}v!!1UXniId@320<IG*lwWIx?-E3XgT8>FLRT4jRQRvB5`Sr1sY|zq%8b z-JP#|x#z{pc`VsYVDWta#(R<QOpKC)YW-|EHT@AF`^fNI`081o@Z4z5JK3`{Z}DvT z`<;X-*&}e?twSXO3Go0^z~AvJ!6~la@j%W`y&5Ly_T~3ULr1Ngg36aEt9L;xu`M`- zD^)Q;A56+DmVD~~Q-^5Qp8TsvD)Sv8c%DiHyHl2}4!rpJ<#^n7oJO4ec!NvOvsdZh z(Ej5o8vG^%0~B50>{~0vg;a7iy4CIxMIP;B`*}#)&FX8oucAqie=11U|IBXtAKA<N z&ymW%@zd~s=$`PkXb`1l@q|vJ85iu)Ty&3wMQgFh!GsLW^lJ7_Y8gI!n~4%tDhnIF z)&Y1xIPpi`Q!a#KGe0nAQsGE<bRCU6g26n8>!PklZ3(Wihi$!}u?+*m>}(WFyI^#% zSo!M1`VaOmmC_k3LbawlsdtU10qIloglLrkYV59TUo(*~kA(}4KEojqZNgn{2@vg= z)WB5FK1DvoJJ`UR14~%Sn269nyM5}=-ZjwX1n*s%)LmX+p{mM@@?@gD1p~inrl0|l zK3Spi_V>Drtt-_JuP_T6zsV4;O{=!9M!lPK#j!jbUo`Ao2U&K}WA9LsGSgn9mhfdE zj<%@2jV33x&4&^7D7I8a%|E0{<1~dv0OBngn^!JmVeiteWc%*Usuh`XHdxa@vIS?O zBAK+wK8A8rdN<i6gRF#hI(mCN+c#rLrEsP0uhf(edjd8dOgg^6NSTzNf0g!a2Bh8| zUYD|-7S~}G%bM(r8#?3Dw6Z+B?<dd^k)_yi!Ml*au*9Q2=ErC-jQ8g34XNSr!F^+A zmyUM%$`R)zJFP3(@X1MiNc=@7ZH+*#>h&!qH9LPRCW-iXr6hIkuvSQ~db)TKLy?)` z&h}%xGNn#Qxb&Z$Nv=?>)i%Lg%4S{iqtU9y`ZqiHT7kx1m1wPx?bNPHmeXtn-10(A zROwPPyvz<|2XIi|zB#k;p=RM{mm`6YP(vQNq8+R`H;gi+A@KJ+lUxuhXeACyVTq?& z<{EcM-&N^zGW%nthve(mr?@RdpQYyov75{`m4Fy7L+EFt#K=2SuQG}Bz=_;Ipm#wT z?=5PT=84Z>q??$&bLF1=qRS0?<7K^|(@p5HX_A*g-P2|2&XiH%t0J?AlKHsun-4xF zVz&zAsv411w}t$f%7!K(f~Pj(xDeb|66-Ei5CbCt&p_rW$mF%DCn3`0vs5eLK`@nZ zN-nS#Z>?6{QEY9orie(>Wsf^10Hi%5D~$_P&_21p`KpC^wF=Y_p=}Mb|7qF5O#<iZ zy`xue>SO8xlug^BO?QjtxwlwZe@1K);Uinh-bv>kwd^WzVeH4lFklo=ruhIKilBm= zfN=gFBvADxSF$Z0r+gInT;3Pu;Sym*<#Wo(G-o`Br=Ha()o?hSpBi8YY(}GWuw)=# zdsuvRQ+RI<!NY@(IwRFuAbl`EPw@q)DT@qMQD9W^9^HAY4J<*Wa=3d_p46Ster}kS z;c+PAm_B1y{6J70g#CgX|7hP-an?U*ns{i2%A<@=`&dxUfgN6t3*ph(B#Lt(Iy+r= z1++%wHE>@JV1a5y1}@5{J0X1(@v{zqJjWXN{phVT^T~{xA6mIMKXqs5QI>k<p6VWE zxA-7>dpgA6nQpk_ehoRoIGJX0zvb4b_Lk><T#jVFmxbN=gPj(uJt#>@1`oyT*` z<ndAT6PWHYK_7<zL~i0WnJu>0Su)B?sIHryx3$lwSiEo9E&7VLYxgCz?-2Jl%u0Xy zG6N{u|KDsXJD{Kbx2;%!Ul)M0s^F_vDr&nuv4JL>HF1~a7$;18bjh@@ROxdARz$0X z`@lbXhNCy)WCZg&e5LpEPs1)8JU0z;N)!UVL+aWtVNJTfm7)25f(g9twS@4D1S0U| z%N2vCm+WOR3}vT%00tl%Y@cbOj8<d`4N^?4NJ~ycFwYcdas2bB4N)bJ?#@wkCj{4@ z7LujE%G{e?IWE1f5}CsT+qc-j=lU|j+juPJFo-RzQvm|i!F!*K4^Zi={TXm9f%`UJ zahuiY^EESmTGUMVd`-g#Zz&`Q4<*A+(T&`R5Sn5rPE!^DX2;OZ3c*EU+jFrgIWl1@ zxYKiG%8WEA**QPm$XK~PU!XRO%Jm|Bqp(Ur22NolcGZ3Cv_=0NtB!2-|A|$X{2i;# zv<8S(w`zKm6CoQKmI1`7Gr`x)XWgh50%Fy@bVuwk^lS?OL_+TQaFr(UQi;2XXHN(6 zklEtoqDg`2Wuryx(s&_oOj|u-n)A^bLsBd3wA8$IsfHwmiYBdQs@tsOstcp6LHBvm zjuhkbSI(%5s&Gg*dpV7-Ah*CefS}mvr^$B*iI?w`4uJHkF3ps&tJMR|UiSDPR38?M z=xOzp^72WB;Zs4_mJU|6%V|KWx{iTa3LsUzI9$2@#+r2X3m<q16dHaEH|LGr?^N~T zw8j&ptarR4T(-;04U!hZ-FCSRbsU1P+{#~DWl~O^1OI_;@Ph0~;#a51!;?T7pt(~I zqBj6bSua2io|~GeJ6ekcWz*^1bgxQR(xsQ1lnAm`rexnuy^wFJF5eLE$uT}5RZk?J zYI&>QytvIjJ$qZ&xNOPi`|(bDz<Ub>NOR8U1uLnaglZGDL@CN}-hnH1hBHg20<KK| zjudY7lzNEQ-#8yJdR(RUwd(`f_!nM3wQDs!(lm~-H&_E1Y{NEts@F4ndo8m8&Ln5L z6M)_D7--7M9&em;X*$I9*TT~5`N>S=j)AE&LNow?@s%^#$tV3y#U~vAZjhvI;Ky_C z&)o&RPkn-Vbs+|l*Qs5~02zvde|&1<h}D7Vv?UL28Oq-0Ji}|DiV`Ppc*S@JX<{=G z_(Nr~0T>N`sLcO@rK0xlL#=;WlaI0F6q*E!EYLknD=0zG^7;F24YWQ0*>>~%i{b@v z8Wo3rwsluiTN^LD0+GFl__lKxQd}Fo4}NeSnH{?BVB8>HQ+~@t0B^FEFI5D>tFb$% zCdYvS?ZxRVz8cgTLADK!iCq(d8Ag(LGUeiw>FUeocLk)+zm8|0@?^<F*|I9IKv3;3 zp~Yf&@Ya{pvA(83VK^0ag6bVPfMNVTM;3Zm)P2nU4md}K`Hk#_|7OXBPGIPz8fp<J zR!)x;*2c#LW5nFjKk8=dZqLPj5z_J&Vatf61-du7d}GRrX`!STvY>kcYRIMq&K@W* z<=J%_Bpruxz?!@qMJ{ap8%5Ztx(_(Y0-y*j(bUq?RtzH~4&+Ct^*HBPjmH2eLf{+9 z74r%=M3nqmhKAe=IjJf?Y<dZ`a(!)OOgXLW)x!|!RFo<zd30p+ZpyLtDMsQ*y%;;3 zxphT13Iza(FbKCioLI}eP7|ZaD%(owheUV9oGOia!E5R8rHXjxoPJ_NLDxFqJo(6j zu?VC+yJWeCH1NXgL@SAI^07V9Sq0W$J)9`6V%uc+ZD$l#J*~-NAokbx+d(z+STXLY z$cnjm+Jf8Il2IdalM_!}#x;)%r5&&1O@tp@138^gY++yTFyy<AL5zjNkzGaxU^s5t z$ORYvlaJY_9m=+Z4x$Olv^#Fp4kZAW)3t<TK{_vsU07Kh&E3)_p(9W=kDh6H<RMa0 zn*BGwA%1cU;ds=TM3aST2bxg`3sfWN;IVW~dd?7M5(?cU!&=^|MNQjz(cRw0#if&P z?HyJR*U`&dJ=kp6LutjZjbcb3QNDgt`WJ2u4*|;{fJB(_{UClLyB3opa*>uykDh&* z^M_A~=g>P-&Wlab^s~khQ_Vqx%9P3FXU}5V06Kp9_63P}5p@9zh$@oC<QZ+ayjfsy zD|U>Kg1TSxE8O`A3ykXHrZfdjk&of%Q8>M(_M+otjo*XvnAYdiUO_Lky7(<l&hci` z?0&BM1>Bz{2u5S2_rt@64VMA^#qfQB;b7~ja}xG;xn3t7aW{n(03aRUB!!cb#c}{h z2O2f~r9TuWE6d+)AG7^Ocn&+D>HOE@Z)gN{c^hmNc<&ya9k%0$WhMg;OJss3;V;Co zavH?=<ueEMexdd%Bq|^u**4D8E`EshMOF2PPw*R=Jg+YeZ!1h(DVg7FzaM1&kQbA| z$T5{j8kKJfK4*_-sojgulCUMTgxM8BfteL%g=4bUE=5i;z4ndUMp!w(KlIDf=NEKt z6S2VO*2&Trqk-VocN*-pS5~3GY&Z@rq}3%6MXYZ!5|v+}c1mQxuiP!wMOH;waQXxh zEq)#*6;1L33F9vGYY0hn!w)15&Lwk${r%R%yedwD3EX*l$?wRDf#OkYhf`k_A}JAl zQNK!ojF+0CmJN0;h)4R9-VZ9En)>_n%|m*}FLc(z$Gf2;TD#>cLs(>3@o%FEvhM1_ zV`%EuMJR-5+c89Ssd^sxQ<&P<MRw`p(L1Q(Pg;%}3Q9BuErxGkxI?jOt_;!q7-qaj zU2Cw6Q2iP;tnDa<5~=5rG^AZw9R`A`DbeJHY-uMp)To${xRVFm_Z2MEyio}*P&&q3 z`dN~jd4=+*enuZkTrfdR)tKexgq)~BN)!cLJ%m)O37WIES^qp~TR9?bz#Mr=Pp^TB zK}0IAoGLANb2mJ?OHOAnSZ@({-=qt3L`gY=WdGaV531@zxykVA(;pew&2vLRh~NnU znaE?gy+06AXG}s1fI-5WXoeVi7ruXX7#3u=ptpl$__>Wwj}ZYnF9XE7DdiiNMNzdB zD%ix%q2@UK;kwvynQ<WdmhaK2X7l>+xC#rh6UnFLDEoRgc~+t1!-LzHcX9Uq%l^gm zu7j&70)KJes-7gC?qLu}RppZ(AF0iIjyEUteHz!~-r~)I)0Wo<aC8G*tPR9IRbZ3% z+wDPwMivY7RQW#ez|GYZLjoQwz>u{A;M)b8dhK%}aDqJ~jx!%C2DAvWz;MPrhxOJO z=TOOlL}Pm*r-S1RK*9cCHr0D@K9KTHmh+PS#ug{ssr4lxH?3Z_)vTER8+58cI;b@D zruA(PJKy&(J2J9r5B-)#EyaEV*>g;l^~OE6W?qb*o$r?!6_clGJx(R;t~oq*8+Y$d zRci*D_Jjn@Y%;{AZz)JCJeoCZpLlQ#ie@nd4yHyXXN(h#7qa36nMyI%q0K}Dr-*L1 zNZD;w9jCQ(tU|7Iw5om7903F6M{kP&)?xl@{%gI5r$j$m#tWo{azRT58pA|H&~3N{ zhzr&nxXz&QtL=|ilj>K`JI}q^9K0MlpN`J=x?jKc5bfL-P1I@ng-;~eJH!C6Lz8;V z$MSLSm)^&tuDQfxgoD&khk@nP&H+cTaivyW{=PT~pU)>%t`Ib{<$N*i)NhoXKFO{2 z)cdu*q=XKEOAoZkp?cINjX?7Ul+_At_=U*hNxP&`M<$L`<39O8sfVVrP~r&I%RE(q za(?o#jm~%2#Vb7A92nOfAr%(~#v43m-CjS7-n@R@IlrDJRCj3VbZcg70Z50-mp>mW zR5B{8T%6lFyEQ)+yzaMo=t%Yw;OjGJNpiF1*BwX4Hlsa}NQr*NO-QF?!e8ELCr5g4 zjlP}Pi&l)@ezh2CC$7xv(qhpPDBzu4Hw=SDjdQD!5ExQ0b6z&0=pG25uFLOxq8-C2 zBOMbt?H98bi?8n%X7rhN%gGr&y-{`uaglucBF;Q2betL6Eh97)I-BW4XfJVkm&L7q zNH<7UY&NCurjaG4-uNs>MyLUcGp1-FA*NP*IrhvzLD8KC`oSYCB7ku*_?o4#KW0-r z!qTY~uDORrQQvH+qETN#v$B|cZZ7HER5ZIfXKH2E*vzc1fvJUQZ#GgykP@u<9~WhK z_={7mlKx9x$8w!L1UESv=e_2eQcVsdnt^uKb-;8Iyd*1NaAG51v`@Iam^G+;u${)4 z3x&vD$pMVthUyMiD44__l}CS2FbQ{-2d@~hgoTrFk~1;rtF-wTv1&`FfoU@-8w(La zDdCPGjTkmf$fWs8B2qscg!S?QK8&Om&?2{%NHMrsccqgSrSk32Z#feRxs`|oCozl} zeBY!*YGih+QkJ-|gPY5UQ6&Ze4h6DIyZ?=<;bt|3{IT;;Grw0G3MY{xks4^aS_A>) z=2)%(zb*&cSf!v>lm~o%)8!WMpBpyUDKxF*)lJHu(@><a=G=No*yCeAQuRFKo>d!C zxFJ45-qs`~9M&J!D&~;%cgPH-o^7@ytXD!LmJ&MjmCX+Q#cC9?<`dz;X9Py#RdAl0 zxY>3txAy97b@kfRb+!E1t>cme@_H1I#Xq@iEXJhIq`+j))QC}p@$aA|3fytn;rjl% zb6aXI>_1-q(iw++%-K&EhxM`Rt~$RaOVzf^_`~MQ#{5Uk`d`?+(zXDa6)@}is-n6( z7#I2*&wXiikt~l6z0@bkCat#Hj9{g3YfuX?SUPt&Vj>=V4o(g+LtAs{zFK)IOVkBq zJ!U=x&ujDDgTR~iwt*Ep!0QsTgMIfUl<8&u%ydk&+sX`29|x;<P5Up&3IOOkl0-RC z{08WwGDZ|R@OVM}6QD2s_3&hN^Q7^q>NjQ3u%!lGOb&10Z1Ws5Kxne-3%VQd=WaHt z<z5rY)S7^*-omG{kSbIFWw7|YMG2KVFA^zGV-8+;;3!%WFrcbLSVR9?vVP&_cxTLZ z<?X@H@&q3?Ve7xS**`SI4(^9D{`@^E-U{+9w%H=gPtt23jXuN6(G$8rV3|~XTmm)v zOb@7ln8Hx)6b$kxIz-RfWXVn8EZ_XKOffn#Cd(dt|1Z$s-akNt;snDFVQ?Yly|iOY zG*0pvf#uB8k<(d%7?H|N)K;kO0MOteaT2k>jISNh$rA31fbrZ=To^|AII{+NgF1ko zPq<~evYNfDR>@{n?_o96O*j8TyQDN$)T8MydVYD~U-bN*{KShY#*{ME9~w?&zl>=O zu!rKP8=vXOh6@^$o6F5rQuQ80A6qigs9TQm@EU9C8YRD#cq$1)t+=uwUHD%G%?BZk z5cy<2lgETB1e=js{S+$sSZf=O>ged$P!`feE0?YS2D#=#p;rTN2D$#p83c&c#Q!Z; zJ${Q-nZm5LK5am{#gyk4jkB!Z^!%^?rst2B8Yx*t|9oSXRGGC3+x6U_JDVh>EAQTv z-MH|k`k8QXrGSbr``m1l3eo98dDa=L(X0%}z(DhcGl@|xZe#2%$KbBceFQiD{+S*t zB&B5M0M#V1M=rC@Cz9!=XE*ZWiXDnGlgA-5EWno4>+WkqZh@L;L$oo@WH!PiDA>%o zr=uM&P7hz#Gxr8Vl(W=X>Jmeh!RnnJW`79%g}$RF@2^ge08-9uC%PH!1*pbo6Q3{> z*5hwE7>b(wa4#dZZ*l<QVC&Y;%x$KDwznuN*!?^|8=UZ+t~y!!tcRG_AQ6(pl|5)5 zAP7Fwgg=!h>wmI_{&ir*@L$-U|MS2qK`f#UXAPn&z`5+0aur2Uno<b`5qK6~??rVP zkTv6s4#=A60%Xmg!4E%jcu&_&153cGegc`|3J@>BYURDwi*Z1cI_wpkIl^}30T`eY z(AU)>SDzA~w#Nuk?9Ei3Ku0Bhz}|SCQAd<FiH+9+{EE^Sp6QO=F149qpElj^y^fI} z^PP?^as5=IwLYEH9R&=#A7aWK3W#W}X#3e6NrGV{0hDX{>73~!?C-D{5#}It#88Z8 zoJjb3-htn9wMoW=EKfEe1{jn5CyV6h*?iE!Z#Vr)@X#Xe*a@7mBK&Ol9pVDL1jzP> zXHC^s;g$3)b-%PD6!x3<2rYx`G9&Wk*ap(qXzLl7>Zf)kjAWbOC^%;Sh0bSOF|ANT zME$p3J*Q8oR}^k9ZOnE5W}bn^s;AsqE~KYedQ(n*wvj}j2kjAg7He#5gGPul6cg&C zqC|Wmz&2i#);!t}1*y?=q=Z=}Y~h6Gw6(_=mfVhUxNAt)^2y=&C0mNZulnfZp(L=j zOYJB10hB|jb>T)<KYB~P+&<;=TEqLvOEf^RQs|2T43G9M>P8KC0Ks~i%vg4pST$x# zV1DMV%eLcjskrO;8=cQL+1Clr9}h`{NA==U#Zx|+b+N<BFQk+`p3Y79>3#0g(6}Kj z0G(f9ICUp>e)$`n&jmo|LtYF})Jp)+`5qzbBm<aGOpL<SCYt7es2S<s==|v4==>c3 zI^QIgVAa+_Ejc5>noT@GiJeL}v8qG3X~ocOMd@s`VPoUQyY?4OANTRkg+%E2=qG1@ zG1HhyUp{!$obASg*&~>7FbOvvU_TsfG@&LMuC;6w#_%p7H~7FXde;!f@Hr#DQ%~%& zPizy-J#Y6x)zs2v<vwd-x3F8<tsGpT>cijxHR-SEpS^h8N?QXgsYNuPn$&=soTF!M zKv%<znMTw<rmb|i8!zRb<K<1T^W5w6|9lu_s6k0j!No?5`9>1W2#HZ}3keXYH4o9h zs<+dmV;>eeujT4}cxjMHY2tWOo}m`bHCFyqgnx=-XaAQq6aQ}r&@`RjmgwHUco4gQ zBFy>$;T6!Vcv09))JP|%M8E(KgP6>B@$<rDxEKZ{K?JW^c@lVc_b%&dsvD2|H$#Q} z40<T*a^}V_#yyiumm3UMg!icTO#UC1Xe}Y?40qnhAYpV*F+zFAJ-Km!CHjC~4T2_W zV4d(UOLXn!5L&Mj&H%S4ts0l1RFt#Ka8?cuAs7Sx^x03|+cKzpClmV+erhMQPedjE zD9ctUPKTrh6mZTht{?mU2u2c$I%^Z1JZX0RwnQvK2zu-Fze&7dgUANy<x-_^vOimn z{Pu2N_bSGBURK_=JMq?aV*Gcu)n)NH6Rf~D2&|S6fiv1enRMu!t=iCo+sdU|QHw@s z*1m%T|5cW7$Wt_6{S&|Qk<0Qa-E_!BSBFZef!c6G0j_9`$@p6Mpj8UP6<WKUudu1& zYUK)Aik!KOqY74cy7Hg^OEe@>(42~}+Et-c82o~PW(hNsMmKyJy|++hNI9W6nmTog z@ha&wE2S05bOp0Q#L}$SqCw0!G2<}B#Nh7$s2xBUyP85c_VoOjEXBsgXRp-TAPyxW zGqyU6J$gvt>i8a>6TBRj{3N9e{osR;b6U1pdFv-Z9&!yDiiCEVm2zmb{N`$uN&l<X zZ$Wo)f}7aScBqFz=%i)zJ4h(+I>We&hmUtBtl~mSv}=vr_@CdGK>UpuQ%Z<NDAn$` z5ht~t4KNF55l{1GWX=gI3ZZzK9Y$~@^zb8%!*Qlt7cyTyH_x%HRAL8YTPlw!H7HEM z_g^N<kJqnbJ9UVsSN5s-<y&shluwe5k5{Y9W?xwMzivLZP~64tbrc(=I(Ifuol&D{ zG$#W_E>XR~Olnk%Tj%=gF|cX#9wCi40Xt;YqinVHP(TJ+p<52J**PE4<VUI49v+UF zc0{8~H1h|3A&lrW{T|JPdTJBBh2CSd?h@B0V}9GRCK<{4WJ8)!_4qELcsoz{(Fq^M zkS1b_tu(K47h{^ycZAW%c`r7oxf)rxHkBWnQMN)nm#o(Cn!)UBJ=G7voy^x0`RKf6 zFT~&EKit*H#Q<r`(bsHN_D1l3sz<>7_wR1*|LHem{kPwcmErGusa2(I)>+}Zu4=Zc zMum5mWBdESw~1}Ba=(PLe_6%k$FDgUFm1Q^aYp#|<R$2~WJa?H8{Y>d6f!_$|7d6Y zEM%@-pB%~3RvTs*?_?OxV%cTKpKZk&ZG?|?b@mA>hhaMt!nRnU9%3{-@dnvSvk*Ir z;8WrGm)6i7DRFV=?RL2%e>?Bg$e}?Y{Wv?bROumcsap827{+z=P_R(X{<^1@wL`<m zgZ4vYzre<c1cbg&q3Z;%gqj8jg;o0F87Dw6e5oT2(o2>eA<>JHlOh+t)~BB(_<y9m zbCe|Aw(i|!+qP}n=(26wt}ffQtuDK|Y;?KHwyV0VoBi&y@7?E~_nz<U@r}q486z^+ z$jCot%vf{%=JT+og5o(zq%iL1z@lMRz>A@PSdB^2f+rG1jVYK=W?>ek7y%J8(_tov zL%TxiC6ftx4DJ_`j&hh$2n~m8aZ3TMiNsn9jwyt@vf~sQroxe>q8c#`GLe9Fz@wr2 z9iGw_bc|}z%Kl`8`Ic;|D~!oINuE@bRFiLmD4k;(BrIL50?Wv^BzVbXx&pmG?VR%! z-^US|s&axJMsGY61leRE4@7<UyJ0eH9GG~m$QWY)8)jI7MF8<G6&Dt;aG|u2Ip+jt zgrX%(ha-I=VM|s$GA+1Gg^jcgG$e@{6WAIw%&P{a6g1ZUq$|6(a+@SH)_D{ASRBi- zWp^4XQc<I!!xtesRX-EPg~Pr8L#KpAMW!PgSHYc}JG~arSBMXFh*b4})2soFDX4iv zBet;bLxWbE@bDT_-VBZ`YIg;Y^dBG$ipb=SVra$4ij$I2-Q8lZ>$p4JvL1c<nGb3D z{sXz}v<yc3<Un?=_W+C5p(KjW3tXeU!XJ4onw)oh2_$LcYYqZOf)25dqTpX~a3LO@ zhqKl}z2!~pZ<e=Eo?m7Jd=QqZVpi5zE`<1O1nXX^K)8Z~-3OA=+VkZJg=q5=c!5ga zPmH>G&p8f9n*{g-7%!?m28M0aJ?@u1<039?e^}%hHv2WVCkORSTwz>Hd^q{K)}J$k zk(9;0|H{jDm0u>9On_Aoy6<&}t=+lBJ_FqG`=}Imw}1T5ssZw1#l1yV<J+%;s}ols zsT8szWoy8$7H?+{B!&=!kHkggqI6Q&&mR>^2qF#xde#rAY^PlvsM`DL`>|tl|61tV z(ZhMdV8wNQ_VD^3_If_L2vM<(+{{p);4Y9dr{TGFlZF>7shydOyZ&&-PLTP~d0*8G zB!!>j;-9PAv*T{xk=WlLZ@03de7S<3r?j<p$q4{doR{6>O!IzNq{GsWlU-snxJx*G z4Zn${OnX?^Yv~=^$_pHo*$ODITge+-cl^<$&p*D8(?7Kj(qDa~Yf*i~(?4i=K2Wbs zykLiwHdqF~aGA>aB*M$(mSh+^6f&^dW~&q66NI6?SE!P?^Rm!Z%Tg23^6KsF8sO&N z&ZS+qI`D9m#<0It<eoM4+-mFH!tK3<r_VldPjGRt`2750G>@O>nr2?rdchI*!+|Nn zD5)Qg#j&8UoM%K9x}wjwZn8K%)5vl;J;J^YT>UXMW51oq&%?}0XM8fN%`H7+b_Kk8 zotedJZF|iE@THmR(quZ8qI)>(6kTKT9u(|s32ig*)T`z&^U~px$*u_Nu#6K&acS?O z$w70(K!6}@U~F4l%jECDwph2=jN^9f>NZpI7j&O10bUk1deg(NIy{rIVcqbTp&9UE zbW2y*EVG1r{Hx3;>L|5EImYC%g*tZORPS<L9(sBbB~9z%_n+Sz*lT7tSZg%YI#gQ- z(Xlhv@GeKDS9i?9k|;K3Jhj{~opS-|ciCm8VMs@oD~5yr=@iqE)QX{vvYV8f<VnkU z{I2-~ydutLd5r(Uuz=MbLGw)<HC4Pcba5hZMX?~@kT~goZxmv3k=dwRA)0RKreXij zU7ebn<Zq~kfstwVad?vH`G$e?yW(@kU0yn#XioWw|N9h|{5ZUER)b7~NPVj*#NkXT zULyO46wYULjQ`TGfc0LUs?sPml}QR}gEX`zSxEJ$X2O5oxMms#Xn7|8Upt@X29PxQ zcszc$9%VO7#~w1CH@L*O@XWu<U0i>s$H(;Vn1}u)A^&X)Kp;LC6%XCx{le)col0iY z6={{yMVsAD{39*4_Ht$J95F|YAX99qIRe9fh?^JnKE|EM6b=Lqa>n{y?qw2;{<heJ z&;t}+yf(S_hB6Tp6savpc=fT*ySFLQv0_=(|20Z<h3~ZOnl~#&CI#KFepJcWN*8pA zBg#Ssc67Mtj5y7SQCrLX5mQv_5#J&%7sgK|Ri+nAB#?!U!obM4$svhMTm^F$)^>V2 zHk(YS?Q14UASH3)FTOygP<!HgG~>+7?274?PuA>Xt5Wm5st*T7zD`^{`S++SnoqO0 zc6K6M^`R!s?B6F3;)XwqaJkZ#Zfb2~4cl5GKIl~omfYf$!3QX{s(9-t;@Afmtyw2% zsi)wvJ=NK-a;r{PY<e`<lu|Rjb{pU=Tku!-Ms5rk)d6aJI#qZHDH(4%s(;k@!m0pj ze4fG!ixyV^9`PLCnGds6k#7I4S~mLJFkMZrXH7+LZ?v31g)g<;3Ozl1*n=HmzU^JJ zRH~Uod~;uQD1zGEkX!j{yd>W*)B)yL3`-rH8foL09qI{HI}{+-#W_a<0~Ff~+dpD_ zcjB0&D<bLVm2S)oQKy5jQ#|Yswl$h$)RQ=e6KdttWqcf;Ud(vW!(|^9-0fX(fl*nj z772$T&?G8%zoQQ^D9<J_MSl6hGi^ZZ()hFD`?S3W;zVOzFkUi#@L>LEi(Vo6BfR&( zgPRn)7rQ4g#Uv1Hyy`UhDG+Nqa)Z=@W`qzeANFC=S%IjlJS*e_i#WkY$WH(t8X&N` zo8Eypf;S>DtHKEpu<kapaMrQ64A<}`L2vR%7|XH2blI_YDa;QZ+a1JdMmJJyO{+&X zl0~v{KT3qVKj)jvxe9?9QBKk>6a*6+yzM2b#Lh7wSYm~TUdk-urn;>B`lN(6s%&Es zLhYNe%dm*oweUC5@n=!*|2*0KN4bNG{ogQH$k2{k6$hwQ0;1!^NXC?zW9tD<gMp|} zus#C$LVWaBBlwuLG7iPmkE``A7|rBRwG@jph{2m|uH|Q5Y;X$`aMs~&!v$|=3Elya zo;^eoFIF8$-Vr7p0uTr+MXU8JRKlt_-5J@85SzO@dc*rHRy8NM7HQAciHyY5^I74a zCTKLsX1<Y|Sjor+oxx$r@V4sF4}s;6+6Xs77WqeQxe&avG5ZznpHSFT%iVw_%pP-} z1eQElD`#^R&WV`skJbqI%YieCyM$lXjQVYzIloJrW+o4T1an$bCph^0N*S7wZk*B7 zIrGX?Ys2fx3qG6mapS<MgNSnA%bgAjI^p)|j4U*$Ais!w>D@&gMJDQPk(Bp|5v$rL z`kg;Z0gAXQ(28a7O~>LMDfs6bl__z%Fz5(3XMr4!|8KVjkDM=g;go9iuKGQe&~cGe z4z`tr^t9tN>h}UnD_D^cSY?(&r&@fxTA-OFOS~zTBx+itM@}7Fsug7>oom)7t`h-^ z?z&siE!9hYdyzR2lY;|S-WkNK2#K_MaKgQ<wyJQCe&yrqrzkTVd&H{3-E>(xqx`He zCkKrow#uByr*O(!J~_<+;gsYQYi*;eeWjzO62WiTY0*j2?o4I65K=3{08FvLM%~0} zt_P{Hpq;^5ElNF1{i3ZFOEY|iHg1n9Xh02SuWNnqx!tNR&eSWCx#P=$DI)l+1!E4Z zd7l+mo@IK(9SLI+{2~0IKc<-v)ubY#c+^;!!D`{TE2TT7KFIh!aPoiwc68y5)3qb3 z{#2|SR&mkukFSk)_FPQ!Fb?Qhx7%(D!m^+Kh&&sqJ~4=EX@YN#NR!jqDI1qz`Vx1l zKhJdp@2FwH?^GA;#>#`*f}XJD#xC74-6(Aa5GaBirs7bGo*ANcgq6=fyPd%Tj=_w8 zZ)Ou6zrxhV&zL$F*))v{ldFJ48XGpR3^4#!sMx}M1m(TDk;lai6FI7vG$DPJ^T<4l zmZ^-v=KVl*t>DO1g_Gk)*=omqW%`YkNdaQ|axB-Toie}KSp3`V<h-m2A=+{$w5>pv zm&39kqA!v(PZQh6f7{+Au5CQpt}!L0s}?>zwg$~UQEG2CLs*D>aBal3WlT2cBHR$# zq>##*<c+@}n#*d*3^@+SuS1~|68`$EiiiVrFRpCV8gToP&VBBzqgZbGgX>@<u&NG4 z4&-4tTq19|1%xrQ_uGGlI(%`%^Kx;Ox83IS`fBRQfIG%_TD1u;-QMmuHHc%~u)7BP z`Ngl%z4`BM3;=uW|8isCWc)Y4eGT0|E~38wp)IJhR-Y5xioOag(rYn@|K*=Hzf8jb zm9x%x;!w~zL<G<B-CvLRd9OP~3y`#5fR(LLHG?7mTwQ3kH(@3SLEks$?J!U$*g{mD z6<P<oLgVc*vN)%c<!QNw6bGGMhzFqrR_laiM}P$`bMtV*{Y3v9GSFK%CMY8zDyj9^ zDR_WNEgnb&Cir$wvku5O?`S#22n}OnkM`(yQQel}3HECubNp+rPz#yIOvI%I4<~ij z@sJ&7rsm$13Cz|cjpQQQTC)ioy(kwo){>wLQCTtieaIC@x>_WW+c0;;5`n(KTps*} zs5wi0YPelBWHKbLOS!<P@xIB>*fS)fnPAO!@mzaC*Id8Ai{mWVL=wbtLMU~izg(rW zo&c`358y$6xz>Uu8S$0><ysrC$}oWu1m8jaMr%uN$p0G{S|{3YG#%UzS_0iwH@UQ{ zqI}QBw9rC`$Pikc54Gv&N>CY-n4nE1QSA+l`A;SHz1I<7AoGzp-bI{Pg%@s<zjH7f zt?bh2@5arQxfvT9+PJpU_c7$*<iX0fAim%HEgl-m>(}yY4vz}De3}EDm8R^n$gkM> zCREiDJ?<f8nloZs6`raa8JmZuIL*Ybfxkr?CfQf5%N9_Twb@dcsGZO*3Yqvy<fP8- z)`%u!)nm$GVVXBpT)o$S+BsgzvZ3c}%HFFKS=EN!&!yXr8<EIT9evF$|Ele#f4~0D zER*VmnPz0)+Q}5=M<^r72`h5dU3PkF(6+@V#cch_D;sIr`kGvaPnE_lKU5iuQFw2M z(E+s;pxiB(FTeTK=STR2v}{8c325RQjn;Lx-yCsU9G~5;WM)G$_cIdH@5Be8MD!lb zIk{;+3!FOjCcRlNu`{#_Wh$+2o23@B9_YHcIidq68aQ)$OJ161rZs8JGi26JbPeqM z0+>0OpE>X5T6N~#x%XZV{=X-`^|%;QJA&M%zRq3P(uWNmsU#Fd3lEq32v5flwxD@( z54yt(Jq$dMtIvMieOJ)3jC$i5`k|Q}XZv>{2XN8;uOY|!?>wo>*spOSe!KcW1APz% zLi?&jDt2T>;TCWA(}aX$gP00ftkBlbcC1Q*;L}ekLGFMMY>BH0sxoM2Hl8IL%ZVR{ z7+mIC--!V;0jzldC~{0NWUmj9aC9*uA+91RWO~^)II}2kUMO<uI0>%bG_oq({I78| zt(88_7B#gFC73vaa_JO`@mE%V7)%&M1dwi%v-r4ZH^v-<4?M)0!Ee0PG-Qd%0VXVM z&%r{KBb&g{feE1cs~I@GZEnNSjcnoI{&3$Xz(~epEPC8BLgY=zA^UR{5XD55W+(uH z(h`++Or`B(!O|YgJ^WFi1MVXjS7zpA?n#Y~E*!afJ)hoAmgWjer43ProJAW(M%&7v zplNQ+GI55OX{DSu;)|8P-@c$=mRVL*j`J$CT?50ya5PZO4XZ4U$`3i2*sjM*5Vk~` zq}bLh`l72>GHZwM<{^PoXzh@rwU4>3{Q7oUJz6tm9_NHvhojm~Iq9Lic%gQh3@JoH zZzKI^H<L!KJ{>1rQ(4jAV>#q?P-;72WIe}zTR4W&Xo0hVQ}x;~j_jVhtAuy4h>jQ_ zjCGo*gc@9+`<bfL!!eOt>U0vjn9|aD!-c^Zp=z1<gCC0^&#iD#wQ~sf3}Hq8a#*~5 z4dKqfrp82el^gAhTd#7d1Me8!XC{X#TNKFCZF@vaN6jkrU_3-#_UV)7p_uKFAhuNo zV6MGUb`Jy<engH~(-6WBFxNiLOp7?Z>_?afm}@g4q`2;?ixuf=Y-|!C0L-<WNLo1| zb7WvL{d?tJlsT$;4T`f;py#Vq90r-zgsfDT*NS!+CmLOS^b3lA!B&}d(v5prEX|vH z|GN1wd3{X|ql}+yhHd?`BB7jY1+mOMy|mGPb#sn139Bxy!68D(x`;nZ%NcJ*KwvTK zubg?KFU#_*Wl65bGu5AK#*l4xj+m({KC(9|N60tfm3mKmruh)4F^pimGIamj%FXX) z$H$A0uT|MmzB$*5Z_%r=o3Juspxn(BX^Q-6J&$$euG-)KLAzVv%=011<1m}wbt?Z| z+G~_-;IdGZ5F2`_UCsa(YRAub4eoif_Yr^SIx9sU8s&c3UM5Jo{B{KC143og;^1%M zljA?p=Koz4l<i-zIWB;n(*F>fo6=gd!{tEs&8yp9BWJK#3TYJtR6(!*a`MIaRc!!T zq)3Cb#A7VENBH{4wMZg2QI9%b4|_jgQ8{+HYq)5bAoew45iCs@v1~Slw04!mRKjTH ziC$U6Y0_eJpHmw|odQ*Nyo56#A-SqwR8L5fo;;MkLxf$|jY<n-!KxnIQFACI@Jgvh zNEgXRdf1$qK)3mZx;@hp?8{I>0VSKTq)B=uNw@_w5Xg4(mkKjkVO*wAK@=h2QEVGI zOwcd0RN$qcZpBittX@R{6Hg*ov4VBnl{VkN#H~V|A@5oP3^DMbq-Ig^K*HG2B#}l7 zdKDTmuo6pEhmtd@3{fSCdq=T^GZ=-Hx^$V~t<~nCV@b|cf&+{LX>2Q_e^>-Qqb3n$ z_XB;Raz;7Vf9u6D>ivn6%_u7@EeEO`oQzZ}!T_9x(Ctwq+x@*3s6I$k4(J!D8#S9D zEOVl4F3})2fme}o6clOj`{Bm<?o{WH7}sw#jG~YlLUE=nbr@lksORGEv!vpKnu$}W zNln`c*dg0hqKlb?-(|mg<On5W8!GnZvWf{J<A#1AEvbOYv0A4sMFQE?nG}acfyZf+ z;}je)pr`+qf`AY5Myt#~oPdBYBEjzgYd8fFN0fQ6ZM(-H(~H^S1iv|KGu~&ME;_~t zR`G3bu`rBtiSeGg)ag1saR{Ka!IU<Z=OD)Cq20&f;qB_wfZgL*Hl`-;FtdJrmG=?E z^^|yBT29f`<$HI!II)<f|54%ut3Y2Nj}`EMMN=h%CDmts(L{^QS0*>1VT=!Zr2_wS zC^x~OZ-2tSVf%QwKL{s3gbs^-^m|De6jk2oZgAenN*-#WJTUhGlw}}Jy>sf$@k(yv zdXGbX<J#!W_bQg8>*@0h3GYmQc=4J|9H;fwT6<)6Qy*?-_-q4!wt4uD>L{-v>^&d6 zRBc>cE`Ud%ZBFE80zf^oVQu|B$Z$Q1Ci}0Qr@R*`WzWPhPmw-PwQ+Vd90aDfsdb-P zniXE)s?7E37p!n?Jw{Xa8FI)zvF-D$V|>}|6D|v<bVM#0vBLNnmGe!d=VZ=#mLAjU zCS&~bN`>+zGY!SNbUQ9u@VnM0tW#vqlz?$8-nA9;tPLp#z5MgVePulJi+H6GLu**O zB+DOLx))@lJXITRj|iF<Wa}o;6l)jo;_@3V)l3@m6~n;-ed(;~19u$euP4v16BqvK z1L~bscQ;npv|YG8cs)2h{3R!S*S3r-v<ul6)!-6qL{Off+P-xBX`m$(N%Og#J9(WL zJP>*QZap6tw=YMxXESG+CM@Ku)dON!0K_hQ4|B=9K`)N0Zsh*xa3Bmc0!%#$DTa4i z?N=*bY{eB&I}`@3MrD08hQUbaa?6eVu=CUzvt7S!{4gbtq?`F-YjRu!Gf@q>SDf2K zU!)B>;GYIwiO~9%qBw-7%FWlCrN{b~k~kO?U9rXJ@{3-w)btXqo*|;$2=U+*x~<0R zg%MISZk!+j!6)bej6~6z=84Mj3^IAXDhpwjJY<k>#|zlwJ(`ZU&WN?%9d1o0Q+92R zC07&VQ6Y@<RakW(DWN!_NTXyjvzZo>JD?Optp@)JHp|E~wMwnfJT%KVK{2s2VV7Tl zRxlCsVBO>WhW*ZG$z;BuZ{8$irDN}cG67anefG8G^yn@6a%#hUN4VnhI9!I<yRBp= zQk=Ov=FF^gUNnq?f@1#5K+@EQQ!8FB!l&0mjxYbK>kt3;Ax0fL2K}0u+IO?ZA3HBo zXUm;c?+$M5Jw59m%x`;lVVj1eo;1R1{OPQosBTefkdENf`3`GPDB2ek2yJNmkdqo9 z?B^cE<dv><C$kwV25e^dhIHxa(AB}Z`AEw3Am(!=fH%EemjMsLQt|3MX&I8zLecMY z1xU(bd}X)ClQwPGEao~erKP`4JmfNj&q?m)(#PCP#LVm`O*(<9TrDR}Xw!p>w2aA% z4xyfJoXrLn)4BGv7+IhuD2li(7D$_c4J;=~X)zPqtI5pTxEW$HG#Dr+uo<R`#0YXy zArxYgB^2^Pla#TBZa``w>}Xm8^(*BIbH?*Q!A_N9SLiL;mARndTXNFb@?Ro-JCu;& z$xGxjO4gn89MhPk*GDVnoe3O1{Xb(qK^EJ!Hfx;Od~I^9KOZ_OXtaIDYaaI1yrrx7 zN>rQYHWMFGn<~|`RB37|Q`8ov8)>H+*e6zLtsATV9AFCw9b|pq1X<FRx#BXgB-7HV zSL+?(UA9`RJ#eu+;UmLcE1YcBLMM2-i5rAluGiq%)w=E@5f@9$%fLcOWn+lVP)uBY z-bN~$h;3`r2BprmFf-fVHTLu|W7mnvV5ueBB2l<jF*l=z$eY+rr;<!;o?eColE`Y} zG}~PO_$9|qCL8@&_W0-5!B~<KNSw1XB8=nTNh};6Av5a<rj{X*C^YnNSu(0d!tdAu ze_i?F=Vibx-(c^ATaPV6hByD5lnqq2)>wzb0K0i88g`2j47{*#oD`+*@V&FTpAORP z`T)uV&U^Zsl+OvUIsC7W<ShUH+E}y;iVLe&;WZw=sG<c1Sj2yS(^v*5?4P?RFj@XK zv|i*zq<`3W?&R5$2>+w?J*~arScUfo1`2b=h{pH_41@=Of%dr4HE>tl_W&>u)gKrr z2K+|rA23kNc#LG^_waeqik6qXrAPGCOvr7DxE=&wVWB3=ua}7F6YVgBd~QAfiG8~- zrt~HYDYw|sT6x-|`J(ZRWR-Q;e;i0h5Et{Q2IB?Ky<38igqOnF(}_iqLoy^M%UXkw z%8q;7ebHd2uR4R~6<tsKpaMS>Xxf`1OG9VjN9{@x9Uw!ppS}8UvWRIWZD{Lo0BVSC zI>9v#{4=7tRX9d;fcBM&jFsX$r4oSq=ytXR4vVQV%t?R+z<qR)7T!5wEnV}c8)d1Q zIy`0xtKts53|x7otm)kV`6Tpm$tWB&oBpAgsu33Q@OOZ0uB91t7it8f-=Gdcif1-$ zvqp9FD!WW8wGA1=IH^*U+A;rWeV8h4O%tZs-_SsObln9FB`caDmK=_lduphWvS9w+ zZmT?7LNtx+Vz6TfoBDQzic9wj9OG&-<Hh639rXPr<<(UY8^KrY$`N-3QTni5X`!0* zft*O-{A$;q*xo7`Jn}s2phzj2<T!WXU!G(@Fl%;0*71s(lDTGx>$O7!LId2j0Pdr! z5lLkwE(IeG?Cmn)Y{+J2kvahGK<5r_VU7a89R$SMsP(Hh{;3c&k=Lmz+Q_e7a7HZe z(1s~?SRNg?WtoX-*HApVd5^sIJ-9>O<)10fGt2U9R*jQS$ub=lLhjw$?LJaoVC7Ni zoe-|T(x(kRME`svfvj=&<vP{Z)APU3v!n~$q$;ZaoV57RHf8--!kV(iyhvfuI)W5W z;?d$SaJ7fc*$JJ-=C(erE@)g9F~@U(&4CNd_hTQJYSa`lgUetudB_}vB@i+TGWdlM zD(}zcDPle~(dd4E3mD)pYCe2YU<`h;OfiDXydXjNhYbSz2OEUrWanpG75R4g7aOEO z;7|EWfFLcBnl6Di><Na3Lf`T4LXzw6I?Gu89YF7I*dP!s?v7fUkO#0zYEtk&on>XZ zKi<zd4GWCsjt7=1Jq2~9d+s(?9zljMX@S6xYBq}(@ipij6vLchWYK&3Mh|c~@gg~a zlD^0m#Dp6vjf4a+LIxoeFwD7aTXKof@Nq&e3(G7U86v`p5fkfUx+lRHtf3pllBLn& zIu$n6G)kRGL`jkX@Y!0xBF}2?R#T}vCaBXnuz`uI&b7wm`j;#z^A@KT@V%v0bb9B$ zaArW1QnMThnq?E}$iOLzaxXCcVS^wCVU4jXWXoaXJ6i{sT5o*)UDz;lw;n?`Zr&Xj zpItUO=UB>>i<O3c;{WtwVq&a_;dH*Y(uczlVNe{pVJAk3Fw{yHWPn6YC_N464>1JH zoJq1cM^#k;j!UU1w#x8Wphh*<>N{%MQz8s#6|2-H>Fo7}^3>x}j>S&8hurzJ(Ifym zNCCXtm41#Hnk~0Xvp$8HOjsezF=wu8{jMZj^h5$wE2Ye^X~C$4y397oqiRm=mN?F* z*#c=pqQ+Y%#LqLgOEmi&Fh!2VT}~h?8Fj+#{)kp;;gHEIHPOVcvbN-4!`l1#C|U@> zgDxIstY^n7rx*urMIO=sUEEdg3J8CNX}NOObXN&wbyR>?-{X2kfBPsg1AG^Ow-hzF zA?f&a1oUT}@gt10vwPPB=^Jl?Zzf&>pvw$+Pqi(+%oz8m;V^>XwDWp|RkDU`L8LM# z-7;GSL#x$&lumj_BbkK7Mis77=nhY1&ioG^1PIgrz=PbtDpXT#0b$Ary}ZdQ=GSFe z_Uwj3p$Q1n8Mn^EcZ1igWUf)Ci-tdVP%BLqClZ<t3xm!w%#V>qb4F#I6N434^fVQ3 zah5a4Ox*{Gw4|N1#@Q*85!M&E3_zpV{Cev+AV@O~S!KNsWE<lQSIf7$&o^MH^V{KO zuyfgXtvwzhJ%(eqS1i7ZU|D`-vC&#<EPX#`tB)oaXsE&)mkeq+Tm*1?u1om<Zm-(K z>o`>C#r1^g5oQq&N@8Kh?Sj0|Ed1{FsQFj?791}JWvILse~jvaKwfHOqJroQ$s1TO zkon(1LVqT@|20=K|2s=b|04DB4{}z@3!+5DMRg5L>uX>obe|xrqz3=e{nkuu4mve? zjGj$RCQNU=Z|s)y`5ocVpPF%5&1L!GWhWq6_O`=_J8u&mJHvN<6O8S%03SxDc-T0G zZF3qe(OFgPe)k}=3G?V#lqqteOC+Y<WmQzxrYKs9Lr-Nv>Xpa$C3p!AwAjGjB4SK3 zHW&1Q1tiNUK-E}hw47#*hSA2?mZ%6>s9#0-eIc`(FOw^@9Q`X%DCll)<6q?L)F3EP zBIT5*)#W;TXm;W2-bB>L_U|5^W7w-Y?(UC+XU|9B8K_DPE2Inlm1z`U_=0!<rsr;| zY!Z?YbMUBzO5BKtVMvob^+!E8K*M=WOwCGs>7-f(O69`WD7GmEtD!!`MWQL1W7P^f ztbNpWlGcI;Rk@0WXR?@8v5#Jwu6#9Z{ICqr?pZ6HfP-e$H5p|UWGaa{@D0%JxnOf8 zOxpj1#Im7!=-BXc%E+?Rw!x*SU+uy(L)2<kdc%C<@q2VpiCt(0=js?;FRoV)g|c-1 znWxt~6p@X2D!<%HfA*h9bo*z*Tsy<fv#Uta%pwfkhq$8WSfW1rD-v6irBcdVRD)p@ zHPu1Zptc;#kdH(#erP>8Vw<%ek3=xu)+c^0uNIB3dvb4)hnG(>Yo<bg_UhyGI$+Hl zoM4ugOnRb6TmV2lOphwk1(DhuPJmqvMu+`TJfPoG#8904uYS+Wt9(1(grRXHNRxWx z+Q<|KaI8YMj#ROFF00l(QoWFQT=A2RoV2X3nP|4nxx8x^bXVRJTSSvVwenxb7%x1` z)t4;I*p0~}8TD)_{2(kCEK1vu2{i!;Q^Pxe<r6U*t_P0Z&N|cZF=#jX-8}pG3eEhj zdvDU(;bGVj9XGJ?>@r0N%T{42zgkE$sDUGhIq;_tCC)>h!7z3@8>6+sQtvrjA1uL_ z#<L{3t6Q^$Zcp*dWx^Uy=ZAvLY&OYP2}u^Y#|=iwAN*YVeg!@6+wmUR)Q-uDqnIf_ z;+^jVv@b@T!Q^cNt4CfAMaDkv+Z5WGL~oUL?Q>c6y#6jr{wLS&|E^ZW$@Q<q-v78( zb)j`-jmv@f?&lxU!}eUbXde>^#R+8xLWju{(n1t`@0o-9^(y*GXYRAdzKP?gX=Ml_ zaW{ze>C&uZr7Yn$Ya+fJY9TYVBIS5#zBKK4Mqy&JTzh!nehLjGBR@4k8zGH+Ghz8R z`7yPS$-4CNLYT(Hn=ESaL3M-Q#Y&`@D;2mmg0s|5-YwY;(~htnO}SRK3hWQfiYqoS z+ESW@tU)PABzi$&<Ly1@j^4uF$*{n6&12MQbR1bfu}-bKZ^2^*pvOCV(E08L9ZQRS zqS0*~7#gQ^#E<RuwN)4sNT$TWM!Jh8gT8HI_y{`$gb@t{+7s0YH#LVFh|vq{G8={> zh|?J^$QTxVPYdyX&_Oj+pabURx+IKaHpNd&RM{4iz(Vk-+{;vf1sIGmJ%x70OAW0r zqoYL~(Z}ytJn8nQ$*c?YYlQTm1N3ho+HcmEftx(+Fj$go^|MsnBFX|K4}LDAPtu}< zL@IJo<chn{VE~+OvWe%Hy~OApi;r2rW;{Yr$q`ioA<W91BIux5Si><Is)9u{hrboU zG9b=$LX{s>h?e~nWonMD(U?H49^W)jVG7`h=%WL7ECZfH)5ZczLvDKnd#8ywYBNZN z2KtgJV&Yq4t}ux$JN)R&$7uzOV9Z2VA=NDsDkY1|3egy!MF#)VNUhz|+Ti8XpdMSn zVr9^&SGpSBVhS0he0ySbjwheZT*M5ehHDFOgyG>eOO{SGxH3Ci?fLxZT9&zY;MAPK zCa=zswlPH$gl4bDA;8X%Y3?DoR%bq?$+1<g&d)s+gzhrzV}NEI*Q{L#KDF)Q=UoqE za5r!CEaB|qqOy~<_iR?L#eOu!V9xM#cf4Wd{Qj3#-{ZxQ){MG8``Oyr+2T}byGGO5 z(5>y=#vX;d+0!0oUX^<KX>|Ft%H5g$k0ON3G-9kOPhC3utsnk;r`ca!r&p|k?pxDX zhSh`Ky}4iW={TFyoLL=8`4T|Ta{4N|vwee|f1#{E<TmgnB#bq2coXvk>9<ncJ{;-y zP*fd=<Ka~t4w5w9dez$JcucoRI=m<CaWlw|o)pAa$bYkxvsb&jgZELLI=Mqx>^kSS zS*Q)ky(_y|vs>a7vEFcMJfzi_O+PtXyqN0Je$;GEeP7q5UoERbsHBe_4W8+Otu6)L z%xmHJ67VCU+h13~x=G)i8NSNSM0+3#X)xS~l&JxeRD1<{ESzXmDn5yjLP#z!8<Y#m z33;D%v|Zw3M$k5Cz|FR*qb<xiqy{0820BsnkX5CrkGlDZY(Li~QZ7Py+%f0SdGYPL zSGyA7Skc5o-OvkMxA*+64%1a)PU~SLH#3HM{h6%y&RWYv`^D<WDZPMC4kMJ#q>s+e zTKQZ_+nrp>qr-6`phL+GG;xnhEyjiE&WU*K)5F6viHz*SAcTevH%SF5Zxgl-3R#=h zY5iYZ!nQ|-_$T9~xT{=l{si<4=N9SS_K?VF=aBA>?*iKW>R6MQL5K6fj4b4|*6t3I z(fpRU#=#j(q%kBz1xzejb3VdoX5tdua|0~OyU1pnL$1A(uuB%-okk|Nqo-XQCVxvN zhAX9GMb8uA;j%c&{T!9xG25jMyIcL20fUROd-$yYE>8&ZV>=y++el!QX<n?~4KUoL z)}pD+xb)6v)8E5PTBm=qvkg8yqwTkq{Z)EI70ZK^yTxSFurXi&iZ)71QIPTBLm<Q8 zy6!bWY8nC|kI5s}A7~C>NeeQ)*Dw%&SANd8%}dV%%NaNEf1l!t8;2K3a*}Ki8Os}o zC-bX6k3ZPW`<ItIF;%=IG-)DmM6n>?kTB^#HVh&9KpoI_NGGVIbH*|F|L1P2`dneo zd=#F5XN%?^S0FN7)G+YvuI*ng>i?YD=cVR>{W=ab20yeSZxUuSfiVGZ>V0$MpS+5# z21^l&K@yHMBxz*ABnd0j5@-Xq0^NXSLNlrsUqh%Z)WZ7TTu9RSb<G(3=NGuE?*f05 zytr8YW+9Y`k>h`!oYJ-J*Vr*buij}O&qIODGKtBg$8&Oq?K)`3Xj}0BB4xC*iGM`O zEC5|tx%<B=qR6PAU4j^Z{ds*MZVynTFpIwgtr#?5Mwc!?@Izx38PtOV`ag_&VIYmz zHAuJNxkp<<2k#8~>DEH>Zqqr6Nax&wnE5!TU}|f)^tIVTyADk!YY?J1dL1d9_^5@c z!=lGG`-Y6J9Sx%7V9#}Rwj}r+1-r1;eR~O!jP1XOvtIX^vpIv{s&hIQHv$I-34s4v z2t;x$q4Iwj?;=TI!rAGbLlgo<v9>Ud-eG|HF_NC#fV?}PzUQ7s<a~YmcIf5Br7cH4 zvg72(lp}9<51LgW{emj4-0&j}6E=b*kemBg&4B^tqLY0goV}+l994^9GAWxq_6nhc zts*Q9OG8DXoLyy8T!~ZZayrpOsD}HXX3t`kn&-l`crI!~XzWFA#4%%1C4la8<1S#Y zlkPrD64Sv%!?Tw~cj~g%a!o8GT@w#DJ55wO997nH+6$xTsItCgUNp<fuw3g{9d9V< zz8u#8S6z9peC0RywAn{pd^<O=515KS@-~ve>Q@Q-K{3deUfirwCa&UKe{Of&0XvLT zXL@m^7c*n-Jr?=3bA%q<|G}_{C&$Dew}EKcN`_u>O$E(1*{N9z?)>U8fQJe!nwMw~ zgWOL~%ypp5bL{I&i|prE`-s)E1BIQk==$PrYRe2|ueT+TVQO6nXMZJ%x88`)Cu)yo zXtz6wNztra=+{LkjE*b8y<|j8Cl;r;ia(uMZ(v?$9FFQ(-~nw_!DF4$=}|i8zr)8@ z-Mrbc4@?0H)!;*mW(zKBwyLcpSn`tIO-Jv?7X--5A`9-5F@~!*eHAv9nU5B>MP0wP zo<K7Bgfj-EzYXa+fOfr*oM?*Y^))bdEfxI+Z9oAmdGZ9DZwVcKFvdTJ5jy9BG2e-b zZ<KwD{`eFe{_8`~hCC#b%XvY!kC$6FuAX%LxFe3Msn?RA9|-2~1qhr;F}lqSvwO0u zBMn?UxN~$<%%;9@w2s@k7`<Y{IC~tG&k3VC>>p~!NL&PD8P}Ujszj*!5RB9)wyc_q zXmjw4v?&;_7ib+r-v{&FF0k#;DP5w*9MMxOw^mX@z`MQ^d|}ul#cna3{2CuzM@#IG zRT`P=G}og13BTRq70-3Y+xFdtsc|)~41;oA+E`7cs+{xT3$~f=+ASVV&#K12o^4-I z=p!#jD0kk+`f%%xlbb6GmOkCUvOPvrRC{i6+SiGqeJCyT48_PdfOatQ11_3=T%DcS zk00+SIC#oVb2m~W0wJ;8X~(}VU1fh<@jd@2H-0SMBd9elDl^U-9Ab%*&%G1s`YfM8 zyeUR?&+Ea%U@|K&#(%)ygj>k<V>(fnhSgW{R3u~|Fn>Z|U!-{ayBiSe-;{khSpJ=< z>|Yj-06$_HfQPqalr@gAfqgL<m1?R<h+Iksbz$FEVx&=En=^lbECR*(1H%edx-*Xe zki4rNbAOYZzbrWlmJpg70}MfMxUz8weL&I0*^hdiD0e}Fnc9M~Pab#B8297*+OpN( z@v4yv9?MM!qHOeP#k53+sAW>B4ntPeV<hEaN9hY~NwSz3^{oNa@SxK<^k{f2T#tIL zb+0T)#$>!3Fz`iEC{7BdqH@ORqE!o^1r&5gja39xQMA715po!_Cu#^I+Om>Wxnkx0 z93p#X<=KSyI;`<d#-H1H<kEuq&BIy7n!-pW<;o=+?)a{xKVJf?fw6`~&NbAqX)(g5 zR*a~{D^3wa+_4MIQ_r9G6g*V(PaCLGO+f>~$@6ys75}NUs;|bT6_pl>OH_-yB;Dqk z@UUsb_PgTRj)aX01On_SqOeg`-llB9gd?nHRwloVvdFw<zT;t*INI({RLdq`7^JHy z_M9vPQ^#ZbA>MaRim?cps!ac7;++RD@un#}	%B*9nQ5Yqv-o+!ZRrOpO|%)?JXx zQt~uz8*@rH8w_r+veRT-i1<C3dsIb%Ix+k&Cf?1)kw+jfuRZuHq{QPmrxQ!%4`mx1 z?%0!|MN(UMQ-Kp%jK6EG%TzNlh$9uJ=J9733{uBoK@7bKjE^9rUwd#Q!yRGjSA^Du z-rNZ{1)`z&19xHkkHapHu|^j@@ZzN)oFH!Vz%#m_P38j6-~0*h;P>aPX&`;kMmirb z-E+i7Zm1k=x+0B>4$@t4-Es3ojr(H1JYxVwnu>RlKif7=ekQQ2@B$xLGhFvOyYD}a zY);*qtm991StoY}J);^Nj`ZVt331-rcPmCUY}{koBOh#};&=RJq%)Z}uH{{Y!HO*( z$`B69fXyIJvLEzx=7bfaZc!|tR(4Q#<!er3S`6i-L;bE$%s}=5x;4`m@V6oJH)UBa zrhkJMOxFeEY=9KsKXSHFYO$p6`LrV*hnRtRy-xlyv`9Us_BUG3(uIyszc;1r(mp~{ ztR=%9Mjui9+w8mJ5>ccexLyP9Hd%1{+BZm1N_b!bQUt<5N@!rjVN@_sQmiLXEaJ`h zP^8IV3C_2~x)7hFlBHA&Yo5AWVU066UJp<aN5lgykG!PEZ%hO?Kh=q*f`OK6f~1(A zj0IIl!1tN#Pz%DDzi-0v`wkN-`(6Qw`{4%E4Ld_%swXk=X#$}KZGk^Ep}*+R0SUFy znbq5#YT??Ho>ji#8FyI1bMG`wSKanMoWmqYtIN-0+e;ACVpQGuxViG_#@Jz0olLzs zxio5ZX_JrbPjerXREuR2DHDq)pZ)&5rBVbhKQ~}-%rYqa5ssxODs>D8sP=v&LgnaG z1Sw<i8nnd-___ObYRTG>@0oaUym00+n6pD1$fVm3@UY6amG>qSg)9tq-=|k@Ape3I z2vsB~)pSEtT8)C38TszS*GX;tyL;)uS@ZqHH?3RC{;s>xFF3Z#5ObJu1^VRhE5dHZ zsIWfnBe@u?brGE^ED_~lK#lm69zkV4&Wj@KJac2{y4u%*3(SGJ$=jhK+|vk`$L{Z+ zr*fS@+=Xs>_VZ5j?Chq7;TEq<3@8*V^Ci+(^pfP4e36EYEBgn-+!r_(F*`kp!ly$; zmGJ$D<oJrYi<Z1R`J3FvS}Kp0H@eMlKMD`a!!nb`h_SlyTCvSOdEo9EL;c0!MtoV{ zZrqr0;_PY}%##i_d=3ZC!*mB_r>*#_o(a@ghWHk`bY#WvOy~F$#yr&>m#$~>4R0~9 zTgKVQ3lc7l>+$%p%BwhlS-8v#tDW(_ChTZ9KVSuo-<A7e&{Y>YtuMeOw72VqJlk|w z$h4Yp(W3dx7q{~E<X)GsT5w>a@?a~<W4jq(V2|HP8l76Dc-K#_QI}Af>K(a-{3_J~ z0M+Ah*a4LLP?i1=rCUhk10-uf-d!v5VQ#x)*9oG(Qnb~|43d|V9%6K7(Ob0#-mbnI z<Y?-2sEg{Gt|Zij1@4v2DdA7mCO;G+BHSw+J`nC5=y;gZUmAx#95MUh(K9eGAFCD5 z0JkD)Y=vxxx>YE(<6C~yzZ%<a@VSJI45KXcmCIjMZu&CIXh1<BA6-P~pdDU8IYd-* zU!`Mitn_iXnUS&*;In42tB@?u@`h4Y_t^Az0sfziSN|y-%=%9}@&CIg`#?kU51r`u zScmwXfmNXjRSfS^JCjorW2(Nsg|dYXR?Ntzpke=1^5WxV`uZBpep&9@1^TOKBn$4e z&)rl!dowwDGd*`*(e#8fN0V^p)oU%<hBi>M$X070f1~e6q|zD4&HH89am+#B=mGzE zQq_?reFq<U@P4)IY6fLy+t@g;Do;@PUCG`z^5*Q6A;u<=;Tn^r=j#Y9s?kjigL(oj z{gT7U-CS$$^$<_H7;b-;@`uFL$pI?(;Uj~%nI2>1J=Rvdtd(f6ja(5bvL7Y8Bqh~? zd00<Aw|1P^c^~{;SQAvB4_Z>ZSOHuw2V85SVOo5{wp%cZL|NKE;U<|=i?lL8aj*!e zs>?-#mk&DAQ04UL^7<C{%nUSaIccsr8?IPnUn=*IY7)?51mWUP9cxqNrsX>6v6J=e zfEt6KpH7+ATvyl$cly3%Q%ik9eaq&DieE0;`2jNpul^DywC7w2`cXexo)h*3BohYz zL#4FsHzTJVgUbQvNPmGFK2R9^xmobd*{H5K#^kowgPrnkWsQAqf#8dmQy&keVZ?oE z9^l3aX50FsjwbnC)*4aWAEytT_fph955j1Xy0H;K(ZZzDi!UWkXYc4AB^N^uJizTd zW0A>B1Nh~%$oj$I!<{(@XI=6#l8VRhJHDhHZ<xUFs_b_sP@Xnu;Y?Yv1qR(UXbjL} zTsfkcfeDZoS~eIF*I_^|IiB|%RT*Sebm{6SjiNd+M>%J(%AJ}f$W}E_u4z@QXZ2nu z^_g=i1KS2CfCfuTL6Pq0$j?S47#1y@y77<fagxQf&=tiP!bv8bpkPrQL8fqR1_vXD z0AyciQ+)IyNUNGDzOoO5r(l@Qs+2%akU4gT1eG~FMe0TAB(c;kdeD%2ERTD7)(sOm zX)eT=J<#U%3dxr-@k9?Bm!~<hVv6leoHYi_ImWd!+jV?%vtg#3m^F<h;`I9oH}}oN zZ2Svo=Vq4@^<B%X8X~8P3axlTK@B?`UcL%4ryOfMj9{Qoj@c<>n2-1aG*g=90GO(E zmZe>(7Ue~xucZp8Rh00d=tGl5=7~*aJ?(8tW^;3!z3Vi`F<K%xa`iKa4W-h&0Nb~S zL4=AI+me!~ZHXy4cM(xw2?NUSzi}R<x|=BzdSf4>*9Q6G<;#}s>+DC423lvg)#gt; zZFZCER)Ps=1i4(*ZG`*q*>{}CcALtag7WU@?s7%rL>T(4VjG1C64B1OJb!lWuW3k6 zQr-p9vre?TeUbJ=aR1GA*zk?esl67707nLHxdgdD6SqV&yP5$kr49c|`71YS)ofam zI<H!`T#850exUB*wvskXvwk9?`l;p0p_g9rY86in*r^t&eNai}2v|o;EkR!Lwx20* zM3k??{)#TLeK)+F6Vh^KMKdB#)2HM{zMTsYc?>zq2Xh7a3&r?_*vLyhH56^!Jf^SD z=xP1fE;>jbL{mj|nYMsm%Q&PR$NN+HczZd1x75;@%Hnf6qx{w8+qKo}-K`Zbw&<+( zMt4q7Zu9$(8jh6=*={~7gVN1?>kG$j%kWiA!?_h!alG1TRSNCqy7?|yM(w=&P1D4v zmr=Rqpd5EXx1cJPpu7*EZO$2M)#@4c{4;xgI>ClO_`}!yAX6fH&|i>O8?r3OsZ-@v zz~omcYF+W_2(&hMO<ua&OWq|NHyz(pBU3QI_Z!$~+>N$qF6CHHfk<42kEf?XIAcTo z;fAlgr=##za;6_Z=>$>q>L(ned@QHL%&aaI6UAr8Y@4L#=cRTC<e?=5ZdN{nQKtnG z`d{S}`#rg-0{5i)SgCT?O#IQ5zUwEUPHv9R^a!wa_rk9*`I~17X!~Y?@sIF2$F1d# z7&iIpw@$(+hC>rG7MvU<z7(O=>(f$5@{DfRMr{E#27miIDxHh@U*|&q?MlMGP_G;; z|6{MADNS2@6bZzSOa1ySX#EE_H?yru$Ow#C;$~!E>gE^)mv)_A>So1VmEQofp=O43 zBNv=}G6KlGoAbsye&-{NE{^H=yJ<<r*@$!{fheNdXah=hIrhyUknyKt+=tK#r$LA6 zY>UAVFiu!bbE5*IVn|3ia#RH1(TqgozT`=1Q4vzHiePOj>J&Js+S?(8>MiElQB;il z(Vq{rF4t>~lf(8i4VVmT_CYuGr+q^n*&(sJf?|QIKl?G%JvkMH55yG6=zAwZb0`rW z8z!hR7L3$#)u~nWSkG^ec)`&O1A|yF1IJ<V12bW^zH>H9I<Rv>@Dy{?A48R>C<k(I zrj7@JS6B&3tHL2qn=P$vYfekq2Vv{@bi+NO<C28MN010n@><G9-VTNjL!)~tD0yP3 z%o6rL?ur$K1B$Q3yrOZ7E473T*$eQLq`Oskib2&k-|9fIshEKYg1{Gqf{GuIcZsAD zZ<DE2m9s~6Jf#n)A@(zYMStd#vIl^CaE`;wje@$Oc&vb0fO7r9p#(h$xNSq`4fm+v z1x~5Ll_P{5zk4cruI7gXHV+CzNrZGK6el92>kV=UUzAputvHAbi&oQPGRzvR)Q=EC z!R&M1|4lnL8#1nJ&ZCsup&YM1YNa5y__OJH5#lHHOZCHPO7)n$7w}FPHf0NCaaXyD z%FqsOaa3-IjFCbk@Gg>wR8&!s*yAW}kqfTXYsQJ+`-OYCm2)&XPXifRV~5w>;lb`^ z_dx%c>Q3^g6@>+IY@%(jz*?{-Z2^2{a8QtgooK3#jqs}_vUs@-K;k~tz}H6f0hP8> z+=R4tst3vQaSNg$Zn-Lki<^1Fcu6jxx}pr9r2RU=J+I4eWS(L_F}Z69LiX{u5g#uB z$Kfv*c>+H6ji{TAVV$k(-K$oTo@4!(s7oR{9Q7<2TPw{Oh7R++gO^hyOorB&+FL*T znbh~7dmiWNv|!+?0%cR8tO=R*W&JOrQDe3TS9NOE-|+3tgDX|d2V=ug63B_=MOTo{ z$pgvz<w4~KgD183{joG$0ZNZ`avb+}@)L^$QI~x$yEa|rW^HL3aT`gOJ4}lRR?lDZ z(CRDPBrs2yvJ`A60g5qGu|%#v#E;rf{4{=O;0!)YYkn@@-je>{KatrtjAs3P$s4zl zlN;vf@=o>m4hWV9cQ#&q)d^B`-wE#qd|R$VgB%zZE%?jz#zE9ukJvXHpSZz7L*Ar? zBS!~){fS<7+c0jQ$W){uuQc-oStz>uWbpD;1m<8LImT83rAb=zvfol{2qz&-hR0eA zlkioqLvjq!z!MF1%hPjK7Ve+N<$6Ci2mo#TmEN20x91Tbop)Z1p0B>kbm|iv?<XaA zOa5+Y>h@c;4D1^x4L@{h^<1|$-p8j04eEjL%*JJ55u?ENT1?49+ow8uE|gfF!s#>Z zwXLAXb=)_o*g#Hs5q<9#vVUhP-F54=a<VbyGrrBaS~*Rt>9pHcMA%LtAD$#<;wHs3 zGJS3-Cn+9RBk*)C3?5up`uy)<pI@z(E+XdP9=3dUR^A`KIRuAvjJ86dEQ}R=)leWp z)(Rmp)U;!br_$axEBbziK4Z?(?~yskxlj-1p8N~^f=Y8^bTuCeh0|cfI*@#+yAkPG z?P95);A%-YuUY$QjqU?nte$~a8}+q+8J~<ahE+JoQf4gXX98X#2b(a8|E}jbqD#Dy zF0AcONio?#wJ-xr4Y?jT?A*p7WfE57gt&IN4C7%R%9_zwTfi`W<K_JY$cygQo<VU7 z3U-;QDyi%k2z@ZzZ{#xstyfvgA4lrm+zJ;v6IFbh#jAS(z{9+b31-D*n}m?$A>zm3 z?WOkIS^37J?5)HQtjLG#+wp-Zv^AsqHW72+F_xD18@4!2PbMOOpOT|^%#MH^4Nj<8 zl$$$76rV@pIJ2T>KcTse&YdrBnz1l9R5Q1Uq{2jC<9!u3nFOA;gvaLT>Y=0Xl}J~@ zVFef>v^(7pt-feSQ19YQgoN9qf8{f4S+%ii$o6TAJ#Vd=u~X>tU(XMG-BtHh>N)i0 zjH%|&K9Lls^0bN6^v{{=Nk$N;*0rOr4W0TKhe1KHMp2k_aO%_jIjSszd<>rBqVM5m zzlzZV&%R{N#n}ljbT%KHH6L_8gm%hJ{uGW~VEo%dE-Pg7J|o<azL8z-=Zo9Ij1Ua^ zC?ys`ti}8~Bp&F1k=&9s4Tr`1FEwmOSI-Fu?>Pu+k~Jrya{Qk^*W%j+_kw(XgP6pG zeyooKzWFh{A<PY5H~#Hx>0cFd{yAG>WBng5VH{{~#I3Qz`p@Va8Zf|rZ)<q#Zf#2I z)N}0aB(q$ur30o|A_K?myq8!z(-%-m#-+IbE(1UC^L{K@QnC1ngo<oZ181@glQ#z; zH=CybNh{%sXZURzG9B%u2T64O*48)|^GbHPA&dk+*o-)|#oSL$z0fOhP*i;>H2uhu zJUlb9vtUYAG17-Dl;Ds7cG;Dd!NEYL;wOTG8)F6nKb%dvN$AEUPN>?bu5mM7*K2Py zs0RbA8JD7kPeP*hz`bBb)Ht&-`;%{PGQ;F9e&W+?E*M|#bITBSt>*f!94GEdG}B$0 zXqS2P(J>UlRO8Lr#LDi<)cy0pkdY6MwruT;fye#n!F@jwQkax}6O#P2=Ob$d({Am7 zH<7J7k4pwtng{od+Cm{H9umhMDV3P&PA}6{C_D?y&<eT~NgUd-h_PRhWdcRhwXtG} ztJXei&5wI=I)4$Ro8_j$i0+tDqi$_4iNZ844a&+)Gdycfr~Y1_mE#ODFbtn2Tbf&+ zTSux>2Ie<n3QoqC!T&|sImL+5XxqAN+qSz`+qP}nwr$(C?bS9{+qUgqx6jSl$xhCn zd-i>(N~)52Da~1<#{9+~S%O;}vot?hG&|AfI`Hn2z&R|IWTH~yzz9K~;WDzB@M`FH zU-aTNZ|<BngGLHouU&S2F!x>is5@YJVKIM0&xg@K#GPY!0pZ6T;{7XP#Qtwc#O;P~ zcdq6=_HPySG5(xr$TZvt$gJ1RHwgxVzvb!ma-+dMBxLOa!naBKfj>KT%Zvi?BOraU z>iv+U+4-o*Vmst+eWcmphljE@vev53gmuWX#dH~j+JGT3E{Q;c(2)3F1c)A|xN2gH zLFoQM-I`0XD3xWV9ZOnuQbkEtM{-x(X81Eg`ZT?jqoGVxo6Ii?qje|(R*CxXQ!wPl z9%N|sZKBayw)zv!x=yVOBK-JrOpkdWeQ1WMYCzyP;fPO&s8ca)i_NfCw^{GfxkE)c zZH-kmI=2@y6qCn|glG@lx+^2*70xpkh$jDd_bgD!;eksOMf2x57^)agv*ObpNRmV* z**e(7&D#5_$du(Bw{VXy%%AWg_?#@<O^)wdJF@sz0i5!}`NwWlNc`6_HV+^y3J;(_ zf~di*+yF``ZXUi?OSOxWo2<^_^6oLlqcqov)^54Otfu7~Cp#KN!kGY@a2^pdLWLHq zor3a5;E|UGcZKByTLU|wE%M<@b8&3fjas&Qy%@=09k7CrdXCpoMWt%F0uiyr{1=Sg zX)^(zd~cIZ&tYB>XSnj$l{3EwJjmkk()7aJlHv2`k~eQgqWtS>CYr02=3I@1L0M_Y z7YnUFD>{8xc7~?38ffvxr-;B@iLm0B2qHOiybSEB&AuDDAgurd2poTYTSZG3=+;&} zs);(Zu{5M|h-E*9FlvMHJCsW~w%b{BY(uDyZm~+G$_h5D;Q8JwmyFeC0q#x4D9L$b zqvF6S$-+Ax`}0}+9X>?HiP2@Cf2tM0%<E-FC(fN18qqebaJQ3LzkpV_`^^zV+1_(} zbfoq(7@S%$&r@X(ySkaH{gAH+V{(@g5fNpPKS*<><hMMT7z7Pv#>-c$AW!(fVMfQL zk$yNgA&GHPfE{H3m6<s<1M630REYMzVn#%hXn8G@W01HCP4co{a|{;s5@|_`ll|$n z8yHK<y2|!|{clSp<_ygobQVOZ`AF*2p}QX4sM4(!?DJ{{C4V*(J;AHKoRUeE?nwcP z!M2R>s#g7|ARPDEYyhuIh*rz|Hsror@Nvf)-;8Wsm}s}k*eJ(@A@hTiX3bOfn*yY2 zft*g9y3Crf3-`2<PO>_Y8kzaG^{}i3J%WD3j%Bq%{4dTJ&T%kTXFP~`x;6j#52T3B z@zB9-W25aIQtZ<u9eA`VGpR)x*7*D~$ObR@mSweJi1-EFbA1B0;53kJe@ZW)(hr{d zr#5=8$9usu&Z%4q<u&9AHkhm0Msg^XXJO|I`TfWx(>U#}G#&<_HDZYg^y26Hk`tJ3 z^tGbom#>{&P}Q-xw>E*lM*CXaw_7uRp=!<EdMg*uiO@-#?}`_4Zk84r<5@m^W6mI7 z;)S690>y|W6aG_K`6oIl69dD4&j|nTBHYzati}fGj|itns87$tP?cDo=jF6f{4hsq zvu{JY-XCu=f<z{jOF}>S{l0Y<+lW%--(-C{sY{gT#*G*EvL(jZ+Q4FcFnxIBc)zbG zENVO~KoEVDgSf7W0wRjhrMinT8FM!dQ+QT4i4Oxvv<J!{7o&R|l0CD@z@(>kW<Wm4 zYVlAhyfi-Sc>gg3D6?VD8Kq$SgTO5A8ZXncF#>MHhpER98|nG8iJ41Jvx7WG7rin5 z5iza1o_b+~%(s4GKXlU9V13nW#*u2(q05}Z(Q1>mV|{40;VSjG2AX%mM{lcES6fGi z{$sdtYpc3BX{#Duy5B#x{B~vW`-)r)mj9TK?QVDeXlRVdxX{W)Xg=(!Fw2tQaoN3* zZEeh*3BJf2H&vP}EtuI-UNs#~)M??+M`-w3Ex0jnPaQW^O&JDu4e7v7f3bPc!ayIG znw+V>$l~IJ)b!E8)wFEItZM=HGtO|V>ok&aac!p@Z7}4^mpLj~hft?Y`mf91S3RMT zdE|92U!6a%`Y4j-L863-l=<-~=PZZD{5^^?MLI0Nsx-<*tG<nV%ruFObV2VKk<e%n zXk0a#Q)s)xgT=|5h$S)pE3=vtWs|Nd70YU^qRE`c#pXd^R%8Wlorb<GsQwit73x`4 z>Aek;qDnQPZXtL^#Af2x4l0uc23bt9ClDL&29dQU1F#hCpHwASMkPB;ZZ<oz5%QAg zRJAM+pHE^t)%PLrH^|rmnZ{nszC_j9)2@^n*N{Nm7}I!>5%5zl5FUsqi0V1)KssNb z)9t^^em$KXy77_7eDL<RI4=O;bU1FHiE#D=7=SpHj{sp?3VmzeX#n7^nD*=$a9A}s zfZ$jV?6i0Sn;$}rd)cehW+K+xW3;pYHX&-SbPP`>LA%fHc}y1YEynV1wqyB%Hea}a zDr`DSq>H$LP+=(L^#%MPu&`9t)ba%xEtiWL#R4KuUipPR6c{nP7k=_QU@3Nakd;+= z+r2tlx-@Ba^cYI>zZgNe&KN>+bU|Y|r7N=fAWHSyg{{I0=fDp)tk$*<@{@6fz=)`@ z5jftpH&nH39%is|iVstP6VR(*>S9tmlgbFy)F_EZ4Vc&YnV*rKAUj=VeCdjqKl zk60=?W?>w6UjkurjN%IxKrz>i1VZ<G_X4lg_Z)-fq^ZTXyAMT1CNU%*)9gclK`Ofa z=D7?+RMwd9gboIy;ughEf%0X=Q{+dxXGxMMX7!(Ayn=Cm$&HRZLX}jS_me>AQ)`qM z5)WOm%k$n7S7D*`SJDJSuv8)>JT<So^j!BkKB5b*)&GccR9Oy2+?g+}yhs`F`h)NV zjqIi}({YbyK)^h!0m?4OBMp_i;g#icVbLgWzH){=uqeA7N<2><gY2A}fQ<siS@aL7 zi`rwD_^||QY*7pKzWOViE@Bm3<-Qt+AMnf*`*Y24%krNILy?{%bjjyr)^SJ)$S?F` z&ya{5nc@7R!XPnZLHSJR0%`4ICUlORbOVUfA~TTa0seK)t0d0?ErcKL0-FtSnpo}2 z$)0d*Gh_tKbr29Ly4sur5Y_C#D;Ov+vkx?U&re1dO;>BxCNIrElX2QLzlcKwwlX|= zjW`V0rAL||XJ2F?X3>S+35W)QMtW<Xon;5C?|(DYCz9xu(-Q<Bv@sJ?GKAopV@xO| z*%@z{(@IFXEIpGgOygmZi$r(>-1{5(0O7hPpbmY<!)^XL+co_@=vtZvWuW_wIp~z$ z_i=Oj6Gqhm{u6R$M1%__%S~$EwxhR01HKoP`*8^OE_a=;r!cUc#D(GKNbE6Zg>BBi z9P~(v3<()f)UK=e7sKUpkCa?0k}Fej%yGjoqYxSn&IT^KQ`r~DM|M$~b&8u<xpBHe zKUKI0gv8+Dg$IVxL#25<6}+>H6YXvvPlmj`AuROJYFR2uGKG~{)#8E1s)|Qq@uP^o zASX@h>-H8$j*pukH@#&fa*aFFrA*F7G)C1`8(X1-m%q>5ipw$0)O0+dQ54g(P3})> zf05nUo2&?M)^GeoB0GG2l}^<Dc<X1T=_J9eT+i22cZFMe;9ab|4OT0bzFV7T?lJch zK`;j(zmqzNem^qR;8O!o&K|RTc0<s0BlQ3S4YKp{W~`jrTV>XVy9(V#!Vn+P!wTP~ zbDXiaH=1y5&(wJN)=wzZi5UvAQ&_Mec@$K<As!d66eWO`#TFW*PL|Ly>#!NOOE!S* zz*_%Rsb3uzU;Ia|eDWTqWEuRFI^0w3nl(~ye@+!-Ip#}nI5Zl;M|VoPk=6IBS-h6< zUXeg*;|{rcDb0u;r$J3^K;p<HP0x#=yg+E#Tth419D5PO-cO)dOvowa%IltC^>pA( z*8f~$?AW+Z*?UKbMue(do~GFczu-LEOj|v^6oXZEaarQP!ycoeE~a#9<>sr|VDXqS zV{&FL$UTruJ91prW^#+?!NgZvxD}HnQ01r>Co+l!5BO^8&?FB^Eaa*ih{`;V>Y02S z_}u0x<AcTd{iWvnUZ`ZhoJi^#TXEk7KM}oqPcwiStiu_6S6}=N8M|X0`Ia~cL*u5% zy`{(cf-mlK9PCq~N5|Kt>jl@NhG-Y;NhqmyIg0V*Yd+wMV?gucwZ5~yReTs5{tehp zv+Mg$eZoJ@Ei$tI|MUq`PCtD@?}eIuDY|88VLw|+7Sd!bm#>OqX0e2*kW&0qC=qI4 zbj|nswIN_+Vn#G>9@Dspb~jqo@C$7{!Y@^@U$S2GW<5p7Y)nK}7$CKbT3Cclg#-)( z1xBE)j9M5sGP8{zz~s?Wpf?-6Z=^Eq?3zO)&=;v#a(|+enD-`or=@l8x%a-}n)qO6 zooM--4J0cVFbr+%xG#LJ*W|}xx-!@ztH<u5jkmo1CSXFFe=O*yaz#gTtvT7a^HMy> zYnV!V`8}m;LO0>yi+rA@gy2#`TSv8|n*PA0FX636(%&`${q(2C9Y|%3@#4ODvu5;k zbaJzEX2ez&-VUEgTihK%J<p4f%dUh>VY2%SbLEn>UwBMMNZ(0xA0pGf0<b|%yVaAm zA*g6R=zc-3A!S||&bLiteMJllQR~hj<c_lWgk>z!GE`}i@}nd1%hhNdcnhpkt+GEL z!zrIHbnkbFSJApiuiQmaS4AGlvRo6>Otsb&)S;0f<w}XGe+gi~O|!Kj0p}j{g)8SD zW@de*7^T>**XZAIExrmlReV(9xmlzpI2WOg8hgnuNhGLQ#0H%gqOGBklul<n*_>*~ zizT3%pW#|)$O}*=<O&sJ`0@*qs+CzId+$I3a_j+$%90gD-F>=y^Lnnd@mRn%7B+xE zi@=piO4Nl(62-CYx0VNIsx3P#z3P{qk$!$Vh-A_V9^yg5VF09d2~p#~z4YVrAbl>( z4?n%R^Y-HOaN{fCulV7?<B)IO0YJmT*XQ3wH8z9Acg+G@TRZ?v66xACGV3Wo5=QUH zc*a$Fhz`^HjIu>l163=9C^wL5>;r-pgRSppaWsm?;Nt!!B9xdcmZdhPjU_#GxjigI zL$xu;-rAcPF`rPC--=n^M#Dy7Mp0MQj@eEg7F`E+1XiJ%cpB1}2EDsWP!E4jVDQF5 zDm_@M77)CZCdqfhBH0DPCgCp-5Cn(SrO4cEwZgiq{NtEni7${HuebVJO(P+{j!!|R zQKpgH^EzGx(5w1p<{MM!?el5)D7mxVESJ>xgXV6-EaLY80;@AFiM-CeJ7a!$@bH)a z)vstFTZ}Pz?6Qu`U|DR0?LXXiK2*(|3dSxeXdEd=g!_El!pfh?WhuZ_mZQEjY2B5m zZzRO|m4uXI!ioq;7=l8Ce>!VzW)9baWGsp#?F}mqBUIahFrIB3c#0}D%P9}{B7laD zIh7oB323(n5z{-}RxwY)t7vh;nMed=087(65$84$85<wTBE~=3DQ17w{lbIpbt5|E z2W7!e$A*FtW>CpdhLU%$qf$E$WZ}5Nyg8y+<PQ75UWIsR^T<rXf0l<}&6jn#p-%Li zHh8g6a%-TxjFln!f?uhQUVI<#xM)q>Xpe}37@&m($d7RDmzqDyFda9UZw+&WkW+OO z?6ji;1G)YCi_(@aWIw5jEpq1>e)`7k_v=^G4j=gMoY8x&oh}on$MOfRSFqn(tiN+u ze{Z4v-pV1gN4HVhv}uGWSWF<wk&!<FKW-vYtHfdwtf2)4(6(D3quo4P?Rzz>9~IyW zpNcBHl!kmm;z`?mE|)^zo`CCL+TGtdHq}P0O6hEw#M7Jfpa2%*#|vc?DbB!?3^>`n zUq!$%CUGA{iod4I=Wn2$Em2W#Qdmv$8nl)`s+QZQvEm$`N^4|G6F5Xu&QX0-alj~c zv6{`NAb>n6X46qr;W9Mjpi8k}VlJ>B%<@o+kGiOK5%AoX%qkuk?_xN*$hFBTl12#^ zv#6x^iGkzbY|tUD4=unZ4E)JO{Vb@%x8r4qtI(}pqOSiOoA&`*G>C(U7urb04gHw; zwmkN(*D^>VgNzh6NWxQ~p;CeL39IRX@lv2r56L-eQ3bxPlS2JtSoyA9MkUqfqu37* ztdUv8Y?4;*OPvgOmcQUr;^enIbFJh}vH|`TXqHS^NgDCP=p3FNOoH#C%PNKv6cVa> zWpMla)@HQF$EGnW8kZ*Jb`s4Aot;Mga;-gWa~jSUar@1s_9&w;{E7k^oPS@6Pyr{` zE1}mu$Ddw8o1hV!{lx3TUScQvO0`sU7zDhSv*!~8%>tbC^M^7Q$a~1i?6%_i@PLxn zzJrM)Sgt(x1_yKL)c4Jm;Gng)M?WiC`xe#eO*28lnBCcQKh3Z9?mVavMrUTQZTRi= zzP&|b)x`~GuU%`dx->&O$Az}QI=g{bZ4^5UYDI~&1NBeUmqFL?xodw@37JH;GG&jK zvbH&tMPt50WF41NB9L5Bq*={q=1nK1`wp;g7AMDSH~pvoX`3Ja;|3q(J1R`qcl4bQ z^vomqCu-4OSty#mz?Juf;fERm`FP&pC@3ApVkc+1khUH{yyOkkKhQg`@HC(JV|yn! z|5#uD$)V27{@*D+|H*gwR?<2<%ui!AHq{fHk+?2_Gte{ddN#k-NIO?&#U)Ju=8cS$ z8E5<Qn{V7vaFxla>#?A1#jC%OX0q`y$r{|$hQ^fVhC9OzFRptIDn|gpec9XQDFYcS zU<tonwy(y++Nb%W`orUU;9h_10XV&^gE(c(cJ?alxyf4P%2-phWI_?;N_&b+j}wO^ zV;DQe;54|_uEsSdE-wRha1|Pw8BXv*Q|g*V&pq~*Cm-2r*<;IKMDn;DNW$7O>x0}H zu6@w5$R~`e_5iGK;~<*xqfOn{a7t$06x|xH7k3s-u8yqe?qT?L$(k_>zRXEqyVrw5 zqn+gN-IJ{aGfvEQLuu-~V_<L3AI*E|DFgRN2ktkQ#sp3d@g+s9lLpG7h8vHmnI}oT zn}&7*^sw9Ur|e}RNC?lImZD!Csw9`jOF685{DzjqqgT^8+tXL#K<-3LrJ0G<evDGR z3YsbC%GopbPLrN0iy5WMqd{9X7ck<SZCYdZNR1@qIrlB<V5yy$g|yGr!d)JE)C<oy zgiGTfM){&mLsZ`*iGZE~->;faMG?pZ6H(9KQ7glT8q}H;>zB&28<LsqJy`f_^kd)M zcOW$ZSATXjO6MCdn79%eo<r?sjWsHrg$66Rb6r<0cyz~%Wt?e>R4RI1bs!`tp?^74 z!Gw%h6xz&CZCoJ($U6eVnYIdHa7zYgy@vI83?N=J-Um6w-(Vhwx$%GdLA`GC0qT8z z_}_fNe=7Ce>_ERRRJlQmB4zV1FZ#U-EH*jG$2Ax(nj7OA><Og}f-yhFfmlWZK0>~% zj!RqF?|`jHY+k76#6;b0x9^r>-Rr@kf9~xC=EX$y_c$o*zz+v?;rqT~z6|C;!@Owg z_jR50_LbMk1?j<IY!3p5y0J36;s)HAx;9|Q9iuOd-#RjSKPL}$<9n-m_ImMyyTYOK zpDv#E>1XqUM=FPq1ky$EmnYkkUouPHE>rcDSlG3wcp=S=6iKF_l|&ov6QRUDiZ>r> zNu?zK!#fDDb#91_Wz&T)c(?mnit39E?d%;_Ev2S=HYo^L^-=5v8fhLTs(-+!5vL#V zbc|rsBuh(S&Gdg)Q)!(u6-nI)Ia!6Fm!BaHPgjGiwM<tI%_TInFn|G(cZ^6NQuQ(x zO|Ca;pM#p@9^ih^-9CK8?!d?1oople-Gm;z?OQgc%Y`Maof<}_oZlw~2jPPdK4=jH z&j1F`S@1(VQX&9p5xS<|{XoA+yrQB06y2Sk2WxurZ|deB*Hj4`r8!mmNhr=T8rCx- zGN|WP%XC2i)a6jNN3bHG$b7v9=%%DXK}Y)+Q}Qv^=^^;#OnUB<DN+iGf`nNMc<8VT z?9x*u@DF>m?ks#jc?R<mJfCNQNf<hd4GRF=AA~N7bRg<Yh>F;v9h}NkkL8vl!?<Tn z3?Ve)#`_Rq5_@tj(=(p4jPvUx@t#`P0n~Brv);(ETSA%Kr{@+|RWk^7>hf!mST@y= zSLU$dpQ+c#c#b)Tr~qWN>27|tdO0hcy#d?Ct+YfIdJJJ9tE^w145eyS)NZvD4GqW2 z!Mp0Gj@S*$rj$fSNX&Z1cdBAp=Yly&qD((h4n0NFkdkpgV`$mOe2X&xw4td8#@XN~ zh%#HOFkxBJTq7#5sz5!B8Pcmk?b@{>s4>J84NO;D*%2ZgXM1z~0w=F1Y4mu;JliS| z<-vqE8$xsQGw7*S;xmsGpr8!&a;=WbtFt8a3W<yf=NR<Yq>?6~zXeF3TyL(32Hvv; zW<Uz+<=GI_947IrnV?k=6Xp9d`mCH3`s6PFr~EBXi;6aFEeYwW?C>rn-7xz{wKo4o ztF5-)#uWEwUVm8pVEY^^n2oqcpqP~@#ndieni*dy+E30W58a2{`R2i;_xpyxUmu)z zWE{PhI2gVL8Kkt7S4@g1=hymBr~lbs*hiZ^(;)GHg}<#4e!!%)s@MNi9$1+FZ4~}L z^~|vT%PsxCmyc-;9V=}%1fLzfA9jd{S|;YSxIWNZpG`qX{9!>2<cLe_FthvQI^Egt z8_X-Rh70Uk9PG`smg~*=`BU>==bWbHc)^6spyc=_g>u?tMG9jybn`Km4q@P*=-vn# zp+XM(<@}oBKKH(Su!P2e{9qs+7-kF=80HX5ICawIO>YS(nXcl{Y)8EyMyg)%!S@Om zsasa)E@_=LRdr0eh%a)|&%O~w?T~SNWPZ%CcmtA(4j4W~0%YJ^<}{NjidB|d??rFh z*7y_`P#*k%ROw)RVke$mOp1Zt+g3qL?4S<Xw`&1F(&_-jfT|(heSYot4XkpK6Jgr; z$lAsSiS=wL3xbp-wFkuZ0GMA?%fqSxiZNTB1Z~<nU?^c>DlGPrbjaD_RJ>}~qSN(Y ztYb6y$M5B?Jl!sH`x|DCk`SA}l+30X6wM&IjK_0W`pcQy@QM<>)9OJ-YuRn}rr+sc zYv<nS7=;qqq1^ik*&8k6r*u>qDs#M`1ur*&Mcy@_<b!iu?E@1s^T6dvJ~9rBcTG^8 ze3bi~O0R$K+nVrGs>3o>7yS8xa*q@nyIo$z92MA$-txiiP#odKscXo?mIt`(W}Zu~ zbPBmbCuoP6iJ$hkn<L<Z4~0fK*99knDx(_&>u}D9)6^0;7QODC0iNxNZ5nLyYIui! z;S6=^pPhCKMz_R^&o55@t-tc?su9m}$z-l7L=_yo>P&<^Fv)c2xr*WIbF!{qv05I$ z+WI!&q3Y#kr#6>6Lk(@d97OF`RBL`0_z2}_wlieAX0?8@VhosUXnq1r;ph?u^C$Ik zHh4jVfeUu<wp?d{cRR;#7;ta{&fvECe#-Y|p<wb{_rJp5v2Jqd>^+;dvU+v&g9_=o zz3eaxSx;e;w~!Che10`|`-gE)mY#5*KmT<@PO^_5)E26qhL0`1I(t`-3g|v8zOFA1 z*N%nQC39!BBJd<sm|*;(o@84A0(y&cz84-IVEN+&XP0bMXP0<i<1lrcSbBQjuNwLO zy1Ra#SbDau^=jFD7@l1{emxF8ep0-Ex80y{2~EU|iD_7(xKk5xWTvJ6F+>VlUy$9n zVDM@4XoA%L%8Hu2S~@#A8~60`{=7cCX^J{HXnNRT+u<~UH&mj#^&QIC=T3l)fM5m< z3OTBxUH6dsx};t2Oj}GYDoemzscie4qZt)$%>NvRmnaN}6(nB#<6W*37P?e!T0-Dz z4x^4}E-2Iv8d_u@yNCAK!f9$h&Vq)?+)fhd0i#wtoC*eucC3yTF#lV)uB`86lQ%ee z9r2=&Dbi`y-5jWJS%9fr()kU@SpX<t$-I@@61>1EqVv)LgtuE|5J}M)hSMoRB5gky zaURlVk@&=FY2!`vX!}j`fmg5S^9KCWK^~tu=wJ@B+Z~Ki(T=UCP=m>x={;*yV(+6d z@S3D@uB@>zT!6>}Cu;~B1%p&_Ed2DQTv&iUSoT+GHvT9Dy-*KN?4KJQObJx9!Wonv zwVDOTFikfdkA`I(wNxOwwH(;c+0s5tbDJ^$CYe*%Q=el69OO?^1WpMWVd#nWU6Fgm zqUc&P7|f>&Xh?feOf`bVOaYxCh&GWzjUv7BHH0N@bFeh1Bhqt>>^%sFkVxMi96>Un zgjCX8%ul9sr{|#z@B#-Tp{C!(m$3Xu^ehm%n8GvS0M=2`U8&si8kukncI}P6-jd(O zFVq@cDYmIJlWx=+s<vs>t@QG#c#Zr=>)lQ_u<-?eK}jN3!MvEQEu)=AmobKN-)Bt< z+ViB#A3DFHuj4)IsOd|$FD3$up6W<*J)NkG<|5JfAn7TPIe!I(d37AG3G;x*B<6WY zydAJb1y15lY+^VguFj{f7F8?6i#x={sDc%EmDYM7WU6>VGlEQiM+~MWYrrTFd@nIJ z!aB+nC;VYrfy}55sV;A0HfM=N2uJ`g_&Y1nI71@wRY~Fz1llEKzo8SjVfrd!-}c7P zkkJd3G6|NDLem&cL@sQlAxPIH=Lx!Ekn?i5F&0wdM}rxZD!E-5C*YMQrz}>G(5nts zW2y}Q*KG)c`MrgH^YtV@!P2tIXd?KTE2a}X;JjLjYf9U}<bghrBA6TE3g6siysUx< zcI%t_gPx|9T<M>R7yG{(KL2H1VP*W!zirfiv_p27-VZf%Q~G=9nseF?Hnut!HkZ!W zjV;-YaS9|G3t|P`2-{4*-v9#ZiE23#nObG!2>=iXePZGHHr6m3?HE0}F}k^44TxF` z43E)E>*3baa6-hHovNo8Ra39V@2S6X+ZC)$tuH~2SBOlmCTR*Btd54b=_N&rNVVc{ zH;iEqD6#!CdKkTTngYjwlN1dO30$08vA(z*{mrpwwrz2=eyXAc%lqRnE7NWdqxEFg z$Vg9eH4Gns2`?3O%*A{jvDTZRmaV_gr}=Cl;H=<iBUi0P?UCrW`~GUH&39_UZ0nWd z<50}>!dlqd)Aab#zPGP~)BVRMZUS(JkIl<b#|CV^jr3+8R8crhcTH0cjPzx?L@G<Q zjb047uD%g7kCv#@AG8b<hiPW|R+8*xZDyB_yxm^bE->P(@WNv>%e$!yZVPqMs2gZT z*Qso>o}S;iv$dnOHk!q@Dd@B@nh6jsT~vSv+A{ue5x{0RqnTiY9Kc;W%iXlL3Td)0 zSX<@Tna-@7fZizHLe2@)7S6X#S0c1B&~zAdu+q87UZ@ie>CGMuXw25DrRD;iBD+2E zmR6)A$?{z$76mLzS}@7UZ4@Rv;W&H1-cLm7PYH<JK$vCtwGro^5DbOo&@emL0AS(q zuo&LpP`&UPDUEvqs%Ge+VV46Wa_-B=<G7^>EyBRJhs=r{k?$Q)(`##qr%Yd5EpW<D z`AG3z*ktRuovWM6CWZQhc;RBXv4mgIR&Op!YEU=>h2c{!u5KH&MAL0Dw6y3}EiK!N z3h|!q)9M-dYhl3geb6DJUK$+}jZ(v(@tEainBxV{ih?ixjtp7WNgIVU!UaW|4+Xp4 zd?a@c;<=$)MU7~@aNTT8Nqn}lvvg+o0q$?#SNmrs*IO8liSo_VWWWa<xnQiapF#!v zvL(B5(F>T#HQ%Yah-P`znjm+mTN8mqOsQj2NC^~G021R;iqfCBb&Sz3q?4?c8Q^!N z^d#kVU<$nPjc~_tlG_E%OGmZ)K^n^Gke8}LqAL_G<p5AJw3hOKisx?BGQ8%*A%7G} zae5RUCq0#l$xUQpD}A_&NxgKJqH<xfkCyaE4*0-W?&ufI7nzNZ%lu_NK~}TBdN{ST zXY0^<GLd<jjzMI>dF;nI^TFA@9sv&A<?6(R$#%2!k)R1gA;Cn)U%~w1#j96@m887@ z7%fwVB-9j-VSl&_&Tbs`NAH+blaFEgjdcur^wHiYoOj4eiL1UO;s^wj!<YA9oBZ#V z9xfHO2hR__BDR<K{`(^WW&Xfr>uj#y2=el|cQez-L(KM_u<-Ge-vo7B_~0MR^p7t- zSTsjhwFZ`gZzG_UT90QZB_6;C3A6#|YsalW^b>tjnWRwd<=;{ghRg)%m+WCX_}WQ5 z6?F)d;dx8dN2~akCy%5AgZV3_6i4@S!Wc;)<H577ZF7u!yBAxISf_Tn*7p($HX5O6 z4lV&NrMZ_NB>|1fVfqA6Ib9&OpuIEB6x3t3`1xzq<}@im<?OFO_!eO}<|uq>G@Jtr z;un<z05|Rl6S^@V6>Eu=M@R(Y+Me$EWWMZQd^2e`=*>iO>)*Au;J@hVxKHD4HO`+r zZ}AG{TCPh>pp}*GZ+u^0Iper{PadS$f3wvQ9-&WGy+kRMzgNA5y`2-&+Lz6C%X!+C ztq&gh1J)^B@wnBm19y0ZJIF!?_19FMVl%HSa^=b-Dx>I`kcUmY@DM5630L4}zIY@Y zOU6|WAbk?hHbFjys^IFwnz)wNmyOphMO>rWK!Mr);0u!n=ewj>s~@8O=*-vqVYC<E z+q!bsWP#Bw3Rd~42Caifd|1cpzcgglnCHAq1>SVwR=?U;?HGY_U{Q}@^g%_At&}|h zkBjFMsGy`^nG9=ID$5lq!bJK~BhiT$8Z{Id09Xq3o%X>~?f*#3)NM5R{56ry6<T1b zzf!s+*juKX;Bw`)4<qtH8!P1;^1w0jK~foNk|V=^#vhYfVyPtlz=NifB5UGhuO8Bm zO?!DaC)bTq=mf3A{0XH7|6I(yqTY~I@0o({p#e`o?UM6QTedqO<Sl;9K{v*iN1-Co zW0=VtTsy@pUeNqj$76+Xgt)qc`wM)O2j%*Y1?nG0O<7s~e+Yp84H|p+na(Cl2)(!= z>Dm|xEAMQj#=KZm2}eYaM;ah-zP&LUg=B`X&;&tGa14t39lK-1=SdF)q~y;(`;MZn zrgIJm|1Kzx&<%htAP2Gg4gv)eh`{|5mzf)6#lM7NB6u|^+VvpLNxSdq%9UYl*dac8 z#;tK$qDo%xtEFBe3~=+y6YmiMIBC_>Q<Om2X@%e9k>{3N3ln&R@-VuR9SHcMD#Y<8 zp0`$L3ng<4ITJLr9ATOu6a*=bllCW`cPHeYT+q0H1-azypq>xIr?>0s*{kT;p5gr2 zE^ub>wD<372PPql)5FzdjYgD(s&c_`rPQ`A1`zE4p=$-l%eKK7UL8)guTjQC%0i*w zut9s`Max+?JIa~_FEaU_=uUBLoQe;_;2BMx-b|ZkRkSnuMrXdc-w;VeS^_8Idd9bB zllJ*96W?>w3^OTd>XQWx&tx_|&e>drv{1%J4z>~#rbcjlIB5pm48f=4oXGgEZE2ij zgW5)!Y4b*j2OkAvpbEEM&fty6ycSHY+Qk@YV{^~nIE7AT4M+$=CGm`0>C+EKB3)`P z$BEA9M~Qe3MQy{OEz(M)u$iN@gswwro!}FMMcvV8RiVp+TQAwvf9zHKYJIbFsC7fA zwOeVn^HubkZ-;55l!Y$zHLCY2zqNCA8aJu56B<oAU^SmaqO_+PyDiOeX{4C7m-4C} zv{Lm#s5M(@ehXCfn$JsVq{dYixYX0s{of<E8ojkcs8t(j0<oLVqtLq2O%g24uV|z4 zL#y7Mp5P}Z@Lv{Je69uKK4;s$_Vd62BdF6ugB`#)%ql|!O{Qv_$k82HWaUuTWt~Ac zwv>~qYLC_T^?3R9p8n}3=lFLC;a^=C6Wf2@g=uU!7KtMGtf<9LKr4%+b5Ypo?(FM~ zx?0yX(cPq4f*1*a0`Bck?v#0X@{5<YE^FGUWWPq_UT5T9=Q?>JFeQf=Qiv6~EzHjp z;8Fze-f?SXY*Y0XfajLIB1^qUn_yA0RTgEfuigW*>}Q@;x=D;x<%B0_pD|*>CnYC2 z_uH{7$a{=8#aro>-k^>)xU94pNbSwFDR6P7$A05w<TIl*ZLmQ+_Bkfob9BBLQXsBw zQ-|8h0Uha1X;Z~Q&)_(xQl%B~iH1%M&(WfbcsFOf0cUuW+CC~S&~9a}uCFq~2z_zv z=fMt6Fd$RQzqr-K(wljim4%IpHGNf0uI=58Kkgd3`hK468XpH99Uk12F|QOBubaEV z)%a?_npk&qo_sXlbR1()Q8!3ik6Y<l8f^e`L`v$aFt;yR3r&}pWQf5oqaRI|`;xlg zN_i!4?<(f*&nYt&G;a`1rHMdsmBumGW)}AGbZoXz7Pn>Ra%&7dh3avzj1TPzT9#JG zX~!ud8xX({Fd?Z+MC|X2#lt+IGgT7-Q;@C&HhU;dx>!g8ji$I|9#wKzQU5_DRVFz^ zj5*E>=?#Gaq;UzKb6B*<9y_~gimFv3!RcfwmUFxaa}^lAz!F?IvtJ=-4WKU%x*9ac z)tGS|>tz2>8kl&`8=Ux}?>m1lF*vdXrnc)b=-3IY-i6ipD{1V(S83p}L1?v9pUtM; z<E!4|K6u|2kn(%G{<E#>_K9fnuL3OfDx5}D=ur<#^$L6yx}AE`Nk7ysGZz<6M=q{5 zZniAF#r@$&{81*4@m{_V8l0wa0k=Pm@<Vh4P}{-;j$iXm+yjgPiRq(UxboIs=YF>i zJwiHC(}Hn^adql-WnlusSeB(t7@@aKV7~*+6K{o4vNX%2gb-yZ<s0Ivpi6q$G*eO) zD|f%Jzl?qt600Ha<e1%5WT08`)RB_%q$3Omi!9V0NTLgn)Zz<u0t7*!86v<1I>0ow zJ6y8A3F7{S$_dSo)0<U6L?(*{v#CMOCg~HgjQa$`qAH8lEvxEA(EG3iMiMR6L*STD z3(=M7yaG8V2sftjc9WFRRFYzC4=U-d0ql`WPHQ(&JiDD@2DH=-Bhfk1AKsH7h|^t+ zuV!3Yo55F6&F@w(4zISZm%Y>d%Y(CTYd1SjZx`;KROgf&zE@t~f!TUgK8LwGWN=zO z1-xDIN~swl2~n&4^5IOcLVRPGli!Xoz8X0MiNn`U)5$(=`xAJOK)Nvd2U!?LZPX8a z72dc}tt-F7^o7&)U6dThxmRE`&Ha0P3?bT!L(~?v=;*{Y!iLIYYcm^?FJ*=$2x|T3 z3}6pw>Lk)1Y&)4-*dS|uAg>qc>A;ydiD{6FjM&|O{}|&jRd#iU%qY!JZR?VI9}vA; zullMW3uV=($`9CO90~d^cC-IH*M>}<xgsz|-BOhrUWHb#K^SvopUatH(@5+ac&&0e z7<tgTZ3WJ4hX8_)Hk78kL57b%Ae9u0-h^}0E0vk%50t=pB`6Mrv|@zSjgy}c>7ziw z(uZI{eR8M(eiWdBB7`wvLUoRlEoX~!3X<ho1qf!^5PlRCB-v$&1NNj;W?&YN7L>%9 zu<ts1AD;T$2Ro6ExTrF%-jm1gG<$!vT;qMjS$D`f4Pg554-V0{+jjoMftXIrJw9X7 zs?PuUGG$}<$*uYyXi_Goe{sD3cfIvWLnCg39m)6R$2O~HtY5t>fSb!^W@N^5x{A5M zVVV?B(7M)&q;;>Z$l3GTw@O_^L$M0ohsLy_uUlP2HGwA4#hYehWVt?u4ZSWEJ<W*z z#}k79lH1VDD7X<B*arb#i^@LYXynZ*H2>lA7PSXBi3}L6)N^1=@8!c5J+-pd$vxH_ z9z`Oh@MzfF{dzC}D6wH*iCHujscldVkDlk(76W_h%cwshV7y5+9z^IpdmjS+xUH`J z>1oiE+IsXZzAtux<9dq2o?4TFmTJ_IYSz`$YqZh&))w<=xM3T~*_HorJ80bS{$b6T z+pW>_U9bLS)UHk|7IkF#XuzyfyB%Fx^k&bImDGMx?qd-`H){JeWnFXwWwq<k{MeOS zKmEGswEIE;?GeZU){AM!N}h4D*nZ~Gn!$JyZzJiF&fkXmk<lr~wEfuR>=!0ufQP;C z(fX!TchgUo^vKOPCB-IKrT2pKiyGPzl}q;;f@<7(y5{nDYJ@s0h9j2c)@NOv&<W?} zqjX56_eCGJ-R*pRLOD?pl$PE+iHU9^>5`+@A|O`RoX$-`*86?`*pa)~ast+6rFDOB z=9IwaSIi4@_Y~>fezMqMSM}zv9MkI6mg=Dlmn|oo2iZ80rRzwYMB57Tpsfe6NS$oO z6W$KpQRhX~19PC>hn{Gs=P+$1fijpO^bP0-AhM8>377uX;2DSY#<Zy&ZH&AWhT5j} zq4I+l61_8O8w`T#aHl_)S)qUDCop~58s{p@2f->Qg=sRo_e^Q=gT6cm90^sKHz&P{ zy{3<m?W^`2nX+oh7Ve^lHqkv*^jEr}uugIWitefMFW&v}%}0S`w;J--j?`@lrd+^I zvWkD?VB2GO=_gRg&Ub&~-Q^@tZ)@y0N3PjD0e<h!&zSJnFvkKM8x$7ASdXqG>wNA& z8%)iVH{hD;Z6^U06Y+^UeS~ZSLJg7wi7};mVw<yu$>hO7=6b4Md%=$PsOBVRoLtH^ zqRL|}lU=|MDg)H3d`4k5w!J4wACY@&+OfE^5Y+<Vsjfy4gfxD;7sU_5Xsl9eEERqC z#A=g|68Q#FK6_lL$f48j&yccfPDHWdxyYH1F`Yz6ja6D=8LGkqbf^jP@**Uc^J;-P z=h+PpnyUL#e-I(PvJfFVa1!Dr5Fsl>h0mk<Y7FBw)g*cRRXmMhEJHrYL5b-h*83s4 z7%=wKK#56W%Pz}VL7a0xq1&P)!S;Y-OUTxSxjDCsX15i9KbhoM?~|=4C59-gtoT;| zhx{Hzw;k!CfMRp6UgiTF=3t`t69OE*eJ2nOLK+wxt$r5E1_X8$8jwzC1AaCwQOP1o zko?CmP(+Swj2GN}7K}0y3CZ3$sSdDkqt>{$>?p2tOA#=|+hpAE4}eX7k=W#>%3xS# z_CB(m;T?)|{!tsnOZFDj?1RuE4;%frfvQJ*kCdo!KC!u8&%dsn1c)CdZs%_;T*D(A z->)ZJBAo}a4PB|5^=lDWLS?C&@{!&U;d0geaU?4XM{B*tZGo)Ev^<3e-($|fet(}q z4SD@TP<T{$kyzBpnE6q6ck^j2YIcjt_K3$wmXu%iipmGY9PoJs(fh>;em4GVO-x}= zOMM5&qjjs0y;rm@yoqU$S+Idz2#W8OE}0iYF!+}!5M~xa5!|N45Vcw15RkceG0wvo zwK>ICW$qe4Xeo7;P+KOS4l>+}FdP0#L!c|fG^ot|-TOIVYxC{5>%&g&#c{u$?RQ!h z-`e!o-+-((B+plIwwp@u8qtNlswzaIR&-wdkm+3bQvaE_tMmAVf*ie7*|dkEaOock zl%_N;4O6*hkWP&yER)s}R<b2ccLGRGtCq>#7+>n4&nQjW3AFhR^@k0@Qd)ea6~ENb zj=iab;EN%ccmoF@8!w)TH<6|Wm3@nWzafZtz^FWu*yRg}>xBHU)-q|DUvfP^&?T3A zMDA0;^l>T6q&p?#YbztP9R=}?n2Bpy^=2bNoy2Ps^r#>+Pw^5quOM67R+6WtSiwjg zBCpaZSJs~wym&a4bya%YRNFZC={5IF7Qkz4V8rrIss$rF_juuc4@#uBCj1kY6w$oY zqBm#v79j1oO1hIK>Msm-bi~Y*I;$<)Vtg1HHa6kxx^4yh1?0`bv&IG=FW>42JWMNI zIP%FQ>rTy?u!Uia=MHtax>|8|PlMz;%U3~uTOO}YHE71ZQz%Atp-w{95VX^=iT&^r z<4YX5`pmGN77HHUxo4oxo6^mjesqw0BzLvKzs$$@vESBKSxR5pd~_Uw9th84J@FFZ zkPx2fL?R)e$$~er4O1aoq`{dyYKPD%3litYBp#9O(BjglSHR-c9)KE27*N*zFIE}o z%n$}ziTfd`%7~R!e+n2bjI*%Ck48u0;U2+M6|SSs8Mjmhyy!CVxCb8lTgVsOZqkO3 z<QN{?u+XE#wb(MP4u!52v&5Gh<6eV=Mfoz9I2jqpE0_!qeH(nZ<XWeIia~OlLZ{r< z#*zq*5b&=-+L~!I$}CTPc3ueoN@RX*2P*goxJJf8D^PGZx;QZ4$bZ3jic_8|X<63* z5H*Ko8>9HfH8*f`Qy8@Pe`3|mC-x?AYa}MVYS!R9RMW}_(D3hQ_>9|9_O&tbB4kZW zSSDf6b0(g^G4gAoCIRncmv^55f67G6odiBMY@R^b2!Gn4c^kbSign1|E-x=`PdZC! z%$;y%%!<?pLvJSdG7EoB`HQPK9GX&JSWc^FadU~6Uia0(pLFA^X4aPwZh;u$g3G5| z*Y~AZrRSJo)gJtH8<xv%avjgKGH~WJKn_)y?TWMe_$U@MV293K7Y*`dEikpIF}XuM zRHppZ{}-S-^uhHD^fC->=$QNyu=;N<91R;xup|&K37}rz3KY<DI$Qf-`y6&TI<%hI z#NkaVMr0qz2GuuqTn~!OKej^u<XqxlX8un@%6fiq4L{D{A6x^WJ_P}AlVFcL{Y6=| zLpO>>CaG;(0WHj0sZBv+vZmw0=f|D9Scc;vQAC(8lE>)E!C;shxhXBJX^iLZI4|-O zU+ZC6q|ja#U3EmKeTL@3At%8Vtl644*WLE70QBK!?MEG3ze&?V&Wtkk+H6#+*(PoM zGf|p%x~5@Klwb3IxqYob18#1|(v&IziQ)ci+i!lXJC($1*#5G^;c7rvZ*sXgFf*Ml zxvm+;;ftv8T5_}j)rLds)9-NE_^28+r=PlGN7*ZKLvy*LamF>Zp1#A`G5HFZ#Ax!% zh?0x;0KFWFx@ua0M{i4FyQ!U_7fssZJBX^fcsUqfv*-5ym7ATXtE;Om@wR5}9(Bdj zLf@00<TTq%(*&k_TJL|bxbo${b_Pb1QY%8s`V}w>#FaD4R#=(8zY*0tdzr|5;n)j` zEY#s-@Y|qF62%D%nr|s5-NYhRbIsk|$;FeSzvq$_P>PSk&4=1KQCv{4mK_2pj9eRk zgB*>)ayVMGV9-eJCs{aXc?2BL4fn?k9dN-3S@snd8jc3&^|}1gP8*3O@<OekPdOad zD3p1k(NHY=KpH?>#ms8OST&4em4{)*vff(W$VqL{JzT17WRXG(*=~8wRHwvath3KX z54iv0NVC!(WJ72TuY2$QH59SY?x^Sga{|)Z2FH(XEt$W8vmS^Ij=I3AjZMI*H7xW= zC(X)yR(SnsDr(ghZF5l9GzleD9TjLUQfw2JnF)QbTRlp+`ZHTo{`~SvdFJuCUTiC_ z(@t;pYSo??2KK6FwO^#_W>@AH6CSz;K&OyySl7ohrVZzCOl4>ur4GTV7^ZJqA*yM` z4k3s~qsZZzaulF7u)FP{Nn5*=(VfwU)~nw#B<{5(-Q&?m2GA!3Ip<~Mt2Ecz(2yyE ztZvgl`r3;2Tozk$N{yU0j$IzFlu+HZXd%d_E5e_ja?ZppO-v)2cI+g4hpR?dw)p|v zZ1FVLc2YGL7~S6VVEkRVp_8+t8~JM(wmXKs>oEd*JB3ZaG7TGl6f{KT0^zszQ9Gps zWbrlk#{+iPU=w%OgdB9>rph{VX|ZJJCRucgF<sMk$t8cuwG{{eycft{iXvQ)-%i1R zF=r{GS6v>w(hGJN;*EJRDtO-~^+dhWay7YGM+VDqPu@t7bv#u>ayqRf|BboAaXNjm zYEwoIn)>)7X=b7@RSgz~bbYJTQ??*&-Ug|;8+#*#+lGR48dKarvw(s=fI>Qg6YNyA z%$^CJBy>p<8k|s9D-;b3Rzp3;KpjI&?ZX!qq!h2FM`hPnz#L1%A~`{zX#*S+GuYfX zzA)hlN<lSE2W))$LxwC4J83jdx|cYBa;ar}UY%BzpIE4(f36l4Yc1J$h$=K8CandZ z>7!(7|97&+n94((Q8EAy(lmv<1qLWprb51VxB`DzZ6;O}$opF0L~d27YFuXP>|y|5 zXBS~_SV8aIpVQxhJpCt*WvUN>xWn2k@)QB@j!_%A175{A-Wb)>e!3WlGsSQ{fLOvj zHHzgGG79KTcA&7%r_H{t^y^>O=_@B3cv-IMfUxo!Y1s4Z73Vyusa}-VLFl{R$NR4I z@(yuN6h;e0(K2yNfR9paiP;l}w@K%toT`L>Km?Gh#wNBw8CvH<-pW9bg4fUeU`RBb zy%<sf{`jU6qmoK|?7lg{`7(E7ZD+@ZflNnHTa3Y%r8&P|QkLQ49rqG2wbL`m;xog( zfZiEgCtWQj0mU>12I@8E8uC@-MZW8nAnrnF;ZCukp!As#j6Rb>k@~3^w%Tl;!Szwd zR)?eP^^2ij!Lfp!;JY_K0q<4~0#FEH0PK7*02qs604$Ng^i3cS0<i2k4FIq>IYDg4 znj4cU#_~a6kK$7SNWW5z>OrdJh^|8eFUFLvQZnmkms9=)?8WG+Xe8>NYdfNtaDth? z3%N<kkE%Y`k8{|0T7(obp^OwDhbK_CQkM>7<6HAkk?)-)&<#N{tE*?&sZ67hxGjc6 ziD#&AXquDhx5}DrSdY~gC}d5I$4`;BJm_*pdjQWY*}TS6)KIIlzb}&dY|<NmoBW+z zKR^sIIpy1a?cjXm&|5?u7dCQ0!;)Fc?+{*_kL%gjn7@EKM<|lu8sf3)=xng9lb`QH z-zxWOPSyn5_=Ri(z=w;cOROWTJjW}%J;5tH(CiS;c=qH7kI43&V{?iXB-v)yv^8MC zYRsjTaLxhLPx=?r0BL4|W{|0|jigr9vPCX*W;YjLp~h(0<Qd;ne=;0QPX?UphC&>C zu|_&g&^5F-R_Yyg>Ro`zp?zJwwD7?w*}QXT%Q_*W1-Yj%7w(=`maB4_w*W`}aNOn^ zu<oFg&eACaka?M3BJq}rEg64@S$ox{xc@zVvES=KbsS0nM*;T8wW9skOI{H72N1b1 zG3z{c8BE!ytc2MBgds5=n5bqMFp5kf`L@)3e$ZRhvqn~T2oxWjn<q|KQbd>U^zB#z z{lqWdsna~Ef&&o){m($icH~guRpNSq_1BGa50cf~6sR$HslEi~^B1*O`~lhR%l}#F zSvlAl{!R4wf0@wO*#0d7;wSg}Ka49K)|j-_W`o(9RWo0+WiAv}MA8Qt1Ga^3=8rd? zUuJ+=$v_hTmfI6c`1YAixEhck>u|(b#MVkndkHTb6OugW@f7d(nk=CFYZbp7l)NcK zhgIDktW8Ntnrz*#>_ow$pcpg}FD_pO0xZ=V2$Gj6ANbOvSOzkh7XP?gqo61RT8=_p zpeng3G%2Jg^dKt%tD}!ReVXfUolZ_#RMRKNTKz%*a9j>L9&+4i5PYPcd-23S!k2=E zO*1c@M18D;&$OFSjB1QZ>@>m9Mot&p)Zs|Vpw{g~3G1{dI9Wi`GVknJXR>bVzCjgp z<37)bZCqd1WdO%cN{%?ePULS`NJHtg1xY*=ii#<kKFuZXIN~c1I<4RhjrlmmDK=MS zk#BD-sONHxYXa0$3d~`&NM(ZMI10ue>cQm-(1<2E@t8?1>YQ$R*)|qW2ofwccL@<% zylD}8YDf!NBr7+NQ(|5SLs2rH1Z7Msh$)tm>l{rJ*J1!SXu6W@zt6f%R=_+JfOve$ z`iS6I5%<)ZkD32U1YW`wl2E~^8iCLkEp!aXHKH;=@S3?yY`zO#8%}t+tu~Oe%vp%} zY+=Ig)Ye?mK(xyeiuYAk6NjoXSF4S<ugYaA)C$0i3Wm-!gjBR%FBY1A$cccqKWIvE zlFD9aQ4dOdEIo~5Fp)W`<vpLxN*rG;MTqzP*Z}SSQZ<V~An{>oXV<d5ldBut(^J1) zRz}S$y$6~{l{fLEblm0m^msaN`Soe-b?@ke2siNl*7Q~H+v4Gd2&d*QGNtzSv!y@k zfRDB6Nom(kmVO2^{NQ8hefZeh%fq#i<G17_;fKY;`}AGXRhNA{f&Xwq|Aw;RMOgaH zD-6M$7_Z`A&qA|3{rY)^`x8Ci5JBt15R(7H*gFTu`fuyLv2EMtjBVSt?abJkv29y3 zPG-y*+vwPKPWHO%*4cIU@1C=&y1Kq^_xn#**XS{NjAwkFhTw2{#_b-y_hM%`k#_aS zn7wIQn_8v#3ih;e#}PcXb4gz*t>&R9ECvkRcjnM@<-%ZC{yI3n$VvV?w1g3t8FlOP zi5WE$lWUG&vAnrK;{2lGA0W+c=lVvM;wT$vY@Vb`9mO#)s8WOF3bPb?@Z8ajShC9W zQJiOnrv36l7UzXtI&3&fa+&oQV*@HP<p#{e`xw=!7(yEygxzKD{wyM!f8gBx&96I| zg11Al-+j$TKccWTiI4J=g5*!h*ravo+z?iyiAv3XiAP4$%Lx}b6SbOQaC=Qwy39n~ zo6+Y4s~6XCWQ2$(wpb_49OEa9*dgH1+tMXc7X0a(ojlBMDx$K?3&n`GjV{ffRS~!1 zhyH~D$8O4EGSe<PZT7>2Al0qIZ<3qOANlOt=QGzH*xPZ@VZM6S-sL(FTg0Ws&+BD< z$n*1N>Ljn~A?afEY-%-~4!^e7;H%!xn`l4qF~`uXUz<M`X9a=nDXd(c*D>HIN$BFn zaebox)BepGcjv+3FXLYZ1qS(84hsp1y0|Yt7eCkg!~3U;->$364b;EW>*4h!!gdb= zZ)0Q8-NsMTGTHh|(s&e~>;Ph?JvBaA9UdHRo%sT*3l~Ad)JQ|?NBMj@&8FWU_f@Fg z3}J0X^gc(m1y)-K+1_Q8({_*rK6{rp>)!Qbr!Pm$8I$cNPY!#B;fNRXwU?O`Jq!_R ze&-R_@ub|O%zFRflB4LStIBWC*Lk^3J3!DK*w1LllI3ynT@&w%r_yBxj{8%NU~g7S zgA_;jqx^oKD`tyJ+BtZA^cf{<M3J`Q{-^=M%n_%XQsz5%TH3$-w}R{eZqOrQVhagQ zTIn?7<s|idi{b2*nz6ik8(3=DkhOksb8MH{<}&kd<FF+sz5wMD`D6;A1*x3i$Jj^O z7H~5uB3ZmwUgC?!DIr`OS4;y%il>{71y7huI~1I$s#fwVvp>+l^jR2q!afLEE>Ru( z*}b^!R54pZ8$1QD8Z<JU<(!8%nQWw7-dWAu`(SBrb3Kwqegzbq)+%#c-=ytvv8r9D z<+{bZx~CFD%Gwhgg-C^m+@TU*O<kh9PBhGBr<344mP-w*r8fO;f|ccJ>dH|P!_HW3 z<3vScoWD<8KPC_dQc4ygaKiVkA`L<1xF}pxuyyCgL06MiBD;zqdvW~d9raaiFcU-k zs<+~L&h(Buw?cc)F0z){G9hy55-0H3{>DPhk^?4rcs>u6#@jmI6y6NZ#PwPJXD;Jl z`c|L)Lj#}V-$eHRdjo&ydm8%P!1sO9sJAvK*Nz5;)-R($jH2fmA5CjG7_%o=p%E`O zyHqSzC!;*``EV@)Mlns_<lL(CViwGInz6h;u^*jW!Jcg6^=jhxa{D7f+Dx*2H2nJK z-$bQY!1^#ZGk<!Zz>D3--yNnQJ;J5P*=RZiN)<||sXOQO^ZCNqvuZlUd($5Nm#0Yh z#L0S{L8fNm5%$)%B*b23(!h2P2qN)<8!gF8_~rf7Bj@9z;nRaOREieU)O{mN+!7b2 z!X^hDS?UYzR)FRP0;Nh8v-u~zlmN>iT6q&F_q3m0^$!b<Wz6V_sdvJ&p@)kPZx^oK z-0i8QyQvTB9<EM<8i(2+RYQOWTd68xC+?D^Dp-l%c&w$d7VSo&FdOo^=EEbA@cvI$ zIRwBYF_WB9u~urk5|;e3oUAfjO^iw6>1eM-ryruxjfIu-oWy@_1K0Gli<>oa(0SU? z$F_TVGY?m<P{T7&y2stcvQ@rNV+9gSRa$J$MpSjV@y1(gM(>Ul*Bb?CFEdS|V4efL zX5uvEY^Qm}>I{KW6Gdg^I;rpf$caXG3R1E$+A~_z{k2a!vgWN7U?EVoj;mCD8$z#% zAQx4~%hax=`B@&w^@W(R$qM*e(0)8v(k*0S!vb*Ba>(_Tcsv=EqOqs8zs=m}_M4<R zt@trksky?8sSQz{bH0#)gR&;nDdK`ZQ7S2KC0K1s=1H+$!%6s8Ix&!oFf;o#XFcCk zWf8#t76hsE698aXm)=xn^AQ_C+gc}`50G+nC(xXXeI<*^6)F7PltMB$g%AD82#_nk zqnPnRweEucq;-fD%(T)vP#{}#*@zqo*%pVxs}y;f<O63{-c_NlrG_hsCWfI(!B|&n zB;sgS&_%%)13tG28LA;_o2!^>gK(CryT9nuh4mO9uN<Oxf@b|n=X5=}a1IP@6q|l< zl0-t`>E{aNk26b}@Kah^5DMQPG~g-`2CETU%nbm=qIN6}*~ecL+Bcp=@_MwwO-cY? z)V=$murKZHo>Cg6*+^P$07_-MXlrxAn=TW}lc9Rapb&$YNPXgz^gYBN)M`;$UcTd; z0cIvA^**Vbp1QY*jcXe~L>)7lCZ5~;csTUw$<1rwHD)|OUMb&CC~AlEYvv95<nRiS zDpvdx+jFv(KQHciOj*C*N+39)c-D4USPK0Mykdbmr#V({VNp}`^F2N4=bc$I+)OA9 z&gvf5?v7hFI-7<7{z9>2YM`{3UgPal<tqQ2E}hxDsl)^bww3SQ%z+xuqo4^h`zbeS z=G45ghCr^gQbo0^!?v#O{9xzm>a_FEg7|}B?blq!#6GATDsm=z@|C$@X73N!bNP=z z@=&}%aBAwshBsq2$OD=EZecR!>r4?XRcD7#5)8ySIw%dd))5=K+n9sVFgVzVS550y z5AF5!xksQaNlqFG$97ec(rLiE58L0tw}FseqFJs-mlrNc*FO_b<9wZ@RDQ0^`21)> z4gUODD~FsCPTEIQekw3Q@>xOo0<uDz7^14v9$-q4jTH;@1f4-b4UxNgV&HV<d(tUX zH23c4C4yHZu#@oC6Mkmk?O4+7l?Fdrfb~iev)<U<&{q3XZ3RwA|9U)+?w#g}zp&!% zNpIEJeCLlHZr_oxYZA^(yLqb=a%Iu;z?`^AlW1Y^9=Kn>1~lT03zAo0)%W{+6NJ<* zR-e(~;1#^=a6E~@@;?#mD(E1L^ni&=3mIcT3-P-!P0I<O5wCYh4bN=}n?N7RsUqv~ zs1l<(q;yACq6fS8pkA2eTQCx?!0<NGj@!}3k5@P|$66MNw`i6T(j{u~$CPzkJ4WE) zp^DQ_<Ew2C7y!U_CH!nd;>S!l1b~M2m;fVOU=eKKf=&B*UcOWsrvW5Am4>9)n(?pA z`G)FNfDi)VJmhtjgs)UiPx-UQ^V7?lxx4!h1AB(cw27%x+t%za|J=!14CI?4TCEKR z5@Y{zM0HvqjX-=cVOKLWG$OfNmAbWI7(osupD4IGMw~6^@lh-?SX=~RFOU=JzfGo- zxTATu6l%YHWc>@Xr!5Vor?$<`$}x*9&y}!$Q|`x%hwx$Z)0n(TA4_};`ljYpFEyRr zaeR?sABD=J9A6FWg0{OQ65+X_$g;`tjpCAmh4iUXPs$!<RED*YZ%a6OiXC4<0&D#- z410Bg@ZPpsy&D1;^Xb^9a$IrzZd$Z<Y0#`anx>NLu`^DCC6E`z*PQjRF?+XE0kbes z7f1G1EeOD{qGhLCrdVaD5`zhz)djnsR(S`GD0R}>vM#pjn^d?)!4DW(KRK?`6d_Pi z+U3Sy?X0hCyRh8AXyp4rI?7xU3E5XlOra$63U{n>X`U5#Z;k$9T`!PBmj*$^81&+c zW1<wJ1d1W`OiiCrFcF2l?Q{3pvfuREKz=0FKlhNiU!dFktrh7Tab*0k_W5yvDXWG? z(AC!k#zREm0bY7US{lEkSWUGMfCmOcu1M66!KM;qmvVpyd@+*}5DRgvNgA~)rLVWL zaa}{TL+o91){%<ob&7csH)*CEWu@E$2#rn5NEDoYDXX>6aYwqZ33>gtxE$gtCxH)a ziJjp=^WN8KoyS%G?Jcr(4i^O!3vtxy-ggRfO`_571RrZ--uH{G4Wmpg+OYr23lNKL zou2>!Q#*>xMsi+0pMW>6#x0JMT}6m3&W5jpS5g$>1O>4l0>N6iXyCLjKPo023c>f| z+&=23C~y|uj|E2l=B~d+A_^vn{k!x@WN=AL`iNmRO!kDsMa+>uX2w6G&OWdA>}pq6 zcGsqOnBwZ?f2tkB(pMr~?zU|Y-~4pclSJ{{!qP2H%J~Y_nC3I^q+=U5*#*p2PJtR| z@HD^wH37XCck-PP87S*u3xU*nx9`c^{@@lEv2~V4=^ipTW9ktO(c~+O`&gcWrK=xd z{X8oDBt6!V-|6hXCcxTqDQNLA=vXBG!~<fC7Jb7UPI`67_q^l1sJCREH!k1HTQp+& z2P3WTvgscvlq^gv|CUPr-^-?MtxbphZwlqrzbKUMP9Go4hKTL0C(begsl~tX-9>iR zq>Zypj*L6?9+%_LtVX`Q0&Bq^QIyccl+YeX0mtLYvngjyPfbmC1pwL}jJDd6NsOp6 zo1QZoeM9Tof=Oe5!s1el{`S2OI|ko?QeL7Y+L4o_Ye9{rV|sB=d8Fn&oF2MPf>`0x z@_DfFdg`Gk1|2oJH-YnXt+|E4G@RjS)NJ+HTc*RBbTj|k9iv{P(Rpy8jrtDlw6b%} z3IbJ=l2)bcv>(sB7h{Jxx1_Pk)#TYqhK;4SjZJ2SR_Xc~ZbxmEz~Ej}Z5H<B;Qivn zpOINtKPL|!JiTcN4#c}Ng{01xYa`xV1xAQ{+C-QGdu!Ie;pXdk9djJ`Q`ex{*F6?z z)@@>6AvQ`;c6AP1u{gsw>S*BZwr;acuIxt%ZUh>~n#FNbFOdhZ2~p)_3C=@}(KK?A zG==eKD>OA(^jZ`Kc(RR)0Q)RVrJjnBDrc1xaDwKgGoIWUzjLpAA~|EP>UxfW8IX~Z zZoUWE6)Ek=pgp1unC6*QwHz#8Yrlgf*YvMd*9VteQ`abN@9^?f>Zqe<<)zcs9ZhwD z10g(oaAez6XSNYuIKr!+{TAG~8~Qz8q9jY}#u6RvvH0g~4Z%6w?(vrq_@)CdD8wc} zk?L@Uzmc?*&SY2)Q;aYK9%c151DQKsV|R(Eg~#NQY{yuoFI@8oHl@Bq%VMvNF!LBr zCoFqs3;brB%eURBV%QMCJ0=SJE)=mS!$E*e*pf}n<g26gRIA#@pw)JRv~sIr8%d#i z69gF{&1*CYnbX58WmO9GzIN2Po26!gb(r}cl#-`W(#6DMNYIT%4sbAm$H6@#A|GO+ z!win;3Je;`H^5qVF?nr;y5rS?Jjbg^bRCqJq7;L>IO(*U8>W`4E!EB<NCH@P?zD)i zY%4sl`=nFjv=9_o#zZ$-e#XxIr42~9d)ryA3V+MpJv%)kW#{Bm_TuBZ>|%B}#t5^X zR^)OM^v~nYpD#w(JeS2MYJ8%EDQHS~>yj=+Z=hlaQV?%AxNf+MG8%S4oJI&gy&Ex7 z%!sN5O-x65mg|Eg0PiyOTf*-~n*5xOMpO<HM}2&elII$g6iQ0)kufh0xCI{l!^}PS z3?STdyq?H;G&>mBF{bTNS6n#vRF{FwEj0}aid}eC&haR}6ys*)VwMWd=Mx(+N^I&? z7&ueTE6KxpOA6P)ncc>CXtlcp#yK7L9o?72zm@a|;T;bqdoCE4lpN+jVd+T-I8cW{ z(F>oY8PfzZLR>GQvSJ&1YzIc7qD#t735)YmyL|8v{oqbpWDP6RjE-?(5@Iw5bV*9$ zKa#n(s<^_waJdNnV%H(p1#PxJ{=+6MD%e;1{Cvm#v23F#U7x*NRA82kg*^Xf>f_m( zAA7R)Fs&%AXrc;Qs>5MWY}sycer7e8#1%*JTULP<s3)zU&0t#pD*|OBgzA(y7l%?o zO1DnD;@t4PLrqHLNnU+URDr37+qjU1C={4esoba&EyI$y*<gSfX&y%>FqduMEvMD& zX2VWz82VltDN=AHOcD<w!c?!BI{#jzN_GTTt#)5{)OS9!*t7lD-*A!4g_IC8uDK6S z4SfGP%$4e8=f%9pS$AevT+H95_z&4QvSbhm0?IDZoW{n)Cr9XA=A8&NW?+T>b|Ki; zTr!u_gVz;LC1cFAS`pxkpvZ7-1XB?EFVB}xFCT{7IfxSb8C`@-3R`!5c8lvlcldyb zMD9j;Q0DFl`$}ZI#Q{EHGb?O}KZq<&^Br<w#(8jJ(xy{UNT97&RlmKcU95K&TY~Ny zG3sBar3Nkv2MVZwp@Tc>sca|&MYgm<u#*5$QOS?A*c!#9k(gLtbvCVoi@!;1w-oYO zcszdwL0`q@qe^3!#@eXjY%EMyyG58g@%y2{kN>!;W@j)cF`JX6PHNfVc%*fy_afQ* zTWf!bn3p#Ut@zg4!!OgYwP2`Z_w~hbTwqdziud#GdgLS&{_VEZNiM1KAPuD|W$jH2 zrD;?SpONXF<1_wFk3EP*cxtBEY)C%1vVa<@hcBm=0H*IXi<cIqXKm0nhun1Pz~TCc z=X5lHp7?lm=-&Js1RMK_Jdznkfc!Zb6wN=qhth|g{u3lrS6V`~h}=tUhKWl|U8YgJ zAG`AxoulDjBfo^AsitXXn@xF%Rj^IuGZ{^-bPO&heQ)sepLO4wv>D9_gz8Ohyg4+_ zA%<x6bzYgzUDTgu0c&O8$M4S09s-0L3P&El?^aD6dGPh+kf4Y6=kp4;%iAU~5DYEi zrtYl*X=)J${7BrprZ_|ce~IGZc?o4Eg8xz~1O_pVh@j{O;=_Z#((L(BCap5*WaycQ zUIJy3+j7iZtQG<JDXL^MfyiZ3_~Skjm+HkQNZl{D-sT-dJQ2ARIMN+Wu9(X$5MfU1 z&RlXH9~!f&OWLHcDVv?QaZY{7EXmnA4V_R_9VYdcv#hw;-Oy-5VCbUEur%hwtlP!M z=vlQ0h^s#Ri;RDuJ4bufpH)sRIw-yCPXE~i#3CeXU3uIETQOa+w={Y9%NG-&P|)@M z-xONmGPz$ZK`5<c$IA#ozt0T7N9KL*etxQye_=YY2XJ&gTm@cO)=rq6v2S?{<4rzZ zD9E*gt#6`SQ9j?U^!o$DK!p8c*X4T_@ISjQ%>OyWdP+;iW&a1tH$|+T2D8F?h!~pR z<!&XhXb`c6ysVL3s)7nSRZ}Jbhkwt>@58+a7ma*g=aw^EcTl_tnC<!jHr~t@Zldkd zH}{GEmzZUU`N3O%x&U^dSy+z)Sc1uGE3*Nv!K)DGv&m-@alT9&e~ik8Q{woa8R-5` zwVp~3ma09PF;=vTUx(dwe7I!v1NP={BCM{uCM{>aF9R$~Gfz#xtluq{YBG<oGw692 z@R<tcvyV=ThSby(&wnW<U60S#OG{GR<<?zgiM#&Hw9-|54QPMbYsrUk^W@(R)g`U& z-G18hw(D>3f3~)Hx8*U^`sL7HUSZsYM|ZAz-q)v3G1}W(22}khWq)OJUkf+K78zkD z<-}`wbluVZXv12$?o3LdgAmzm`|#{$Fx4_1I1_*mS)6XSNUO8ql{@ELJeNSx!hFf4 zQcNTxm%ljzs;H)^VD&2Ov8Ii@;e3<L?y7}w_ebol<jRe?@`_k0m!J0srhfNJOi77Z zUdR)mem070wG+>k__;9*3aPHp2#*a+*G6i+jV0b)=Ag^YB1)Dq2P(Btgtwx<T@1<} z^a^I7DAZQU39;gj*jKcDnACZ)|4yGAj97TCL!VsWB#4azKQ8D|0B0+XT|UdfPP&sg zMBPB)YAx9lMBoYI{fu%ih;*+XGQ&ZN?UB69O|!v6WM2*B1VXF0?GJbP=ci-d27eED z`<KwD*h&x{4&-RTtRO?7{HRa}F(gbf*&cdFpUN=|zYH0a9ubbK5xh7ipoRN<G1t<o z1#0@{lxglb4F11v35#JELlP;%6}NK@C%JyRqdyH6){<B6j-I~{4VkdhFS99Z>LO_; zucK)4jN~qHmcv(*$Ir?P9Hkk9slMIh2iJ5oT4_S%>RTHJkxu}-4&ib4b>8B|f#)<i zqihLS8I{g*Zo+wy5ZXQ>S*|U(CR-h*TKLPX;8(XAZjt%%{JHDg-1ct8qUV#VJBd-$ z89mKGih@DN_Oe4YE=He(xTaLQejrr*cgZ_9m1`zmO<9m#N!_V65eEht8h=sHFzej^ zx2WPA*aVrmH7To<w>p{=scR5I+Z`Oef~Jsv-agDUCsZ{U-$3DUXwI}w1~NISW_P~+ z9B6uSSm3C_Pli&~y*>t-!wcgXo+R>?J>f(!IB@V&I?%X*Uu(6E4(#c=N?K;&t)SDw zN6w)Ge?w6Wkx8~@JR!_VmPH@95rU_uVGVNfFyk2rxJX+K^3q0*zzrNN2}%$^IMo{G zd#FHoXG~j4a`j@?y78v<(@+Z0Z=SCM$5}7^hAWI=BJ@W)z>)Y)t=lMuJV#mTJn@4- zif58|-0K8YsiiL;xh`^<r254BW?jh?nI(^E8>JoVYFtODD$<4W>f9RpYrk?uQMkL< z@U6eh_&rh4X1mfCoH#AAr+=X@Nj>1^VAB&2T$PV-Q?hwFgh6P4h0g^1qF^%=35O`= z5e}wBKoAlhPmFJ?nWqV~jBfHBAneBKOwY{Gje-BmhlS@(QH^NXI^D#wn>}ZS8g7Xp z%qG)QVM+xe?>egLNXrv=%2g+`M_`6baMPH!fvZ88R4v7?C3PyPv(IeOnOcSi<=(cQ zgitU9jSWZ<BaXiHUsQJ)@upyIC|8Gaiw}!Z1aFR=s=K92qJ;vws-BXEn{N5b*7b7W z4mPxM;d;ZA`RkAj;4=voYWMp#>7p4aG?zjEcrztWkU-oxQvx~&HljT&NVJxiclD#l z6IvHNN${DGmsjhc92dfBc~J-_WUtw@LD~E)@!<j__(5^VEhiNZUlkb5u}dt7c|M_7 z)?lbOxTd8Fm)&=<_5hW^xN^YUN^EQFNjvz%&t?XA>@%O<Q-1=Z>#-Xb=NG-_=99f4 zAqYw<XN#A_;ZD0H!bto4fHjZSM3PaC6C4j!tlLVTld1}KNMR;P7H>17D#W`AePoPY zBh9UHkX^mjV3pbw%{XfEgvo&Qx7+0tQj4N)Dt!|5t#{Lh-+<#^rkGWK^CX_GrEFiF z{i04g1_Qb7D6L_;w}E(}AoCZH<s$sqP4u@JP_?6VR=~{zne`@6%@0X(Cxnc_`3zA* z>+(G^Kv<@vro*B`4O@Q-#<AwoxG+gNu2J+mzhT@mksBZ?*-0HqKy@@=i)~x5rO+ED zw@#I(PrilvSgXWKWfrJ&L#EyS(i1tkdmO{*HVSj|w{L@KX#M@rUy#~D5w$3jjFLmk z%Sb`;lBKfZxh(jbwwOBw<yIRZ@xQV9@=S3{SUe31<Z=hcJd`Yp0EEaA+rf636lg|o zI{U|xHJUpKuJOXkrnO;g=6TchsH|6BM^XRGaZOr9X?;+_{Z`qkGufd8bG3%Z{dKE` zU5SP8v)mi8semNLC0)W)SUWEXKVXR<7x%S^S(BREz2Fn$jnQZdt9taxGrQ7Y1>J7n z3P7&1Mn5<FAKq7tuRuydjch`C3`~u*=!vYi34_nvBOQb0x~{^HdP;2#{W6sdLaB4Z zn@X<(d`pJou7WCuj(Tz8-X#{D2A{-PnBM{)LojOhB_T6`?BLD<$8lxL-~ZFfI5ZX( zE-y{^vWHc<o?SNw>N?noZ;IKA4<U30wfC+PQ39v8qUKvJn~vvdYxLF-5rpe>Gcjx? zq0Jh)xNl7kXavNAYE}FkJ$XPfzl{bp-NmJEPY+q13K`Aq>eNf+_2pjZ&9nF)t%1RF z9<9}!rMwckr`@g8`nm^7#@G#b8sxX8K-I*K2*AFsULq;4UVDdOCuh8-d)Z%m$+lfV zw#9m#`Ihf_F?&j{np`TRscSp(+s4(j?i+<T!V~vZhrWQ5iLYAzX-M?F&+$LY6{i1u z%VSf^;2U}h=l@hTW6yZIS*`d5=xL9=@Rm!Obay#x;maeLO|@@4(4J#?nnxs}(z;F7 zpL1pOjT8g|14a=Da7}MiOJ_Oj)_-6qEiLn0n{kpgYf;iI^@=TO6A^K7HAAN%RQn$J zfet(@#6P*|eDEN6`XRrH9%+mATV*>IV))E2XN)8A!h3$*oq7y4%1*h<X)0s6hL2vz zsdqE-;it>ap1JWU+`-8}yLW$c+E9YdJwmMxXH*D64&@tcnam3sM7172kD0My=izXr z-c=LY@e{Z@hH(n4!pybR{qtFe7Ysx`BbiBuB;gdg@iwQ@&Tgh2T={hv1?Y~Jzriif zQ}6D4z1g~Thx0F{LYW;A<<0<OYqqCkYS4k%bhG)w-@efmpTJL}+c!akub}fyY65VG zywgrQ<yk#r3$oJgTAF)@B%6RaS`_>?LWD*(uEa=R8|bWx-UrB3`*J_&Qzz|fyB5!k zyZBP{476}w`n{<HaWPR!=z`;pAI)Y|MqS9cds>+JCqai!)67uIN=@($&bfyq7(3uf zUDJ{D%V0DzQV~^95T-bqL$U*O^RJ*Iu8V4D6B&z`k1}9DmA(V&W4bPPx-h7cNM(M) z&YJ0_el!*bN(LHDEC~Z_Nq;u(yu(}{dK{P@R@Pv{A3+|`efThxvhAUvum@d;8Y3Ln z6QuXv`pQ59+lU?()<fRf2j%~Iu?wN(rJo#vrvvYsDUR}rjN-MT@I-4Vyig_2-s0q2 z?HmHmI7@0Q$tl~SevlV8<!}61eG$u+f@B81?gWSdU@ke7Q~1`V@sokjkE~34Lwi}T z|LA9kOyMJ}w>9Mjc210K`tWK6?`&GOR|Z&gA$i8G0ujK;x9@9G?gZ{I?*x`Z^J2LJ zPv6r$5bq@;S!OEZH{(_?3^%xvQ6WNA9;}4&5VDShPHo?GU3>h*xqQzKYUG6h_Vf~7 zCAt=(yCzNPH^C7Nr~B0#m5u&m=7EKJ&zEFT0pZZJW3&|ws-)iT44qA=^VMAl^)R;; z(``B*nl6X}32G{~?=C{on)64&LO{1@GD)yvRI+GA{<PyaQjr0_v!7hiqK)lamCD^Z zSYjfh3v%PC+aEPOK&~k;LSCDl@Dw7m3uEgpLCh_2GC_383tFhb(e&cU*VBRBOHP0H zB~rF3Sat(CqXp{hvST3K)*<=9S%SXR{X&CJbNq%hB(#uHWD32s@?zXrTQ$G_O>6V{ z=_VCKwmu9j1*RWBj!G>@EJOT7R|TP_QUR(;#D4*EoE;2v07e7Hox)0kMVyq0k5sst z(1E7LBy5i>PDPI8Mz%A(dae&a`n1Z_kwuq!mt`|&!U%@qf+J`=MT-JwP1G=Qm6pE* zhH}<pkl8^!Pl!e(f!MxcYZ~!J)TDreju7x}-f0sAI$Jsa3%SR1oE1k;`T$8vq27fW zIFN(!Sm&@LZ$?imeC9Etrg?NMQ{miaIv6XCHvi`KvSY4nk?BX5I&0cENJKdu6zv>W zcP#2C5iI!~@Xf(dj^1T@{|4`86b<hn#l-1bomKhb?<xYIH`lh(mppGE=Ss*@;xk|* zH@*O9Rm1?VX&bi+^<_{+o+?P96gzaON+8J=TA(l`HJ}EDqfPLGvO35u)YCt20GmC8 zyueQnl*urSC;7p;O&?YGTTV2ZRB4+4dv%PrMk4e0lH-L|vJjQxnR~2*o&7s`d~Eas zbEQ<m{%p1=YrkVm{)Qjnwi3M5wwsZi487?sHLbIjbyFhMfCIWxs4o7u(qAPo;coDK zfeLvyP6}qqSfBIp3hg38OnE+s`fr2b3OqLtrp;}y^*#8%w&m5YkK1v4pP2=ikEbwz z!spu9*|dRX<l=Th!{xh4BD+>O_r7r=!U%|PDqARqp>o}tYEU=tkxfsaU`Gbe;h2M{ ze83kGK7t5(?)jvqoqD=xu9(Qn+p)TRN$dyse-)|iM5$#XQ5_C`#~WzvREz>QP$z|y zn_OVP@iS)$De)TGX@E}`)Af&U#)7K4y@&R@L*sMmJ?~JGJJjLG)VU6Pf^m3`4Nc)4 zM0y&YkZ{mLRAdT?Og?GhjF(!B=9$B>k1JjULL94Uz(SM6N<`VL)K?TX2_cU@zJpm) z4;uQCWW^RehOJ=u%2S)HH?My6?W-KXOA^l1o|6)7JI#Vh0*UVjfdGdcr<5lGz@5^~ zuZlU$v<IQb3P{7tr0%V9V2*iFzPxJPmO`PH%J$zFB-hU)<Mq3~n3p*xY`el86$zmb zXy8bFFZ*dtK?Ri!?ysfg&cRSfekY{=E#shfVIkdoH77kx(6M6h|CpGbgl6-|hFSEU zzo|S*UH8V}aupv<b=K-km@nTvjF%FNv!^y?A|J~3i?05~jxhi#QQgn(wzzCWD(%Hy zNas@N7uT_BE>az?nGDsed-=3zvQT9&XkpKf!JW!_vo4JT3F6c1V=;HKE!i=2?&fw} zv<~oY&DLk2m>7#vwS6n8i!i!FXSNmKRro&feDtC28Rt}NA%25%z#2iBkq{B_W+U5S z8AG%ZH=}XsB2tyKM#TpfPRN;We&`}mzo9BBI`bfyxN;FtW>h1&vT{N|FB;UeNa=kQ z*XvEO=H4+zoo>^`nzzL+K3jyC*~F4EcC+T*1~b0mbE|%ZfZv-@SYJ3rOT=|wOb+-1 z@10c6|5FL^jo|y=CB*+xGs*SeG?PF6<AKVQrj7$1JDT6N!LEeo&9knLt&CEMKAIp% zh4mYds2bWFxR`3EWm5j_)k`dgPOB@fLS|Ha_^%O{!@G6^S#7T3c$cDlu6T7=%|l%s zB4*oWG$^+G^1${h%bg(nfjGsR9Gt;HE9n_k%w$whdEb$sRt#xrj7A!a;y;ZqK_b8` z7@R7OvJi5#tG#oAk-pK_Nt4+{I8gpTkRVD7@{p<67Dk8;S`9}rNF3WH?-8nB7(O!S z+b+;;F9h)|Kr~NH6<5HFS$lAQU`dx{Lqk%V?x2Cr`k$>*plB@`g@AklyUq1H&{n?f z%VX5sFVqZ#_*R<wiW~cK4FSf0?0g+3U-V^Xs~$*p*v=o7by2JtH|k?8z$oh35blB5 zDrtCBT%8AsSOZwm)j(z{+n_+W@&g2a>7N7fz^jyXWAWOw)1WqfA3_-auIo6^4XXbs z9M&&N#uH_vhUyBQE7pExR?S@&uhHmIxmWd<x*CY!PX(@EwF``5!%}-8k=UkqeGeKZ z(c^V%)cSy4b-!smN*7zUIK+Sq?LqFb-;p{~xn7dn)k1!9hi%XJrPYp@R);N$YUO$& zt*+WBNEOCHrGKDHOOy=4$Di&_)*T{BU=~rik}D%{$a}sB7>*mhcqX@6B$RIeMK%N@ z=?ZAspWm;!S=DYGt!k9muJL>%4M+A9m)^DK=ZdS-Odfow76bQ(Vp0s@{yL2ev9TEQ zO^!hkv=Qf+Mz1$zc{kkZoS`KceAODu4%<EYyxy+qnv=%l78!+**B1*MGc%H^1jt9p z#zCy*%GJ_$`6)EdSS<9&%#mL>^SY)97&h3*Dr2*(IQ?|e85M}4PGoH-7lYcI7@7!? z9GO!g;)T(vu7WWK$Xb?9vyg)$XNzi_+%WUZjj3qQ&R^%6Q37LAsBb*0e1C|Mez*RV z{%qz$$e+KPdVL4n(qxC6yfp1Ib!+!@!dy-Nd{`!w>Ee8|YfsPJI|rPe&dn=4USZBh z0|2kyE<Ifv6stW?1GiH{t4R-?j)`4@EqK_Kb(b6$?0<RIfd)_JQ$KI4TOf|dTI)G= zzPP(l=}Oa<dvza<t{ByO8A~b8rm_H~c?tRo+w$9T3JT={oH|EH5!TUEbi;}k?v(MG z1wO&v37LYAZ8o=N={;J#+K^a#RTEX;esYU1tIjUouZQQ;(G&CY(TjCwb$Tjqha?{( zx=S4y)`ctM#1`9>Jq=dWXndWU@-aSy2?@f)L2<LZmNwMhDTIQgd8TN(Ch3svKM7oe zAnqctAS8SxK*SgtGhRob35f&a?h{Dar(f}uXb**ozQs&Tzfq(6qt>EzY(>P~r6k$C zeLHio+_*`)+KDL<<$5NBo)uW`<J3)Va|71lkUeH3pN3f@zox0n@g;=-P0BNn(&ZkJ z=iX_fwQrZDP&{mlbPf2e8^D%eQYkD%;+QDi$gIg~E8Yan6{6U;e?}$X-9@&aD=a^- zaB3LmYGcqqYQede!bojPg_*$eU9f})VuFH7WR*~+L&Bzf*{}skfnc4p^SLTrrbgL^ z-0ORvXJV-I`Pqn&i`z$I78FQL;jj~0gQf2)oG{pkA5sg@XT=K_{0gdXRx<)G_9y$i zuMR^hnik8d7*|Rx!+sX(8`lZ~gt~~xH3!(#6yIz7?6aH&N|7j$r-X#!a^6&T2jB|z zUD`Fa2VW3Y-SRxs^`0U#Xe%j)O`F#ti*AveZ!NJJ{upwT!ZCr2q*}1p1(_P01z@R| z-xsFpF+!4F0J;7Jlkx(CUv~EO>}ejp%U_%aixVA$gGYbkjPs#pb)(-YI$+sbgN1Cv zz}v;dyvtAeJx&U#Gz1ke8_?ogIK>S#l~}ko$`pi_9%Ybem<h<}prFn>?thA8g}}CY zojFlE*uST7{ko^=yw~=Kc5jORws2usZ~aLPtrhgH4%YxDgWgZJeIAHn&%hT8C+o?6 zZ7w#;gsZHj;*C{`B~qAZ5GOWZJ6J9$#`<3W{4qFiEt(#RT3uG$Aa$m}JMPDm?yKIT z;fB&9;<iRfpkC%{Tyx#jk#kB7@S0JF-&+e<X=>0Jb$~7T4oW&Agz*TQ$MG`9FbugP zV%j|eME$u7R9Fbt-Y*pzBqxGKLs_aHqDxVJSlBaJmIWCz*N>*8(eqQjz_6JlxzJPB zTB<F`&7N&H^c>NU`Osz(r${&^7W7|o;4ir9r|^mYl=j&EfvCjH%<&&D1zx0Y{?}4q z-}Z+F)JiniB-@YzmxKKKtgF_Uwzv`zHHetHZ9(I~iHY9l8@||BsV=5traNwZkEp~J zzFQaJl`yQ14XjSn7NC(MU3vO;MiI)Io{&B=fii?V91MC{yS7?qec<m1z$Q8<iUrv3 z;hasLq)egMBCe@^P237Q*(sG~e#><At>`F-ymjLvDmR?BzuIxV^CO}L{a9b8es89U ze>qhr+9`^&h=?+E`{(k2Trw7Nt>}ZLNh+l=21CEy3|xBz(Rk#%2lMbFW7RQ&Nn&L> z^dPUd{{^FY+S9iyt!$meQ&GFWz}?aQ&|n^23v^p$ce4;&>EI-4>uU(<3Cc%D`#?SZ zK`gBQZzXJie4eopWR)5LdMJ+L+ibzgU!18QI%+h5(zU_NB(sMe>HBnYxy^DT?d~%q z=R#TGS)Py#m!b0(_1jvBd|;94FIklv;cSFwl!NFg+6Kex6p3wzWj~HOEJs7PHY|PI zQcMd(>OZ7N5%c=VXz<e3B`GUJj-e2%#rY1Dm&ir(L`n}?@HaQuY>&BYk2O}2A`xvD z4D<BaEmx_unw)gk2aC`kc@3U9Jd-u|m4X7p8$k(5*7hs#*)T}L9v60z%;q$$B&E57 z2K~v%9`Ph65Fv=a5qooFWK(c5!STFGeAY{YE(cvBq&mEf(c##h#gP(gG9#g2XOi=U z`mJgiZN<ZGAgFy+yFQe<UD45baW=aOBZ?{$SyG^rzFM86xfVcoVd8&<njj&f7?`MP zGO?-P%y*2R5uYXv^;tpxm{PQLk0z4IFRy(9!NZlAe1weCtP^EA2dxrn%S-qSzWAg@ z&*J)XYq7ar!=5NMWtVFqFXW3Tq@rFVt1Q1L$~TLNbOJ=F;DUYdt+H+>_6iz@fR*)# zuFruufscRg#2@XpbrHNg(d7Q_on|~*3mZ)XHi}Q>Lt<Y!QiazhlIBOB64NM=pgGa@ zjtDNCk~0`D@P$VGrIcD(Q%j34=WAAl?#~?}@>bb*HHdClRb5rMP;x!9@xG*l!+s`8 z%cq9k0U<=k@oSY~+Py<YSWUyKTwhz_sVeuaD{|l$Mlf&3G1-zccw%mdkMzOp;nxs8 zahFMnL*`3IyE8-IRqJ$n{Q%MU;^B6jga#|A_A&RVWEJb0?`BQx?e$lGQ%YTGvP@1H z9d)pq>d&(fEa)q`G6WD2xF!eqcN*ARlFVVNg^;Vt>*-j&>dm*e`Au7r>RUYf^RGdO zce!_{vVm!uQ7-~<iqJay0rKG=hKk2xuVU(dP`qnhMyZKg3E4AwWY<p@1cdpuYVL7W zEBls^Xi}imDnuOzjXb96GUc=`86bi=e<ke{2pYBGqb=H}0RV#Ch<_jZG(Su)L;y0P zd`os3_%!Qu4u;i*ED=dA>*>PGgNksI!Fk3K8thkIQ?|?*Jsr8-bK-knvy;#Ml^G3r zQ|AWO=Jyt?Z>{DOxvP_zVhX;9L2i7v*>yq}zi9#^&}6|!I7PBqJxPc&XRJxWVf+-I zM#>&}QefWd%37?G-IEEzpE<@_2L53sii3&czpq678>+?0`tOY=qW`-d>LNqOVT}nb zVEY9<^)XR0+JvV8^>tY9qOuiq$u6i8CNj`6zFv3jVS9R5Dos@u$2Yw^6LPS@*T;u} zpAbdd5F81srDHyot66ua|Az@iIzwP^{sfle8W;;)DR8>gkHHQhJPp{k*osG_S6+5d zg)wT~s&6jat~AbFNo>L}D#43xZ<apLdMl9|ozuZqel)<=hRN>3)`&S0$d7;7tw6?h z$3drw2Mnaa9T=&3jlpxn#y(IklvxL7JwWQr1s1)5NU|Iapn;v?Lc|hATp0oZ-E67D z!6YpChIGv(OqQ5{q;ck9KTWx>^wi_w%g#%<=`qcd^d{fSK>){C*Gq$MK`3()!bP@d zOJazG%W_(|Z|{n0rBBkdZ|60Px>+At;w2P+&88MyVoyxZpx){fKhZ4x63=S!K+b-< zyelsiJtN~q0}Jjp;IyW#A&VyML`JFy7|)`MA#J(NN3HbA(mhWqK}9x%TTiZlYE|Y@ zU{yO2Q@TNq^E3*Fw5CxQuq+w0)hoY9^rSRNy=95>@jBk>jI+LU!hapIyG8L+m!a!} z<E|yWr9K64j%RTZH<y-NDmT(FENY%-VJEXpJ$aG@_g;8-7e)Q%UOJ2*x%u<3Z$3WJ zh~-T5L?dOtdPKctx)pWhQ5B+!qR&b>e=H2!yLO|0PEJi2hRnDzGWX&CxVi1Xk;~|T z9Fj*_DAPm=Vps=n*ocs}=PtXad%%0+)dJ%W51J&6WgJgKDvop1ACg(6=Nye>*B_n2 z)i{2sn*IVTeUfyn8YZaYN@LWh0$mhO(kZ&YJ>hOqiY>l7tW!J__uD-4%H1h3<CfRy z_f*tFaJK`}so+FQG(_RJV-3wZ=PtQ6E8~VLszK2zY_e2&bAlyAG<4~r*6@rIT^0hx z{QB91l?9t()V(jzuUxd5jo&bAk4u4vY=S&a`MV|oKiW<_>XL&(aTD3eY$TWB&s8PG zV@X%j95%B+%!-Ayf*T>s;K${`&6X0V-acbks)V%e!dKs32C9Wt{e`uR?q{lk>dz8Q zw$R2skRc)m&d1LJ<%ms&rq6na{Bb-BP>cDf+X-dr{P}9g$k_?H@2@$|yR9?+srumh zhvg2=|921ZKZ?rj@2Er?*}l`zT$3T8A9gaPyoa|8UMX!Qt)2r@Lq`FfmF&MY(ffK^ zb(%vNES?RItn>n6czn6-=6M4pfvN@uF)`y*@vc1qf_$WA|6>bo3x+QpxH%G!V~7#d zerkB(_XwTtGu}*Ppz*6?Hr0x|75{++emtE#)IijVL^q`><5q>ajS^(oMRX((p;Zux z_U<Q`F#i+ub%ZY@uX-+XeFSu*ne$IrUO-ilbqbU*iR{g+Wow*eDTL@ROIREvktFR* zd!mp9MB;A?3e*B@m#N^+NDh2NLUE4eOVf9zY`CuQKQ$aUo^!xzk!&#D3|ovSAl$7) z<gs1LHRi;N(`>=LBh`i(r8+CBA54>)xf9VT<|OPj7JF=TVh<s{vSVUDrS-wHEGcWu z4vy%S;R=Q2eqZ!(AAq)~WJa(pm#C_^6=yz|7!|&*C)S}(9bjWYoTJjPMud7~U^W&^ zbTrtc)^j7k0u(bO#<VksO5NAZPUH{h&ebx&_DWMa;+)T&P{DDnUa>nZ(J`>l)?%m5 z#<I-Tm8U>V=57;lsdbiltjCw9+=R<<p6O7>w)GIi_xV~f3mA}u-p!gFIMQgc%p+hM z)U}PJ)XH3So^8}?Qo&bgJ!!M4ia_P|7yBhD@&J>+P}C<lLf-wC2vjE?zPqKA$jMs6 zhzHQnGs_e^c7^EM`1;znnHIq7SN#U_OxOB2?<8qL_q_C8P+UuE2Nc7VBc~bQEEn9x zrjv*>nt3l$B~bS-QbVfQs<O~zqt^K?)KQyab(rL{O9qEblKcAlm+n^T_k$nLTbCDN z0^W~qvbL7o>b?OHa2u!6+2(Gn!s^en?!DLa$@q@4f+ca!MoiR@YrvzURzz7_o|o6! zuZFMuhT?x=%>U|yV*8#kHSwh9a7`XlGiAv`ZilkJA9iTWTa*_dSmQ5nm%AzQV3x0z zeRD&nJXyH&aW2c3lxm8!C0bkxGF?Cx_5DhuDCbWtmp-B&{XWIcEFbeM)gk#Fvja!m zuBjEUGcAbFjI*?bv&HBnBZdTsOCB_A7ZcJ@yB3&~^D>VJg&(iVT8K)<6GbBZflLAB zPyY~$%>Seq=49pke|CcZqgeb`h8)>`LHk#RY{+>Q-j-e`>ZmyjcmS`Yk%JQr4gt*7 zZu|X^?<hX~4#f(!y8zA}{Jbx&$G8ZhdJw1>?*Xm4t4<IoPQyv?Ch{F9m|-A7q*11H zF++PVq;-Vd{;1+#6>gZ}ELReN4K8gzg8jM@hBHS?ekG8zW`xZ3<mP}*yAT6v*PO2u z+d6)G{5bnKH(LD8kQ*9MR1uK<b`E~O1dE6N0ta0R2E2Vt(qET5A6i-9GF|wd6-dJd zg;=ZjFOEO6j$?(D6T_n%HwIo9hQvP*C&GqE7N#H><q#PBDodKZK0G)J6(HDz8yT6; zn%_^__3-z!Dn)8oR)(B?l48w*;v5W)foa+-xge$;b#)J_p))n-A#kc8iekw)Ds5=i zGc8#h{qajWN8L^Ub5iN&Xmh_?7weK8-T}*UXi)3GOCL^UthI8cWl7bXsLG&~F~p^< zaE+l#rCW!qH1M#aV1`otV$(zyQ%X+_O;2KE_50|kYl>HPb&OVZl~pI*rq$G%eyUVC z$EL*7?EPllem%FG5JjAJBzU?IL)&;+CFT)DCOC03`$Tq$tr~u1q&9~Km6<x$sBCnv z@**yKVM{}cAX){Yy#oh_($dfjeD{*3_ZYvzNhy@NbMG2ial&;fPmVaS-uqsk!W_{= z2_a=84B^@J_ZR8dyWz#VkrGiqxj;{kfYhf?W7rX!cIqlSuMFUYHEV+LPYIL~39~*J zj!Y^maW;C@4&NXj%pA8i4b;_dXZuc%)@Ml_6>x!p9Tg!bS<+acXy0AvC9wvc)2Ds1 zEwJBQaPxKoj2@kAw6ER*Zmn<dSJPX*;fe@)yK0ybI3qQcw)3(}mh?fM^RhnC<_e0X z1uTN6EN!yPHB&6H2u7<bPvMy6Adg#+W5-n_8J<;SCJs5KU8JkDl-T?Mrk^)Q(@i&N zO_}C{7nV!2)kRtoP0PZp&OlS*m}L=JH<uOF`<f#Su_kq4CYQi?xNk|U{>lPLkqBm+ z24+`Bb&UvSU(jYL^G92hRJ}oXw?7K}Nc)L)CvCbouBl9`U%fUl52nF;TA&*VVtg}C z%l-MP*~sZLcz<1U)OA_f{6kzavHf=?|No&e&CJBi`oBBV99+!*={Em`ww{9y2a4}< z-OhR`V;7zud^;0NG5j2TJuI3O#!3w`TBFY<PL_0F4PD1qkA)|@vbM~kT-E~S%A28= zWNg^LF0qBDtvfTW#Y(7YxhiraG<9Sjg%_hRvlmunX>-9b9G3z~0x^vknFCcZkuq~~ z1ZJ{HKytTKWKqF67NHV<emK8uhD`!RwPVa2ByG&t3?;%J+IypBG)iBra{jDyXmuLY z!_hyU;pP<2d-&!egt!W|4_=Z|>d2_YnZy9=t~#aH>rK^l?!udFQ~WV(gYKCAsvR17 zA}>@Q;}cklK_fO2c{O231yIDI2)zdsP_}RBSac-+Sl2cG@Q=)#$cj+5q{wWR!+`yU zR!<YLG58{=NC)I;C{a9dR^d64ST&L`V?^YB7P5M|AnNLkjC1Wl<f9mJy2htD4IKmg zpkV$W)#5rZHj%R=M0;N-<9Lck4CPcc^Bv+uQFx)rvB<KRD-6oBKKY~ZDOyhXf?vij zf280HlSwDIv1CREsQ9Cj)QpqbTW5t!730+~9Hg<tgQ*kD1f<!>5sSuva2g58vp_^6 z21}KZ6p%}C!e*_lO;-_ZrKjxBa1EkS6{<K|%o`vB;)`~G>EJ{{1_ZP2rB!FLL??sj zi2`)<mvqEr<uL8=kp3{+ip0#FWoha#?!n-(Z;}|_Xey(J!r8L6=-U$|b+6^HaZz;^ zQ8XC|<O?E<fIL$me^W!kgzlYbAi-B25O5KZKaHjJb#>`FG`@bWXI*9io<0iSoSU{D z&n~*NL5J<Gjc2=$uQ;wQ)jvKQowc_GUeDG6m|1y~B_a})W8Sv5k)|@f-2pW`Sb_ZQ zLSHA|-GQ?cyY52Ej-BUV>ILPB9>T6P@i0Bmb>C>q&)mDI&%&QCm)7fR{=Ir%7PGz$ z?VXobnbDVSPronEE+=HH;k6d6Z5V8tW9;D3=;To@6Rcs434EH-3LX}8b<;0PPI}h5 z*3vICyqvq=uP#130O41u0e>r}o3%T#<}f|nl3usy>-wEnSsC8|77z@6vW&hJOZ$TR z+1hcNH`l2m{QHOFo6ks2w=(|U_M0!{F8ONy_+DDCDR0mAhnBEGC!iZ(QBE0aNblGj z8BV*pvoN&`8cr$W@b;x`y3Ch_p1xv~o4kjZ@<9dN2E<;`CRKhVy7cB=({-ED>%yI7 zn3#4!mnYUgJGDF*JN<i}wf%D6>o<EoY?e1`9k%J}E-$R_Ogz3WFV?3vTRS`Swzg|~ zuRd>AB@ieW_-UUe5z^7B<Sa~H%1D!_)?#?X6TY=<w`SI()qh``N5~muC;0ie86fM> zQXuR2;c4<RWC&ooF-zZ;dwa#gTA_NVV{OG=^?HBa9X?2zxyxl_REwy;+L=XhI+g>k zK;p(P3}+0#CIm=iibGqKSmT;;!_u5-)u{}M=PM53l)U4aaqsGeHTjh<Bfm6~@Wip; zW4E7F6H30Q)9fDSh;<NJaH|fZNWAWvG$!mznvu<9?yt~0^!gRN;kiljq)aQJfem+E z=u9io=A*mQGnxqLC`%Vb+0dt-^t7*6>pyZ@QrYM7acow7mR;1rhC`|$c804dFc7Lg z)cY$w4CX(`Y(PuNWEGdl-O`jhuhH7fCO2D3Yk&WwW+r0DY0+D>WG_0aPyG9EsGw+6 zK-a3gX+t6cuy!e}AZOv#brgQ`f(sS64B~9zO>L5B$9c@4+mCXzn7=5SHa$%{Yz#I) zt*uA7{ORRG!=f_W@R%fG4zmg)(I8?TwW^+08a639w8z&WVSWofc6O6c;YZDa=qHDj zkq|#|2Aq+&-Y$!fQT|i0;UWP$=Qp#$_XR55Wf32XNCM^OKB>xwvMIrPCKC(arKCKh zX(3$DU6RQ61Vo7Yn!JJtUk)K-OCuT^(MPI0b@RXOUb`dz*;_i9W>^P`A1?)E?KV#; zt1HO=eRsb=>KHMq2J$i}6QDbZkT8v>4lVU(9Y3)_;u+*M`4w#*Kqi*zNVB^BYd<-- z7*;@@i;F5PA=M;dpJ13e91OrY=N!>!MoRxvTK!X>O@4LvH=&i6a<hmWqE$G~C(}jW z>z0M@Ra4KC*7jSqEC_8<-#8hX8A=ojv{*(+VQRECgLQj3;NOQzKxJxGo>h2;d;0(1 z({pbLzV$oM+O994sd)eyFyB1D3`qL->0g)spV$8NZi8F~(uJTZ;S7T4d$?72CF0lj zqvPlEgnz{)nDU=0B-IESGW156YGEZI`Xp_N7Fp|z1(pi4|3%tc2F2BN-J-YzcXxtI z)401k!QCB#y99T453a#ogS!QHcXx-&`^kO3Iw$wkbLw_??H~J3ckQmV#++l0HHOk? zqS>-R5rOG{UbY^HZ_E%($p-#{xJ;jxc>f*+|2J0z1pZ%C!vB>r@W~aqBuGTmWG%vW zfG-0YE3Jd>p~`5;q4MGa_dc7_w^I%a$^L@rh_JF2kmxSCb;sy8;{Ja%rTG*3^GB^k z;P{J1V-R&1)hJHb;4U!&!QFHqj^j1AZA)hQ;UqJLhB`|p!CIAgeJ=GkeT<}p2fBn5 zHJQsTsm?ww)v2F#@AV<a6ba^K{=_SypFpHHRFBalDAL{-jQVWgEHJ18a%SQIu}qm% zqJ(8n{?`)U&oqNj%W2HMSb>>FCvdXBdL&RiViCjAG??+Xm8)A1mS!Tk%GIkwAHcc% z#o+nr%-yEc_+e7qENUym(j+PvR1I-{w8tX*noxSmvAUNy&q1lJdf#k2v4nea>3|e_ zT(UBmA}Tu2`wt)aUIk}?<~zkIwH1yB&ZLtJYYATC+6+`)etKdbaKbrvHt{Ppw9iqX z<$5FXi7~4v1a>c>35~zR1VgR1ij#(l%eay5)0W>cO)Wr|mU%;Y#>JvGfl1m^rLWV= zy!1T(*mE)PT`Wy^WD@sZb?-`zD4$7#b)l&sjLn!5H?@wM*0E+q2Ht=0LNozgycbB~ zo|euP^vI&y0U0qFv`NlP#=?~<$=XW$)Jyy8=_%zZLiecacAvbE09u#kBjD;!WShYl z?UVY*huN7=%c|S*vI??KT+y}&Aqt464akgaGisYrIy&h=>EuKC<pKb(1SiY_-0K^P z7iw1Uj*_)S&69O!traNJX;F^-SK%AM@mct0bCd=Se=<lx=o+jIZ0?=hCoa7ls~)59 z&yus_;cE<%H<e!5iz{oq7toWPf+YyDgJp=wD$#f<Ve$1eV!s_3SI;RsyKAwC6BLd} z?6GAiLht>JZ(-tf5GhmYt`;JO$1C>J!q%au4kbay-OB}xz7v?cz}2Hc<8nipCm4J< z*zL@-^wN)OrZ=!yS-1dM>SBH_^?5_#SP9PiS3qjO)qVp_bA%tN%;pf&if*_VU7viZ zO*Z-nGfJ8fR{PRZB^=$NP*TN>P0m(Vz!9Mtt0es@G*HIBP)j;V=~nv54$Z3(DBWKS zHW(KS?4+Q6fY8Mmfc$M8vi-%dl7sob>e_$Qk^XP%kf|d8h^(W+B`{aeSSDmhj7v^O zboTri_faHWCWqURs>zBKx>L1tlWoNR6T**GKz|j7j%zJ$6f}f)K)YHUlt^#_`_l81 zw8cbeZsZBI33*%%5BzLNi9$#(#QYi^o2LWv-DvAs(P;6=q>V{ogS^`~z_Sm8j@ukY zM@Wjxnr=*{pO(67(Li7884qI7kOJE#?&!hd@VUWZT6qx(%hI?v6_3WgO*HDSKg|n@ zeYT`D-@FMDpBSl(u=CPcBz~SeSVNNqR>;RS3x<+Q!EVi0`?97@4g|E#9QB(6JMm<m zZ`zLLuyf?^AhcmQMWzViJZMntLZNZ?JgTHugjHipXCb&1L&scrwlxLOO-Lu5jZE5x zq{fFBqNI|(nRKBKOFBw4^~km_%mWb};>u|RSFYZ&Sz`%ImC~uwPL#wy`_Vk;bDPh8 zRBOb!%vK3>p!(C;x%%5@KRRWio9<90N*YOoa#RV7NoZh;h)Qdm{L}HL;*%~4w49-7 zoou}@KnvNYf=uJEAji~)@;)E+Dl>fIO2-rW9LVuWEG=i2q-ndJDU4JAkke3oSx<AK zt)`b3TLsaF<?EsyG%)sZvCDGjEv4y8uM=$}^y$myxJViT*;h+h91geDpncMzG#JF} zNo5|@gFYr}LgpL}j*Rh84AO>aHStM)bg2IJLaW+6N-ZuNbH@z#z<8$tPe_Mf8frkJ zl$SmddSFFtkq%|WGTnu0>9jA!xdF$osJbo!LU>#kp%&TF7@#Zd5<J#ZhrdZS;Za_( zsqX`1T-VxHFJ>wZ%ieaE&ga{^+#U#oybm2FwTa6J*vo3Ane8_%QTkRqw(+Pu2bds} z2;)<_O;F8cW9^;rhlW6nca45Tc2dV)J$wP)uM6%s5qs_s_lo~Gt>wp;ot%Wm+Ly<% zHJI<I2-1M7YXW0-fFGmSpu|#>r*qUwZlJT$n6EwkRXxTVY*N=<xRtu$P~oj~Z=apm zfd3+o&n&0skwX0D;4qdE*t>!Z6*k$v%ncqRG%)tvN+p&b%gqAKnAg%Xwd}JMt;8Uu zkK>8CWG|vLYyaDV{7l6C3otVO{{hC&1&K++_3I4g3_)2%;y);&{{%*We=3Uy(=<KS z?=b%V07m3~7&;KJg<tE<bA*fdc8dmMP&=G<D7%rMO~S;z`uP4~-DyuOouG}UwFDFg zNxuTjzsf{3uQp5h8`5vDPUe%V3TwUDpJ>62#=&f6iBFJFBEro78b$-lJ#7R1V-ymQ z;;@U$F&jKvQ`iBfdm;^|LW4rCoOWzhzQmjNiHnVS1fe8;Y_2kJWPy=Lxv8WghJ|So z<7<Pt?5*d#dh2V5!3&ce1`D2@MD79W9fUvJafVfeJO%FS0)L3&4^b_!x3Lo#KbD5= zJ!tNdveJhv1``FB4gtNH*lmo-RVKM$;ga}Fh!PwWFaD@?1DDOMFrU(fWMmM`H7i$` zJZf`s6Z>c;M04jpagn<-BM|q!EcQm3)#MWw5ly)K8*p`uTPhDL%1(v)@~+8*)|8DE z+ow!BD}rtQ80Q<R-nWN>JI^SsiLc$)M*0`By(w$YqQU_J7+g(0aZy{XJPlRID*skW z3TrMNci0^*Ldg`OQ$po3Ms02Mgtvi$ttgcAsrzn4wtmEhX*MXmoSwCC>|5=~TM(7m zN#N<%_I<g+IAOdljYpI1;xufLnvz|kuOBfD(0fi+P4(r({-m;d(L5v|_wyj_CM+rC zz0zOOZdj0CR32@xQ%{3P7=dSfBk@A5Q#K8vwrGZKdB<s_E5EcYhrA%QP7+o>fiZfu zG_W-5U%<$zWl4YI<v49CZeM?Gh65k(%uUOdK|a26?Bih5^w3VU_JWyP2`1g(SK^{w zKEfqgZWu`VkU!_MZAHfolIAZ3Jv^?@ELjg8KaD2AcI;YpPB_pJLNJLq@;rGRnT;{| z=(&gEdBNj|mz~8qxhTnl7wIBzniXt}FpT>-G~vdIZz+zoKD-<3oqSt!Oq-di$kh<8 z3pPCvV)g+W=ebaQSgz<+ziB=FaMzjFKV>wiaPT-45q#d;O}q&_vw#lhGl@n$P=HoC z9?~09zuVAM-CaP;PJ_Uy`aF2_^=0rxh~y9QRc>DnLb?9d-xeb9ABq(}IU&}6b3$xP z|6JCgZe^t<j{H`sSF@4swbVAbv}On<=f5HVM<JK{i)l-$Q%>aDu)2ffhxcR!i>lCh z{}=ljbH+!eWt^<6CEgdV;q;P7srlI2#6^h_&q*=WX=OD<5r|&gr1DWs6)A&WYAbfW zs)~o`Uq7v>Ou%Tt5=fgsc|D;V#g>$i{l)eop&Jo!R4Z*1IZvkce;ins*@$wQaZc2U zuI_K%70F!cG#c7SS4;K7jX=H%VwuBn_HH+)a(+8V98DVq31_b{#Yl8*^dKAAaFYa0 zJprke$NR3zXI6<S35Dhcub^s|Tz;zxsn>xWiVXe`arMPw2jNSpdLyZr%g$GfEQG^e zN{qLG2>TenVz4_g<B26a499($02O1foh>BJu_)QY6#Ri7$AA{4mCZYB@G^V86xiiW zgzOasmY_a+Y^?Cgfo{Cg#;-EXdu+QQu)8z?-xA?t;M9ed?215z4W$Tl3Qnl<5E*D6 zkNX!4@2-(4x4B613qA6`EumKeJ(AW2@RSjgzA}~Jv+F8xqCDUwjP&E(qSVn8U3w8W zY?q}((sbJwK{yN?e=U|G%|;4LtiAH589*l#0L<WuuM(x$_#5Gph^F?f_GIe2FD{SN zFsZuujY2v8{`JcGr6I|v6csPa07J!8ty;NM7C%<U#@U*JAq~4?F|zE7;jdB_X?1da zw1uQ**4a{d=b9kg9}L#(5Fo3`eGOm9k4`B-nkTd>d2@}h*g$b8f;c$2(pkR0cb+Rd zwyV=EB<!EMv{vT$rZc{$vP`D1r>u>)bkFNEq!VSRjYl|Y@ynzytXcn>ke-4a>c+K6 zvnxEbW>)o|rq&81D9<OG%Pidw*~=)j)Geb-In%qDTX}uA(HffMs;!&X-ebr(QaR<C zk@H@0p>EK5QRekz>z)iKJc^hrJSW2y_Dec(`spU0%<Q=5^%LFEH7U%rQdZrv?i^Ua z=E{6?sX<XieH9$c;{Gx$Xmoxdi6%YzRGLLH=Yna<q-PKo?2=6NV#nDKU~#_(xlQev zk`f~q5F3x>0v)BxH*BS4L0`|w$5lqaGFW%#)nY!8uBY3zy+L`gaB^~yVcMDMYhFyt ztM$HAVOv#|!hT}P^<C|zziq#*7>Or!G1^Jzr<Q4}h{XG5DlC_!HA9a~rs8sQfKid7 zX#OC#>GsdLVIDr_uZ#x!3{~K!6!+$5XVGbkN6t*=Q>hkF3tr+YKs4z1=%>xpuwPV3 z1WeMi(S$iED;0sst{QLL6<(zi_H*My#|@S~Z)dJSwoH%B`hMyhk62AaeA@6(l-~lr z)h@dC_;jP!Qouj>bZ5uFHR%Bu2A21E<AnG3&L80JQMwJ}jfvbw?nMU9^gQb*YndM} z?nTz$U+C_QTh!GYayAP$(awGEv?#L~kvR(4a~=!h+r4_evL{*}Q~qWtW*=SBfbJ~Y zzugP7Tz4W`INo-g$Z5Q2mAnD#aE`bOXS{8oH2ut&^khC!%`g+Rd1-0OY?@3VQqjSW zgUxZnQO|;N^IcvCf!Hgs@zPPCz17<=%2f4^wuvGZLl5YaFf?WwnZFc+rwu0d6ukF8 zg<OKG#WH3b(v1xu4ner?4>;EkH2PhzX8(gSY2fB$DjK}~$w|(25Ohl{>R~UJ09pib zp>z!ccR}^kGRBu!Lf3)x^qOlkLMl=)VS|ZzTPo^_pT$&6K7B8Xp4o_4yBP6257lPA zA|94Gf3#Vi_uv1{J{5OlZSViQ@D!aQzp4!(=0I)Ga^FHAjUsw?2h<A7Usj(^q4CiD zueY#xsJL%sM@WVd6T3b`L^?HGV6HEb{`(VieHlYaEfR;GC-Fs*Jcue@2z{4oNHI2_ zIN|?&f5SHkQFOun|GGSGj36d<3b{P8JnAmxQo5<T9KsPM5_tHBn1p0+8vL)fIyVKE za=$AfO1e;;OE2Z7eorQd=Xp)|pC5@YlH@_;@j|GQBw+=ykeqN1n7edC8nJc6W`Yy` znUI_*|MTZOem;Q@klch{et!WlAmA^9e<r}EZ}ES;{(&4vL+ev^i0<=HMO=*qn`#l? zdN3|$NU4EomK={E@kKb<Tr!oerM3Q~i-=mOCb3l@(?HAbsQZ${-K}!tiFg!71jMi3 zd_Ri9aU6=xN#+~)I;J|zauF<DhyWTmBZPc7VhtBX@~=SU{@`m)SaVKTZ;})MX2=bB zp^)bEukbh_xO7P6x5G6MorRwU7GowxQ;m=3hkx+AaSa+jX_qUjl_?4?7?=Fw7?{A* zQz+sRPPWHC=I1|b0Y+Tx$zZOxD=@>_$mCF1Pih%y&g9H!!n2YHs3l9$Tmvv9d&RMQ zWFo+9*qWq>qn(B}&9V7|(YB{ML*BORR;z^$tm5?Pg6Zd+G0CP_n8+|h`d-ZJa}@$= zpKiFF3v*F8=L$60tKRCLCe)Z(D#B6>@-FV`H{lLX>iA}FWHn#5jTsAMw^QnOdHs(U zYw=A6*b0=gugLQ?MZSG?r$FQ@?^AfKH+^thP=~@69t4O$aaZc3B$;1}v2o|&B)OPV zH68<pNl8>|lvh682@b~gY_cF%Ezs5`4KJiKAy6fJ1SdU$AQuCZZE8Glr^JBiW<t+< zSO6N*uwsn12NpK?Z?ImPm%BuaMF$ab^)#y4aej-?4{N+(R4b;JkX^LoK82;<vQ>RV zGFI}4v-}^%?1=#oC;Oh@{F85a1vljRK(Eh(9FC`gj^3~SR%s#%Sk?mNXsFfe89(qS zwSp1Zt2D+Vez>$<uCV})3c4{10YHYE^fY8o-dL+ZDuyJ=Nr}1w$!>t}57p-&*|M-7 zy%b5QUP@sW0^mpV-2EyI{24OwbdqnfumN7|)F*FzjAgJ7gVnr8>ik?U@THhW7#;iq z9hIlo{*4uyPm;^@UNJ+uHQ1CG&@~2AOh(;&QJjYmxHo*UdprKxI?_PAX6wz`PxNJY zQEZ0qiW;4$s=Qd3iO7InFmek1o+5;B;(N0dY49pw4$lZQT6e0k<&2^wggdVAC0F&I zdAuX*>wmUAY~1dzFAy4LEconGZXov}`0>6N8mJ9EMrl-q^O!t0=09ps1p+5d5=Rl0 zY6qm4-(*`)Q)h@jDy3-{SqRe{kY6-rZRa&;!h3dwwO8e-BvN?qq$x?(N&-<n<D%$B zlI~d-#76k|f3DTj^?zg9x;uMB!@^zO>meOy_wk_9Vy`R@?^Nhx4@zopmoL@(le|zk zbz6M4a=Wg>Xq!@Zbhg~#aoIkaq##vWo9FWgB~drTf?#P%G`h>HP617q0iFy^_hF{) zBRaM`tnYJI66SnD@74&#gXH#(by<<)e=s_?=G5@o0SSE816#uX@e0moj9t9>XzS6Y z{rY?fDoJi-?AC`J`x-;6A#}XB;&VUxhoZRs<oibzfTTvI<3?4F{inr<pSe#wk?s}? z>l;n)Bp$#k>al`~#gkx5kBiw!=Wja^(_e&v>@5E`!odF_L5d(lSa9*-^n{}?D8&ZE z%O$mbDeQwRhy}!3pZM}~%e6Lc8(db`Ffi^$PIg{o@z=@$p`?HKRo#)DS(^iX$6BpG zg%bV<K&i9YY(`P@wDiac_i#sKss8Y~;?yj|F3Idq5<Krvp6Hf(9&q@3_1R4x<$ z>9iDaGZe^nF@|Td^zRpI>*ys$aa0pHJp^8M+^>Sn0Ao#XKMko%y#Ltcqmo%le)G{B zpCBA(6Kuw?A@wg=T$}fVFoNIs`U*F|l8|0Hb?S}SleUqQBR|mlJ10jEYNmz#UJUJH z=MF(pt`BhRq)A{V{M@dLeOnTSFQd{|YHNsn;Y8}g-oDG-K{*1sL%wvC7Yh!}cL){S zBDX0Q#qO>&43rx5j^}I7RLbwS>`)oSa;HepRHZ4a;Q!;9Jgi^84XGw~RSEmkpS`vj z|8-F+NytSbr&=Nuc~>)8O5#-a{95^u8EZfzFVZkct+ZYTzRn}%J6D5#R%L4E!Lb%b zyM}@|`b30ECjAP3Ih~3q$~~hFP)_MPmKoeSgyds~98*Q|sB@#T+=`TkQS&&Q?qQ!l zsnv?TegPWI$qQY!ra~odul&sm$6AU_bJ@uA6!{;|FE6^|*53%R5FS;mW)EhvGuROh z-p&6!h}~RXbA>}O@6}I)#}C3PNpuK2V@wLA84!=@#-HK~18pSPxZ}CwKX8Yu7))G1 zM&5qIK@K%TE<JzFY@i*WuZcjGctLg}ej|~7zl}5*d6!N;i{4AHVw8!D5o$S0EM2+7 zA{e3c2XcPdD^|sErE;ap5eqRe^gtgK8wDP<?y*nSzQt&d4uDckLTwRqJ%|bV@-%15 z4$x1!EHJsc-h^FR6OK5tz~o!lF=IEd)K$*7m9y|?9d|Y%j|xT-UZei$oLLOzYNS2_ z(4%Q2Q+EzEX1sJC;B534j>%l>9NaB-PR~MLHz$q>Wp^Y$qAC3z$N1~o`OBb$3GmMo zh5kcSEA=VgdqStZ>rWmrb?sPhpuGcy$yKH<(2rJbz;HN4nDUpknaT8esl(z1-DTS= zNm0HQ?$b3r;AegvFff6@1o0Cr$E%-Uz(;bMG8+T!M%aY$hy*=H8v?)>UasdMuh{hP z(qgi?{HiLK*fp~^AK=tZACH*ROq~{4UBuQPMUx~yjp?=$C<WI!mykT0x|y>qC#vtP zuhtd;**Nj|%xQ+4F1mXs1FKo}L_l`(LRz&PMfh3iB$iain%cPDIOW4oz<~9ssEto! za1|v1qFE$T5FwLB=oEn=MyRCouye08z}x_HbXYkqUYRo|Ja?x1?En|rvIha9_DznQ zIi2Z{g1&~4s*<{)fM70Bh_LdWZ$#iKmYrCHU^XE_Qfn_jVK8ckGd3|8jY-2?f9XUH z>VC=q+rkY`*7kJymy|bMK&sRF-9TMjnBcPEG4@j}i@0-KPoPjvN{<>_(r^Z<bs$5u za2m#dJ;k-QY_qcw_mGs0wTWq`<WAOeXOe-AF(YEr7@cNi<G!2hR_>ZhsTrhn9Gnrl zY2gnP#$Hs*>kCy;>RtvGJs?SB?nN@J<b`N*WnssGmH}#pV5f|$73+Omk~yQE&9)|& zPK!7FSn+G)D7dB~uJ|ZGLph?&*e0BG5Xqi8OTF#$ymO%hU8RkG#hPJ_6y|_=+qe0l z<)W4$74YE-oC8&TqrBs`VlzbaQ3rr}@xoRs!%DF{3%B3lPkschgN|^cWxG|oS7na< zV!PM#GX7&{hLANyUpAZ=sh<SvAZs9RgFj3|1UxB0cr)&~cQh1uQ?Fv|WbmT#qJ6;! zeRv0zG)|1Ry#*MQ&L<fbJNab*yJJ-h6mcVxKo%bMM(E{0!IAb6Wv)Ik(H2$Txbg9& zkY6c`()=&uf;hL5dqov7men+~xE7IszFUPC?z067z5qlAq_#_0Y?D&32+1-G*h)r8 z<T#<jIt|2fl{GO31B{3Q_0n|9@Hr`^(4cIIUOSYsi^|(l$@ub|1m!r_jMO{m@BM4{ zgi>mx>?lD!DnePi`{pFY4!)F9H5p0=i!+Mae~i&EfjDPx?gV|UNj=W}CN%luwrVYa ztylR=z%!p4#2f48umav?Hoz@}UzEuQf+yUE$&J-ZvfbRI9ZRBkfSD}T?Ik;gc%Bjf z*~ufA8r>gqo#W`dJyVS9ji__J05SEZ3iAH_%THGiNWwFgaGk?p7rtfyOV<4jcNEXE zMb`I5+>p>4%G=1Q?_!Z0#t<Ku!s~*BB7{~`FLQ^SF?kDb5mP5@hi@deBZl)G-|abX zhp4}6m9dM#qfQ*IYhfM>4UFUrg2#o@(arLz^cQ?Db=?aB%q^U>1sSfO4%-KQfI`N$ zXZ&@S`JV!)|IWh(aQt(9le*5odIj%?D&&9l3fS?a)YrL4VFZ*6jSW$2d=>QYbB6d0 zjfqPRwXZKa;mUMv;WHJ(0B|1|^Q)cA-ciRYbi?n*1{W2Mz+?P7vLnfYz|i*TLM$Wl zpi4v1IO27xJHF>H&^h8&9WcS96#6=IE0d;NFcx%gx=b45&bkyPs=KC^2Trq3<-+<D z_d~pSi4sctvin&vIW;Lgi&jX;Nw>D;X^t^hF!q?;7isLL?I-%hsAMDK@-wsPJDB7C z#M%+2p~T_X27(fRfp^Bz_durcC{voZZo5_PcL26ha9a+b%EfIKOIBIPC~&8F{eql$ zv1_CfnwQ&E7!)HERzn_Az|aD|{wV{ZMyHL?<8EY&C4Uk^sXn+ABD(D$pvmeN{VK$u zghH*LEn;r;x?&C+bq|bmVBw|ENNlZ@k32<$Ax>c2ZyybT(IozsKM6k!KQhkbj@M6@ zU5u&m-AxV4uqr7T@9I5%gblL{Uz;2Os_M_)lCeOy-fe7O7R>k78g$c1&;zw;K7>+e z1@cxWQ(P=yV*s6hqEG)^S$_tR`cvN&1db~ocB#q@=t{sSWv;C0L7|*}Z*+2D5IEar z3mBA=!x%vTx9umIB88GO$QamZi-JzO{doZs9`tOn(Xa@&+J8KZKr%=_<WEYIF{DLU zsfxT$tu829D9Sq8yHG{{%Cuc$iDGvh3vx#Ud&tKN7PF6|4k9_UFPzQ$JzF%xoq}+@ zZpWMY5~*N2_xFd^PFM<y?rX`F-2IRnCG^hOXiAXRtlJtdaD6Mm<-2Z!Wz!WzFXOA^ zi*+Y>>90nzP{31fW4_c+n45qz-CI%VE87*FOy1Y*AV$0U4|@VC8|N&6z)MPWZp4oR z5$J_C<r*^Ve(kVj7cc{o`NoLMJvm2?hdFJ=(=}D+^ZXx@M2%KCon5b%T@BCc$0s}G z*eLdy%MOjH5#lg)4LN8X*uKN@dv5MYI>}r*n8*$sS7C%$3rV|PT-jKq>lT#I%dyP$ zcDdad%|CGov2=g1r73r>RE8T7oDwbh!dS<HSOum!JgvjH)GP)rTgE&y*-})MqJEJf zDgU)7n~C(CKeO)kxc?^l;G_moAVl67b6hQR&7x7z=F%ui#1$ATfU*_+;RSei#G*yV z54zBptUF3F8QWjrlD+0SFS;*abF9q(`6GGYvgx2Ww&qtcVqz*qM%iY<HG+_q587vb zYwBgs^JtT@iY>*|#%P@{(*}}eX|!Bg)0d~dccl4X_ZU*1EVkFvNaWG6AK8Sk#QjG4 z)gLJ|R<X~0RR-@l(!$Y*Mv{pZtuCV!^#0CGm2*>UGMhE3td~Xk8#@GxfbFDPqkF8) z!V!;HJl`I$qw^RmbiiNbf@Xp^6<(A4c-yteF~Rrl%7@9XrM&7X>UY<Lw)VA6*e7kF z@RItMt%!;9e-=Fd2Q4NiC)2-acXq%(4ptifj9A2DhyRRN%>8cFbts}(P(VTz+c>1E z4<23w-UumZZ_i*;J%Na7cKH5An0?l+&ydFgYxz^q9sMp;oVTFFu}E9TE=|g=z!Hqp zl#QfSxg7S?i8E1q%iO=Y6<<lbz);DhZ?t=xY7Xe9j4)G8!@b!}ZswnuKO?bS@~4DZ zGMCH%OBmZ3BR<jvR*97WzdPY5Pk_c9Ovi=kx+FknY)KUkk;Z`&>JT-p7=xJwJz-W< z3l(*L-k5J;JGIALjX)ePh$#A7IGO}Z*s?kNw7qV0*-kogy*8633d&ao21r6@Fj$xH zIh{O?V;XV-=TK|%Ln(cUJhVe%`|8cjJG5eWZno0&XaLz&30!P7>r|;UYQ#}>urXWJ zk340W9!newPE;}J0$4T>M>rQHdi~OP5;Duuk<c+YA%O7@DT!cwj6copsU&@KPB^F~ zAOvFLB!>WS#a>*PFgtu_4Agb3)?IP~)(V68k|Thy|5-*Z%sN&@53bVS!|#&X4(RT3 z{Cvr62z;T6&0y>h0JtM<T5+ST%8hc38_Yg6*`nasH`&E(eO*vx>NGV=)I3_vo<C6- zOwySG(5_3^T0pRYPzI;p(&`B4gOLylpI=P^B$!7=nbGKhSkc?{@0oJKp0mvC)3r2( ztQxb2gIGs$QyF^+pVmCPi{s@iPz<qwcMF{OgDeQquO<nn!v-QvQq4Qa(}^OG=2Tn9 ze6;@I$<}P^%9g=MvG%?<ZRqvB=XAeN;K|9)PdI@DCMCde>T|yCRE22nmFjd6eAGiQ zyUQH^h2@smE^?Rbo+jup;Y)?f+C=opz0SkT>)Wbx)mq)od(KP*(%wvn53XGGPI@6c z<>ng8J&vwy$WG!5P^Q=MVY?sVgK%<mjIc)ZzE{>RMfy5%gur$`a*aQaTKlZnf@Uv} zrPwFEChq7lwDWkMqO1BOy7JX9j8L-qUb^0+!lAcnE+d+8`Rx2O63(e@rvJ!m{>-(j z!_&xjl8+wKjNfJL==9dn*J-QxrmHPtw65;yDUX}$j8V>vsEsI_-vN*xJ_%;Ja12+1 zTi4^>N|rj*ee{#%tXC38ii0c80Ok$l;VssY|2C%c;Ag)0{I4{e!bjw$=(LjH^|Foh zv=ReC&bPI+mV2x5F{`e|)U?13(^gXok`mTF8zTzHdyc#LF>*sjlatgirNk3frt-&< zjhqzPs`>i%>thS`r)2_TD@cFOgVv3YM>O&3Cb3coWVo!u)9agq-YVP!0B(MR=$@p_ zKzg`ZVB2`=S#zk(z~O59-Ja|~sd}qp1`}N5H!>jQO0AgjtxL8r84%Y|&yei;xJ#?i z^JdAA{DClCu>Qt^(<<hd-*4&;uW+`36H1n(=9$1NSisuK&6ATah@Q^F{ayCSI+7md z`6b)I#ywGp<inS8gu4D9=LW-@s3WYK(VHW?n$tz`wW{7Liw}qQ{-|LRu}5nQfllSi zcN<?s<hn`e7p7c>>UXyWrlx_6aj7Az+=`%9^i$P3RCD@1MGmjoGJjjlVuyB`Y0eVy zomQK#xXzfAuzGXm^^bfhwKlApU!TgJ$|Ptt>zvGJ?{8H+&K6o_^j;eJ*8=RW`fY#E zT1u7i^|#y1_7SXDP0?C@;c8GYUnvPII~??J8J2<VKj6N3JxXhFu#z3KYRazktB#Q! zN9d#9X~PYb9T-`nZ5?GZvMVvRV3zyp_L4Yd8W~AR?}|;?Lk~_#V5FAb+ua|!0WW)8 z&N4todS_%UBF6XBTDq|qDzo&>CWs=oVRk?PO{=5@#iJaT=nEch&b4gR<gbUy2gzoS zoWOECQYn-WEwcJNo@KLkHuJsBx?M5zRWf$AQM}wUCpa3LDSw*ESzKg%=4?mn0I}Uz z(OH=B!`}LOlDfRv!R7EsX?OalshSe3iKr<iF`{xdp`CP7qJfp4)Q~LTt5C9WyfmZ2 zjvp&^yl?y~)O;K(VHa^{>`_&y>T%~%uIg1*!ab%G7J>7b(|RmI<(udQs^)@UC38_U z?Q-J&z{|o&*apgBfX1nsv&`}ptC~BRv93ef9OxO?(;aIxAf)4rzZJ<-;^i9El&u{) zi>$$>Yvn37B;j@p$gW%2+@*_^v3bZ&+qVDG-6)P|USnUaq_yl)jH}F6AVzg`*H0?N zE0ghYOQL=#1?~~@_RH>+KMw5f4Agm{ISGt1{+gmWJv+FhFgLk#cZ9P2k&J3z{`o`< z`N>plg2W_S(<(ne&v83%|ALLc&uoGJO&r3+%F6mrDg8B#726dK<j<g{Lq#yl-~zXq zoyHdH2*VYd_Lq1}KN{v}5Upb=7e?PMW>OQ$<eh;DD60Ff$!<7=h-MR8R4nQcEY0cd znX(fMMrhdaR2a~8Z35p66Tdk1gc){Q6RrmOSDTMCz#gy}0$<b38u>Dc&s!)SDsO;# znh&?#>!OjtjkTht`SNw_e#lI5T)|)Q0$_XRhx@IsCj$k^5Efl@j6%0ahg1_X<XKXM zH!^<2b1-!`neNgcqejBAG{RR>`pT7TjNYf%g~dG1oGU!Il#nxtL21I~)jNbTgiC~E zB>np1tiie|ruufVR9M7ol!?}zpg#hiE5v2AaIw*uy{7xd)`qRl)wb&`PAgZ>_Di~Q z!GcM?yya%IEYnlZry$-zs@VU}+{R_kQ1m!xdMP`XNj!Ovme1SZ+)BjC&BDb5()P5! z-DSeyjb~?bQ&O+O#(}F9ch3A?(Fjjv6-tUhi*|7Y;Z*G<qlTtgbx_XET?AJ<-|EE1 z+ugO|4}|H+h98W$B8_$+=kk7C@4*IIh>Z#l_khrHiW2OvniOSAQh6{5$gnlUV#hZ7 z$SATng)Hr>=u2FTD8%er?rEQV;z_*)F2t%^n(ZV@ssoIcg~vS;cLoNVdyVO_%bDts zl2*sq%(F_GDvFVT4dYFZ?h;tQYAaLoi8)QdmlNlP;dvP25F~X{*o)Oj)$jZPODh#M zwB6_8Qtk$8+H>L=eSu6hS*=+=1d!A9D)~imQD<z>^KOuWKsdBeFdQ$E`o_~mBWJ36 zdSxP>8N#;|m@ti-{kx=CB`mq`nsX&Xn!hf<W`p>SAg|VxdNFb|I(1wcXZ<48agmKE zLJ?EFmo_=M*Vof06WOE)0dWH7;%H8$-*>OE<GpFGUGjM9b#8#Gyx@h>he!?EJ>lxy zFLg!uW7crV^Sov0uh@evS#UaW>c#z{qOm!Ewcrvp$nU@;;|5rV_8Vf!U2S{y?h{Q_ zJsQdL1S~_bJur1x=Lr*;dVt>&H_B|(b;GEj<^_R~`V2uux>VXx;Bx-JS(B5I2^9PW zru_9t$Qiq+mmaVQK{8f)f@GK~DT}@V_cKC)n4BnA!n_wIh!Pk~#Ytxm_WO#{4;Dc| zp1XKL4F145Flw;Oy$viA#%$I7A^>s_{Z5x)<BIRtl_&9H4IMhhl^T(;7v0rHN43pL zDW#O^E8h-VbiCa>8PNJT7ZwpK4|KzE@&U<#O*<BqkUzP02RyMuP1vipEm((SDSS#D z5nCQ6B1Z*Lz$*w-IF5%3x@Ni!dYz3GI+~G84h#NXuPG~Sd~MArnm)D!h3=vE&h*IP z2pTMxUtodV=a4VC(<8Nz7r9v0oaD|5u?0MX&-3D(rZ-hm_cY8bW8NL_^}$Y7hillM z-OU~;!_c-I_o8~G^LpZq3)JdDyHpFn$eumcS#WNQyH~;u^fbLg5s1mWp)8Hj|KfA! zo6G0_6}ftw<Brq*t>c&(#10i)b<a}7H>BXm?RG~vu(q4(hTK93Pl!Js*e@2BT1rWs z;MVhNQzR}72@_+XvZ$4T9U;VQZ~-IpOT0NJCbeFrK|`=e`WY=9cF-ww!$ZOeVY=xE zxMdzZiWHx&?B+ZvIlqu>^Hzrgvte!(NA404I^rTd0Nx4?{%~!acj3qp>3I+mD%~0m z-tC+iXPy@Dvsg`EK&|cPj+y!4-Wg#jhl1_uqyLjy1+Y0>ax6#H<dVa$ZBITmyf-U? zSLP;Cf(DEM(g%PoYJ<0H$E_5L5liLvfYMi85TPpgM!bwy5X!Q`llrWDR27+{S`r-+ z;;ybHw{oGYvDCEH9g><*mYxq9-3vyiaL=;0Swr##@$ji2U<Lw4`b{q){aw8F%&ay) zA|3jcl<)*{h2Bbx#>K$|JXas}Y1IQ_$DK6#4;eFN;`?xham-J07AMW5Q)TvcwYAN< zD%;B|1?PZZxl&tX3ED_lRrcnoP?1QS6!zl<#_x#UI5V;MgRjs9Z;a8T+O*ST$RuHw zPx&3WPxLmEiaUemw}THvaASh6!JPq@dXiq|_J0Ez=D&i>KX+m4`1Ga!w5$2_rMLS7 z$BNeNmcYSgze7>Xc7Ka%#sd#2nVBn*Qn1R^)foY8p;SN=f0_;P<M+8C(FU{thdMMz zbE<c9dX~4LJu=zXuW*&Bf`N*3Cdky`<gk^=-AxM9PY>mcpaJrc(&}d7{3b2gjOOSe z2PUm6$9a<J6?9{>OW)P%y38O<w|_XH?qK&PLLa%@pK&85U!F;WpsL`%8kyOGGhm}; z3UVVcnE6grH=&Zz$jrRfvx%dzNmpyYn5`2zj`S8tHMUOAWyV%FCO42$(xc<YJz9Vp ziQrtopN0{`NTZ0rli~Az1%pl`5p4%)!;<v$41+~Yg+{^J^gX^;`d+J&pOUgyDb=tv zuteDd7N!i58^EgXDx-{-YBg4q6X=;hj>=?nK(`v`w-1S;&mExWuY59qq@ffeECnH$ zIXGyOaz7Il3L^<~qTi)qVA%MRlrDaCFBL~~MetDhx$%#4ioJ`qN|M%s<}qjQmJU=U zDXECj2_)nj^a`IGR+$2R9NEpDAQW^C5%JFNyx1=+`g+59&UNMC24CyDJpFRf?Gxab zdbHvH*eSO0)K9z{T=zB}L*;=ZZWR8^KX}f~@)Toe#|`BRGb)A(N46&yz#iaO72FML zw-A7h>SdWuk{s@u@O^X3h12;O<)T+v^V>0&EQ&-wK>8B2K2CzPLPQH(Y(A>yW8XHd zpp*D{KoW%R#EpAR#<JYtJC+P7W?0BGn(^iq?<51&EJpyYo<cNw%xYOVXD$asL63pb zENwzhVL7OTRkVtE<EiGvK~ckjBRAB0dP4On*PE1Oi1pXBiR$?EUgBbdj#1(<TOqSh zmEs5!)e0T6G!-tJYtNa8-T_)`w)IF|jOBNoWVhnf+p76a#7^C@O;-?3icbsA;}{eB zC?*}f<AFf8U2XMCe;#HU(!f%#bbOIMWaKf)Q(|(#YtFH&O1DTNnBWR!G0eos?VZ(3 zv12k7dBZz_2I<ih!ET5zM79eYKw>bZOLBZRAi!N18}m0?cz+dWuXv472&J%p{o8EH z;zVwYhBK;@G}2lO7!&>tx{3T20B`G3-$NR-Guj3+#_gw3G*c}a*s6RVo<N&&=x>~- zy(zh2n8Fp3ANE+vK+xI5xT*P!x76cPTf`Ft>u+EU9MDk@=T_;vEjch$Z!l24H{XhX zK5W|`HU#S%*&MNupAY7P9VvX8+bX+#zrgUk<d;y%n$^fy$S6?XPxg^P;;O8nO>QmA z==+v{L!)-S5FcluzCkYMt$NNQvqr%{kqmi^m8~vkh8hi-CzaJlF2gj${7xg&lPH2h z#%L1%`4E7^0(Tz{$Na0$im%w(Q5Zk2sJ)DgVF)`&wgAoWHxlhoTlhj(;!0vp5GHhJ z`S%Rv-)jv`E-N#)5g`{Wmh@b+Q-MJyIR+RoRG{k~vrMY=Yi*E(nR37Ol|O6&lJWo< z2p-~A(Tw$aKX(=(MK6$!-zL#iTm@Ko+G^}KkO8ERpg+@Ei>_p1Y`ykU8P8KVB3ZzD z!NBy*GP_lX*P16OE>#V8@Ny;(P#SLt#bD7bboRL?6~%-o`56~}sYI8RJsTv8I^L8r zXx&VCkpN&B8}v3{TL<Wl3pYTUz9azAU8#G$Ms8upVIF<}-R5v}@)}JFwGJ)f>G%T$ z$Vqq2-+#i#i-jgU1}K3J+B)F+f`|cz?4?Mkcg*=`ikEgI`V&r>6f$qq_$HHQ#C5)} ze}lJg4%&h7gNc^+!~p^UKBFll%{|>oyDGZD@%N<mR;%70L)6y%*fX0f-3+#kSkSSF z$E~_&*AHisQ#lw-P2+DnCkU;*l8eqh>F84`8d^in`}Yy}$4{J^WOiSO?LrQ3aCe(y z>8lhcEvjv#IrQ(A{;*krr8U|Y?Bq=6-l<gWqhJ@pJq)efboKdxeSA9tg-Dj(gS}0u zkhmeB(vVQNw^jQP$Z!n^XvoYAol5Hj_bQ*X9px#l-S_d$ax>NOE}x+reycUpmH#1( z<o^8qBQ-WuEIz}=u{#c=nF*=?&-YSqu-m!yHILIAREp@2^(t9(A)V8VM<Q{7bEm&S z4%^=x(f}O)SV}vtuH%@&@vrg2)L7?l@LF<YB6mll1TH+v(leJvG*@h}@Lp?p-QR2D zU3%VI`XTj_#bGyr0%~dpnVw&rf_|eC+x>X~T-*t-K=Z+CFF@VkZIT?eF<gRy>A>$( zHv{n{WFp);<A7-2c07}-%W_6cgTj!$t9(ygW135^#X}<tNTQQ}q|8tdiTushH7@U& z?|zX(xSv4wqbcEu?=}oPUghE#4~+VP8xm&O59vKAnRZhFPib)fj2m#`eM}+?A}A#K zjR%*D@HdPHi`|NsHoT&+IrajRxRjTXYDz}IdSXTVW~1(19Z`HE+hS1m1!x4vYpFIp zOfI)@camtSm9n#irZ&mBjw@W}o)TJ)lyI&JY8_CjFg7kMimr>v#u&ZL&PC#!xgJ-& z5t?^UrJ2HBDI5l)D`Sy}T8mi3;oeAdFkqSmH@Y)2Mm$r6<rTOC@$d#KT>pY%&xP2h zd#R;RVv)ZSabq`TkO_ky0)1t`b134+t@v0~B*OCM_0AxKIzE^%ZOxaeEjBZ4&Enh1 zQ3Y!W$U^MoLkMl}kg78WrjCoxFmT*w6x%uRxKTz><L2aKXCfixu%V7Q-5xo(Jx0c< zGw^@hy&7NXp$ysK2V)s5LJn|Bgto>`2@}I|r__0dYCkOp^?7=d12wpOW#0{cI|;(B z6H2++yUe!?6X=h2oXTibJgi{htMftvS9c||FrGX)LL<<u9t2;-1Cr#7c+Ugpbih6j zpviA5*rsALhF8ScXRm*%MVe|uUY<=_+-0Geu%Jkc;WY?umg!Z#PRFW9ru`D7b17Pf z1D#|NBB^oi$VGZY)oC!5qyW+?UP#78H0>3ks~FJno_Hwj=@sg7Qh)L|2XSPx>J4J` zdDIbX>w%N8AZM83{yfvWO+iY%x<VtjiQCd~)~a+>JL2I^V^8Wi$?Hhr{1rT$qUGx0 zjY9En3A6HG)v|bn%HCb3+%#rLG<+qr{Sy=0Rs>+IFA4GIW47Nat7eMCTaOypk#*jN zE*>FoDMVW>DzUa%_G+r4Wky}_?WuFav{aHU6L#6O%IBRit!$-}nX~*59-_xyRnG4n zTSkp;ZhFga4*ocC2tYdaTgvt2b*@R|>NXk_@-eAu0;aF9`{Isa>T1hW>dJNs*<#dA zxLbVE?vwgdlnPqazR)aW1;HXj;>-}h8MB)~I(OZ$n``<yxG;c$nu+iFJHhx@%Dbl+ zyJ{_1G1U_p;xz*<t@YGV@SvJ&G>D-s@Mdf6NyHZy)kpNrXhw5WKj5C;Lzv*HRFcKt z_~c)?vmXJ}s&AHcx>zQkmJYREOW*B}-a#SRZrkbKvmhI2M$Sgi@T@#j{;an$beBML z#$jpuvAVi4kY}INpSR+F(NU|)K#RMzAHSXOut7CmJ!#N|nf+K}6y3+A+Yo=`$A<mY z_?O*?`E!==zq2e%O#gK_^&bc)KYh$ThoL_<-e_S?MLhuH5fX~-Rw*13s^k`@2=wWs z3UmY06w;M+RpVV7xf1R&MWFXQMg;m0FpLM6m$9#XqfCO1B2!PBXHEcI#~^gMf?f0H zP(%NuL@GJ#WOP~PTWX2C%bQzNd*mw#p|(bsOe`+^T6M_cIqQxolLR(*72LV*C8tXh z0l@^~)|wJ@RXU-%{>>RPe_*T*X>}^qZNr@QPYF9ZQp6`PS*Q!>K6gm~8iiH-#6k0* znIzLuW;7t6iwa*!Na9ks=mN%|@G8}BuuF#O+XKI@UKHcR#fENs+G>t&<e+M5z3|~P zVN@DFF9br`Z<hVWlnel=pk@gAJEK$niQSMWdVz-O$=nFK$R)M|s<K>dNo_+Kd%{OK z7NuM)e`AyrLS1@sP=lj5gvODEim9sAT!Et*wGLgxD!jtNPf?pa;p|Ew8ZdlB(XoKA z`78p$Hj?G9&j`*fIr`1<KOurg3vg`vV3MVrtlno?q-UI1itr^f`+gvrGex5<AFalP zau94ENzkF6I0dV2iK_KVD5Nf8BT)B;A*<dPvy6<kOAx8LsnUy;-#KV}D!U`;84t+5 z({+rBqDAkx?R=P0!#75hxqz5`>Z^NXRjtk-?W)Z2T*M66?E8WyGZw>|P7qtn<#$VN zWAkf5@Fm!W{C*N~DzrjvYa-aBzY_vMIdK!C>K1wY?uyHXDq06s$-|7`j$IAlu=`=n z__Wq7AM}e*t&4VvGvCOXQ+onyd~q1e>Y*80J_{Vxig(XOsSFQuf|lp#=J2L{ORu-{ zEDWVuBGpghNJEn^8H(vbAxXmzh9(dRmO7L58?96{%mjL};yRRsiiviXaX^1EC1?>T zo2c3TxxJ^k(f~`nqUK5To3w4hZ?6}r+ufp1<=L!Ub!P_y9y-59$E5VCMN|e+`D>jd zlH-4Aw6-|opTWhW5=uyU5c?T}qryB3f)!>Im-)4%9+}KE+#DGIU2duD3l3s$e+xFS z^6~pt13M3rB$+No3fjGg(Am@|h930N1nlY<zGP@I+Gr-R{kltO&}E&l)1kLM4>)P` z8Di&4h2F`i)4Cz;YaCcFM(6JYMS6q^Tr>0B=F`-8{UAHviEF+H=4fQKZ!$A-l^A)8 zjriRM#rbV9@(()KZk{fqT*am;zh*++ePrPNq*yG3^bDwsG~u70Bi3229s`obEkLp8 zkOLAV`A%^4i(fLQczhT>kIK(m-?oC}SK6>Hr?CW+)@-5ZfiL8Ao{{u3b2P5Gm5q5N zf5wjYOom$3g9OtdHZvm*_9s+LFEbCKq9#W`*!axYKjy{0N3dDT>C$`ZPR_f}Tp`w3 z#qP%mFIQ|ZNWl3eq;T(Ldt&9+bUoNcrPj@3Jz+5gBN>M@`#zKh_R%FPdXoN5p%sCk z_KN+}>QX7KQ+#GL-h8XCdfM_L+SB}Y=5Bk5;PkZI&krK|h~oX1oeKDQVE*4b)&FT$ z%JJ_bN<cQYf6Nz;YwE;kHz9a$=;bz1Fybnbi<SbwIAB+y%>78^{2ImdS0|09ofZ~# zppUvPwz68R2G`vxcL<yaPv^|tO3A``$elwp%Sa&U=^>{Dq8!Y3bEuKAa(?@=8pVDa zYJreV6Joo@fsL$^#)SX!BoI*G;3w$E<*<cc(2}hk@C9<zSkS5)ggJN*u&EI7ECBX3 zX97pPq$cJPP(Eq@r65hG%|N+~Q5_t^kcc&sIHdT;ywX6XP)>{8%`bJW{huwhld!jQ ztz+~cDV#jhbVdjbv1s&;82Pmz{rF!U>E@!gRtyj|;`7a5r)Iqhs*zvt=Z8XA9fn?5 zlc#+U5Zm>@VHOvDYx^rEOkxm~t{{0D{l4Z@=ZY}u#^g{NRJyF7E9z%hD$_zB!U=8$ zU|~wV|FVm<9u`LxS&V!3OWK{kLt}RI24E*^Pwk9__KDM*>#~67JWm_$`UoLdffQ&u z(=W!cIn!5r=bmcnU&Uuwbu&aHibez}Ek5{>(Xw*V*yPst`z*Ggv~~9PHRvPogDCpW zW1wGuM>zh~ipddh#?<EjnSRu$Ipgr<az5SC;bl&NAc+Vl7QyP3D9H#=1JI1(YsV*y zZq<y8`p5z_y;=;(N2wptYWX1%RJ_IC)#)P!x9cqf44BkVRQnd8;X&C;_!huk$FEos zIBY-$heJ&Fr~QI7Z@!rbRTOrtv>=f~M{2maFB2ICEELE0nc)c6IbH1z_n)6!f^F?z zz1b|j?c{uXNj3~>+H|^V3NByZf4hC_$I|1Wi!6y)<mCA(3QFLm?xB*!$@XKpC|x=t zd}p;FJ;`VphHL>J4c{oEns(rdH_z@@-0*OSq3JSJ1u8E{6D;%lepGV4b<M~C0;-}D z<44kE-AQ@d<*wu+uds4032O3SHYY5Op~**Sa|9{LDZfd|?j5&2=6<ikWOB1G;g!6) z;X_l#$<~t-mTutMMyC&^%Z6;%YS7DE*ULpYtez9U3|3p!598L>w!4E2e&3oGm(~s+ zZ)TY$&tTpCcdn?EwNK0RK&;^zt(j&dmGB1dn7dXyDnBo-A^wim*5E%_FV?%&$<|KT zhg^#nXP=d59ah^x)l1vnjUGeQyLZjY^|NWFZSvmCLmU4^=aToGe=<_E+i%^iSN&)q zTokY&!)frYT~uZh7+xLtcb?OCr?)ld-|pV`&yBtszFtd51qtK7h=!^IfSTzdQb&Un zGaUD~Ei1Q*#6Ylyl7mou!HRe*<vWq?>Vpu$dujymC=<d#`}FQrlkDK-B&i<oiSsJ~ z)#y2^_~Qb9n%^wxX2+^|yLC0>h6+6B-)>2TFBhaK48zmUrs-NloPB7^)`pSiSQV}B zkr@vjhWiVCf3?U56ss?*8h{NRp)7%;B$+B&lvkVJKT`*?2K0Vgp~__OfUT3nR-tD} ziRy{Zb<YP#>2PFNqcfo1w3Qm;ZFR}+T%f*JB?w*t8!I)3Xr~)}Lej<CYo7{?e<P8D zzuy}FwgPUl;#BkbASx&%VbwiI5+|w8O$4|8CNQU0uommB`QpFGO{Hj;TF*QT<|&=$ z5wi}D+*_&`noj`Y;(@$#wl;pUWqVkZk-|85elWU{!pK;)fAVmc$R8~CMAGV)70LD` zzmv{6-&7X%tNjuM-B7|<t!yez4^naq5-i%a=$=iF9J@%PqB?#2&;^YcJ8%MJU8?e{ zH!eGdXHG`A4?g=6_^L8uB6&UHHJ7@DwCZwvLvYedu{FW0^AsYu?1}zdMY*XC>q(i0 z+IXwwyh>eVy7Qd2>bS{&UaVtAszng8;vY6^ckL|!zc#-9w0w<1y;tkIyrJKF=419E zrBZ(Crz!DE9vY^~6Q~1ihmoR3%HtxoS0%W5E%07IqBGL#D{1O30w#fd-@AekKnYC; zVWE|PU{OI%?T-ef2R^J$q9KyR^zTpXC*p;Fc0{)wnIKdXNz*O4Xb=jJcC)f~R0`9C zY1A54;E~+u#A-~e_2c2{duSlz2(!WPUx&(IR{f(pi#*`X&rztoOB*g`S*A<G+_R-* z6P$b9!t=#jzr&5T!O^8uqHM;1X4TL6q-y>@l)Y1wEn(MYnYL})K55&wZQCbp+qP}n z=1JSOI;*;>x@wGXbpL&^Z{lXhh>M8zt~J+u$YqX8gjVw}XUZ?g8+$Tx04N&rmwgUW zD}dz`9x-NWZlf4Tu-lWQzmkfrEG}J?X9nGY(3c~68H{Vjf;_6fPs;=nEwMUAJf@tI z0a=#`%79LI3v)7L?e8OaAw8G~@bj#c0A?ARy_X7vLJLU#Fn<1dOm?n1kiPZjn67XJ z%G;Lks4q1a;h-2RN5mhrV1d=44{5}^Pa0toms>QK6wWF+17R02yeC>#iU(j5D=Ic( zw>t00xeux+f@%PDV_RW+YLE5>v?lL^w5>QjyMf0`?mbt?V<Jak2rxx5@skXyA%TrX z!YmXS|AO>S5cLa9QlL-pXpDI@7BkX4K`f_`0N2+U4kg4)bIvGnz&P=Qf)^Rg`>qfl zr{~`_jNh2&ma9l4SuB@XoGWZ*mMCrx@TOvJMaEF3S}38TZy-W~jnEScbzt#{3CnFy zsjqW(8FR7%yKhxBzZ@~JB?qvKLSFSkN3~ZvIygfX)+%k!$CNyn!y53VI?(qx{6%a1 z12XN6Uk-yHVnkv~W<zLpV4LkCfQlAqLh@>fElV_mj`u+L1!Pg9F)hE^x~P@I9slKl za&w{x$W(ZMY^vEVM!BP`NS=X^Q2FkS#VE<MU+u^_aAxq%<G|_&EIAuVa;9=Pqz5y} z5vbE`LHZZaj+_+^JfL&=o@mA0!~%(UOb0H9cw*+~T1pDVj!AOQlnp!>9lr@#9onsY zy6pEb58NZNeE*zBX@ZrYDzX_*5T|W3;oi$NBa(LJ;ow0HSU-M9WQyW&pAmBszu%b` z*RW$U8ht;10kf}CGb-Epq_B`>K=_E(azD!l^4P~VCHW#B3Y975@xPQ6kseyWhCEJ7 zF$woTq$M3iFBqgwlDWy{a%(Kz<iNS5uBvsOboTmvME`tTj&^pc`Te`1tEKZhf8S)+ z{xNg=cwer($n4bdTi?>v{i^#IJn6+g*sE64*$`*>l0r5{jW;9@Y}2MszDHbjw}ZyN zE|_8|X;Mj(=j3|@dIvPHC4ktbnmUKQV%v*?>S<|EP@mg9dQTg;eNabTfNUqV`A3*f z-%ueI#NqU)#d05svr)nMadpmkz=({+qKW^Gn;LtgP1)lT?jDhfpEcoy9+h>NNRKhO z7ZJPY8M}IIwgTPl+V=IJSA%0Z!P%&LhuhNnX?nz<w3`03P}}Ts>>J)RQzb>BX|_VD z_}!<nCw5EfmA1xX^nR45&P6}bBn>cX$L{3eLURJ7*bvGdtSBEhNUf^%z8NceG_?@B zq@J4lF7m7g>KUzj`cJyNc_gZ<E<+K!q2%5pU2)p3_HsMLw{y5UC!6-mjIFr4p7c9M zE68f!{BeXfdCiZ^&9($(ynZYb0)45EW7A_@u`i~`*-lDeVDrcLtjc=a*Wqb|y1k&4 z)={_Qai`or;#y{$Vw*Ob%=H_*Br*6uWd$)a{qGpy|0I%G+5dlJ0sXHjRKo8RN&o;N zz}Qyyvux4fT-?%(Q({C&DQ*Z-go+4r^y_Jhv@cb<vtd(64E%4OVeSqcTHeY=!OHOI zmLUs|oA)I7-=vskbqzeyo}?6Xd!qDab<JEGfvmeAubysYqvH*}eet73re0EP9v?h% z$yifMR?{U_uVhinPnWxXqyfU36aTshmEHZzQ)|X|UPA^6+7<CfpM56-k<Iy&+9l0_ z4e&@L^4sdp2uCYO^fXB06!nMsQbbl&`2iiAeLb7RKl+KrK`o*VuZ)a243gzvp5;CA z6G|*WAJ1p_P9tBLFTFn8y<Ke{ZXQg%>DfLVyvvncOa&>tJSRHfidF+UaVJ(Bt40D> z_OZ5*trhYgcfwE>p_50tNA2J0(YTgorY4!RQjg>@_!W1m^xCNs1!9vhMvkfHwNsyB zneL@xUQgZ19{GGd@~Jsl)4Q>VJj`mz6!0lHvuVY^57QN5y#e6~nt*9zq!|?Kqzi5r zdA1RTp<1OUQ}rZ}+yE%@4xu1bC2xYDtSn7J#NihY8Kwo0o&{t;$|gBxG8n{vsacOU z&sby+NV=val59#n+BZ!;3_Y<!J+f*_akapNhJZrdbqoCte1mS;HY>5NL@>xXI#SJT zdD3w8treNG*%`+F;Z6KAk_XfC%-{vqRRg0ftLsPMA3_95M4cKi&OW?bh%?7z2x~xL z)kwuk7s)CX!;pw}X)w#?Ug*e7T)#Y&6EAvO-{+Gc*?YAif+RO54ySe@+I#&=XZOTy ztrEPgWesz+MRsAm7^w4!tWh}xv1P?$e~l-Kg1~gwZbi>luORXRT>eeHghrrg1N2m3 zqmEbJ-~4xyU)j0MG07PnJ)W}Npkpbp69XDBCW?|hDpH%2ni;m=;mW<6(P}RZm>k4K z?gKq!n~UwSafgo={~s{n&91f|4vAeRtPr6ct|Hc`s=|$#s0yc-tZt=pdKkvJPD;>7 z<8XJ*!WkPFLfO)*Cnnk+v-V~!=68LKj<#<0G&;H3>eiIuXd8z+Q6o?vcq6_<&2I2G zD6l@3T|Nowo@;4oL6vl-^NcDu_6Ac4^j)C^TbwMg#EbgfM{ltPK6L-QdfJY5_7u7q zv&`-%7YaL#c_J(y7R0U?EFccN0KiHA;xMn&qgdC%j|eJHBP@82j$BX(5P>0rq6E}~ zXfC)r!a}2*O0kAI*)Rf}p%S$+*0!NGQnNP;N)*y8Y>`7;9!Z`rHuNaSewQ>cFm{v> zTC&!dXLM1`<PYV_mZjPq`IPurqz@))2k|-U=^QY4mql5j{FPmbidK#h$i8zhnyIN# zEp$lBB>Gk~r)6p#=(8C*YE3`RB@#HupzoPi_t&(~F8WxKaQb&OIg9^wDPqT2+>`SG z-ktY4TjX`(6SO};*hLtxzgY#v9ge*XL?p0%Td*y|f{?S6k8GPiIWCv>{Esv`PSz># zB`lj#Om?a|l0C;1?C1ato!ls1_34I2hzXIDB#IF`%V(msj#aT-q|dgZ3MhE$eU&Oa z!L?!uwo8@;hCwPc#r$Y`$b|S#*|U{XbB0b7UK0kYzGfXe7)^97^^ed`m0TTOLnz$8 zRF}!JB$BA*;!tP`o{~!jFqgK<`8k_-t~k0l4!LbKA0XptoBBcEo4+-~97(FrhtbGo z%{MHO=a!TnFI4^B`v83$1oK=V9(qn-e=rF@QzNc+^tEHfuU&^jIN?xB21s<-)Sj`X zms=HT!WHF&QUim~PhS`~aZ=LV4V*Rc=$bNTckiZN0FFO~iW`)87I<&*DEW5r_W=BT z1cOgG_$FKrTBgT-{n*C_3?Y?@%VABw78Xo2Y*+b6BKCMSllziu#i_fNt>x*{IbWI! zgRPOzU<COOnp(?h)z-}2xXHG=a%)o@!>DK|6ypOVLc)6EljSnbiQDxsTyE^U<Mpr$ zGve9@%OwZz8%6;5DFFLg(5{$83d%cEYJo9o!4e7Y$fIa$U04@D__Jkr3Y*`9o#>A8 z9iC<~gKXxNTnfH8UoPKCd4;ceVvv`jGe3nkkyWbBE)VcE2ANx>?l8zB%V61OmtLV< zemuw0tz9I^I_7`qurUAjO8%b?%m4Ze{RY|n7nkUlH8h+y#1VW?)XFUNiYm;xGlWKa z#&O`nVQI#+)@2lvh@x#Q1&9dtpL%z4;)6JXtQA|vdk9z-7e`mOn76R1wk*{<&9lIx z8{u47(LGvZns-H=7#wZ1oVWw5rJxP38n4$!R(AtM4I-GZSIXySjHzG}*=x2X3zwxy zG}2@igcH~{1P;6gfh4OmtYT^+wFjEaS6)9+tr(|#=KKp!EMFoVOBiJl%}~DOniURW z!RVTX!tCGFcqOxOrw7LNa=Oc#YzVb2eNaWA2lqWYl&PvcP-h$A)>$@xeWRQi5*P(< z@AN^p)yW%XiB4KSv}k$^WZ@KK#o>{g11tGNiFqtv&-R}^d{86PJqBmpvM+|-Je)g6 z6cRF4UMN;2BJq>sm6Qwjz`bAPZ`(IIP1LMJ%UIobEWo{Q^|(<~$@zA$@UIr$zFTK~ z(l_ttT|8Ba(7mj}*qYHDeroU2o>tjxz-N?4x0Hq6-oER0zL(E*zC3H9fB9fW0u6dy zwyfc)mHe|%Iuz#cmoCKQnslOSKjj!Upg(PIUdOzwo;teocs>_<xrso=Gt1ad_1*_< zZ&w8X#wh`{t<*yCc}RT=1v=NC=-~%OWg+#-wQ)T^lb~EfzEwU5T%Rd%Gb>d?vz#Ok zJJeR61$O@>TB(L+ro!8zK6k2gYoHx1iRK&}M}UJlJ%zT14Nunx^W1fL9yDgzZ7<U_ z1{(<e)I~6H?4Bx6pdF}Vpj_~g#bfLQOK_{OXS>jpcn~B|bkiOaNL#E^0OmXbWN>wG zhH+GBlMOeoENs^X<DN!5_dC(lrP&m&YLLcXF8umjDqs*Gj}|x7YMNZto==F@olxa{ z`f+N>Buv+h?BQE+zUG;?Qug$}vhyL}5kW&l>R?FLi6u43OI@54wSG+dJ}uX^rhCGN z<&*Xp!W-Nwa9!g?08F4gvQAE`QYUXIN!}c~5GIdiJVg-yVngkp(rGJ$BAtwxtk@D< zwS^PT>MYWT5Rzr7n!}Y{p<u-s^@YcuT*2)uIBWJYT6@)U$fOofeHDMeF(pXrE0xFQ z>XhNcaL4ihQz<SSzG;DmM-m!co@BF(3Nj%{{0ra#(-mTHWS!2iAZq=$nLAL9R}?Tw zD0N5e(am5^(%@s0h2C5)uFFxE?%l|e5^iR%J!5-xjMFd;^l64FoOG$s&0&xJqqY0| z!Vp5)fWbq?XyyM0Gv$NMFZ|zO*0ui%RHJ>;UuT3uvk#ng=r(@IEyuqyVc&xU+H&L$ z<G$cR1CUumhiOg(U`n1AZ0#PWWb=YSQpw*5ew3BxUH$eM1|Jl9CeY)r9<B@&a{kNl zrYKQmWEU9c$DKTe)`5uB#e1+s*mq()(@+v*#B4+}&xARFD@e0o(=LehXR`()JZiND z(+~wIPfoVIA(HxW$r2rur~Xdd;0hmQz{*hATh$Hh$@$*7hXJ{$X7U7`j~Ih7gHfLa zjHV|+nR%$b6>H}aKo6*v2+gwsck#s!dbOuzHk2C^4@Bc&VAk^nBvy}php}-c%4o8E z6~Z(*rs}YgNBtj~{x~}yg7_gcWk-x7o>KnJN{EAi(%SA?qLJg?K7ej{g}|4PYUQP` ztc&X~XlX;F@6#R3%C#C)xhMoNc|Metpcr8hSSHN~9Hi>WvlI~D(bs*T29DJC0?FDD z*S-l`M?Wc*Z``zS8YTcy<CXQ^{a6yDsF-A+J0FWC9Vzf3sg@~v)Ddbbs-+WOR5NVP zPo2)`*++_f=+KO?PU{}Ts%b?NaG(Vl;wKzLlCh;eAurt`P<GYy#8PgQ&E&xpiocEJ z#p4^UB<nEk(6NJ798$xF%;|61JfijXm&(|jN*3K@wLXLG<8QcaLumsWI&ud_jUj+f zYN4XASfb{LXO?!>hnx@5c7;Q)eM0zrTA50^toA^FRN|V<$w~WmgFy+3S;!fLB%fR1 z79HztbRf30(Om^9z9jU$iJnlcGXS5HLC~^Se8T69`v36ZU}5+V=a*mH<G+kFY-woN z9k3($&i-yx(larrk|>znBy!a=r>Dy{gnKcpT?^!?H_=wX)yBx0`F*L@i|Z8r3mi7Y zLy8|ZtXHqPIWSP#v?y_PeRS|~?lSy~hLL~5Xw$vyy$HcA_aL-+OJjp;rRO}V-`IWy z?m1<aQt2nf*2QUC!DS@3uae+MrSot##pI%U?>%VNTkE%g6N*_gtIuFS^{C+4q>cae zF$R=hu5lG6pbyegXwy(g-<zokW5Z`r(m%l8iJp;u+@?PzU{vnv^cYL5G&8_rjUM@` z;B-%Ze5et!o|$BT{cLTUUQ+%;d#oq3IOBllnwLwHvf9e0yIo}`M@O%EV%Az3`DFOE zIUXAs*?4p{sz)d1%iGINtRpog-tO4d@G;NQ+<t}CbF!GH#yq-Ih-8Ff(sfLlW)I90 zagd;fs?x%2dLC>J`BW8#ji~*CS;`wX^ObX=ydi9namaOsGt&NV++Qyj*FvudiC&Ha zE-ca$Yk3~Cwl|{&(r?h??*pH|!R*QfPc@D7bVJmfi-qMT+0K&0-$E~Qbu@RNcXmwr zr5pC~YtxqU(qS;ZA0YhsI=gesSjR{8Qxevv_R*-wgbpHy#8runRftC)<#<csCp%_r z&msxw<>Io3u9CIIyw})OauHoI3E68<Po22zgw<$>-W;h}sPcI9r?FLE0&Xaf_hABh zPgAO-SI#AUrg2+(RwCy>vM{Mz01Jcj5$o$9X}z1oh^FgTT?${RIoPDI-2wp^3MeW% z+HIkxa^=bI9ypKbf@~JA<ohy9FNfkud^u#S+an92k*G+SM1d*dctoZ31u~90QPrdb zzJ#vSFHf}bpa8U|V(DA(J<`A0FCl6e3W5Ky5C+3g`$*9+VlbZ}|8|EX@Ybr%`8s{i zl9p%Q9Ds~?X7#1*1Vd|~kn6v3$o9=7;pS<R{`Aj{)eNU(cuY8yQzfi?h+8V9Fs7Rj ztUa*gXi5Q|fX^}d#7j2F-&5qM#oOyZ7!<PW=_odyE?Sq@Co$>nL~a37TI*jvOp7rg z2%V3!L8<G)O3#%k$K1Q?g8_l--&_!qrNPQ44i0H!L}oOR3D6gh8FNVZ$Seb_3xZtE zEtstEXT?(qf-|YH+B_@t94Ld8GEtFg{f5SfM;up<e=1TT8nCn%i73y2N(oTXf*|E7 zivv4o;J|V7&LmV=a^ZkQseR!V_h3nNkhWp@oC88#9amQ>v-kEL750;t)04&^1Z5&o z1$Xw4VAG7@PN<=f^6OBBD{l};bOR61Xvupw>T1{8)z;9<@#WIg+Lc9q>5??^CTQS~ zSA`ls1CcOC;a-(QaS%07R9Rv;!V#}Jwy_ig9r2)$SmrrX7!1Lxr;QmpmJpSpyg_g| zNc}ANU;4dYz#h-T7uC0&TlRdHzr~Ph3k@P{g6P9$S)Bt}_z3w6$Vfso%}omz-ROHu z0QyP+_BWysv<{BCvCWNS!?MPxp)GO~Kkm`MKwq%O?1j{DHv6*TDp{uU(9YTeYn@F= z7{uW_jW)wfzJ&h8yDs{3RfNAK4=jp_%<c{ZxN^^}#JBUC99R(sr_3D^#)W_+ur^oj z)<eNz(b_lq{2^Qf6?OzE1dzHR>?$xx&<T{RERTU>%3m*qZ$9O(*oRmk!o4g$d;KzQ zD)-*h?SGA%TaZw)zbWb%rZ4{LS_PV%^^hhRnqZe8$q1fxHX-OrGvp#NRiS)IjFX29 zn%ab1elQwlS6`m8gCoNuo*~)bR-gF6=GxJPm5A&`&cWdto0TVc$byUwzoO+EaNqa| z!imerfo6gLQQ5&hRxjMa(IQPW7q1UCADK1|hqIBaOjM9JE4{{GOty5I2DurYewjBa zJ=Hie74&teipszk3QP(*b~G0yF7ZlmOt|sQFL_84pHTNsLYe>k15Ak;Dt0#392T=H z<$UM~H;*VT>O6GV44*mTe5lF8>1ZP&Mu0aTPn`(a!<4S=LDfItAC|X`h^R^y7S{hI zv%V>2!P7v#;z$I2herx=<a?~Z1p5{gqu|TGs{Q)iOksU%z26<zUxW7Fh{c5J<J$a6 zx%0h2yIR2jWBppH3Qt|qdh1JE4kwPq`SjEvt{8NmAyc>VAo0SF&Jrtk>e7$e$g!)^ zVLJ*<`WbrugHOZmu5XvS$=rtm6whw-;yO34p_FG4NUV`<zz1q@zPOM!F2g?_khg#e zJBiZzRE21533KaGI;rB^ZPNx~7X6DJ!V(!|T@|HqWVW^~ClhpibQa2mH3%{2IKmRL zmWV2$7jg|UKh>kbAEm`knCNuTOYTn<WeFnnC~nFqq~!%{STT4}ntybJy(MIJ5>6pw z#Qbz0?oD^kc#0yaTy1ZP6K~|s6-g7hrPxdq93c3$%dN`u0^Qx;HZDErts58zdLoPz zT}r*!DYhwFkSVG-@do2Yh5R<8wj*_qwI8NOt9EtbJ|FO$^jlA5HRR7~{N*iT)#ZJs z8sV3uZ`kGIv{cxKh+5`MQ@6?;hOuMKz70Hr<Q_5qngGT4oCdu{2*xHCG|(@k?fR^S zDq%eClDrQoeqv<B5kM)%3nNmn3!GW72Y*-Y9j3*28>03|7DSb4A~ug-UUT1r-z7sK z17-pRx^rXi`iog&i*XOn8Vcr%U7bL+#&0}scxmFN{V+EL+wpInd)`@aY<zyE=Fz@J z+WAhopiFd5!%r4Y!;9?8ETU%OJEiwzaMaWY-Wziol=4~zGX`r`Ay|$-lUN344v*;w z(x&7H(^7>+#uWF0wbjVMw;;z~xDEsI;%$P%a>~|hs)={_LClqL4a?$obf%6IO(u*o zfQ^1V%9tlAWxZ=GJ;AokcJGTRJSEnct@WHd`hGiW4?Y|c?!m|n#;GN^E+O-#$U$pI z-@tQ$ut*zR?)d?l3-n(6hiZqJ@qY(6|6f1^Mg|6!|FyNv#Lo6VyvG0EOx3ieO)O3; z?6+^PVGrwD0jh{1eK2C5#4Z~@G=>9I6D*98XrTn0#7$JE)BN`b?~*5-tm8WFYUd0f zZ>=b?!mK>Xo4g`aF^sRcG?TnEg*zVuc;&pnEfOos5QQpo=#(+50fk6)92gNTaB>zn z6kfGp4248{o+6Os3LOd`0`xaEs2#@(Czkjce7})+0!lSKe9_-3IQJz0&_pCkb=;A# zjOuK-ByK$rxzqR}bzJ=-B6BhRWJav>IbyTQKzXWv7q=}W&751k{MoGG^F0uxL?2^) zLJ(PW@}Wp4y6B;K2{Py&5Rid|aEgvBQ~5BjiXSmSts>Pi^Q|Z!a1j2^A8@i1CY4eq z`uqMj2wlZXy|Bm#*7o!fikCZR43x$McjZ&_O(op?#X5<q3%cOriq`wLV^pf(=2aSZ zxPXcUXa0=YS&q4jOyc^~pnPHOUeL*5&zSHQaZ6r7+~Ra4gx<yP=4b)vSOFHms`=U= zMt#o8g-?B{R!}Rz`>d(kLZPS4FJVG3{UiQtM5)`v@QB&f${}girc>sIY+eTD6dt5e zfTa7yn3ZcF#vgJ7lGAW`;e=Oaq6Ac#vKk9<-K+-Ex^TvY`3}d%3Hg=Q9fIK@Q34Dh zA%rK!5P2ttN+Ag_pp9mvxKNu@47+GYbfmDPZ@+&-`Z8=RHFyIaB0F{?7Lt!hvcX_3 z!VsaGS&bp1++-{1^Sl&cnX+MJl$&onP@ryONbULsNVnH6Rks16B)MM=(b(mFe`xqJ z?Wfmj@bY+m{(f!v^7b_S&$j2u9^m`vdbYFHRc{wiP*?Y|$M(tgRW-uR=Qcq*h|yf0 zyv{zYme}s<7k9fRaC%9dti*TyohqFXU*@cIPF_@QMgFn`-xJ@wZ{OF~Pxx+~la-VB zqh~A27k*c^J6*m$K2EKfbfcS-l{c<_uaAwhbhkG@{+N-2jssNAJ~Cpi#vPQ1y?6Eg zU8|(dVeOr(Ci*TDZ}DddYmjJf-E_cQ)1T(fm_sI2tRT>(uR1OgjO?$^qs3B4H;(lL z={Q;}N&(rtXi*@`CTS+pHO9~+mo!mk<QX#|cawWsL8zb=wV_)(KX<eJETFAn9K)Z< zd*{=!d_AAjBjYb4xA${}I2KWBhXw5>>h=QC8)O^MQ#|+<I7G^!b4ZN&5D1whVsKj$ zHi=bfp_hLmRB3&tZBecYp@}wyp|va1Z`tMtE{RTO*yc%Q*814yamEpkYzhQ0wI#de z`T5a0{kBQ4nx;TEsM41(F}F$55t<8%qTc}mU6I)6Fy<Uj9_lI4iO5GDpR;{eUe}+N zw{8!|>%72fMkvR7Hkpl@O3uEN>fE|`|GtWke_tVoVcw2Bjc+QQ%V8M4{6_ornBPhc zUcaTzhHU-0;&U6E%=KzHIdHo&d;yJXs_fJvF2W6dYuvo}^QZZ#qptSDDwBS6w)ThF z8NEzIhrb}+0HeLHlLz09U?|LeqxHu20qwwT#jcL?YzJN6P1XJFF9-k<?uR3OQvygT zo}Bd-cr{9w)GaqPpg*rR9DaCl7p~!{5qDJj`yjn|q$tJ0f+Ph74E4~dFi3TdYoQP0 ze?vH?p8zs{4xg`&Wx6YkIz65&zh7vBKhKwsmL0#&ZX+pBUwI0aI-_Gn%iXYhv5N-+ z>kkR%x4H7|i|X5<jOoO)5Eo1`4<TeF8SxXd`g-DYEkklix5zYM#n?-@DM5$eNYaT4 z*ldt#K^??m_VnG2iV9OMIjIZ^%?I}mT1Ld>vsa^^|2A!}&rF_SCq_thIB3REaBRN3 znqTA5PEXFg!wrFc9S#Z#Ea`;?jN#)zl~v{U)q-k5ThJah*RdTpGuB3PR0XrP)K!7% zKwCBKsW8<hcqG$Q8f%bFQfa7;H%O+aG*l&+{NI-@s5I2ZJ0w?B8fp?;lB+6>bx8mF zrFndaoSUm#N`KO;R#$%3Nd)~K$em;mYsJApx}WK*M=HM`%OFulNGV<ACeNIb@+Iz& z@mW%d=({Zhd!i(WlJ=YTeuL*N0*1eV7#2~H`fQp>+$HO+(&bT%R#;Bimb}2Chrli0 zKsbUskR>xh@C8vy@-v7MHWSb)fL$gMq=)U&3(lN86A<Wf>T+oG@umQ*ZAu(flPy6D zmiI;vlLNk*ZPCgl?1b?YCcNMiL6><qSB5<j*5He%9M;JwfJo6@rG1Rj^Fpc3rXU{h zu&K;>AdCocS~2U4+J4dzk9j!48g-^5(7O`Wno^l-^eCzGas`V`S%9PoRw9Rge;iuM zvEl&(2yuluWL3y(ikH~XQ|hN57W^GoOu|{B&G^U1*F#vzpo)Mxk`CD?4U*<J9R%{b znu^cbipZRDkiUoIRA&5{(%=wlA_=@y@=Qy;*XWEi1hE2RAGkk;NH3z2x@GJ85mEiX z<WR=B;B^5a_AXf{6$QQwI*T~WP-C1ze(s!xQfK~Y5@9%3J8|+zHgB2OLklqR7q7L0 zAr-kJ9C0HH*>FIYc>Kjyb1!02u(TKU;1D{T$9dmqVYM}L)1-0XFib5BVfd4?N017+ zb4Z?xP8Uvg8|4|YTsZHD+$iPlG$gk9T)-dN&6&zL%%&<4mO?8>8|XQWw=C^+^!vne zM`(mn=P1)+M5_wi*XYQhdipq0f}Nn1=#+MGcEc<yq{>gy9Ew=SXTY4CT@4FUh)0NJ zeJpWE{>bH+>KP<!K3t|+<j8x4%oV<hxGQg!2I0hu-6Jj>H>=X8IpJz$fzSXD8kEl+ zp`3FtBwPh)*(zyEw&(yK6b*`=l^<I~HAOWjtE@FHoT6*=eHWc$%1gqtTY~qA%hx+| zqjek)N|g$FQH@z;ED=~}LPSOLsB%o(+?nyGFKfgMv;+!{&y?btPYWbXmMP`TX)<xk zA?1?kDWz9p;U*v}M*HK$6|4!gLAN;b`#`p5Tp5+xtEW1tmk{_qg9HEyR@rCP{o43T zF`G`EDG(c#Hg5bkpFnR#UL~cyp>DHdL5KmPvPWwP0&#tcyFiUIpcIzTMwpZ?k@=RJ zK+?6c16Pm(ig-Q*Dz^T#Q#3{n+sdksI0eCq#Oa0*E9RDMR7XNNcC0O@iU=IbhB1+g zeQl58neZ<W8XsxN`wl_sxj>#^Sa+r^lhzTLPENuFz!+dzK}TSe8{tAy*AdjtMSYrO z$w@2#6XP~UGTR9_f@in-f8w%0g3o;QfZyA5BPos&pT)4*Kyo)IN{TKe+7U6zIw2bK zB4^7d;z<SX074d^A-c5WeZE$}*r%Ugji5d;!#t<#;*s?xzBDgHX*-BgpvWf{FLRGb z53mL~O6mm21|;khg3QX3ApPE=w9dd50VMRgxygA)l64s^EZ=1a8ed~>97QpUWqP}E zy5JaX^hji?QjL9Xmi;#*=>i_3TNB{XjeaT;4o1{ghO?^|Qr6&jy|7?g@q+Wc`r4&I zhEZD6jFC{oMP!a*>XMv-Y7${T(B<_WSQ36VtbvH3#U|2d5c%i8^5~AZn{Mn=sH<5i z=)sXn=lZCVv6-fz1T$+aK#zDm>|U`9(#WBlWq~Uz<!2BEndT+$8Q>6~L*Yi8qH(m8 zvPMdMQL!m~baI?(&O$%26-t3ulIWqejt#&YuhWiPenHph_<3jajhrfN`0u(yT-8IM z8$O<86oVLi&NI&(yZmWMTR9^mP|5wsh%035BqjC>%e?E0oO3&{ufPg$g_HI*!q3Gd z?mpkAqnLJV>%M2#6PjxSHm04`f@WimW%849Wzy3!SE=R?u<@Vb|Kwn0`9CW3|2fEF zVfp{D)Uflr)bQ(({8EEhi-ehi5{XYp`$OK$>?V;oJX2Rq3o~qJZP3u9@jFF$;ku^~ zbHr&4XDs4>h`U`4cjLYvthGV3vPHc3HN2hSz;@3;;qHCpu(me>?FaSPfd+8)SjiY( zbkh!8kB)0i1`@`;-DX|ml9gXRn<H%4-D@-_X<#Nx<WMfo=r6pr9t4oq|C^37I1NhD zXf!$b5;GiTcwPy>6fyT%Ns)?lnBAKS^t6oT>U9YVPhd}~te`qi3&dsos1Z8POF!UP za*${}K@z;oHGKPvkWn6IVV?U8zPhMKH=1~McGS6dYVEnq_vONXDM$bACms6h-RpPe zez)=;>Csifotlqhdl0F@Gl}u<GH+GW5xq2DcG>$;OmPHN3d+G9zLP`)WxMXct9RlN zyfVR4<BVsxRaYKm*B(QnJ`&6bEu<e;e5*)dPcS%WdCuH1piG{W)0wbYD+R)ju{U2c z`Bww1O3j1Sk#odF<nIIsZ5+j+ee1c&haeh-`YXwSgSW6*6be+$@r>$>!3I&Cb;0fD z(1bfrW3X$aBYoaE&(*9rsX(n5TU}E>w1{ffvPhs%*=$a{2fhm^@Fh!8k6cpT5J@VU zueK~UEt`^QXTVj-PbeY#ND?+3UB1(qp62M`y->etKBGyf{FAm|OtvFz;!H*eAiFzj zgNvqKuz1CIyqPFsIPj5GRDK5wr(;Y0;Bn=NJWZoVm#F9@wn4e51+}zC=s%%Te5};W zv(7#Jca{X0FN<HCa|BIAOZ=}AJc4EYA#Y&u{BSfMZg(b3jo(dfVK+Mh`Q9IUBmrP@ zjP+d*V0fU54%a}6I{t!PMrpFgrtpAxl0{uB?*f!gJCiq!bcyu6KvS@t6vS)Gj4{I# zFwu0*p{d{24G>qfq)8>0R*|7vf&r$9d5vQSJ`RH|VgcDY0uZba#MBc8Ayt<*wX_g~ z^A$M=OpYYP2_6EGTk&L3H&dyOLeV75qzRMOQE=9ghPE@|RZK)2=D#Gs{gQBty%oc; z-I5D>a10+h{TEGCJP5Tu1Ui0^2hc08p1k@!>NR>b{Rn%|X6^D&EqhQcM^Lb|cU;Hf zfeCwQ+E<klU6Tq4L<_&uhn)WT<s*+DPnI_)sj4o!z3?A+Lr?(OUhMjUW+;9WV%5id zbp>Koc~N!k^5`k012W3h4}}7)0g=oB5s~Sr9KS!zOAu<z#)B|l8TRv~(CEmQqbN1B zhiimmTa)NK2!BSf+UiSO>qA@xd~#juH9PYH+Ko3iKyhiW3`INhyz_LZ$Y}8TZYzxF zi;V0$Yg&Ld2u;4F{0{bK^DMnt*>Rs{Tb-kR$~cc(ou!uw2(DdVy13^U4V<O(Vj#Uf zW3xyV-cg^Bw9ZMfiumoSb@v^fkVLz&{;r&p_6S0;yLWhk*6MX?{{T!}7f0g0PDipr z8g)_Xzz*c~sCBs0>agmb@3lDJ(VpE$JHK%iO^TiEKfU>(R^4dU>3)(A>|!f)VCL?M z&-wtdp=aXb5Bvh+U2bR|3eOQFY=P|EJ^D<jqg{e4OVAN!H8h{k$ue@bAws9VZcYwN zZK7O`yH~p*(VKu+FRj2VY^{OVmoTRo)3>Jnl97I^+THS&02N$3t=gD!_SXj^w^&<6 zkXY!gT>Ie>E^Jy=_cXN;Iw#CvL`k+6$Th0zsIa+$gz|JzfK=S9T2$Ix+x{vSvZq#v zi>8bL_$n6RxY)SNN@CPT8mKBsC05pHw84;ms<{7V8a>Th!W!ED2{#UDI))x;nh@45 zT?HUp$r|KPO(s~|Mlri&mTjD#I;sgSfQYkkZg7)#ZWrG5{mp!Yw3|P7^X?G>&OM{f z988|ZOp3Y56mlc`>-{Q@Ld>4oy>j!SEZJLi0tMK{)gtr>4>?M&^dGu1EdNJ@&Hs4k zGchpyml?X{-voezmj6D3nnTAd!`v3hZoMYmq>b2GltBZPZG}JyZvh=stdM#+{CsEb z5>LTd4?nQ^%Nt%&h6#6)`DSX4Qw5CE)#>iy<lr%^oF`913T^xAbBIr13N!rmIoLMr zw#E^+s4s{Ir|Tjhey5jqv|na$H90J*dE{@MChF2cz`0aUD%1P+zESRG5h60mn~DtA zr+2%1Io*wd{*}Oq6DU*^SHLUUjNI`Z6#%>Og<>$Qhw9l#-t>n?7>TYUYU_DD0`j6} zC>Vg5E^MXDsFy$r5)&ni5bsh)igI|>De2XhmNJ4+*}K5s_U-t(J9wJDx`@TE+3xN9 z^8Px1UOuU$PV4dg$!)botsi;pZ0jmG2psB9a3l$KeE;s=WtX;e;vQFR?a-xZj~XPI zwA^Aj4uw*K4jG*2U02mGn^}%JX?dW3ktx(_EgAnY>pJKyQ@w7MU5L(X*OJF^rLHVo z-Dc%<y13i~|D$ziYvXj{8{1MmP~<_8y3(vqKuCeMfSG1{UQxwq1eIuz(iDyvUgyG= z8ohdn?mfL3tyed13l(*bZ`HW8JEb0kCM8mEJ3@<myCNysQQ$K9qb-j}CQ^#sN>JY2 zS96w7;BL>?<t4ED!hjfFN3}%_s3kYi`~&9N=u+r?w9T6~Sk^(GCeoavPM39L&qUBn zJ=vw*$v!sO;#l~SiocaN*6Ojz?nPrsme%Y~iXlRjg2x?2Oj>}eo-TGi9Z-3@r<-Y1 zN8znhyrr6Ivv91!A#fNK6ZqOhg>WaiQ6ErJ-Pz=Fz%u_-Jq|qdeu5@TM}1kYt&4~^ zM3AEi9p;ZbPyp}E?sKdv(+E4@tZro7i>Wvj8+a&$2v!Qmm)1(`D#&XQ%bXc-Iseil zF8NY*?ZQFQglB#oo%_=<zBv78^g0IEzHG)G|MAd$KC#qsq2<niH;&KkuBI|PV`2vu z+f7$7Lf%fVzKfZQK!k|=Nm+aO#ub5xcv;_R(sW|GUW+MYW{4gwUvwy&#GYZ6ngl2n z=MHtUEq&nn(pKBuNGO)xcN4GAl!v)_$qWv)W{ST|hWu)sXa)vpi?_c4*CjH#%Xo)} z<18&P3!fx(eE$z%#*$2Qma&8YN<<siOgfn20N5zT7=sQ4Fm`WlO#zcV4`z5ss_v5N z41|7SUj*PWeB<TH`Gkzxe(ip8N%m7#IEV!2QvJ#YG<`J=yKq6Y#)Isb(AC$e(TF~C z$7qMPJz_xbp}@YDW;kXgswnby@FdsIl{tidiW&4&gRCwwI(5ESo|Uz-2H@F%2FrDI zaN!b8u@9%QhI6ocO<w8Be}#3tLr#M_x0LM-CD@f)zE!6Kxo*-l&Ox+_#UUlnextPW z98oqJWM&_I-<cfvK}k4E9mf%}TvLQ6yh%q#miU(cJs-sy*pG58rxsjO58?5w-^;u& z*aXArIQ(S|1SfDap<um`RA*IXi<`NZ=4*yMxWQ9eAdFW8QN<#n_=#%^j~q&L_jG7c znDGce2*o=VL|;fgWm+B(0p@B|(7JNdRg{D@?iKv{@4#E=ls{J`x}z?QQkby9kARzc zop2Dmw6op9gHi#97@~>MeAIITc@SjP(e68nK}7g>yHLUbvQGkieu+q(=|t+xDqF1k z9IVO{%d9(_43B7s4%QtD*O>!|FC8kD)B(B@Vc?8Bq$e6G6C6WCuDEm0wO<4@CVCjv zH#d`a{=NoV7KJQX&Q#;uyJ@dw`kw!y+v}PTLBQyp2i^dXA{Ji{EPv~~+nkU(A!;Cv zXucakVG<yt&zcDRBKJ)}z3D}Px%snAkU$9JR<*yCD(*oiC+j_|1Pa>==d>EU7p#;s z1yd;}mDfCAVoa!{TK{#>&-^;ogf=9AN?Jmg1D@}kRosbWa=Yl7o~gN<RSSHn0=KoV zV(idfiRFe#qS?E?<l8na$i;i~4sa-(RvrCI5?0N`WYa0rY_r4ZwaEE|>4<?DbMVR~ z?<k;?cWdb2iSZ*h96o|TIy<#@8Bv(LgKBlG0LmOjG-(18miu_|=K<p*(^DfMi-MgX zM8yH+-CFs#<8&zE%WKG=Xu78E1%}GqenWJ*k>WD}kFV9j)4E<Ymu441Z`5nPRuQip zSCM_tso`U3oHuco?l8!%Sd*Rl>jS;uV#H;eo6G49YmhQv#9c5Eh4favt6>{ggh6tz z8^oaU0r{!%2Lc)rMd6&)8bMgF1R^Nu>SqLRkZ$?~?%3^m%f)Oe-gE7}&@0$I3%aT_ z!;;%&D>a$)PN}l6`-SRTj~$wGKFf`X*OiI&*M1su^=6~EOzfEvzq#e+Gtufp9nw<- zO48=mdgie!w{!7v*Eu-j7&B=+pIe6R2Y{uw8d{qWs-_Gex6sR;8E0BWUFT-DvS*g{ z(#!9U{0v-}3`(0(Lmz5WVLZ5CrTklV6#f8`c@5n9cmat|^p>F{QMS_=i}1Jkl(zXJ zI*BW9m$KH^%uG{O+l+PQ%;O6)mg%(7pQREFo<<9_ohpl*u^hJPoeDy*ti^8M*N$1? z(x=YFAMAfdS7#mn<alR$$$4uz*wEiGuwn|+fkcFPB~fB)vxvhYmA(tEe)L1MQ6+eL z?2zUA$G`9Mms}Q}huwbkiZFZ2rImkP3~c6WCVh;4;9DImE&o%g!2BN~I+!>({>!Dp z7WS`MaN=%DufJ!Ue<;C=6d!jdVG)?C88wgJ5n&F+q&`_ZIrXqjZzsK5zH7XNgdFr8 z$=21(%<P1>vEhW9Gsns2-q-bhl^Tovmn##<ULT0h!G_oyi)$NjGj%$d9D3<m<TLH% zKv|(cu2YcFE3Q0rmNaH)A3N~OHdawC_6W)Q&E8G)%Y6kn<M0h+g81jpK(3qX{Wj=y zT=$#_j4{~vmQSz>cd&F6HQ;{qFZc6nh}js<Vef@h`>zy*m3_1QYYllDF(Cigi9A5v zO-L3tOoT>2Q`*tTUnvf!A_BTS#Rn5i6Q|uNe^}lZosj_GSyCIqH|>sq+w1mtw2>F3 z0rGjO?2Dh7M5S|?p3?gG<ouZvWH)gla{G~Q5V&DrjI_sCWOzclhoJ{!`I?zcN_==_ zIuLCdXQ5b2-s*?9b#Gm6;=Dmwyj1xQ<0OQ5asFy)@DW7$ge2051KcTjj`B(4n$-%N zUPDFO1a=+nvvK@M7Tt4$EHgcxSnieK@*A0^-vilLqp;E2Uo&A1m6rHHhfEJ;OrJEx zv^EJmz~lv@;vxIh^7xjXpb~b<W?qqC#j3dlSS9GCwywFw$*!sr6V5;9e*_=6U?I>O zzl{@9ErbFzFLB?O4|FqzD?M{eW3l%6+=Gk8490g9*#v(mvTe9LayGV98(UXkrorS9 z<nT<`h+wqoz56{OU4(uxD*=^x-C1)x0zxuuGQ}VCzq+n)TtC~+nqtKkAp>bqC6ZA* zE35>Th&7uHiltR0v@t1|gG+*lqTTizJEINC?tt>h-ZlVe79BgiCb}e&N1mvdKD;=Y zaTf)QD)J0Ql%wAm+1jU7<qlL4q?v})Yw;5dQ*lAKF8SeAD{<8P2r`U&loDT3_W0vP zDEe=}MkyWpbRgUN9PTi?=nJ59B)vR8qu}se@5_){V`E%7QHgI`n0}*kSQNqFWx3-t zxw=+oLvO!o8IlO|b}#2ptRe@^4DoT;jvff=`w4xmbErZ+Dt2K?qBOQhRdkGt4J89d zy}j-Q%w+m01Qyd-B^mU0Eo`btbx!TljkPW+QpTYLmkd_KYpM<~ycY{}yRCw=%vG>x zT$L12JQQq6H@dxVj+KPC4(O0ac$iW<rcBz}Q)iXtEM#qF@Wdn>-f$J4<RaoQP%rc( zTyli&b4(=+5XNF)9Z-`rG3fZ;yiuv?3#d9|=SGpPqD3j<^2G2iZcZ$JLdn#?Ca=Q& zIQwi{Yqs=p4k4aR<dusj&00bCk~@#t0npAdk>;`frL<%D0z5RNhz2OiX97HOV{U9> ztQzoRX;TCoWVtRsq<ze|q=|EF$LZIw4D-%kZIZCMl6u&vQkBabvi6m}MJYBz2vvRu zYJ?Y`N(5B(#B^TpNmK+<i4+{JVf%OT@!|;<pv{6+@c37wTp2Bp_^9kh1ZmoVru7V& zj>ZxhDisSwUG=c+L!T32-JPGDnHyUTibaV%JJ2li;wl2_ckzZf3J?O*f08O_k1C`N zW1wL@#njU?y9$*s0^d@|l)$&BGC5=%sS}!*dxkseI5d)|e~ta9hfL!FnX`F+-o3T+ z0{LVzNzwFjJnU(a(#l$rTGB{Otu$(|8<{2kZwi$*j(XbgMy&ai>8-z7s7ZF~epCUz zz<q%~2>1hNGyW~Me=(;2fyUWzbwfok+hAT-ZrX<~W_(N?D5%B51G?>&GP9!Ww?=C6 zwz5?zIcjzaJlR?LSrQbk@gN9@ige!@c%vKc`jWN<A4MSN>Z@5<%!1|m-IAlDudBz) z)!^0F<>uSf^z!J19r{M>>k^_ZMZd~lGySM`9H!urc!q;<?^;k&Z9D{M=4AjK@WEZl zo}>^LL7|-K8M+^b@4d_8_xsI{9lP0|=euLiTxEc-NQ0#ha;@r9am88~H>Hne4xt>G z4;oJqYk_>JRbsL#Z%$H}sM$C`-d=32(GG5!B82-lg>rmo?msYJe=Mf!07$6y)-yP6 zcju>Soo+LqOrJ~bDG2!qg&dU)L)p#6{R|C9+4)}&X_2_1XbJ|ssRn$L#KL}mb+Sp| z)F=emnX|n=HEJ^Mh#NwCt@!@{#M_<cXYT9dVSRA95hs5SsTjP-JmD!(N*deb!ZKpw zMLmig5l!Wr+3RV*_zw^=up2e}v#Ok-BH!GYZb<aVgBb=VAQyYRIEgKe5U+S3`Jvq4 zrbr{A2~!`Eq~eB(7Gb#UCGe0rAUDl!4HAO$Qfz<8;uaZ>itKsTiw1Y*g^tg>rDA7s zC^$h8Bk&+)&9POuIRoTN3#w7j95lL!*&!iV^=tVzf+}QG)`|+<obV&SHg*SSF3D;a zh8IU^LWFDoO@m5kQ?30#qW58xOQr3wrqTYPOGs_&?=u7Sv5j&7N`NE_QFdEK1Y*FS zICM%!$tB=IJ79sZ-T?X03J00;W9}v)w0PL{)lhTV>X~5SlMTcjK&Uy~lS3BGM4(O} zL<Bti8_?CkU=kIu1Jw~+{_LTyY~Ul42UA6L)db0kiY%LX4kyZa65L-06_nNc&z3yV zb8%fzMj*@!duR|z{$`Gpz*f-&O*RF#d>T^A5JoV9bgwJM<pl{%K6he>KRfqIdUBY0 z!O<_a>ED`LFO7NW*-K+%=X$H0TPu3*Ed9;3Ot~OP_P^Ck8QW{k^KzIag{LGNAb6*W zmeJ-CH*&0W$VqmLBw8D+$c?}rK+|}Or6lEH=bYX3bf2ZLeBm74G~wfBT2k($PTpkj z(k~K_seT6wzBqW6E{PSn-}%eWMAc87lUU;SOuJpm<BiO&Jhx&8A<wlyiv2m*5Z|#0 z<spBOa~K4nSKb%EpJM=kUIg%@qimznq_!M<SK3Mm2iJ>X0d&08$meJ+9=I|}HjfOI zO){dBiJ)YT!C&+-6Aaye@O9m#fRN~GofAuat4P8+C7C#&_Kv5nt<X`vjmha!(WMUX zl~95v+oc$M%~^?rX1b;_R;|^jM=HMtee-m_7ALQW^5RL9ud-spDDCRBq=TxlC7OU{ zdEyv%)pheD)?<PDxcTEb<)zccMlT=U29^OrFs6}Je2zU;?CZ533mZinuWd-r%zEId zOP6lTc&;=0st!9=OY38zx`pb&Yb8WS-^!+q)6^yj(Z~h@@l4Lh2CB4$4Mf;#kaBT0 zB))+J$6RV4Ue(K|L}tfcx7Ee~0F0FgZz34_A7_V{1gHaPu@2zYek|W>pD`t({>?c! zV&}(h(5B!f2-^cyQ{j5F516Sgo@Yx;nY0uroGLA9T7655Q$(g^jnPG0(Z+tAGVSQc zJH6)jHWoXJkBS=Z%k@>ICX0I{!v$y!j9>O1Fgniy^QUSsi|tFOj@!RWt(Rt3IN^K) zkz~Adexz5<IDXJ|5Tu|<TJHjIBUr?&Rfh)Px+_Ei)k^E)t4aq>j#yD<Z|wQH@;0SE zFUJe~tcZc50|&~;+z4zsG2xQ0b<i#$_zbD*f~|V0v1JrtYw+9rB0LNZ3#ff7G_K~S z2CaB1^E1tx@#EOSWPq|yOS#s8iJ(IX4jXlnGG}!M>k#{AmU!T72p&f89hTs#53ir# ziSL+jrB4^cFnBP65AR`I_l&eTf%q|%D_SqP4h2Y^=EdakmTj^^Z5|sfC6F!(HNEmO zn=dZO`(O<oy(`PKt{ARh#IQ^7qAw~v>!{IF*d7`ep<c<dG1~Gkr(EsEy$OwWb`MQK z2)TfK)*+V2+hZm59h(7To{E&4y~q-3owx(rk{pi^{(^WK4IlCvkd!fysw;#H>=UXp zy>o;(D2;F(Pi;cxdS2K~#zvU*s(gV+W@4>PYTsp!7hNAc---wuFB?M1z%bGgg*kYL zq2z(Nua9B9ez1aX%zjEMR;ka!f3C5&@4-!Ho9_9Ufg5J^EY|pl5b5Fr%7YS^!x~|F zY7hp#r>LYN${fO{Yg3nYV#~tr9?S656RPC){QwWhX@>seLEt~gub7zs>ngrsO%12b zUvB+Z#W&L>uYwqmdD!J)eUkPIYNjM)S4<^Ers#)vB9-5U{rU05Hjg7B-N2L@KMp4V zVC$I2e+N1<=O`#lHS3+3$>~Lyry#0dF=Xk)4o(u*j2%cro)&E!J~bi;$B}c#05zRb zzFjv~dGpS(WAhMIWxplT!M4`P>|`wbODWA3O4r}C09a`Kxq8{!Sh>Dl$_xg*h-if# zL4@SMkzqH(`z;~{jqzb493ECU-<{cxDM1>R0JL#2|9F{ew!|z4sn%kFA5F36PmzJx zktl*7@#sE4QQU8nQ~TEr5A<OOC6xdlnzz)+DP4KIX`+?=nOtS*zPD8=N=#S@u8MsE z7W9asOR@p<GW<jGB`pF{so>3gIeq0IJCr2KnHiS757%1Q?>oRvBi%k<KN5q5zb)-R zO&6#<u(-T}MQeW&C}?m+C*H13rMl|d7=va?U7q~cDTC=ug_l&>@!?||dfm94%IW?) zr^@wJQKuo%@GuL{07@-W4VFM-2Ob&~h3vB3B-Je7(%dA{TXIrLdbM;>#A<b_BSan% zuR@9NaqxBVc{smvc6GXYo{s$W2h+`(ov8U~cX9eX+@G6rdVO3UZ#`{JzM!kEDs|Qy zbH@|GnN~IpsitVjs?<rWtQj2TUJkYByqs;olU*>4t}GaXk=8`vWAD>XRzAu}zHyf? za1R<SBA&p+iq$`!9KIi|pB82wA|5{lV#xTbNCZwGvGa$E!S&B<TdW6WnkXcueJI`A zPMO4^jE^X*5}_sWbO@cOixFlqeZO+VK%h79jN)QF2UWzwk%n75V!)<FYlV~i%MVrI zDoqd(rhsfBA~I_Bn|kkJUc;d*G(x}57AO%cXg{aV%Jbxl1(Y4<)Y-K<iEDS8#p{d2 zxi9OR8WOX2FC!#CTzD0Sy)uV*MnRHeS<$2diW}bQWc#h>eJ*+Q0XfKb3CZ%jsYrcc zSImI4G(TiyZ*JG?S#Cp8M$SQKqpvudH2*Kg-YHhJXl>J6wrzVa+qP}nwr$(yUbb!9 zwr%&WN~-(s<fL+LW=2Lbl6m*>eV;imyXB<hTv499tcI@2)!Dj18BnRc2$s<e6cISI zN|mc3Gy4OR_`s)Z74|(ZkUiH^5j<BO!`bJ2Q&0SYQLj#xR5QfF)~qpk5SL69>0M=D zUFsF#$~MAg^HpCT3$}yxz5_vIGWEw{;$qOfh;gBX#`@C!wCegAFMCjaSz)g~!a>mX zGVFHfZMaTYOUGHBPF9gtN~$89wV`8LM`0hAN8~_6neszEMYqT7dg|6RPyn+<R+Q?M zD$2PjDRGJ;gcwmkz5X(h`_MJpH3I4d$F#cnh7>OZ$*oAqrQ%60dN+isg|rJlq69!= z!A@Jy!U)<#rYm?GV(lzWr@+%dT-tZ~*x>hJAkQQw8MN3?Kak>1vs9yInk<L0B=AsH z+}ZfIwbwD#R-Hyx-Q8Xl-E=ybyGm)}3t7hzvBq}>I6zG1staAT4l5)6)qN*j`!}xi zj0{=VoUKy6_4!OY*y@m1PC2$!2t1X_navru1HoUmyOz%_m%j&RsGv)@*P?Utli~^V zvG}j1+VSZ;2d9+t2+Mya!sDxWOnkWj@Zdc^4^{D<U%HoR`r6<wsK1SKV)qCOQ9f`a z_cLe-yd-aX_R5utu5Z9VUT}e(xJX;gpYV){irC-Mpt-M$wfNd;w<!b1S9sc&u{un2 z(Vb=|;4bOykBN}>j<+!o@}_9;eh>LIQh1Im?MP)V89o(ioP5(o)$z4bxa>aksUMHN z`TFup^5ujGNJ1W%0Td+%;$w^<OjYiD0A@y_i+VjV!bb1tAqMf_Q=AgDt(eg}B+8ue z&9wh8^SBaWnD?atP-`!N9^EW|K*uIOyJmTHp246!k%qj3l0`u%RZmvJ*V5J4((*|Y z61UvP+k$uf1Ci2m5Q5OJC{RLxplouWoI6>Gay2q5C}e5K*$eK@LrnKiM)m}Vh|chJ z<?eL71%0knjTYl0!y7(EaB>8bA?z`5!DbVYP#c!zGnFF11CWAt4h{2{Gv#Ahupr|W zWb8~JuZe*{ol}m0Vw|xtOt|j}<B-1HC7em>KBexu)k`qwxeUB*iGAfQ4qdN(^sT1) zjOLi#G_e;};160tFn^UEN||1h+4dH~lY7bSgbJYuw&9AEnH(lMAccIPporGP3X(vO zW?X5EJ%&IBhRH*eQls#pgor`%Mi11S@ganKqJ|CG{Th*mk=qRtLInhZ>Es3qX30>} z$O#gTA&w^$C({4jxB_RHFXjgpSC03IdJ`kMXWtJ?SWEc<h$s{wx+PF>PM~;+AA3!p z;6@UO8VaC%t!ygj9&?ysrIUglrbQ=GFXa^+mRQW`u*XSe#gweK&GMAVY$m6sd66A_ z;(z~%Pj=#~t9}@jc}ik&vS+6TEjX4qW=9NBo!_m;Bj0<B4<%ndbZwT$)_1imcxg`i z=<~|Tl^VNNlL+ZfR~I^5k$aSYZ@O8u455+s%1`)2!4t1q)Y3W|`03<y8h1Xof)=El z3fDjQXY=rT)B7UTet;XOU+6#j$g%>U1ElBKqdIab8!PUl3+8VT^S~EN2PCT3UZ0t1 z?O<_}=&7S~ltEKXjo;f9c&CBu=0V!~ew-59zu}<A^kAqJz#pjIj>X9>sbnx{!g8m5 z(w=3oh*i}ac*oBCswMv^j0#O5KBQ}$@^%7~>cd$H9P{lsA<R#%3$yNmRB0Ku%dO*% z1u!(grp6wd;TYyU$)V`xI$b!k5`bsy1|ayp0$pgL|1Y;GP$|iJsgVr}aA<Bej)BYu ziL&}458s*6J6fl6ngU9T<vUY9xn3*d6wzmM&PMk??Y&%>or%`CnoqPRNVK-7%OUWf zF48i5UE5U<Je^F9Djl>m$wvWH<)q2nz$B@e&SiOykm+%kWSCkJJ}indz+qQ<YO;<S zW<X^8B5T#nc0_`{f3@w7)pn=vI-~iTw(ZWH*$)V%h9oOW+M<r?hn#rh>d-Ki(f^|9 zx)N&D)t7~*>khp>a_hPd3??v@e&)t?X}`IVLq0v7tH1uW9N5&8VgIp2V)e^>`i?5i zsYJXGw5Q}@_mgdW?*OBhWv+TeCY<$&=2zwO>3+jatTkEw_EX8kw`Sfa1o7gEkrHWo zA-gW2sUTA^TGCFwc50V$)4SWHlXAN@Y4Cyj1&2O}(Ebk@8VmjZ+_nFIH+lYhQ@?9X z9lHZj6rWQy^@}K)ka6$0?>TTb21x8g`K!{6n;L4gY!sFN>hzmZm0z#hHGad|{!o6w zzctCA`}g<lr@8G;qpYm9FxJ^izEGB7u%_6oj>X2J_BIsJ)|9Zv@+1+6PciUh{YxJx zT}&7_M%n`r<FhgSHpa^p4bz7TcAn_4hql}pu+MXu=u16I5Ya<m8vGlq4U}x2Zq4v{ zb@O3Hw=n$9)`wP%4>Nm#g#DP_y)0iFvn<?25s0WCl|Si8s$l)%kYc<hG>`*M8>8E8 z&|l>?ANTGXQDukbiSb(bGraKFPZdDIL?(ZLXF#Yk4SkB0jb~VRmqOxCNbs~=h@}1V za9051>`W8f5(6{~b=k1O5{B#E%S1vT4MWfvZaaCR3?JdY^-#ik#kPH!XB?-5bKyIA zPbV-O`A35<JzCjX{1?qH=YQtncnzh)<}cKN`MSCuIAc~wgWs&q@>sD2@MPnRNIw6B zy8DCfLPZd-UIy=^xFMPsY~IXgpa+-bdcpkTo$huK2`<r+3}s(4Sc2(}!Zy+8%-J*x z^4W8FI84Q<@4*}fIp>z_gWPW7MHA4?EO)ZgDqiQIlR6%^WRBX2wj|q_>{AG(PgKiG z)Oz2z&iIc#aD=;2ilq*=U*@4IzJ)IOH7-@@-2+8!o(%dd#nrUxJ|3X3xhM`h)<#bF zcvSOQBiOR{C6W~&4I3yNJ|3fim`TxQLdy}>pp{vW?PLpY9;{8>vFrGaJKzZK$!7*+ zD0CH+NS^_YNI=&;lL!k%>G##vja+C4Ty3A*Gz^$J<tK4aKJ4vI#@mFW8j_765*?ql zb{CayO0K37RpBeu?gcGdZ>G_-F2d}j0VN>ii;nWVN-CH`N<My}Yd{U82JTgf`=2Bi z-Xlr&c<tDxh>=O^bGIr*5=zm>($Zl~Cn;i>@X%aUo+2KP^|uSIq{De}W$@3QDY=~2 zD0VV-LJU;Y7(Ei9gl@Cr!Sh}|mN}q=er##81C?Sq;8o`Ieb7zmcH)P6!v6Z=)+)hN z_saaO)<f=AIWHN<f-xc*gnI63ip&+hH<Z>#WCuDf9i!o_D_PylH=Na9Y@)t)aCebO ztc(NucC4KW50prCdVUo|m(qXCcbvGsny8O%X?GB7_k#W?I&W(g`_U3h*v7m|QT9mv zgyOK9_KddO^$hBL!VUkOPGj4(I!|oY(-?Vt`D5BW3kLHwd3h;;(#r$vC_;rHANO}? zsg@uTY%_oYi}jFKAp61jvavy`Hjgzb7!!#DYD3x_jYDN@<i)6U?A{v1mr;_)fX;Ky zQ(#u(RGH{+gIAhh0@Rdl-Zkv1RkiEM>(izBE*Zx8`N#7=hX&1xw}zN5JpqCi>;Ur~ zs7ESR{aPOQ2@owFa$P?}_KSfX2L!&Z?g#>gT6#nhG*t4y9z@lesFBS8TF&(7-;(No zObJREPsi=(WpcW!r*;Cbo71TC?Nh_e>t|R{$`cxvV(*f?kZxZCIy4cX>wyWPRrx>t zXydZ6J%8hrXkNC4)lvf)TA_)*%-F*AUYfJNJO@y&;CgpKWzoJ`YK(6B)8<;I&e3wc za)bvdx^H>TXpTHChSAkJaOqIJ)amU)1fiJMx2JSU<>}j^0Pb#lGX(!Eh(+)ZD7=3i zCk`h(s_!$3YMCoPzf6WkP<V#(GayZ@i`$PsKaN1fsY$Y=c_S}VmeXEC{Y~mt$_cpG z((wB8?ZMnZQ&h>dYdD;hv=G=SXj_OuB+NZ}1S*MOLVQ*JT~#Vp<b~Tm82M#KM8ZtJ zV4C&$!i5yl;W(7d_UH2W?&bc@7&*a!(7=6^=<*<9JnP@a5@K#yOQQIJ8MXhhC3?3W zGzVB8%T7&B?^h)oQX+Xah?t=Lo3P@{j*wKO8C&c}V__vG&(!Yca#JtQ7QfB#2Wbw@ zupeM`SlfS`+R?NB4|kIPi|p!uvN9Q&SpIAGl7FfzJDgU;pBlY-{7pJ;xYH04eGqX& z3Ys|}(W`&WE}^yUO{r)SMS^jWkK0ceQY=O4Pt_Gj_P+RkgFXD28T*~Kv~}}vAyX;f z4F7Ug`XJ(YuzpZ>4|=O??&KwQlk(-fzb*udk6sQ0vg4Gv;*mMU>5u#qAnn%qcjUu@ z>Z8YNx0x(>xnoQ2pvk7EfbGJrctMFkx-Ne^5<x3fYSe)z6hHxvsD$%93dQpq9-;Oq zS#l5J+8+>PBgR-{@-tsRI9d+4xhoea_Dm9yw?O$RZ2`GQ6gH48_KrBA8DLVsArk{s z)+!k7T>%F0XEvN&bzO4#6pGK&1eV=_@X9A-_z2X}A<vlkN3Xcc936Av<_g*6_%XR^ z;eetz;sh!l*C?yNI*SF=L9Fb-mcLT(tLn0Z{i#ddA;vN{Iyq9leGEA359}b*Btkpf zf!v@wX#-uLx6CC16qN?B)NwjTj`u`krYqGIi#q<)tuJjSAp;~A-=iqoaBqcRXR8Uc zs|x0~S%kDIQ$YBUU@BW3?ypCu0h$CEiunUYws+Ro1S-DrzQilobb+{(+-u*rIMvl& zna-90QFYE5-~>U<JYL`8p{&h9S?59g)nM4oSu0aDI^2)=J2N<`UL6A-QrIS;Uw{+! zSf?54<qhkfc#9Kr^VU+k*Lr}Bt1R%Z3y)W;vW2RV?>>K^*>6YM+Wp6Z0yPw1SSSV$ zpNMhE*!$sNc>HAg*H<rey7lxFeU&_G6~FY-^*iqMv^U$jr?YK~HqDM$k>9)Zee>it z>vmVMlYRZGZEAH;i=8)KD_u!{sAvRfi;gn6F#f~U{oZh`3y+mgyQ>|8l`gE;yDf8O zV%E$k_r!!vQem^-yK`Ip(Uw*LO_fTjuorIE+bPgbZWXbD#25n(4DLps0j{(TDMh{! zCn8nRDZEEU2?nx4H3>|vVS)jrp3bs8N-Gxm#e1e`g=STwG<hO%)S<8m8@{Y$S>ExH z(MT=Ho}gHLjVM`Ctk9^nxQ#R+y@Pa^2DA6-R>FPUWu7uq1}7~i+G4?ji&hJz{cl)H zabF_jdprUI-u^*qvL^|rV~TwDTLq|~L(+j4V)H1qdA(7DU7<eY@GjI>ED`jtSB&Tl zjN)be5Szwb3&E;<LMO|>{#&o;DW3Fb+MrewS#*jY4(sp7s~^~|>6w)z$x#Pqw%^<H zs#_lFOg-eO^mM!)nk=<|{G0q_pxTJa99Z6&?vXhKJ_Q;73!V*X!;ZUG9DN77G3^pS z7@7t+4dy1U&sbWBf?kkY!_{0{Jya$x=QXk@Fs5|Z;|jk;i9kAc$&rty85|^!AQH)R z%8R%J&?c{OG*rJ9tzxo<js?6S^v?RVLMDmv^3NR4{$kYQC7NW}6)uZs(#slU2b1=8 zU^ZFr=y#+hoAo!<hl;Hlz;;(hSGpb@#J<7f#qoKaN8^_RPgiFis%{J)4SCjW{fnco z&vA@}*G|yy#lhflm-aUEOw8-7$*1qv%|TqjF?2N+(hDropGXSE{>pnK0(19A8c`_@ zHTB+U{2EnkK3j;$oU_(=V_V3Zp%}y+T#DVo+?E|Sg*#Q8Kdr*?8GERlh2Bxw{-L<I zl%k|^ZIQUPfiTK(rEJ~JC4Ykh6UsM{&dKuY`LMK3_%UulLkfiHba4vf;z<cL-^Z*Y z6tGxCc{di28B4r{Tb_#GWAEr4WgAHov6Bh~@iQprdBO9BJ1GUi1Rd90L#`07Cv^6^ z|JMhE3wh)vx*@%=CTL_R7OO+9Esa<TmBqPaMU>&KeU7tQ1!Xv3RiN^+ze~}oKKP!! zHV7>NVOrI4+T69dO2|}=cwVwZp*ra5+2dC23xMCFWFcY>ab2={{5jmKJN&%@f(*s@ zJv_o0mpPLscnZ&;DsNH2O)vuQEcl{`lTbpY*Gp9V9#P}4=5D9z-oNfNpxC3NZWco$ zR|vx*U9|`Q<T2jT6U?B0Pc5<rr8IKh<oGioZwsRqg?5e94=<<3a<)k2PT}hW$_aKs zJ`Uhfp?++U$p5emF@8c#q;Fe;VBE$luL;?8j5lvC0i{hAllG~W>EM(KvfC2oAK~Wr z)#1ma{lyJ`H;*o@nvj1LR_C$BFqbWfqqHP;F}6kIq$~M)e<M}6B*fwX1F4iI7O9+` zIj%ppB;)0<0%q618EWFE8Dx;B^;RQ*0{`mlmdy6TsKNM~`H*A;f$mQT@xW{U{x_gO zfW7A(^&y}^%?|ZF=l<x@K<EAUX_q~p+14y{UTxCr<M`?+%qO#19XF5JQIIJFU)+P8 zCZZO{XPD9y{Xa4?;YEKB7&BiZuOaa+>W<b8J_4(AhKhSmU7jM<CZ~aD=tI69`4z5( z=6m3fuX^SRlu_*D6HD`>FV0q6`sciJZ;dadA@zsTy#!*>{US13%*RpqzHhkeC)u^v zB`o3hnasz0)>9GNxts*u!a`J&I=Le`XM?lx_1H#2GqIJ}N^BLb23LdY|Guau))H%p zwZ>iNY;ZBY99v2FUl%jD9BxNj2~Pj#@JQ3JFskJfv6V*Q6S0s+QNg$DAgNdR)GP^3 zjc@XymE0qIF16Gnd@Z%~gVs#E8mrCacs=&N4|WMGBeL@39S^N$o9naW@Ed)Eq)mE9 zZ>L;xv#7tHaRe|G2m4Cdm6wz7kI&qNZd_VFQRVDho#*E>Grqc_)b4Gf;fV#c)Iljf z8ie4bSA6OGvEK5X?+2~Bv@=?u8V82KOH8)p$pl)-Cz!<2wB{S;HTRfLL*=US{NGms z-{g4LQH#7hWfep0ad^_j4%w1|ldMh}2;`P5d_lPv<Pmd9e>(KbZ3K81Yj)?EKJ0{2 zxtTo2b#g}MTTtAhY%iPcm@k;l)@Kr-Iv$Y_j^?y@KWUy~3p)*!2s4cY{(-g<r=VTm zD1dS-JmEyvFF{a54h6(5Pw+1vcW^aN2be~}mEDrCkv{bga(>lqIuGkNm?$FsYsF0@ z4Cc=wi)>8S%gSeznjK=5G8k><-|iR-4XKk6l{}6H|NLF%GjG}50`0-XVNdNQ>_y3K znA+^RBFk-++7a2F?<!KZ+@8^y{RLJ_$!hvfwL05>n5HnWv;Wr#*sz9{(xxcNKl?cI zQo03_ohnxsnN4sgSwTq%7C0uG#Cr%2KpC6ygd>us#oryL7b2+!26p<vsOF8ycJI>; z#^xGo%kG^|o37Ub)VQkfA%VW?`w~<|B+vlVk!X+_mRwDIn>hCw|BwV4oYmIe$gUdQ z;$d&yqa#h4t_f4Y7}0|ThYA|WgfjZ!?LK(xw12AIx9c7Iu2+*;(2*raY*7Vaq7#jC z@7qH&OBsXfY7xjd;>)Zpj#lnG<lRI1Tn#fXzbgeAZqlhyLf&Yqf@4Lb4~MxGQhP|2 ziEJ)iV{(&JZT12l<P?;ug7Q2%-Fj9sTmAuxCa`EkI{nBQ@{z9@jmyJ6aGl03*C2`N zH2L`lNh|KeER^`{4L#hGO@Na%2h3(WG{Yi_KMDR$Af7{nksyV2=~}?((SyyF<df|b zIe=>vQb`#NVlmFgXJ>Pe72n$3)Q?w_igZgMEw+ieT$cyW=iY_9)xwVhLJ38~X-+Ij zWQEz%{m}lx4cW^{tPG>gmyn5n?+D}_CB)A0Zh}Om0CGp;V81l#sRat3Mgz=Rf%O3I zpJ>k-yCzCKv&%;dsTCDeFf2X*uEs8}kV{~?RA#(8SI9b%IOxHik~F283u=Zl5d|c| zHAvpe?VVb%x7PV627<P`3WzmO(mpbxv~t)cmmdfE`74K$gcx|e;4K!w=5;y+AD7@= z`d`!1QsypnQ-`}wVN`PbgFKgNI?GAl!RB)91Y~MSo9~CFNMb@)xf#eg2F=X%jLD*m zofrT#PN0*hVc>mKOJfW(<nq=yWww$L+`9OudwJG`Bh9l4fdHSX8T_gMC|0M_<dPgM z^=$yQlPlCPoSq&4U%5YpmXE@kmjZ6cJz;=#?%6bA`E0ImNTNtU>$N{m3Nns#9(b}^ zqta@O(MPbzq&b0<!78QW`0-#8dhbVv^bglnbdnD$9;YEMf_J{;@m0Ge6|$&Wq4lE_ zm8~c}xFXlA#Hq%q7k@shIA)o_wY{EH|7Ezd^?g!=_-Bc)plx9jLH8?rE}R#>Ts(UW z1&G|-146y+*a+wo7$r-*C@w(gfG80ncd8{OE#-|wyQUaWrT5}{Vv#!mU26Obk%C_4 zD4Z_&j?Y^`VhKJpiIhM=S!xlBVNlAI;}v}^l(WSMj$jYvywF7&se0#&lib5H9ZVP? zgiKcnyi2`YB7qZU{RYhOhQY;84C_3V7ZF}HNs@MntMEg8E)rMZP{3y(?f9D%o*K&+ zCbY@$d+N1iU{n}ZB;M;L5A>`dn5(7c5X(8b`rr{x6FyJY^-GO&UbMkC$c&9DR3LI1 z*llsoRN!2v=4RQq?YRT9;Kw5i%f)?-8C32cIwZ?7Vh-2RQN>lo5-r6@trZq#g?i0* ziVDk;l_s8IUlUQ1VQ<CQNXW33Yy#qBk=sq;1^3|e$zIhdw;ZOv%}S!8o!47f=FU7L z>9O^0kZVZWQy?0f{m0T`<+7}rryf=qlBqKKzr}~*6lma|gY(Ajyxf>_vaj&I__5@6 zp`T&&Zmv(O@-_zZK8CzID|2kB+nHeYgA?z~X3<$BX1RNfYeMJ1{ss!?sCP0t<!MnO z1v$ISQp++bQSYvuE=vc|cj3(p##;2;Sny(>hp$EBKlk^>?vCZDKbwR)J*hg`9Uhi3 zR!+psw&^pGmdj#+ya2~=8+R?NUp*VyF|T4q)VpI47rI#u*rCB9i1zWxT)ZIXf5N%7 zJXYUk7YjId6Q)df@70~~to+~`X3%NGccX)C=R|I{AnOe2h9{><v-16i!qBI1D_aw& z50{|Cae%OGkkaJk=DVpsFpUrZ^dUkl{v3gn<`LJSZk+dR0od=WJ?HcNnbz4cJpPam z2uNDtUfpXc!6e}1jj9$9ubb}kX?^%OenGJ?#yNQHStR+^TCy|F?nZ0Q=2FlZ*K}1T zYXw8x7Z8h#&6zjPVusN_8`eU7A_fxOs@Z8YTliCq_G=5282D$-o-5u{E=p;VW;L2U zdwlEy194tG$AaSmt<OZ<tYT<Q|GS8SuXlM>^X>J+IIoR4UT)$`MkCazHqFFd6zxrA z6oiSf@gRRU+p$f+kdKP3LaY}P_l>qutWfuFC~fT$>vB*Zflg`(h}L|jB-(DXwTB&( zsx@!`Vn+aA6o>7Fvv9=M3B%&433xEbGuwu5Z>X@db!{f_y1DCxI`Jc}UIpj1w4Uv? z$sgX<vF(cD>DJ8@x<t{0c#x^hJuW%{3p7dK`h1_=zV+*Bjw?G&r?oB$#tcX0fEPnc zd=d}cB}-Jk@4bj5_|Z{eCA%T-ij`zagA#D9td5N}wuG0x9W&HLw5@f`u_hW#8S;%o z6c$QTu%{2xH5OwfcZ1tMqmMQw-R<Tt%{7%=Y$!WEl6UVv_w)O)G$LOVG$AMT=e2lz zB>59?eoyIsWk3T1eOBK^hwmg1fvH`Ux4RcsC0O`qj5J%?gvM{LLUIGYfN&4>&HpJ> z|Njif|1Z51270Fd&%%a@f#bi9<<nYPad^Xs{~(3wqemt!owPm))FiZyNR$ckdxVe; zRXt!J?g<)154TQ#-FiWZ#@G-CH&U;!Gp^4$bac{`mU$F}*;+*s>fYn45!p(OW11vl zSH`p;0AXFUpj^eiPju>JC9}$&vmZ`KJ*^-^BcEVsw!I?_Uk5~KYXtr^{8t+-i1%4^ zcPQ9DZS1j!pM~$RO$@B&M|P5$*Xl602(W<(cMzQq_f{JX4%3%3(}h-8pvd+uViMU3 ztc!$OBVh4iX-AswiENM>r->O$yHCI{E;tTw71)kL;FaVr168+}Aw(78cF9_EWwK6K zCLuE3L-6c@_p~PM1kgT&<0*zB%?8mDTRlj21Z7{Wf$VEp;j>`qo-WZnVt@id>O=v@ zgkN@oe;rw;Fr|(Lg-(a88T*QpIJM%YTKr$EQ)x(B%o=Ui+n=r18sb{;)L*6=L?yIZ zAPZC2!a)x!oU~-sZJVUwaWW8aQ2O74Gs=U=*heCZAXV%oEA1F_0C}02G82|hZmTQ= z73_jYHQj9LP*!!YsXtv-!6pr20EP#$K<%Pdo?618p7|&3jZEgW`&iV&;$eV64t)Y= z3NZ`XUgzr9a=!$@NCR5Rt6_F-B*wvlGSd?qyQiPNeL>6tbvs4<=eT#{08sDL8NC=b zw@YfMFrq!CWv&=>otUzW?#YxWfHPm|T1so$Nxh`g3i&<eh8h4XVzBGng<Al;d#QGG zaV)k~tTIt4*CEDhJ6Ua^$iVHUqfrSN3o@&@y?(ydr^|kSOs&~&dwqSpUawA)ZZEbw zejd?ld%ayB`>(Tjcf3#bXtpM^_;$X|PX=edI^10!SLbh9W(kUT(jiH<r!&VdZGQwC zZxHZ5x_f#2dbYhAw!ijY7B{a?imu(RUoLCy^m--pdZ~!p#HpA`QP!xZ!DJ+t2A)cr zzCN$JUvu|wA^DeY?*y_GH;AQ!19xo*Qy$?MzNzQzZg;#_Z!|IObi1*Bv1)I1yFW^s z=)iq_d7*UO@wlNZX6YxPx#1A)&;15I6L6MYXqF^{;AiSvV36-!Lg~ezG#?@ypD>|m z?y`eJ!f+zoh6e`Iu5}k!@<}b=G#0~^ie0Oj$-pBQ-FCD25Y1D021NIt+!!CBJk+Y# zzJ70*el@d85WQiKm3{nqj@8KomLd|<0DI}>lHDUaL;i+EP|NH)ZwNQ_+082CI}E2p zw>HmkG+~)qcE=&R;2;OYd1gaa-rSj&RgW37Pg+kEN}ZqOD&aTFJ;75ycSYC-&k+CU zk`Z0KCeJL=5Z-9)!DBB*$699CUpIEHFday<?~0RLLpqH7xgEJD7|3~3!*()w@Oe{c zPowA-&&c!`(nZW=Zbf#P6naAOO^1xQ62+UzlyIw<iq`Ni^hX}lr2@s(aLQa>bu}f) z=LrPVF&*H&=C|LF)&#T?NMjTo2PuLq2}P<1qG(FpjxZfCAeT>`lpY$!1>&+H(`<ex z0#;Vn4^<3IreY}**imsf1>*suIf`xuTqd39Y-MqP@MP$=dGN=9VZh{2aP+F99`DD8 z^fi4W?vcbRwjlf47?bTK!|QrvNj$rzUuK&tKCsq*_(&{^oM*`$`3NZi$IKSQ6=Zq~ z2$S2eiFlo0d9r<6$*&~{v=9%nJV0q;1GwKDvkppz*qwbw&3FrFya%*Il0nVI3-)wQ zLPfRL`1MaQO8)hzknJ!OZLu<wsi<7tJdr(y2bQ*O^#dy{5daU#-r#PJqU*gCV#VG` z^zPVbxi1ioh6;r+^qP+xF~iQVQ=i5|1LqQ_#LbOp{>G4P*Plp@ClyR;;x6CYhQCm2 z#lJX5B4D(yxu0ZAaWAZ03nh4(n0=l}(1(H_0Oeg?at<EATR;j5W>zGYe?jvYD;7Y+ z+BR<lGPksKx1r+@vt9m|w&Mvq9SNCH7{J+<oQbr6hr9zU8RtMA7;}ZQFwd#(EmMfD zyJTOG+wHt)eF0eBp^2-p#E5@4kRf5SdO`wnW+^&iJNMXfr$F=KXazJHo`LEp!|+@H zWG^A>nQ0J-#C+rlAQ_QwJ^GwrjvPixbvR!vKhT}3v~tv6(GXwzcAa2USVmtO&l5SM z3H$>#db~u3qPEI^@O$>^h-$cKT~IACI9|de{;yaxmHjAbN<KLjazMZtJU?inOGGS? zkDw9KnQ;?rn7#_cOTN2kP7q>wr7p@^-2(&s-~1W+vT#3bavAv4gISoT{HYc{NBG49 zZovbEY&mm@@mp0DzrKoM`eJ*OQ*#s6Rmk=%<KQ<1E&a60fuuY3M%PFA`+Snlx((kx zyoU|fjYdB=ech`ZB7y99Vn$g=f0=wAwa2(QrqgpXC>cfK`|)!Op5XM)XtPk+;3?}i zJbg{lDKXygM+;)J2TQKl$;>sOuKA%$*S9+>{vdl8WIxd++%bS(-J+S)f&<+4vG$uq zFAoqZRSyI|lrycmSMYrFAU+6`Tt^f((UcW0xd_u6VnI7GN~KHg-96CzF;?n=g7775 zi@?xOH}KP<VIdU{8^6)!BvGK{<I0xgc;uzzrsxFI{1eMF8m`^HR<tgDHIWSq#PUk> z&DDMor%GV%8%A}wRO>cEIXvQ&+Q>qL56c%ug=<q&316)Y(C$iZJw#b@2$gcjQxNde z$@un>tu!kC{!Iz$NkAxJ?EWBMHOQaHpR)uQr>TR$AeftqYuZTo!9OSd81W#HORdnF z>K$N-<gY{=kdI^p(IW{vDTyPQeA=t^COt>Si7xCTCbu$_Q3rKIwW=0B-=C7)ZSIsM zA%DpCEnrzd@@4`TgwsW<a(JNZ5nhYdM?PLngf`88E((HrhPMdk;z*vB<EIjMRGEd@ zTHtZ6mPdeP?CUxEyupv>&~SJbjOz}xNB64scP(NrJY!OMcbU^nW9GsrGN>!J2rgx@ zD}Qn{?EL|h+(9g{S*%CHV*!06VMCI@zw54&xC=W6k{Ou=XyDs5t)R4*k0IK03{Pm= z%?QBW6A_8>C>8FAxs06wEkjPMN1Ok>gl3f+e>sTvY}>BLX&3-`vV<&qX4XI6;ksok zqsKf~bYLbe&3=+D8eIr;S-Zk3_s=W##yHc8r|9ZwB{r+`6f@8=>;8IX$8UnGaT#L3 z)#4~#hRfv_NfF~sil8E)ies-%Pg}w46=Kg@h!M<Jwf4_q(?xfS0n@rVWl4`Mff&Z? zjPCCt@R;9tl=e{t+4bnLYdEOR88QiFzXl<{o=}rwUzXuBHSdW&Acc)3AuhR!r&P(= z_s%vwBakDA>&%G?NtNvB5m7^SxLkCZ@pa~E*7D51K+R3o=D;@%_mUm^r+HY{Fs}3I z#yV`DJt3Z6VPT?_3X@s?>2kl2@jE!<+u)6I1(~(++qV6AdG)g<G};F`I()@>eEI0C z?eTn%%AwI~9UN2;5QuecF{~*z%0UH!aBgaBZ4l&MS^p~o1@BqKH1_K!<m>SHVOu=_ zy(!eX*mzlij&mJ}Uo+-An)ZiF8KlOi-H^)wk5+A_=AdKXk1emS(<U$GT*&pwVVtft zTVCw#ZA%)TN^RUE-)LhNe1LIR&*#bvQ0=^QR8RN!jSTi>?$++-<e6SFylwAp>Or+o z%USLaaUy>SFRdN@7+T0%&+o#v-TjY?{DywD(E>bdH}gOVB3+EL#Zj23b6RLG^Vvch z{`;|nX%O>Tt<c@x*iMf;L?`ZYTwxutM_4SBwm*>-v?#lwI(g(FC-oED^&sya45aoN zJ7Z!jOt!v5r?_v}OB*eJf5i1uFZdpe6_fxX#Uht-b}v9l7Z>1Micc}DXRFcqPC@1Y zC<PJVW*Sm_xz88ko(cTY1rT!+y1JZ`jIwF062bmCWB68u)*X6&zCPC`I7#^VO9<@3 zzCDYVRS#_O=}sD$sdCj;M#%_gkrT_zZeQ|J<oMJi8)0$fh}W-|NM`@+)?cR@0OP9q zCJ0*?S8dZ0WFF*zdXY_T{+g539WspU4L3R4xL$kVBg(ixrd+Q%YW+^vCQ#v}>H?UW z=Wp8;#7O>RM(H!xF9OIx1BhBW^D9}i(ktjz5g&f`ZTN0I6Z^h3jSVsf`evKk^UhUH z{^>^qkqA76-rQ@L(VP<OYwIs^v68aaAXJJwMmg1%qhef}uZ&{k6fGr4ajvX?vt_TR zD6jH+{*7aTqNc?=4pmqRT^87=<v{*$vNBtnw8n|!bNzyIx$fWnr%H$Ye@>16k1Yh_ zf8Uh6*4TF1Y(w;W)$5nmE9Za)l(-XWf9ZEQTSL#go`|H&I1&|-svCwBxp;Gk-8}!@ z(V-R>K)IeQxz_s94~!c2y@e+js`iS~vV;5K<#P8p5K$c>6WG&e<oa_&4F&WkyN%ku zYJK6uoJ%{}H|N{fgZ?xE0FCNFB6ECx4VL)RrQUpnu{Md5#?hE3+zh-Im%VSCrVJTV zgxWErSsmZ|D@98x{c{{BB5BN1KHEy_4ev1o{BWv+_iYq#)ztCigMCQM%9&l?d5?Za zlO|oC_EF3z%*poGgp$wU=ES@ndwo>w-r1Kms!XhL^8D-M?Ca|J%hQ!P$LD}o3|==E zq!ft!0rRzc<+-xxu=U>B7Yn~Twk)j30RfV$CxXuOaXqXuedQM8tc@4hcC7}SCN@&( zQlAdeXm(#(cx4Th`i@xBnF*>b$2i8jxzQQBh$0Z;{Z7%ayrY#e621+!P69%cpBua% z!CX!3qK3kaL=%4$Fc?NC;iUO=<}!hZ8c8E}xk37(kefCWCzSb~&GQa_+-a1_nd2we zfmU<Y30HeDn?ZEcjeLb21nZus;<9!_nVR}Z3AQw6zK!+=*Yci9!#nl4LOQj<o7hUE z(|o11;kI(SbPG%DUn{+8ZJdeBW^523)bODy$ajb!O0w>;*pKfke?qYRzP3Qzkpc{l z7hhu9=uLm=SQqV3+Hm*A7;&&($4L2t3DJ+(Nuv}R^@w$C7wcq@JnFgvguO>U;n5om z2a$e1OLDQZx|c53*<rT3@q%o8;W*w6I6)-IOT(u{VKW`gBj+UM%IZDg=qroc*^O|} zhzJCJJN})U06%5l-@hk^7U0d>wroutZVzG&0)?SI3Q_u(*U<-CBcW`pQ7p4kEm7Q3 z_r3be@yG(}P2FOgW194-LjsLBZ8PsauWB9Q3i(BOB}UQk)KjI*U_QBoN+dbqM5^Rq zvgR!I9r<;Db)%Y1C&8W2A!&N!`v?toTv-_L7bi@{JFifAYo1k=&-N)aRFL_}!h>J> zq2xr%qNRHJt^paDh_Z7URLIpWW#Iy|MN8&dYs2+otiIN8#RI(oz;)yM#1quRUT7-e z6wFjL0jqUIF9u}I^d#<04N4}$L#Y@lnGic(n_>UOA@Nj1rm;0qRlAFe&rH)ZjI!2T zRs__{Gl8iDnb_0nL`Lluw?@gN$}n4%lVrACK*K*q#&EsJLa-dKS5PjpD#q&@<MyOs zIjD=Acz-jwulee&ZZ_k_{;_R=3(6lkcamt0A=*fi-dj3DXO_<H;C%f3nC|g%u`vlV zq5Egw037n|rk)U?mGX@M$6)nbQ`MzmXU=Nbn)M7#xFR$gL{?wTq9>l`BytCT%%Gc< zvS2&a)4NQuL>SG=h$9qZPdgj}ifH=QB6JT_Y%k2y70l3-yH%`e;ZxgEg)-#bz8nXs zyeDO#u8&E_1(?2m#dtY_e(mWJD4nqgfoWP5iMv!v195mx5RO1$Ju+woF#9UJ8dw}e z+}`>c7(uX;HeBLFw9<|S^`(2j9u&>JLp2Esd=A49a;q8>_$^cv6i70s(>QswRg_Rc zEQM_4ypWm-QY$`}MKGckzS6m#NcD=HWSb3A1A<42k>?nF=2%o-il(5F#Mt@|q}kb6 z1t^948HsnrIV`JVu;ge|__cxwJ!LcHxIPGDhH?j=%HXUff3A+6<zoIdcgiJr=6F9c zECrQ_K`}pU-ZE84<Z4!c<OXq!3I_$X<<mk~%90nrP~%@n?M#vCOo4Gr`gBXLd8<xy zuW&g%X!4#2vVHo@IkTBrvBlQA+YcJVcXU}lzkjfiQ>cBLRwRDe!YY<z-xaS|F!OoW zsQiz9Go=c1K||&8>ES0RgC!aAI^gs5U3;zo08E!m6Q04d<~hOqDEM<~flbbMG!k|B zT-e608ETKPd+p+U`bAqJ!pieX!(09Nv%>4Vw0KuFG^=eu;WaJ>Nb+LIVT~=fonF7) zYgV?R_&>dgnueQAuvdvfLQ*r1DBGaMcKbR>bO=UNF$k4~<4xsSHlQKG1%eDm4mw-A ze?X$NQ|{3Fu7na0MRLLl(Kh}2E>U62Nr+;sE$c~uMp~;Zr%N-dSCp(W%8f`QSarBa zz|7)m5A}`Lq9c(^@#<cYrxuB;Kgf}cA;A+q9p(uvk#$rgj&4%)nCmJ4v`7i}ffFR_ z_<3T*Vj{slMUc!<o<DyK9Qyjt*eOY;YY`Q){+70C$y6gVlJ26mSTN^>s_TJjDAxEq z-zOBe2U0Xw9dBGal(=q|zGWJVqBMg`u;f=-)96gTM0NFMwTf+%;Ir%cT{8Un5YlIs z)%dakaCpE)=mkD-<NtyS|K;O<`o-pVW{3Wkm?J6#5O!`2KeOP@j@d(o?P*ARh^@2x z74>_g^2K+SQC6l(FG^V|1!9LDWKiEt&g#QzpK{oGp@rvit?41Yzp>d_Nvb;ipbfMI z4q*WVtZ`g);IBBeuH9&7%O^A5dX}Mawuol9cFuOC%H04Rp?yt1(_5Mqg>yCW5@~dj znb)yS$4B#XH=5V&+QZP7^rOPqMV6_!W$LMb37(P9juXUw&~3@fbO$YvI`mUSPbg@t zgqF|*PdxI9hOSqFmgkp9S{9Yj*HD=ylZaZUoPJbx$rb~Ml6zzoHt1*tw-^(>IJ+4; zMdp%STCF?1X6pRNg(Fw{du_mf7V5b?YFbkvkMer)iJ>dmPHD0%s&O81MGP7zWT~08 zbf;>1twxOn07%9ObO=zMkN2!nLrM!SiPqBgEw@eGJ?#BtD~c|5pM1UxLU-=rz){rS zd8zK_lsCe+cy{FYuN{<j`*ik@27PF#ME7Qos@MDWVTldR8i6y$hV!<OWna|f)$974 zM<*v}3js_B<d^A4L_vhxd|CPSc6H`0%gU?dnJ~CTldfZTL?qJy_*N5rvYZ&|EAT9Y z*6w%my7+Rs?cZ)dFh{fxeewyEOARrl2btK99kUwJ;pNdasyi%uo$-eMp4oW)pHe4| z{|Q|GKfBi~?Ekfk;<3iAQ<f-#@2XyZ5p(m*EB4KNGbvlfngi}KQ_fHlA;hLMi9H~x z!|%t9qd)&ZgNcTW*#`(t+4ik#@AfU6!s$xEjK%G$#H~Fw_b9Qb)xNYXP8yP&)hJ80 z`H6Jt%xDjZBmGg$Dm=LKb8m=4E-u)(cka;9Ob>=w<J^u;C>yZorvcUoAPi(_$_>+B zu+^m2?)l<ZwYUJIi@J@3Q^Yta^7L0;T_rQ9+a1nih(nIus0=4DDuHAadp;-LC*Rw7 zByJnpfsz;zf0_Q`LrYQf=E$hm+gRFN>7Os|4y+tGDDISiK?b|fKBtHm=C1l)Y>Evz zQ(sPufs3NAe%dEw73Q|b!%ZRzaM!z|3*hKRD$T%`Uf8w^qak}Vjr)xOZtCqobi?9j zo*r&aY#!LPl;A;rNO$h|zj=meUmk5B*ux$eX5o1Xnt;3=Yk>CWEs$^1>-ZlQU7851 zsHnO&-Jg7OKI!Y^^iPcPB{tBJ%jHuo<x@ZM8sPY`GqgKA<n5tt(kgYavavLQQ+c~; zBCRe5RpVrt^Yh0{L_=eVro>g@9Y~3LwrC%8r->}v!p>hm-d`tAnD-6=AzgwlhPYw^ zn3)6-d<qkG=q&^f6cKp<;%$Or?gDxPE*PXWj2(RzB=a>)D2eV9m7By0b2t>q%kGHa zCGc?91dwP>^mf~<t8@D%?L-$a9Bmfs<W*1c1<idM;BO6i!b;3O?4hA%ePDF{mgZzl zrm(^MYZ5eKv;|$c$ZrOo*<0`!mweH6<9hine0_7?uuhkVPCOWrXXn`7OcMp)kuIm6 z%O2atRwnIzP5w%<&}EnDC1i;nQk(qjR#`0w2u12F=SC>Ah3s874JUzbOUUq?(h`C^ zN?Hx`y*oprglvKK=gmp(Cw{{$DOFF`$EFNfD$L!ZA!!?lTgi(ZZI)p-lNhL?k0yk) zH`hM7&R<V!VR->S`b&5wUQuDv$iTxYP=pVJpbF!IC>Dv$19PM|l9UG$jT&1#10hwz z-3GwJS{(Ub!r0B@U{j{?_9~eaFTj~>s)pJ?Fe>pjH}#PYF@4%F#?u{)g;t-aU<^s| zE9eIn4#AWZay1*_EmN*3`<a{+m&UlQ2Yaue<*P}MWJjjR*oo~;0x_L2F*m6eY&AC@ zBPtAlNQ#zYCh2qwZPSZl6RA!_3i&*OB~-`{6Dl9kiP)+1Bw;;Ate<?p<KMqN+*&;o zEegQu(9Az&!~EAuFmII+0j((*5P&XXCX`^NDlo|f;!MXGVD0t@;~_=jwBEXe=y1*B zpxB<(+rDVuG4s%6t~1R2Ww-S#p)^JGc(Zs{;wa#a!%ZNGyD4n_L^6bs-|TrQ_BV_4 zmAJLmIZ#64AuDh1hCiUjf(qDUg3{Jrl!Efok7n~vX%r)%OS9=iL4WH?U&v%9JR9tb z-dd~!+)8qH$TiS>1h}ec?&G#@KCb47M#4nUWVzh@y^`dQT0H85p@N=LxFpK$c@D51 zp^&J!*EaeIUDzOf2y<m2Z3s6igKgtHc{20`Z%Oja1C)Bi08tnGK{C})=0xQNMor{C zATu{Ol_Gw_OLbw3)tGy)hgC2SzWw4f1^ef}?u%0W_dZ@4iZk?8b)wShyKClP!d8}4 z=ogI{Gc_17{Q|Z@YE^aaYgE;;wZl~aL6?^$|M0F%tOAlY8d)89ve;`V(I9FSq_TTq znFQpaQLPhp!E#Yfg~cDaHRp#mQg6Lc9<ijvILVZ6T-%R1w8|a-p}-DX7H_=VzYB5a zOsNhrubpV&xp+1XgiO0}Wf#T{ym_=A<CaKA;<CuHw%Ck)aFO>bnfj)vxtwc3=(2JS zqv_S;6$3c_3qS=Z^9Q}|^)%1vGa759K&Ln4hgn)~u*+S|ChDGiOEOKxUlj$^{aIKE zN9<D27}l*Eqo_}@l~-bi<)k?kI(g+`SE;&yzK+^-!{)`~0aONfZB4Ouu_L&0aC++( zaXPAKvWpvT9h_UYS$)+dKj0*nXNN2>vRos#c>hD~W5&)CBf;jUrt-&VDY!E}-GoI_ zq-kZj;gJ6M(K1dw`}m&{RwA--Ymg=pHMJ%34nIqvcl1BTpZ}=+;rOqqV$&KLN&h?k z)b1hvRZZgHz)N})*QOmEr;>Y7g(^xA#_R`+XUo#d%asBPMv=Jc_#%q6_(=aL?L9|) zS;2eJo%Pk6@^v3Jq!X3EV6>}$Ac{Vqe<}<vjCYSJdF>}>hq*zs;|4Q|4!bMx{idQb zrY}>t>Md{BR!z0pI8mt(Hlsst>@@=+sTX^pI>Z=G_F8v+*@yFz!tgo_7$JGVYdTsv z{9l@%E%cr1t5?hxTSMWH4i)rMXXXQE2w7-@EiZien=+S<l<F#A!7ov-6XjS>3U;D< z3veT0%w4WE1px%O5Ojw~dUp>&aB<{h|18mvShC_AbBG88WXLn5cwozc^)Y8i2OMcy zL=Xo&J*#wACpqC@L8^~XrKCeTKvZANBdNzXMLwaKU2vRF3pDvFKUKa47N8Y9A3we0 z63M_mUZ|63r{B{i>OX(p#|zK4^XzsD2LV7q!D}II={vIleg^(5eyV_%p$i--!XQVQ z8#8=`S-ZKcgV%JzIf_vRhA@#c3~c#s+g?qj0`~vdevTg(X=YTyV7%xMVL#Sv{{sg2 zl2mGFZak?DFOXE?uM(8EyFfRf2X$`H#IhragE$2;ykM)aFv?Q}!&4YM)vj<GS5)cw z&O<0cb3ljR@lC#<$5gI1EF0ZwE8q2tQP(|~%g<2|Qxry2YT`Cq!)uqVc;mSe6QmPI zM|^rOCR~a@QNSAQ5A~rNrWnux687b&f&rAso(buqc~IVpHr+#<SlK<93NL4qBA_G3 zI|g|cEl8j0z%u|BPZ<d2&k5SHD@$c1uhI^x1(0nnvv8xvozz=YYHkQ7q?I|i7_lgu zBwYpypunxPFe_i1HhmQzt39K@i-FSyjxgm%8jul}GmI}k5gvfdt4kliBZ`FAkr%)t z8lfbdaeuVU+)#KuUHRf)IXF0nwZ{l1(=$eJC&TrxF(roick~w;BYE6G9^Lyz`5+ku z3ynY&!5Q@p`ZE9>#3hZ`{MgZ}0iM;y&VvOE<H#Do1`cynA(G2YVwFh{OU48EbE8`@ z(>K!}H^8SX!KPZRGCs{YEsD*OvvkH)H>GINz2iq6pj@H2v72HfaP<^OM1h--sw~8* zZj)_0MdFNrd(($MY1KoAWtfeVIPP28jpvqf><a^|%~;FUFmp@N@eJ;QcWdMA7`O_6 znl5G{!;uN{Z$I8cM-{M-eo4HW7#F-$jwLkE2S^kK?FeaDNSJ%Zy(!-URxKDLTB=pn zOK0B3Iz&)C66P%h%KO4)2uJ$~F-8bvCXtgOPf#;bxNyO*q8M8kfP{tv&VwNpBmoTe z_COF_?WTum?yNQdax5zOm#gp<hPo_Kv@iAOOe&&Uh^tg~Vqr)}6`oRa9g)U2l*agn z*8dQ>4W`}1lqNx-LLNZo4G}5ZFuo_nL!kPLdYVQ#=4>m#ov(lMvL79s!8t)=LFBCz z%HtJ=FPar2Kvjf^zH`j9euNxAG`FF`y_U*rPmn02NgM!^8I+O(X3`rE%y5lqZvC`q zvS4Wi;_*!YRnCLp8BjzVG{!clKgh&25YRGah$qq}@SB<40kWm!Y7Rpf7+%nKUD=Rd zscU7_hs9Kx$Vosv`d3h=suHY%E9nq#E?I<LVMDh&k?cx_n|j%0t&C_-Gi1<Wtm#>A zS-EYqI5z)@zE7F3SIGh#6a%|Bk;yb^_$Lu}5;j9q5r%<2EbV!}i1KVw5crCg_siK_ zKHybEDZfd5m+U04>P}p$>_1p|h<l~a`EbpuWqYyd%~7;-<Z=}3l*mvi1;VGe*5ora zt(+8`KY5*ViJgwgisS*|?3@mh$+g)ka3c;o#Y)ktw%42Ne$B83!#xz6A_9eVX%_l~ zsq0?uervIO(Y$^ER267Nub!}-^|)YHwA-V7Yn}ea#2~`zw^gau0Thw7m;1&C!Mc6` zdRot!^Hsa~0at#!n?2N25lKl8i24Q8<{xGH4{?H(p5cE8gZ@vQ!v62}zr+?#Ym7T? zvLkd~{&6q<O9a9-erbF!O~oQrl_7QD$bdv$Pn3X{=y=eZXX~FYF4@w&rqr%Zkg7We z|BXctiv|cwE7~h9R=XR;9xhSX3{lD^AS_Ykf<T&WjwXHDe=3i}k$Xo0H=SN_H*@6j z?5SF{Dk7U|yXVuwSo1u-6^#iiWAT9L{I5oV!;BeGTZAuiTb%DD28*=l(-d)#Hlz(& z_k4Pf1ardpM35&+WPh_Ys{yV6QBdUfLe-A_!I~d&muwp#`*Bw*<f$>Y7oj|z%rl}L zY?59rWj#)>uWLy4NbsUjPON)#05%#3v4*`0*AKQt6;4EkQspHAHf2im&yWp%7JZCm zixv?s2Qj7$hjF{1mf-~Fb7f7V6fKUHQ<>@v*QX-Ntn4{h3i-61Qc16AX#ey!>jfn6 zizS6!Tu)!T!~S7t&YD}Z+H4g`H9|mvg(MJ}xRc2|6=8a`0xsYE{dr5c;w)#!a1ZqA zoKJzdE0cq{RSi876F5?bVG?jA+TQVFd@h~(?0fDFT62)y+mlw8F1MED?`HmChQ|8v zZ?ECh%K9t2+IrL2)?VR#)X)_H9s1bAih2Tsp56lw3{DmUStlah@*Yf)7)>6nh!xnw znH6A9$uB|k#$pM=Jf*1A)7hv$z{DjKvMc>v88R1AalQ8R5XYtDTcC{Mp4rRAp;umL zzCq9$pge%IMs6i4)??m(aooAwaS2%zI27?RnU>?h69<^VX!-vz_Kv}!21^)bY}?6+ zlM~yvZQHhu6Wg|J+qP}n$>#3XZf(`x+PeR~nx9|IOuy6p_R}T)6qSe~fgq%S%awEh zBrgd(rf-xJQ%k=UM<6!_-n%6{dF1erA)Nlp*lVG7@2>MaBR@E?8IbtDgJJ?9Qk(tI zk*x^pfWi={P}dyYCO$^c$e&bH)M^B8V&uP0<t$We&(W*jQ@anbabcx`mXwD2*4fV; zfRd|*B9o$iMB1v0x}EOez$r$;mVNwiEre@B$>=J1-v2};6)lbzpqXJ3myvt4Otgx> znz6m@9OG|Pi)enO;eIliSbfo99QWAlkYf%BH$$HTiKk<d3{nL{Tfa^N+))X(UTHzR zxv1l!T**0Mud2I8Mmj>J+ZsoxyVa4bcfAq<iQT$|!MQl=qOwL9>b-uzjKc#1Qi_m1 z@Qelk0F$ZI<u^cP6MEGQ;Xf?nm211SR-w#T<s>(DTx>yX-DGwF;KGr~KfpPAVTDtB z)jh^?iL{_@(XcoUGkLlD=dZ(x>gMGJ^dO{KxjcJ9l*2Jq{jUBtA%-=zL6z`zL7+Wr zLr098Nb;K1nFv)_o@JeQR<NB#r_=@dBxdf6gqePjE}jTm8@J`8EdWzy5PsB_)H$sZ zK-1ty^X@hnBlX{umxT~;71AmTSG}BH?JS=V^pIdl3yP^JdV;DeVV93rLkCaOoj4m* zH(*hN{B&K_)$ZXNJ%8bL;}Qr>IH*|kgItsX1SJ{$cPE;v3uP#upUd)WX(lCszkE|Q zoSUzX?U({B;H_M@!kPU!(ILwDf>|UKG{YqII<*-T`*3Ffs+s<F<*Um60-tiRl`z&o zre=|tDh94>kq}@UFbT^uTS9uUwn`vJp^Tyx=%H94f>STZJE(KpZ}{M^sLE>PT`LjU z)cn!_Nlyf5qmL(Nv<5`daWfO@q(iWX>T7|3g=P<KV(h1opJ|o}J2^+J0%7X|37O)* zFm|PhG4(`3J{98Z6CPSZNcG#^kI(RbFAfs2cQgEyBONW+I<KJ3ToFogV8E+gIAsu! z=E*!a-rt3SF_5hcSD|52M8)hGvF<e|$HT{4Q{~;)kR2lIsMQ>`1YWoFesy1m^POP5 zBm9T=@bQwsJ0okt<ELCMh@o}RANV_fvDzpvHvsQaE^W7_UJ$i4-@OA%=DPEz{DtSL z#F`$bDSWUOlMUre5sjHGmB7&KxEACNiq?A{xHPdQdgt557mK)2w%*@mlk_iX52K-u zd_2acaquO2af>qoJemBcw1fJGj`{mthYO0Ij<GX$*H<CvLP8825ngg3v18Ej@DUVq zQe7Z#okBKj5vs4TszH2T3{;ik`{Aa?lElgMf|fgldMYYA9m?<u&{osW687`RjLN_k zbBiY*JUzs{5La5V$sGdzSNW~pPut({HO^+LOgQt0;^*mN|L_MkCfQNI2C-T)ToD|H z5aaAPFS_(}*U7{vGhAuQ2_Ak%m%FR`;%Kz&f%;KDLSF~zLnU#x+>e9i)YCiq%4sAH zY}Sw=#nPK6K5sT#Q?$J>oZv$m-6g>-r5I8Gls7w;uEv4RYS(F6vh+pLtHMiF?)< zrqGMo!ycp+Nw2kTRMM)RCkM?h@Q%T^X-5}k+%Vn@zlSb<XsaM&8ZQrNKJg2ey9LIi z)0VeMUUDc_d^A@>r$0dPe8Y}r`+op3UYxrBYiMQu|AtluMmoCxHMA~is3#mWBl_g% z_KB8T1n-i*rmk9&(WD$KN@csWC}_bk8Ke=85H}^<)yN(Y3`vr?YA2v04$hs56nuO@ zK!D2v!ufQ5Yz%Da`sh*0ktfH4!e<cli-}_j(F@0ez{m83#_Bb_Ki(?#=0@2=0$V@9 zt5>U9VwK%~Fl^m8%@IqhpcP+ieS~)G+(0}I0-gy`2BRGDw|9KpLW0N4J}Uws8KQQs zW_S2Ohk%&MO$UB-_-^Ufkcud!=DRmah%!n@%4tB9Y}fo9A1IV?X`fsA7hBt$-b851 zjDmyctik^aIL`{;Mg-BP2nbUQ;-5ff$YtfHFFg}dvn0M!7ZeLh4dYJ+z?U<fRw0Yg z8!@sECkS(Nz8Gx0@gyW9F2j(?WW)DWmq#RZe?HaO*>JsmtN9x}K&&l~^KIhebim=} zZT;3Z33UMCFW9KTI6ZI^pHJ>RGvkB)b$^rNE20Pt3JPjVXM3(KqxUmrd|gBzkEng9 zGlUq!M`&1^m85CZWx!^Y()dl|E;C>0&b@cF@tFGJq8n#&(IsCA0r%1|Qw2W}<q5~^ z>^#NtP;`=(6-yetgJk^ew%Mnu$>dBIwu{&?*9VTtw!bpkO2;mq@SUh@vI-<d(63?{ zKo4h`z@ex{Vgei$S`@{IHn4wo{)LWhN}5&lm#}}w>A@9S`=!0k`Y+P=d^^;z*C0@a zF`luD1ZV)rM)6Iy(Xz1J-!<42Z$=0cv2d40c-!y+SD$hpU9~|BN-tdqACaGh$x)Cf zlnWyZ!_2wT=Vd8SXn*oQR{(U0Ze?tK6eL2dP8yDr@`LWR&mTiB-?6CfDyOoH3hp4` zc?s_}BE+H?S|^-dcGvGry$SMmRmva{(gDmzV$C`|wu1Y`<dQGSptf%no>dw3^E}w5 zLuY(mCnSl&S!<Or&{?RmJU_`(E-WKtL;PGr2g`B)2<C>K>2O5;M)i>)65qd?M1qC- z*^cE?(Lf62{Og7ilgvl(FLXo{+hM!2TE~<6WZ`@FcqqOGMZ9bbd$=A#;ixqxfZelP z?2FA4;{u-##c>{7X)&k2x#-4XC5dsw+;5ewVKF>cMDWMd4VpkgCQf?=Yo#i@Q|0P4 z<{37ocyFb8Gj8?D`Kr^v_EiHM(MzMNmD+-v0L!5H_4vf)?gMEh^97LBT21*=mz)s) zT`fJaOB0S|G<@^*n_y0bQn}FABe6ETTl9H{Gq~EKTjs&u>0((AESM_uoqAB@x7ck1 z-AVHq5qF92NmWN$_*jbAAjP%1sPhJBBa-}~0ywdc#3+tn-~y*bs_usJd%!4wAnkzY zwas*6DT62V!3OZ@a#wtz3^(Y$L<kn`-7)N*>{1h`296Pif&fk9zx{AI!GC$S_L%hS zs1ZdEWt`)d;udunqyN#ax?S`o5EwK-RKvz3PTm2iWDks#1yiFQR+}o|Q5o1UR@1)z zyAW%^dU`6#1S*W?Ei@9#MJsIC|86FISXXnJdP|{&9l@951Xt5008VI!Qe)^3B3IB7 zzQXiu4+1J1ydk^6L{BbRatEqysg}G5|1t7XF<RN>UH0f$WO;hh9a;5?3hBMV7@uyv zZ<*typNrrkXvjNL26*CCcmwj4H$8K$W3{;uU6XN4q1$4%={Oa5K~+W%lMOJk;gG}I z&hZOo*hF8u@w{5EnwLwtD107DfjOq~YN+t29#>jndFpi3V%ca#1E-yRp!?_XH>%V+ z?IZkrrG1W*x1B=!V}Zy1FKFvgXrZz4*&;M31IYGk7`=2yMR45|HEUp-mVW1VNt;qO z)7FXNUCAvzm^>16GXw!9a_mVD+>buYYbsL8T@E%`w(wxzpl#rfmhJXp*Y6L#V|Y;j ztLVB!f>dA)H8w?Y`I}M1OXG>_`eZFJ+0kAz^!jO#+87g?&$1-2Msjt))2VS&2G0+2 zG{J_zDC94?;|DA+9G57FL`;Sb35+yIL(C8V^0R4Wfvt530t(dR-g%0*XSZ$tO$Zn< zL4!n|C6_y$ot6PYU_i*>n?Qi*ccaN&XI6&>Rm8lQ&1d(s#22ay+Z@Gy8wJC5A@NbJ z66UXA{U&f2)@v58y-(Z_E6*#qOc{U0q}Jf+QgfXc_pS+*5o10f+irq(ZP~SUQf*`S zEUVsz9=cCM+nP??gkux}gb{&(CL^uMc50y0rL4zGM8N(~R)lNB7E8fxf?W|%ZM9CX zTp(ri(Ze&~u)a^@x&FSsCm&HZ<~0F%Hf^kvO7BJ7$oo-e?!pp!Ed88$vDRdsvR?}d zho3~dLABMK(%6KTgOFlP<L6Msd8McwBa^^mfR<LJpWR*d0B~V))qXSHo^UQsE5!ek zSx!~W9ut2nE^K>jc$@c+u>MjYoP4x@|3Zr#u?S%gU59*&?T$+9Kc~g(^8dOWq^LM! z2oZ%*XglQ;VuvWg7+@SjqM!24!)k0747OLenPqTAVC&!Mh_qZ8oV)H7Wdk50Q?!W? zZ%YSv_OZh0Zjo?f>&>LbQLYmh+&U5yz2{K<F#bx5c-jlb#4*AxBQzhfgwIddCMY=p zvTJ70a-$-~NI6K%!#zXR+Hxd-jF-M*){D?V+_3Gk$Gb!q45`{P5$bzZn1vM5%W%>A z2k1*5o2w^SpV6bbH9_wZ*7guIQ&YdNWUZqgcq982cTUWgS2}B;#Wbm7i8Tk%%Qj1e zKEG8~JiT6zE^hp|KXL;7ePB-3=xgvT-3M<AJp_-CnS*yMl~`9~AV=*oQfw<nXYGSR zsnV8K@SjTNV!+xq4d%=s@m5&CHz(`!Nld9V*SK?TyMVP_Ltqs<g!`O)M}OX79#$OW z#_f6fYa>oOIjg+9rU)p>Y{(`Qco)2viPZYHcYFEGW>lt)EUeSGMlQ8oEXduq&0(j? zp@YP;(Q8qRW0J56uz22<c@C4V^bu_JUe5T$9T+rx>b4E9Y;6PS*lc<^DWkzja&@<3 zpSSl)H*rspDt<Ghgs##L{8+bq-ZTL}iX{}87hK}1=RXFTm!~mp9dtv~A8^X=diwvW zrr7_Bnxdy;`Crx4l*Wd`?^rtT7u8zZMX8{DA9pG273-3y1vPQ910#k;A<axNB}xV7 zuNQ3u0@#0vR^c+kviqQFRJ9!^I0*f7(m@3c2|1)>yx;v!g>iB5!U-2*`h`W2zxAGY zGlmEn!{}Etsif!yM8vxua~(8Z8P$m+N>Rs`{S>RX_KKFXr?6c%?UFYXJbJ?5NJy3f z*@PWg88Wh;Oau%J(Lziy%R-8n;)#R_S+?}Pjvb=N)VVq9B?nCVzSv!uYV^6GF<mk? zr|f5TTFCyUm+&Wn!T5DuJYC}=&s#)js<w`2cy}!$R(B3Z_=e6PmccEmhBFW4!Ubg> zN9qZyG&JM-&-3k_>4vk-t}&>WQ<H?sD-B}zv}KlwB+G;nqL2e$QKeo5cj)T6mXu1> z3=i@P^JGuphed5R=pXkU$P|2f#US&J*;)=mfmp<T>b|Wo0kL@JJ%hx=Yu7kZVP;_^ zVQ?bK%klLb#tbw{HFZmQLcy|zR}&%j*Ho$nq)#$pnoLOiv~51c5EPaV;3`DpPDm%c z0WhUrczz(0rV+447e-goa-2A(RLDP2^!mNYd_f<?X(eMYr1RnmKoJ9NJTAK`4oG>i zh56ie`vUUD0`;RN*UyW_B0Ale_M_otQ9CJ=VLVRTJLm5gPz<OxAkm0Mz$bSz;@LG` z6MuD6Yj(cwz|Upm<m_(4&YTCJYtmu^`~ODqqa^U}DI;i`cjZIm4pBSES-G>fvAsCI zAR0E;$GUWI-io#_;=j(8l*d-wHuZDrfK1b9MF3b_S|2&MLM?Sr<c7=yqhE)E!hK)^ zsOfWFP6iK{ZjOOk0vUSzqBU5U;!|-A3Sjl3*OgLmiJcMxST;j)ah}Yi=!WU39Mh!r zhluMWCl8dB<Ku@Hh_!QoUZTXbI36?BjX&d)dsLd-;*y`8*)i>Lcf6&wX`#1V@>;}_ zfk5m?`yR%_*I6)3q}x_Pv|TY}g7l(m&DuTbVp)!DDr@Nn!k`seKuZbk9oGyKC4$@+ zs`K8%n=DTjnkN6?v|r1~7d8AN0=6z~v>uikC<nG~gg9fEKv&Q9IcF@-bw3!6z)PTW z-GcEvBYZ9s=GA;+T`t!Mpg%%z)AdD1lSs?WmIn=Yoao6Y3Ra%@UNG9jYMdQ-DFd?N z{Cc)1EZ1m=SvgyA*5Iq4>anlsx&x0)e2`%5ZRqN?#ojcD2)+PG(jrxdi={0L)1`U# z)NGYeJ=@2-Yc>W_@<WHPjFEO>QORCJ<L1`hpjXNEVF|YNGXCm(m?!M07r&Z1>fU)g zI@3I)(arMI;K*r>a78b<Hn_hy%h6HJ?r}!PpWb<^c<9mf4Ds@PUw_H;a&z>!8+eJO z6A%P4XAV0E$`_-1CPoq=4~L+SNuU#j+ng|}^3MqkV)ydcx($FFUah^Ahzw&G=!d?w zNd(f&P3^0}gJmRa<UhjQ<C%{8whN8^H8sQ2Zqd{Q^Cbn?2SKPNBSbW|=~F(La0vjI zd1V)&_7Z0ZzqJ`(ItCjxuY6S((W1g-d$6K{+(zLM>s3PLjj<xo1z;HAgS-z}U7+U) zd;z)o53f?|Y-`@_TVlLl%F`;qDAEdXYjo9q<N=UiY?bNo+1pg4>~}G1O_hpT*cH<I zs`Ww$!Fpx`6;oDM1$36nJ3DVhOjgBHu6KZx2(@n@^`xa54{>yfFE>c+zDA?i#?+24 z?00Y4o|spWVX1m{P$Pqr=z3w>7Kp*WiRB>_ADe}o__+nl@}u;&`DHH2_TTy)j@sR^ zh44D;>WtdLesW=a-~Q+DkcMGA!~SCglN$hM;0l>aZX$`JD-7KOY+dBGy9#@;&wd=? zd_43d7{8{&=c=$t#RN4%4?Nvi-&OMlem4Q5S`pfR&De+Yo$&mw#t6Fg<0n9cWqp|p zR)<HV5MqWDf2W#SaAv7$eV=6P#<l>T(<~<4JtN33vCj8Zygu}Zj&nm<fi{vVz`w_n z1k)G9BX9}$6O45NhR9(C5?;FgJ$i>>VhRK)voYzT0$e(>g^kThTfbp;PHClV+u&I~ zhx}r#GOe0{m6Gt!3mdKm)@y7)HoWEGJyWkHcjpebL3;076EyNwTP;(4Y4njG)l`Tm zAN+cO-pFE*oWC|>quf8M)aS6bs}v9Ji%abDcFnl}dQG1RA5A-Ka&{L;OCI)GFOV$` z5aTNBLSFDWlo^L%cJcRuTRlEM{^Fo!Wr=;htc_{)7W>&m(FAPTm0x%x@tHe+bOdtF zNpel;j^J+E^zF90<#0j<pb}#V+p2;bhns(6-sOrvDg)vl(hl2RPny|iZ3;vnHv{fi zSxn-AfqsdjLJ0cEk=9835U~E+v|ab6a`802@)F3#{oL&U<vgpvSm>CZkHt}A<FPnO z%yt-WbHIiLJ^V68U=fp;bb3y(w#+YeHl5;6jf*r4z@`rS-p*fp_Afiz78?wa5dZT# zS5G?1%Vh_@Q)16~*nYK#GZBHl;9C5t=U=(BThQ15Fv#_NhU>lNBLpTM6lNWXQELt0 zHWEW8B17k2BOxNA0CT5cm=}Q%U)w)|AcNyD$P7UnQ~k5R;84HP8*Nm1xj}oY!YukR zH|1RbKAR5@|F0ojjsk15p1_?xLx@~pkULP6gx-R5qF19Bx6ST%Sco7me4NMaWqThe z^dw9?`Cz+2cacz?Zr-XQd7_BpB1|qf@M$_=yRSjp_BU6fateI*kVZP^p>E)lF7B0# z_Prh^fV`1+t8#dJA)@qN+;fF8N%f6QWh)?l3->4f4p4#Lf72oi{|(l`LeKcWYLTU1 zbJsc>g3n3Kt(NYjlpL{o{E;Y4ER%KmA;gvByuKDuK#AT-q<MPi?|cs9F%;}jKA*?q zce%q_jjQXHkE?OLljXi?@rxP#i`&(NXd!=uY{pDB9uWnI5qNT>LCokZ%M^soZ;sDh zx7(}{5G$&0FPs^r4ngm;=Xo=BRdKvy`*gE872nnO4q-kdPNO0P31SMzeD{m@zb?bK zTj1bKVDoLX#3yhEc>9xqPm^sHUrYVVQjz2<l3(&zSF9M+5dB3<F!Y0nMOScr7#+~o z+91zRm&4*TtK_Wk@}>32Nu^ZL@4UU?$Vu=AZ9s2tS$ZPJV2+#Db`qQT*5jK@c$T#A zF_4ZxbOBJ-AWsncJk$e@fpw;ZLPJW2eKday)`L3UXD7HU2iU<)1VIsE3Y15is)FNE ztl>NK7mHWFs_$PYaVjeJ=mIeNdk`|v9NwuMC)-QGB{4r4vXOuJ#%-&2#QgsFY`8!< znb><5Y-vN`@9ViqZvgBRO?XVDAizabpw+Mv!NsVrp(9S*c(`Xo!{G~gFjD#^M1IAJ zacyr(X+vC*$X)w3fP|k%np)$Dx9KC{(Z=a%p|f6_=Rtmxdp2>5xx(fYeE2HjK6-`M z2VUtkjzn~@%vikphs)XV=`%Ot<?`Jvn#Fld`T4V@qxjcKQ&F7I_1`s*^g5|C<iYU~ z$ZUwHPvO*5{ewnqO946vt?p*eDKQ#tI-6ycio5{h_S}3LFykc56?FgRjpH?$&DTvh zOgSULSPVew8E6IM!ZiEJ+dCorb)poT#B6F$HXP9>!~sL#y1sqliyRv$1<V4H&id>B zXuqtJ9%v`~EObvUdgTSjjuk=qFUBibB9P}Mv(Y$*hpMxwwmpZnMo4h5$Y<PQ9<uMq zSR={DRFzswhmulXLjXoz*eU|{56c(i<?{2dOk~L&@{2?K>6Py}Ol{(7Xwr2KunWLQ zm}$&a$PD@rlhbJ;VA9UlQJn9R{L`dlf+y7_#ws;wI%ET4-ka))LMon~anrMQ?D+k5 z31iJMM4{HyBbhN90Ct>^!at!8?Ea@Y)zUYYA8ge!_d%4vdwXmuwK~U|p86KjbQV5h z<ePGaiP1_frIA#1?qt=QrPH&cC7iaDU_;reZ{=JM@Ls$&CYqZJn;&S<UC)45?u|jR zyz)`3p)j@+Z#E-{z89&`n%ZIMPtjFu{bg+Z`k$f<naiA#;wLMVlLVBFx)8c(4E-d) zsS0>A6d3V^H1(yDhJ~RNmIUK*e?QDA4D<~VMne5CjT{?1%qhCnZKibQNJ%_8YHtHA z!e6@!$z#R{G1P%e@8@}@6O(c?IW)!rYAp+yjUn{8VPY43lUU1SI2L+g^JHGW>t!Fu zcVB}i9e4mrVs}`n`Y%KNu!2b+&5t+pY9lDeT!6?>Rq7SK<Mx}!I=4c3_KGsQ&>YNF z<E-b8Bx5S7*F7b%HGxLC=($r00~g)QkPz-Pnu{qENBxIeUNhWC>;T}OPJu1E4p^1N zDQe5V+L`I3=%IGFfCfb^W)`Vy-S~b>eA4SYQrDE>N>L4z#G%ZVe{$BLCp*}}O(y8c z5$)#j<vDUnAk)9^O6M@%xX795A!ii|%FvJV=#MC8k`W0CTm-<XLAw`Gpb})?boN3N zbk;7kT-h3Pgu~SnH)@>Ejayj2!Gm)}_*xp}F)NMxY=$Bd<WUz%AE447bDO(%EG9}_ z#4A&qQA1@g`DOW#);@Ym=*FF%i)y0#I_l=Li7h%-M7O^6oSf`^ygcSfuTS`0-8}4h zIB=i!o#`>0XQo9|2d?$hIP+7PCz~B+j9*R-ebt(Oy6io;JwHym-T^&Mc&AL}cJ!B1 zuGh?Od{M;=@22xWsx|2Mp<zFq=03cZ@tr-p`XHz}JbXR4tQZ11NwS%Vc${l^Sl0Y} z_xE#rJAn~dk$UA~ZsA=mDoJZ(0Nds))3>6zPHpcAeBu)>RAKgr`n%py3-(6S9eE6R zG=2L#8_h+0JyreY()iI{JC?>ZMa(oyO2MgO!$2;hfR}Fx^C^O&(4o93HcnRl-H)L7 zm(r@)TOQC+^Z~%F==>3SE5`!6rBi)QSL&?vBKH-YtNVPjs|fw;4Oy|}{tf!8VeS4) zc>0gan2x~KzygYk3ySvt2T;Mz#sWqA|J3~1nE&_iwP8ctg6O@XdQ0!VS4(3Q*W2$$ zyGqOlgt6@{Mo1Nuc8zDMuW4x3<p1!(E<8o$l%_4u+6xvW@BE~HSF5Jn*=T$m3&gmT z%dTbuMZMQ!PGB$G)VmA{DKP~K+opo9WlhsK+u92i$y|UuVdRhGtn9C}NqoYW$lw%D zVC;~^XAzC;G&)YBEY=hx^{<%_1Xm|E^+2oS(!14|x_Y8ErEEj6haLSSsD;G6CkjYi zC1qA~iU&*tpSmp?o7g$4!D7mJ+c-Xi2P6nd1Wp_Xxx<*wn86h*vfpw0m(z62%dF?6 z4gNR3`fn}aR=p&pHu$~<>MtpP6V`<FJR4k5tjKdC%kUTmi%QjT#8l1P4p+mE|1S@? z1V2(+4M5zYH-Icu@m^3HLm^LJdF*Cqhg$25{X{IK*AX1D^bkp7>wOtk;iZoVBgL4r z8L4mw+_S{Pn;+|7;l*r?@`!$Xk%w8>M#b_;0jPOm7d&h_AC3aQU76!F_vEH?wV^$( ziEf(#4u-T`TY50q7)~gpTv7ByZ2N{MTS>JeMF(78*|p4L2+z23kDKLn&wg@6-3<G? zHH6-CbYl`vG>(G=51f#=47bZ(e5S@q8Mx&NCh;Mt6SEP#)2UWHk4|UsgKQ-MdT+CP z4~hf71i!%{Y6z4#kV$^SyxeFeBaX_TX{}x<iK4B3UgEmuA^_1Ao)6O6ScNKC#Z5m2 z5))CMFGPj!_r*@Can#ttghAlfLk#cF=k;MlO>`jj&_8mL{8PkFW4e2i=fMsOC*V&H zS07BBE~ttXyx5S`t0|p`w}i`_)t#|DNL-5w@WL4c!_AM9!<+eU$Z3T`K3{>*iW^#& zg^VMH%#fv*oi4bFmI>RGJ>-;@pAYB0h^Lr|v2)E^jcHn5x2DqVZ=<Jyd;OO?0}UQ6 z<=E<v5r!UJ--ZwBOpg??<k8f)auiF?(C=k*IwY7nkKmv8PcQI-5>@5}^QZJS^lC4c z2w7W)dXEQt$F-cF@9)o&geBIF2=}(ru431Up6c)B_vgg-K;$esAs|e1o&zMvI2y{j zP=q4#BA^#%*UyaF_lfH(8oljrrYoN}V^<%QAIIipX#phKB5G`<$Yv_L`^N0^No388 zg`BOt8G%Ip#@}o(GYCOgGgjAZiblRkM~qn<tisfMrfCyt!!I=YfkZgPpnpab#ZvBZ zUF)AvjiFj^KFc8{5O&47w@|{V#+pfnvwG073cKxbbJc^3p>WGe_%lxb{X0dd#6_DT z@{q}uSid&-4f0f^fk78|=ZvQkuipraX+<gG6CRy}-D7+L@<=|5iH2pg-8{FR!64mu zCR2pYOsJG(@C}%DC{=V3OncyxLDe&m9@X%iSuEops;CRc0Lv>IAFn+;>gg8A&YF#G zDIM;&Wq^#blBBy~*9kXCc*=veC;4qV)dFzhGw0jB7Etkj-h&uwj>LGNjuA?teL?BP zhO7JPtPsM};+TVIvR|IHA97S0^eng_4MIBxyu270kExBY0g_S7umN?bk%{2u5XrA1 z3}7Kkr{I<JwYl@iQAOWROkG*CtP}lHkKYP$t=%i0UgsOXb#7VNulv|VT35j;heVDr z>JaTs3^dQUFlQ%($fY#r*?OaBcRQzmBV8v1sU~6EC+xIm*nPw00&LMx&5?gIA$x|v zGcyCOz%|^=x1Yp3IBu-HIY97PbL1F5Una&7mC1Gbb^LaH*T-t7xWLe8<d+vCy{lOx z$>8kB0qJ1s2m$H;z7PdycObcYHryOe&jbZzZ?eTPc7+0WmF#Nc>FHKQxSNf6p`IIx z&oI>FJ(1z(XQk@I@PMI@)I`k11PGTIz>0xvM{`-l_M$ezUq2$xU5LxC&g8Z6k(Qop zqO3q{;SKB?jT-3fM6Blx$*v0YP{^j;VJcyMMhQ%dP(;=Bs(R@?QK(XJaSK0V4Np^C za^PEeJDX*_ohBXHup264{;gTQg!-^=*1&$*xY3UC&j!ZA3$R1DAe{4?dHOH#v#FW* zEJKUqn18NkVwX$b*B~w$YAQsujn7>)z^9<&mrR&<X=P?fcRXBu;PdKK((c?$&rB!( z^fS-6wYlnrcEzbZ&CtkyLBk#wCW*#za(*~-e>HNEiPNaj{&J;=@DUdStQm{5NJg|? z8CheeD|h&8O6s#OOa_`K9oHqs${j5qxMUN?7`g!D^ILy{P&9wGgUczec=EZLn47LD zFPsfznzx&c*5ne3PK)Orkc&*dTyV(Hq<o)gJ>_{kOFqKQLU>KL4`CgQ<qz8Bvd>wT zrnKyY);a;^%IA7&ui%e^v}Mgb@MprC8J8*-Jhsmp7t6w#WjJh&w3idQ0A{pmiPL>0 zBfqB-B*LBWr`&BC8X06E6KG!-+|_9l&P)Q0x9_26m7<eA2N;iY-qrc4wnrHEP8l{d z(oV_=ve=S3%akq{OdGBk?+0CwHU)~l%lsP%s00lQe-faMe*kqX^fCWSIA{59UD)*O zEdR4bZ%acnA%g|QXXig%*tb%Zez722HVa!$jBSnBtlnY_cxaZ^STHoZg&S$#FWG@0 zU@$B)SuAG*)xk8PCtfF%{>D_W6K)=NUzhuLO$V5Gcfod%Yh8O9gUJ1M-V#C9lW4=5 z35Yyt3M-69gU83BX((?8bkf`EXxi~fSnbgUWg0E_J_ee_lSWA6V;^gbf$VsD+2Gj8 zhgKWI*AW$KLpSIwj~XG`wioV$1(Ogf=(anW!$8B?m}vH1Gp|b1TG)}CL5$$*b$9Rk zC(x1+28iQz;k-$D)%u!)N8M%;q*eyX`P#M#wPEwbwCv^LXFDS+jgV2)VHa(~i3<H? zq_@!u+ZvXgSq?Olouj0Re3sZ~9vDTF$r_s*4ut)vU<?_mW;PAs)){~fOex4C47@Vr ztbn)6Xt+^paNucIP}{$n_a9YzhTOy^ngh>B6RvoxsMSV|N@qiBu<yegDTMtR_$L|q z1N-Cp>q@en#RnXqRS65p<O{gpX%a>re|QcPNONMZYExzN+d>e(ZD7hioB8=|LE+1p z&agceSn%aJLfIcuc?C8nAF)t4M$K{$B!GYNce8nBJU}mc(U2h4_NfG{FHS$N>n<?- zUg%8l?}m#c*+*9>qg31z7L!Q3&W-7eSM-4t1p#tOh0<QrOM@$CEYQaIFM3s|I7fnU zJqlbV0IdlIcCU+u)OwbWVO5JVz~@k*d39wN`aGi4#wcmtitdyV-_n%vX0(BmzQZ9` z(oB)C(oLOBrweipaL$dRcwxrZ@`!+a>W#^Ku3c-6Y^#SkfUBZ)M`9m(YFH4qI0!HS zi~xUD{}9;CQ}977Z^f@YPRbF;Qj_E1?&iP_&-wmEf@HRDv?SMV+1jf;@;spKF(QmY z8(Cl@0Bf_9qp11OyzpgOkNZ;(e`^lcF$-CDNF#kfZw8b)aKC+MOG@K3++@-nEysWa zPV)*e(XT$@R;7PhX7FliOw#*>fFb5&MTZ#uF@(IM&XvVJ4dG2k{u~|dm_VR;wBV;= zSHn2+VuR>G-rez-Nr|W{MRMw-38A`;IUbFEW`I30F+`Z){!Kj${b$&SFw;45Wd#fN z_WloF(5)x{5Qt14i2DU8F}lE*JnBKeb6Jn?8}VXHw0m><yVh`3r*c%4@t=m8x#<xO zZfs?Hdf&*b7_gAH6EHCHYh~TcC^>ejO(ykk{B^Fy90bmP@}N)RE<e;@&&V+t0Gr_~ zKRdY0%>~m~8Nib)m(|W48(r&JDyj`|M3Zx>4Ys5Rk^xju*QC{$6Aij|(GWWv_OM0k z-X<WRCRBSJqcC**-rzyNd0taeJ7r!iaoqv%k2)-@V<2?;$IgjI?=le1_=D~m0u|GS z3^2`YIvLxnR`p!k6!-q^Gv9n1s&iMd3JqNSz#@C9n&1X(2z@h<h8tKfb6h322j0Lz zJFYRbR4%Ecpd6moOj4TA$*=IilXHI4;G>W)NPZ$O7W<5~tHBM^NuiE1+&Ry9rI^C> z!p*v)C=W?6Xr3x`W}H(+yw6o!m<?+ZD#LX;s?7^N>T?Y(=L?;V7bs3$58cKW9r7Hv z`PQ*omg2TqUuduQL2o_;XD~$4oMNuc3WyX7`hX#LxyphbY~ma|{^fN^M3{RZ^#HN8 zllVr6LUn_FvfOUt161ouE8T+U0T!VQgsrXwy=*ia?wZxvH*qg0g0P{R3Z>J*gG1tt znrOt(OKSXoqvMNow0oMBDP-8-2++*eaRUcwU`+TEPa);!*L+%bwA+^?p%(etTr!N; z8OHak<*7rx_Zg^;ua|7aL9n5Rlu#t5>Y<nKz5=ndK#!8-De!pU<6#{>QFGt!5%-nr zA?k%6$&iGn^le4GF3-cDpD>XZBOl2Re^3H)j!C8>%(J)Ab7D<m$9UQTje!<&y@Dy! zF5jx>QBv*2QGM%%<*L$oc=U?X1j5Trla4}S%nSomuWb1I&38{3)Gn%wkP^kk)_~zA z2z=$L1o(^lWx1<e>?aW>&D8A`D(js(w9ddGeqha&;ummiBY-HF?Pptba<`c=!j-$x zB$OrBqKt3S@`Rf(ELxe~k3X6H5}7zq!CxDpSg_L&ya0zLbybf_(5i~$atiNMGU&Mq zI-?++QnnnJ<*<XYlV0vBPej~vAcZi#{-o9v&`CPZ+SQLL%MPqkNuglV?RJn4tL_`G zl$5HKsUVD$#{ofm@T<PfDsx#G=}?4Pmh}5elMaxp3d3-Tr2GGC^3X}Aro8uy<e+36 z2qh4i7(KO%c!k@+Eyb-k>AXZrS=y0WRkTnB7_?Ucl%uDZG*&vY2eCc3i-Cw~qNh^f zSN0}Hg#q{CZcPkd<mW#h*J9UsGdW?!T;5W4p(z*2$Kli%75U>yr>pi+7I3a~M+m`4 zoS@Q{kJ&Pj&9s@%4DR_>U^>%hrC_6eQgY+u5o-}amZIA7Kvtupv%~du^z7jB3#k7z zaRIIRU7a|YIZ>tcl|%l)O6YOIbX8QkEmp?FDM>Q99i@>kcL7{@!9{ir7nObcSN4to zZEFN#=~X?*hA0r4QBwMqb$mf^M7V3l;>$&aNM-FT4fg}qtLG~EUqU}C<Ny05|9`*K znb}zX*O&U0y5?^eF^bPhP3}S(oK(LFZEbGhRiwp4G}4HSF$t}>NMKQtG`0U<g7A`r zpX~;81cE~~A2WOdUbTs}hLiiOh7NqBW*TZM+?Vgv$86lXSt$7&M-yo@6+ijWHq=Lo z{lWCfDtMMZi*HQs#`LL%c%i`(UMRG|2lE7t@C)j7NaA=$_UU3v+jjFG9in{5nuQFQ zA>@VG%$iR;Uj55B$2#hIb@&>(iO1vjULjsFeQxGiFW;B?$fP2RDS~hEV7N{oQ;_|} zi+J~l!i)C5rMYi+n%_xE$e8r7SAl(YT-<D&+*r6h*zlwU4GU*x3_){iZX9gvY1y)1 z2V<g_hG|m`L^`e_+#y`NRQhHb?wo9H+?l7!Q3!va4uf^tpsbLCmC_6<U}%78y<;?J zo)8VSYCLZ2tVAaSxNIx8dQk+_MnglJgep9+BtLL8ah`zffS>CaaO}!qY3H2>@}K&S z{L+O8WE@0F+6q7##46$EjSzLwES0b1Y4l<PYQ^+Qn|v1VUxSDJYts!S0J@NZ2YY`( zl_dQ5PkFO801Q>Gye&QHC`L15pG$gLBt%g#yn-3sQ6?*dz7+XwYWNXaV=@s-!Djlq zAz^nu+;HI|wD-EIbH?IZJFdfeJBypmy((9;!Dx^W_g}j<oos?25>@-eFTj^$$V+}u zDZVa2n{Y!nM3L%5i5lQGH8#TL$veu*%Hh>Kn`zT_6o-9^&0BDnEzoOM8muB~NVv@B zl^=@EZ2R8tO)56)t53CLkjJ-cqW-3lV@+`W-tZT=D-T?p&SAE`E~U26MB&Mj+^I$3 zTqiWR2IwY9TnS5=b{H%Z@mve_tCPa-z#fZvtKG>zLeV&^k73+s?5hE*mxGn#H9_{O zl`Bxb)|S;;Ue@U><1he5{`?|CYS6WD2hS`3jH5RXQ+sD=foY4Lkwm=2MbR6eH7CeI z0RZiBx!pGzz@3$l&^Rfe*&*Zsk$^{R?Xha38PTA>*q25LA5TMKhctFVR<wMhYE$KF z1qDEoq9}n=cSse(KJGpSY`vdd>6vB!)jb<Ek$>gFfcuL(-e24+jRf=f9QnpvD>1I_ zZWnF@<t@27jtRr(sV{Y~++(?AaQVdIQ<uSce@bp-WMa3QV7q7A!~Xyd>kn5vfHd>U zy797M;>v`Uglar#UU1kt;n{2-Oi@!C=1?z87RCX_C<uF-(QFGkwk16EF6Sk3hdtGP zG~nGLl>*<!J#p1%dp2Z?&Oh|T<JGfXm<L?iyX6tOrep*|gf?c&blR0)y)RsYT~2!> zcB!f=h_>$xXcx=l8R3#=Ot&A%QC?(_x@V%~;|@S)Ew_Z;2@bD+#?qUVjNPlum<Isn zuQyR0HC$P$Uo@!~D5+QlQ!JA!H>(xMu2;&JW3D(e3}RKvQzjKxu-y;{{4gt45^Whp zrQQ(htRm3L(f_t<Y*Zo!r8Doxg9I1>qi{8<6OmKa7VcG~Z*{2~61ml2a;5aS+6ia< zGoaz6vwZAGTh3@0a3vc!+r72p@@8c7ttxu`tK!=?hbMLSNvSjHr=GhZ2&W?NLM@6a z7CibmDbO62pLm;_E^t=zAmFY1n|pinqOO<1LqI~7^HrPzTdGuuijwzs8I{lFrP<fQ zbc2e)YiVFh``vzsx;jUyNgfM&agYh&+iy7sX?6{6+iwc-CGAoVZh7^{4uXTdu}yBU zgM<qMLmb*?bLb7wj`Ac>L%xubQ=ON2<=)8LuN9;B^TnEpMqDiQu=TgO3ze+qnL8F^ z<Cy>}@YWRHU&$Q4>>TN4^zK$g_^nA0BL1D1QnbNg$(el53U3me_MNjK2OczN?dHur z)i>YS-W}Q(SA|*x2APM>;OgBpCT;Gxm99o&h<_S8-HxW{w{GE3r<KUB4N}RqHnKr) zgfkt!SRji9d>z{im-mSIQs15N!KKkRxLUm55`4lSti4}&>>)O(mzq{e4cr$_<I`C# zjFcSmo#QH!BkxPSK30^$0V0}axm9DDE>ci=`S_w<UbTxp*T7|R{5=1$zRAh5g>&KC z+c5B;g%fx8YxVs@-AwLzB_DV3q?mv=ZxsAQN0FKTuReCh|930#|4%xZ{&x!N|C3K< zU}yfHSr=298_~bRqr7)&PDc)d1?$U42?;Q6K_!5Q{q#Qi!U?F}`<p>GI)*J!*?e;p zGmnJ+Sxb*xM}i}$Fypu^of&A0%lw++d`2lk{t(j>!l6VUy6?t^h~a?m(HX@tgf+)8 z5ktLd?8nweLHrKc%U1XlXC)ZV?GqV=r;K8RAIhMb61?3kL@Epcfx;J@HbRL_e5M8& z*^T<MfMD3{4r(|F12`!t^=G|>VX%@Ey4PTDm=+!-Al!HengUxH%zz%#Px84qx1X;q zwNU^VwT^W}(?0AODRolM%#e$&<T(h&$`+myw(=^f@T{D>A`paOvY7gQZE-KJH-smc zABKjUTsg2yG@t(;R{5YHlmSC6Qg}KKveFc+?zo_YbR0k;6IOYlAY~CZ;GP^wY2=vD zv(T_84Jd;Hm&|a3UanDTu9Y7vO<J8&8~5Kpq%}`~YKaB!>A-b-IgV16tK)zot951G z#N1~*H9rCA4lHoBkh=j()C?e~h#IR*<=Xdd3K8g0J1y19o|vmVq(~`iCjUYck)g<t zL6su2h8z|PoK-qwTO17dKqfc=YbGp6t6F)mGy_J}gV{%5=D?tHx^%3yM6qH1E^)<y zTm!ESGjl>9kWe$*xIO+qv0cG!0Fl#ZYy<5;iQ^*u<ALe^CY4y(4BUqh+`GX`Vqsy0 zZ(zhajQ^NS05GrgV`I^pAW7+n;1hs!xJ2AI2PQ=RMHzhYC$m^M61B)@AT&j-8`j2V zn9kV1>3&~?a^UcEcXar6vU}aRcv$89yuV*>WDJnKz)O0&nFIFsaD2YqrVNzO3Vzr* zzIIN>3`nx&GVaXpVn7ES+0$(yWvNcSxw$=Cv3b$sd^`Odec8QQy$*Q!wse2LtMs(t zrcits=L@*22Uaq62AOLu(iZkNecQjD7GVD}jtK$*h#%AI6*1UuIqHv;M&f<Zjx$C= zTOJO$mP0o-hz?ue4-PIqIyN@mXFOiqJU<55d^Pc31~Bp%1BAKs4*??48hkJhILm|j zEyA3|ACx53MpetqL!_5+EaZP^CTBuYAUc5da^OR2zQ5rI;Y;X<pZZW+pSCt`x;>vF z5*ln1^uMPE5?Q6uluZF0HjM04f@Y)>(sCOc5gA48lUrG&MPQsD>^4Y8h-Fv>LPj_# zf0*CizP1cCcTU_K$L*G$R~>`Q>oeUxgXH>yAV*|J!NOR|eD6nj&vST$4+Os0g_ylu z4<Y?S(cxbn&{0`fadf<%z1Y0eeZ6pWx@?DOhifjT_7rymntJNQwhq&qy4!p|=vG*g zqYZs4CNAz0KJY_Lb`=KI%T<OY&{D4>?f|8zP!{Zc9^zPIckX-oEY5zyA+o}<P94Y1 zgE;?WiDivu&B`Q_3A96;5lWm;Wi@1q{O7YUB9`X=T>HfowTCUTmrS!ePnS8$WI3K^ zPMFL5XK_>bkcQ9|v50X}Tjkp8{;Y!Lud8}n#He<V3*x%48G2q;gUhtX;ipB394=Hp z0T4_$GS#2^0>cUcwl=;VN|hV*0_YAaXF1}~Oz0EALWa^qIiX9;0$)Q)z}kMYOrtn( z<9U%xbrl`-^pwt1B<J7Bq3o1-@)47NZ$cBeZ`H4S2gk@ssDOPiPF{8l^<ho#oz;h( zaZPy}ZZ+=58+284gD53BaP84{Bgnj=?jb%JQOVu_3fX7u8rN0`BJjT=k8*^(p4)re z!IU^vo`6jG0Qi#aZl5pu!qd?_gxFOU!<kdX!mYL<X#u>1oec|j8TK{7B~*NEfy3=` z46;^mlIdu|^b`b)4jpQYlbS9sgsbp<f!rBptodlslYvZAI+a^5f#Nw~rt{GG$)G!; zyx`0t9VZu*ib<%(YLHc93gsNL&~hrMJ^)E#fWVXm!N<2bHwsoE9s|5#3&eztM4R?1 zB?y^dPmut*@^{2dt(|Br#~X5ERGX7i7d?h5%cLk4ak;YtI2Ms`OPE>zoK&&VmdKen ztg)zO`?=_@Lp(ZkKcbw=ZvfGzLsdjuJ&?O6ZmS;N2T2SL@KJQgg{XBtl&Z)V0)MYb z7!gN1iuufEQsd91lOB@7p!O8!da~>s4l>LmlI7`Bi-}>|>&){YrV%@5T17FZFT(G6 zJqTv$#_TZX{;j{HYFO1->U>ow!Dy9nj@E#lt3T-{T1GbTHZt9Cm;V=m1~}>=$WbA$ z(vw^}&2zU(si3<oZl?aJRa%Iv$|Fpi=LPhSJd7uh6}U^UGG@9UP3n)q*#QFbJf{|K zp4<4Fl>*k%%I`R01*UqPWDe6MCjKh-xXy$55i1rA8NRBo+NjtlKH5{ME;|n(52)u2 zKOKgDXr>>V`F4&1vYB(Ca?OIkOj3K5BG9yP$*pqHim7hGtSuU8F-tisbT@5}Yrm}K zT#(#m_D<B(p_FdmE6E<j(<4h0@nZ4cIV+I7d<C<W#SLjbnZsckG}V(8l<hBS$C=A= zZu>YV<|9z>UG{X?-ax<p^g`<s8z7G{HVJZZx%F^S+t6&9um`|tqYn5ps}7Xn@ZrO+ zMx!dcvqZGrET{{uV)gNCtSGWroce}=>?i`-Q!%J35_Ujt_IZ|E<i0@C<Hku!d;Phz zVgicda4S>$mjHE$B;2(+4RcYX0HAbWZTRVgfsw<oSZ-@*!c~3-$}>9_iX<e#BNAzb zWb-P*rpbp<dYX&K8<)*aqQ9}*fa8Z*xy?JjTMQ1K&!`v^Aw2B2EfXxW?$OkfV+uLo zlS74<GD%I2wJ$7LVIE^x`Mw(N<}$MdxC!BWBV?L17v0HY(1|nkhEG<eN4|g<BB!2s zF{h3g*K(R97plVej^hVEb6bYx3ZaLS8;Yl!FqJ<a`QrFrLq23vIN0E)f|j^x#?1H< zIyEEX2iC9{GB_Q~+BFOn$z>aL2=Sre$QTa?XVQAuLp_{r23%%B11CD7FrI|j?zGx- zLtS<Wq}}c&-5sVM(VxjGMO?{yV<`O@?NCG0MSlUr>Fawd5RWlyaLu<Lv&0P^nN=v1 zGKi>9c=PE6t~(?HF$#0FWA+EFmrWNw5GWOIk(<N^1SLSarbD6Z8uBS#KoU+30iu9; z%siCdDtbr<;W~<S3Lq;+k`quqMuReA`BWg`w(g>q2y7nxGesAmO!8Z~^2`DEzO1?u zU>gCXdoh_g6f4hY7uuksOUM_`l^7e_o-!hkYm5XcQLIcjc$(`3AB63WP^Jcx)L?k7 zq`H2r1__9YeA97^+^;9Il(x%tg&uN*h}=7vo(E|_K}8s8QE)~jCMSG>7aO>I=OuGW zcP#mF$7vpU4ane5^m2Y5haAa=AG@53t+A31t<!_g<*@*$qS@v#Divz0!%4FlgYEIP z0j0bJ=>+it+-2KLs{PCNx#lr>?c*rg)oCu{gF|w1BZY02HJ43P>#63kJ{z6e>;zyF z&kkZAuTxbmThE_)4KwtbkEiC{E5+|LXzLr@h>xa~4TMG?hc4=bpQ@FON=Mt4LWjq! z|HPGC89TB<<TB(o<n{3SlctJQIHap$;D7EPfPDT$>m)9VpOZ(MTZq|S`%1|7r0x_= z`^+cy%R|$b^6{6yr8t5km$R*FTx2g0<_2w>m+k4x8ZzFsJ|ud-a%Crgbh&>54P`>9 zvTfP>+w;M=Lj~Q?h{5C%-j4)eny3F<up&t2nR4BPQtNX3R(UW1TSylFwnr~;hePiD zxfn~paHjY%fWGJSKoYe8=pb9mvPi^SIT6P}a06`hM3Qg;II(;n78z}<+~OY7bKI+V zAg-5-NnGb1vzvI^kWP6ZzBo1byVa_Ve#r-!r|Y!B38FH!YU}w+4ZD%%dC3TSAuWjH z*NY-2x-7HK1pN`^U~N;?1A?TtJ;dn@ev3*SD|tRhT)6ZFzQqQL{;&C`{{jG}XJY!F zog!1}YrjnwD8EjTTH8aZAU*Kc)FGD)ag7y~k_B-tJdq%48ES>1!q)E(9jZbx>$pR< zvj|87c30lc0DC9wy;G}O4<<MFai>CgN|Fc>*0_E#NzAfDLh*cgJnu+$q_J2^+>D^G z*9eM}hLnTy&mj6PVOO8C##UAzCw&{F07JzL2dnssxsEW#sGwzn**?Vn%g0?KrdLxw zJv7lm)C%VLMA3t>-2>EU2Q^Q0{Xqp>?$)e?u>Ul)(sjqsfcL=L(SiQ<HO%s04J?8U z5c9VhVj6^z3I@<epTsC81U?H&ICEvJMBHssw(k>2|Gw_%O)}Ho+wF(*r;mk|by|Gd zvrP_y_Frw0V<BP``10oo5#i*@ta1SYtYb?Mz#=&Iw;zkL)c8*z2kd24E>coT8lhPW zBMF8vVA$dXJU8V9cF9+74BZU(%GZ0OD)KWkZW(Gm9nI@un-vSk5ZT^I@(972fcWGl zzv=a9W{%VF{R{ej2*GS=El$`EpKgX0Koj%|h0eV~3;rC4vA%Ec-6ISy2(!bz^Wp5M z91MXd-BG&WHt_e(OSj(OhsKD-(lwYF_M%hi_&Gj4ZT46}&!naKmfjC_xhIiPPFpf& ztO27K(A<WkDkc+-pRVLz%Z^uXgD@ttoUC)f5Gu)n#H&#|%EtPIbYT9Ir_^BPK|Au6 zPp^PA)8b!a`OvZA!>Ugtg1N>)0!k$$@Q~HHlKNG=rEdr^i}+lY_hvq(aN?t~sby(7 zIjw%L_Q@ZqmlEANHVB$Y{3#DX_iPmn;dROaVq6z#4dKVcdtzfwtW)M<fZOw0-~&jh zVZ_Za)GqqHHaAxAdu;OaHqCr!X1hS)B>AaK>I+r7%*CWY`+ZM!_nvhm0)NDXb$xb0 zOZZ)M55J$LJiKI8%t&t&dl7{6!0~#<#_ORfas*3#zYe}U8*P$ubC(cVszT8SUTwl~ z^Rx~0^5Oc}ZvT>_1e3kM_0aWp8uMDVpb&u`<f4R&q=sT`Yq*V|uhND2-xL&=PxLw^ z`4>6BOqLetQMk(6^~i0lS${%n5h>WC`~XeKx03-|_C4$C)zbneY@t*t6gs{C{2!FP zV~{A%y5-%rZFldsZQHhO+tzN|w(Z_+d$(=do<8@^ecux?|Cl)QsVeGIMn+X;J^B3B zTKPK`M{aNaZ5^L*2NNEVO?z@gdebP151ICK$Fs2p9th8PzkG=wp9a7A&v;gf9@~Hd z^W=zhp#{i&ME4HW`;_0R2EC*;Y)Z9TB-;@-O%|Z(-WhFcpAW66o*iExM_=Q+YqwH8 zIncM8UN>dBag_I)@^w9^AJ5DRw(#dcl%^Caa+W}p)<-US=vFer%M)hXahE{wDg20$ zpAWwI$#^$P9%q4qSxzamtr^IDrpYkGAq<9kiP8C*(XTc|Z<=-0N3vDbuZfNn7#Qqr z6XM*@*z7KYF@**2)*+dC?0!`pxOGLzV~MM9HzQs(FbtHN8FA@9I3XUX)(mX4?7Um_ zgPee;LG2walMS`in1anyz(X<~NRQM4+nd(T;#~-;W{R3GMber2KI}NzV(B(^XePbN z;hoh6+vBJ~_cBih>MQv_HRGeVnluO7@!Nf%?r(Vfo%0*<_^Oc~a??nE-}bI}Wgl~A zW!Wd{d~STgW_~*y7&|;!47)$)qtne^$Lwu!bt4b*aIH^!J+7vZDPv50FAw8VVqMR) zaa(n^lsq0p_br)oV9-*LcSNUSTLvq&GI`PG+dwt)+NPOryExH&FOOL+AM86%2~Lls z`+b|4RnI#>y}Z~O@IX5amfxi*_;YONReD}4>&L2LYdPBLI&*T@nitf~Q&ZIp-;$7t zWr@7Hn0(Jf9{+qLoZT{kt*4&bcGH<{nuGex^u2d2rzW)hL{N?H!Z$Rh#s#=b`Q*>_ zeYA~+B=F+i+KnbIx%!usL^6@&=CYC3`(eK|ndNzVL`y1vXG8_|8yK1hCGek?eP*VA z0|@`8?ZC>y@t?LGHZ}fRYxiHvesstl+)cepVpF<o;;^h9l3ZwtekO8+v;=3(cMmjB zk;i>V64U8JADReYCv;Y0CpZZlEig`(=BIbZ+b!urfM|UZHG4M%im2u|{}74<QkHEH zJRu=BCzlT{{mYMW0rL4e-9mQ6lJe<Is<%@&n?|y-Mb2t|C3<OPuNsKxo_`ZrvuMVh zexsfb`#>L>uNSWWkUBWq<EYOcP@zDkwk^<Km3(R|VG)R^PxHRa0+kVYq#!iG(APG? z9%(3JTgoNj5Rem`4Z{b<!GXjD_;B*X<L=n{BOn6mk^DdYal)_uus<vwi~%R|qb12@ zRj7O@vyr|O0N7ue5n-4xJz`41m6KaMWC4U@&vL)DVgN)a3Cg!GWN;T;fd;A8t8<4O zpTRU;-2u4$y5VmTY-651sT@-@fB+$sYRuzZhXj-M@5c?Mli26p@0j6AB$NWpx)O$l zEP&?&LGx>Cd(J34r&lTRg7N$3?DCqZD!H{ICjg9Mhy+s^=KhVDnwt4}8=F}69|hkR zZ{cydm_e>>WEXQL_kEq}=~j|T!#5HGBB%D76vklh6C!{-7EvYfjyS<f)DnmhPD%^A zwLgGx7(c`qpURUIjxCbXM*S!g1d)$P#R3`B*ydoYx<2+~p0UDkoU)8Y$4p)(d8YyL zB;xX=G%_OMTD};v>=KMr5q+4AtF+hbs#fRe7+C@Phc%fFQzV3y)oE(q%GQ-)2)XH$ z{0hh(>>fd=0ROos4FakSn2&g)PDXkoq?I<H=u}%Fq!f+;Zfhuxy%`S{+(~PRd`mIF z2Su1%EFS=bab$qB+OUrJ6$U!IxP@Ig?{N%({iHvIt$SErF(@P@<Onx6!&XCabL=dc zwZkdX^Jb+AtfH`>Qd7vO&7hY31)tKVWkNLt!Jg~n=@_<~20#mStE?UMXU3-8bAc#G z*Rq3krf6FYHrZ8T@l}kAug=QhamY+h*Nuw3RRziB>xcDl$EA|ndMg2+4FS?n60PlT zL5fj(7kN7rMS_ae#s^VC0qIe9RXgnyzXrCa55JKuc0U;-^FENJ4|;P@P|u+-0VzY_ zh#wslL4zKKP7bgCWdlG-{Uz9J$+nPv43#AQj>CMbX|J?&5GQyDfmGv!>5Vay-emf! z7t0Y$n*0R;hlvcmXit6?k~~%TJop&Jmomp<`SiBD>{vinLDGu8d)m(tF}rgv(JM_9 zMo9f&a#<0h?GsN%<RDJKl`csIKMcYhiGoP}-QcZ}EFP-TtXDv_e%Z1u{<881UsX8- zseG`ro)Ta<%JySAmM~dyC7E=Ey^{`#i&woHIMKuwXY0M)=E}UXijLt0yoE|f=N3CT z*#x;)>5<DNsT<pwV9JH$HTPJ{m7x`Dh=in_5{tqZeIx3<r=KlV{%4NfgLm<Igu9g6 z_4tK1hAK3x)n#PmnCPz5ex|kCx#G=msD2b(-EE`XYGzYMhWJ?nMMuQUanYRF7~E28 zH?H$LeojsAsNv^OlW25ePzJLS5+Y5mh#vzgF(|Hn%$MfRyo)`5_=$b8{A=Em`RjS5 zHJMKJJ>Wh;$3od7j!$bt0HuxAVR!t>dXKIb)0p%H8wNnqng!C+NdM%Jb)})|)}KM4 zvmnvdX?XNFsXa%g+|`Dkla-!!%lU_c;m3hNFGeO1H#3rA>MPt)L<VrHFvN|J1m%!o zS`!i`Jdh6DCf|b8Mx^V)P;_G+FM=$8UO38I<i1=85K8Y4b;nYM-f$PhK#?TtOYupa z7bXC&{;gVSo%}R*xoH26$+mk+7;Xy$EgusQnOw`u>+ap8NMH;UAJ_txi<kA&&Ge;h zIl*<oN?usrGys?pFcafZU^lSQt|JAfXZ6mQLiN~)nfm-)U9W#!x=Fj;=2V7K(@+aa z{PYM=m`fJL!jB}yO1U%w>3rMN@tfIJ(t?f~5J;-|n5j<gpy-nYnPE@;X(qlpGZ6=A z9IyVjjp;%TeVz<w&Xoovj`!kbTZQ+1^Lw60h2Dz4=rzC<AI}|z@#)UP%BsCr+HDo1 zs|1^qrvOKBmN%xycHL6}eTk3$m8R?!FLdK7>8bBZ*psQ<5N6}CQXJHjQv!IdMBxvn z`_0+zu}*`ilCZo^Nx%jIe~~Fmk%^9;4mgjcC!I;$=rw2ayqmi|kpV!49r{8CQEc;1 zagA)u|K7g%|2DJ#hcw3jEgb)$-QzPN5H<jLTiRuqBr=Du68BHZk!*epgJXn;#<tA_ z{F&+UND>?u(4&YVhG?e^XEa9H+hFZ)Oz++g4_>WGfPWKFXxMuolSelt1w@i3khE!o zsS%19au!O4-6n<KXl0pp9!JT%K^l2RU0oC|k5RU$;qPZs^ci&hUJ&8#?(xR9FNvSU zBAc8-B$~V&tDG2Hh79OrCpc`<B$n~0Q<tl$ai|M6vjdJ+FA56#m~#2=9ZnY%J+b%K zN=P6g>e0M6N&tnNJ`xaef5)AHqzC)<^s)n*U1@M|=SE|H(Xvn<;#?T+-*84<PIU$W zgcKtAEFu_PygEQTWR!r+C1JeZMaky+*+hMPNdReOzsYhKaeOls5rKs1j-KyD5<bo8 zSbp46Yr;ANDpv)A1rs7W@K>{?LLNW78d%5b^wzP<KkqQnxW0SZDUd4nUZ=Mvu8`b7 z1EeY7deitEOs{!JDwDfA)~iy=aEtSH4*fCK{hfd)C`JfniAhj#L)=La!kX2h1wyUh z_s}yxm#*62y23biM>@|$BA$6=dagDf@#!v)S$npJx$NmA?4b2GsX8}yk6RrqS@GeH zS4-m2bvR~!yIo_fy9Ytmtgv@Q2wvDHvq!S^)eU9@@?nUqpjKHwr-pbzFQ(c^^Z2s+ zztFRNgfDN96KG$w${%m$OeVN=O&pzjfg4Vv(b!$KP4P}eQpWW%>7k}O86|X#27h7B zaviyX`9lg81YpXq#GTmVvC2FgFqESrDQa-@4zK!VE{#>bSno(s0NrIF{-!^6edq!c zYG~5aV-MZ#>`u3yR}(3Jr9ZT<)JeWRI&GK*1P%22y1&ZqOzg1i-Ru_%5P~-3*%57G zI;Q*UAmdUlh9EZQEJ{C2Xsn$=9bFunfJiTVC+I?bbo<0Wf*vEG!zIt+nq&I5B2I;e zMpoH7xSGk{_+*+iaf6JuvX8V|cR|f*o1Q#@%>{4bqmo1chh^WCo|V~27sh=r3~KWG zj<Jkn3gdIxEE5W(N~0^)lNysnjXR7#f+;WvLKm=P@<(k*`CFUxlu}~fDwd`OKuxjh zWzr~;_@fNBmU?ZuS=!F{WipAnnxhH{y!<%fNG858wz)EU2am<jZYnd#4*5CoGoxt2 z`>&f?e@mu|k^e|pZ2|5E42Gdno>@WPnTq%dx8!dkHbCqsCDxb?2xDS~7Lxv=oSvFI z=Z3XEuiaIu+27tKH@=An7b&T2nETw`3~~#<z1}!{siU)*m-t3mm-GYi&WmFVrWm|M z_v^s0m4o=Q`dpKeJLUtf>o`7NRFA2j4UJlPE2i3JtN2UpDf*dpJzHvlA3uGU{T~Pc zyZ0pfQGJhWMr$?@<oPGE31hEtPP!2;ar6=AEt3)$$X*g9F#)X&NY*inq(KEwgk3cN zw=J5tcHfjELv}ih(-lOgHn=wq7DMA@MeGsHuGuC&DZgwuRCbX#E3$F72$^>f4F$8w ze2tYp$`axxknw8^5Zb{UYOnH-EP4y#!pjsNs-oBdAh5;P8~kZwaN{wU;L7PJs;%<A z)h+!YjsyQD4-fGd-$F7Sdg6A9%6d{?QYI(wMUVmorD6OQodZ(>A~@bR55hv7{*xkF z!5&#vStbjG$=;hPXnFs<3}L1O@@Zr#RGDX^Xo%A^|F_w}EEPor%Rd>(q3TQ}zX}5P z4_wA(td+~#G_I%puQ&O#bA4<QCw^ELOBge3?4&2o0nYeJ%sTA30#U0X39ANCs|4JF zX3voE5myJST?9b<Q42(NAEI&*Nfn9eLOIiwPng||)SuX%+ntZ92Z(G2&?0b}x$n^F zg2p*aYT2(6oxBC(zwShZ^P|TO-LxSpF%VqP@d`=<1!d^*uvyz$H<tI`f<))|O4yq8 z`J-)2p5q`$hQ?M=`5=Z+Ekwd?)KUVZ>z(<ytiAYaXCK+?jYimS1ZS68*hKVw2jpl$ zVF(l+Kxo8>>R`TA4Hz~JX~QaLL3X7L>eXUF4m#e$21g@_OS;}*Uw6o_(nKXIw`4ZM z1YsZ+xD<TD&Ut!?M|VX`297OEyJg$yb-^{F*}Y1Y*X4Tib%-aAEO^hrEcqBIAz2~E z5Y!AN9q2Rv8ZwO4&yaKed&qr5d5x`4966lxY0TgCB`@0q5oHNoiab-_p5huGRSCoL zRgq3DGe;O7Vcov%V>9Z08yWqUz7!TDcXB?AzIXprxv~E9X7?WhV^bPZPHW-_J@-_~ znNej>i5{`e#x~&+5Kn=76-n6zDETWD0C!OFBL?5^Pv)W+0d>H^7jOE%i<XvoK0ku% zoR0O6UG``4ZYw6ZM}&HkCLwvbporxp#a>Y)_CS!2he?H5`M~UOz@9NuZ}c77Go|-U zqbO&1<O&a|bB+yiikxWHPC$P5V*mJl3#rECgmI5&n=iG!hG#==c<loeTytzgjinF# zt8P=5%U0O01#2<2H9FmQQpYQZuB}_5hv-*ikCZA3cZUMzN+Qfv5AN4UsNtAE7l*ha zmq0`vZ#yKM%mC@!rJmlG=Gs?Dr57X83&`EYjEPV1Jss4VtViv)5=4TGO<|-VmY>@& z#DJ8{Mk5?WpNDAql}N2i-9pR{B9P?;Zkt|n4F0b|uEHy3{*`9<!PcThw@4r!Q^gD= zRnUqAk#?;`Szf-mH+vlt2qJJ482JD(2%#As3@rB~YcZ^$Ls`bf01WA;wGKImXfTEL zFA=qlDB_DG<Fi$wBbyA_TXcs4hM5_a9J=n6cSyremPOp8p}YN)eop65zo|-b3xz_s zRPAJ?jyvn-(j}RG-F5lhn7Wu;R8N!Ul1Vv$f?_1ueb$@<E?F`JwCea_C9XBG<EZX+ zy&*`w`O2+8sH76YxL6jY7GgidHp#sOV=UiN0Obh*6_ef)zhiKB@)|aBDv-ruDywDT zVSpc~gXRv<WV;7Kfe{j4Z|h~koLodV+7Do<fL8O=iKxX92uWZ0W=@DDoBH&?tF0dJ z7l&^ZJEFQ*1Igr+DD*9>N=2JRitQt?FK9Nr%;rmt6Lerwm7egbU@xFUl&+mOp)jK{ zm^ZJ^y90Pd{Q7Jfgfn;~@0rnDg_lanZF8TC>oDNWO3OsVPaV=&Va?vNWs{$4vB_OL zKY;)UNC-hI+Uc1(Yi6Mf>$&gU*UwCC(@$<a9~2^B(IG$N!BGB1EJXF07)XmqzGkx4 zf{?4<GwtfFuI3zWf}AFS`zMW+@~PRdisEt8V151QvJMc$18Z;9f;@s>G8|c2C?7-7 z*97Bk%0T?{(E!4%Gj!P{(M!Z2#KW4z4Mu2>X%Lmm9z#;@0w+}01w*kSN6E1`QxSuO z!nJqMg;MKp;wZ4GcDgM*cC7M9oghl1SqWL6e+yAYuZJd*eN3>g@o@2F?6OSA^4^FK z*M~kLP2=Q)P!A8s?$@u&XnfP|@O$p`?es(vy|f|EWl$KUbWIV<*gpz{X;PK+)KDtG zlZDi9=v4exiq)tl@(;c2y+hI(hb#>W9n`6+YA%e{JjHqg_Q?<E81zU*Vw)4MC{Huq zd%g=!BrNN%4fM;*6lT0Nf@@x{K53aMX+x%fIDva&PF0cjQciC6m>5lsuDy1&py=K4 z?Mqi++4=46b3IqEx|xrQbxxa|-h5|%b%vh?r9NNz4OE$H-F+^d+gx_w*-i^oux+|7 zHC#b?5`S7`T$4&Y*jXm#8|yw&q)Rg|$R!Dr3qDFu5fZ}|2;r`~)1nGZ$<%;6cwb4K z!>tOc{^~lP@P9TtH5PpH6$!mxTW~c25Pt5b(Wd?+(!@a1$RkQJrw9h$ojKG0K8aYt zGv)WOUWQd)JXG54vb<Y7X-rWC($4Z;(#SByKKzou$B3)smOd&`Lhm0dI8r&^$y!}k zTju~qfMM@v(2kbUl%FYV#{k3uintdaW)Gkh5E&aTA~mePa>=Nm)*Uh^;XvzHei*0n z0}EcH|JqQtg<;~1WCQaHq0pBx^S{*~rOU&WOGO5V&pU}F&z_p+==e5Lvjdwh2-YKV z;HQ*$@kk3BPEyFBDfCVsT72pXir^1Y%K@tN_n@3XB9jz3)Hp674F(al<Pc0+U+1J< z&4!(=L!f3vY}>-{X3>@EB6B$Qs1_N@0>rA4t@hDgKvNy&KD|&qB`b+-8Qu<2D0#Je zo51}vL^>~Fh|S$P(dcBtaa$X3fNue>D#X=>8{wB2F3jVBVfBx41Eld@<n>yIlvM1p zLy2LjW@6tCUcCGMu+@T!eDrfkVz?^R0mU66-b+m@q`}mA=n%+0QhF1h@?FO3-dw8G z{=m)by`lhin8SnN{M6}Gt9gMP&%O0O%b5obnttCs)NcizEUjCh^rHopJ@dD%g-2~$ z2TaP<ea(R@^EyR(dye$sWl7N!BrTA<+XIK~i>md)Vee_8Td&>s$ol!Hwv|+S*-`KX z9*aJ|_GOvKcG5D*zMxI|m;R}~V`us&2Xhwo|JaP<Qd7q%lO4t9xmMp)PoGScgfQ5B zvc#1w+qN^){Vl;2BQQCQB9wag^5|#N)0NQ24&*b}b~EjSFBcG3d(QH5epIpMQD5=o zd2wN6$M5V%BH!6)CVNhajo;b01CC^`CsR6KG7aYvI)m2Y9Bk|zt<uh#D6?m8nVa;+ z{8i2@w|uunxRMewX?W_L(N&*D7559|p|l!tuX3-?obknqKMzIAc(D>eT;6o(C%65V zwao51HZ(CC!jhVflP$xH2%gg}N3$)MADn#%2=Q6D*rU?^9Zg{THK;c-#xIEFQ8GB> zr-j0-@%Io{OOxt19{dFvM+mW=n`%N6d6MYgu}Pl4Tb3?o@7r{+Izy91G}wg*>@ZVR zbV54Z%Xak6RsTL;vL}c@9E8q0)PD};=fHZiUF60>HUioETWSXbnQhdbeumd~7Du6B z;4|bdPAT^mmSMO&wF$D4(2CI#-~5S-`dnZ@;1#VGs{hpZBz8mI>tjL_BRhZ(Gw|w! zmw9b&W+MqC><6}jFam6p<k&YsOO?oZOx3N+d;xApv#P;0yhhR{76Q@cS>g^cP)-qX zEM?b7VT4gxNV(484+c5+cUS)mnM#u#K#+`hvoZuC!Rzl|C+?7qi~QXaf6=fH<?Wvx z#XPlNmUNlc7HIxgLbZc=0})xJ9x-eJf?aaFG)3fn5|i;_T|e$d7tHRCbg(1*&^2mJ zWV1m#O&@7FFzr1L2!gDT7b$ZfYPSMyt89qyaG_(mP6$~@l%s&aTu^?;qh!x(-!y;N zx`r&X7S|DgVQv6vwjg?(WQz}kwE*e>hafB_6xY$6X5z|QQ$s#s<xE>|Rh2c<;%@R_ zOGSQB>M2WcBWgNyth?MB83=(<;t1(t5?@bNJT)YAsTCNt+u!jCDK9G<;7o%q-Y+pF zh6wwTKSvtgLG7?Sd4#Prd3v>v65X|Zi0+*{dh^i36F`f939P4b2z(?AqLiw{Z<3uW zgi%$Ti)`y#Ow*6Imhmve_gzB$k^!5VkT~2f4R+^|j}O647WBRf6IzLoGA7Ws-A$sK zv_G|xe8TvRN%+-SenwM(K{ov=7VXNCyVbQFr_evbtQ3%J<@%sOUW0Uo)0Gv(tFF)> zbA9s~>yvP|?z+Fpk98eI0J^7CmeCyjBeVMk^AGwqr0?>|%%5!Tbw_*tu`y)^*?C1Y z+$0bjhwr4o8}C619}U$L;_%B+9)4d*8t=h0O1-733y!pXl-EH!yh$JVk$#1EVYe8& z(z_F}fr+3e)Vc@7%D3t1Wm$VDS$({haY#u-SnUv~_Tdng%;qTw4xv;AuPl_PiU--@ zIY$NDo#SV0%~>vpPtMrM^gXk`oY>YmXI0$n{2n~6YLVefVCTikRjoEPX87>RGmXoz zJe7r|OAK!8iF3+mVYuQfnO{GVJim+*HHstHb7u%w`S1f}#b!#X?luPaVzj#LR~_OT znmr1~3aH>W1Mvgbb6bo<g*<FriY5vQ<k8LJ-yT5ZsDRvlF|zT~KeEkZ2;m^wqXhj{ zYlu!zuIQ5n?V{Nu@=#8N?+gTnri5ZDI}?B>NCwiLcE;<S+}EHa&Ng$|H3ts!>{SDB zGzTocFJlf-Do1ioImyWfVU%WN$<<e3lS#bDx9sk~CbV>h<0#?RQd~{Z$dWtkS2qVs zTT!|7iJy_V9Q~k9V2+S!g+Zy_tkpG*m<IAhuSktQlkO0NmGSSGbQe`wvLs}ZS8nK< zNG&dZa7h_tQlezBk}pxu{N)hOH+?6qIw<fOG+6}cQNCBWmLy4VrsdV+q_Z7^rh@;L z!y+@4N%6SEbMKkoRdHEONqWxXn}c<~0QPjotqU#|<;c0n5H<g%Ulj$y<6}G((WdHR zGe*5sQFpb>;!A6xDe?A9PMeh8we(QZ<Sc<lcl<}|LHZci$5y5L%8@0;w;Y9920azM z@Z8?n0asT>bQwMId3kqey><6wlj{C8S4dPX`JrZ96Es65d1$^XCuxyLhLU>9c+DjY z&WcaqeIsxA8=PNf#J<HrWm^Asm<mmoDjqA~3^izeCegz;nTq1$^C6F1@m_smzz=W| zWIyGfYAz<`f9sb0U-)PacDDZ?k7i^3&+%wYt=P>UAMkCx{E?>+scHLB%s&uu&>Lvx z0eNFWTEz4uk(NOuTYq%XPkXP~){5zF_tagdYZ~FbME}}9IIycp4yu&0FZMH<q=zSy zMSW?N1T$>RQk2KO(AUSV2p3B?J7%$y{yIyFVkb;g?*K5+-!MCrD1>IsR=z39a911< zk8xMt5<4^Qh~3GLe<lP}@u41~AiZPg&5YF6hjF8L#W0E<#LtHGw<)C;8g)42E-pB7 zI!~fBOEt@@Gv@|oN`f#_SDjb%fpMZi%n?X4*fT<0Fm&dX&1;A?DUHsel$Ub!(5RPQ zmfu9z{%dw2byI%;pXvkimN+_#R1*Kvl!f`1mQFx7K#(ESPvqH*Uy{_1_Cc1CmTrA; z&Ko;V1*}!cVh=}$P7oQ|88q@&&Ba<AcYTIbK!2W9Dv`;!a19|f%k~L8LE|W|sZz~> z(aJ>CQG!$k$rTnIv%plSnSObHM=g#rnI2-Dc+LB`fW#fDK?X#L2{0vv13r`dUM02c z<%?z3ARCHNnnJU#a)?H_i5|E=`X5J1x#EkKfUwkx8rY$<OD6-x6}fH9UI!ymsM}Xl zFx%0oXrJ;LD!sgTt9hhJS3Npb5s9oB{WgzQDmF_81yrboj%)B1L7H}Q>b?TLuKuIn z#<>P{j|b;}p3>TCm`lc<+Rt+I=`H2!1~FJTAoqWR+*e%jQyewLc0`G9idDXc)2Y;t zgS4HIT&#!D;qi2|eOP)b`rPk7JfGg-e}6118_jNpO4{qs=zhKIyP@a$xUw;6LDd<p zFoGXF)5DKN1eOF%+OGg0^NnUHk{=t9g3420xsGd1#@6QO$i?Exq{bqCV)VHFh>JIn z)V#e80fTmGTGeh4gz~!D1Hl+q+r(%?Mz{wtHY)ci2d>qhskp!H&X3hDGktk@(rJ6Y z&TgGwZN3jZJwq<mzdtt|jK17@+dh!U-y6@-@xY#6(Nq1d>1uR&?LLQO%r{29mX@!N z>1uq_bJ*D#AVKcuvI5uK+_ye(1UFn>L%;9MW@-o?#$?#t)O$VOrtKYGrzQ?Pd%w<~ zXMEe*KK9OD*K)6C!nbw4Uhn8q^>`)TLk29><r!hY;wdcb(FJ25@nn%MRRMZt+=~5} zbiPi{)+-^sp2A!o7v$7ta?bp6rmL%lTZ(0*Ce{#CchS3Ri<PxnHNQ{JysTQ!&o^mX zt{J^))tft|3ww-2!nFb6+~YVj#OuO^CL!bjL!IF#A$nelgC>=Q@|~kG5dxDP<J#rR zoa54w!qnmW#Z`A(PK`buW#rzQ<#O&0c?>MRZ16H(b>OE?*}TkSjvwTc&;%67PzL3M z<^{gsK*!1uKzVzEh+J^pX4%ri%*qBhN3|@)Uoq@h;flo4D?`&>F_<hH5U!nPI@6eZ ze=b~UkdgP62MA1&n*<4bl&9UhFeBL~`<o?OyR3H#w)ZKr<6-K$9?Ka;V9M3t>4=Hx zaExZZ1C%&MwL#+V37DYM;0yFoOm!vj49SWR=}Kc63V9z=j-Ty358)Q5?$(K0F6*9J zE>pyV@&s-O?g)$#Ob}cUIKv6sVa80vX`Pn@;hN!yJDnmSe8_i_ganDFbb&Fq(|_q| z^ZBjTtZ(G<`K+0JKkJp9OeNXlNe6e|<RmEmsPl-JpeW<t0Ml}KKRs;u9-Isdk!G_C zV#f&!Z=RQcWvD$}g>gENGX`$6up-t~%_{CYo={JN3YSb&b**D)7I^$g*eRo<C<Owx zKJp=>OBEu?h%HZaQ%%!bTWX4r*W6X8Iu5+}F{N%6Fd2i9na`6fM?dhANUCjql5tcu z&WEw-u+>Hj7NK(SNwWa^K1>G^b0dZSDjhOQO8R6c+Qys27)oUxs~_27&rmnhJ^LeR zkPz08)!t0`In8Rzt(#0kYvZw+JLx1QlXqAaxUgI@tn=h0p*VI3P#_AF=5bY)Dmcb! z0sd`IvO%`lVAhHc5kG3Kdd`;;l}i5n69-gxgvFjSTy`#Kb<{?hLm0x2cK-Kl>2A1b zGfV{uyxM~fa|%8_E$GG~X<|)2(o$vKMAu5&c^AtniN;d6+z*~SUOOQ-ARTOmA^ci= z?3X}G^Gv9xftJ(diJs*(<!terE^%BAeo^wDtml%y3HT$B+$YSVGNvr&)r_p&c?zQ8 z7gy3&+N^CauL49b;tp{P2N%B*0#0}^QX3>>rOusJ9d*VPo%BSK!#k^=<6Oq4;^h^E z)SrXoNp2S~s%skZHFVGvVtIzlt4VIs3jTC-FW98Om%mPQCR>@<J)8-c&J=h?w+h1+ z{CpN;v@h?mLX()Je%<$zN3^EFw0`Ff;pwDcdqEk6ln|?r>QmpY$=^>LXY0R8?c4yw zW=#27@a1K%AAlvF1U~&^mL7lm=0$7vMr-Pgg!f=!F80Qp>4`no7QQVje6E*$*(iUr zzCmFp*oe0fu7(=_*NxWL*V*3x`Py>8j#-Gy3OQmWEW~An9x#)X68_ht62kOQW2^)V z@&CG^G`mcd?}+Q|5h^G?>5jMnpI~{v)%+s)L_#D~Ikl2r6#To8CVC=MmK|k0K}m|l z`3H^3;*<v4uDyt<BrLzZh+O3ZwJJB4kT32v{pHu?nYd&4SI#>cwiBdnL}?u?Yz-`r zc(j#<Y5^&owT%FgU^=N*`QMpsbo3&i$JDphZchqwo$+4`JQMj#oT$QL<*rJz#K-9Q z2qAuSo<fj@x@j8)Bu$Q_>x4;@K332>tE%XWQ+G?pytNj#TJ@LFq<D#7q6hfopUIj5 zYPo{1!x26aK03!XnOfEwccv~AG&Nex0_VzSul}Zzgo}4jWxX2V;kV!cj?(^`RzlS) zhH?#}O*uI4MC8;3ISYEsdD+=ehE2Hxo=nkCK9s?V<MY>~v_L8@%B|#MK2W`4@+~6n zT4i*<Eo-bUIf`Z0hNJ7t%pM2@&qGCDP$iczHrV0)z4^t&Vs+)KP#%EhkPQTmdn(aF zp1hC<72{d7kVaP9;&bVz6f|pprwpHCb{bNiP)GelupIa%!smPQH+C%+zhwHzEu(fk z$ob6T54_72O!BbpmGzujTN;DOD2n*8SrsxBJh%?dI>RK<e{|z;1>WsCj|GARyE^4f zhG%_AenO0cKj5M8fO(-@H2Lv}o<MisB7Aq0tei5D3KOQMGCx-rExk7oAt!_OK}eM4 z+$Z%(vDl4*N%}eTeZ8&$Cc(Gu4<)+!hA_ULqoSmh%J;mqw_YFP+sWE69+Jr*Ezd8R z`{XCR&tqG#9X)1s!tp)Z@fZ{$R+HyXBoqj2IkoU0S9i2bwXEz@c5`W3R6A-l7JE)V zg(9L)SOuHg<t+=5<J0THT?;HU_j-=KgDdPEQ98c8P?c<1h?WC^U!!0q<9t<-o_iF! z%Bm1Wc@cDgmUGbG6UM=xaE%6iB_Gj<vtCafAdJc(P|p#*mDY>9z5i0_50$Si4I%|J zNG;M7L0!B-nv*p?kjjL<<<J?~R)p#nwO|M@od71scO0-9y`pL*ck1GZ<NlevC@JCg z_0)25mdV~OWaq@vO!3pQoA-u@;VxRA%w?PAwk4D~hM8LBS3lg;1hs$oPiANPC)ZRa z_W#(&=2FAP?#IFX>q;-*;15AQla%6K)S8Wd=9<JB^*Iim-dexBH5nq2R5^_sZ0OfB zuHJ!o%SACLlymiaeu?<jZF^^!TPcK>8r~Be*NkZPNRYfI(oj~|*2z3FhQu@vqS9al zTZU(?kD&35>q9@Z0ZlYJM8>H=MtPo8$U`oA;-U1RiDHRJO{?o$;dCclK=ukTRk9+H z1hF0Cd6#cgH$_$V4Zjg}ckk46I(j`qJ$bOhQMSw1g+4ek@%V%Mw{o5cw7D!ojl5Vm zaisYyDTdMaNV#Va!xW1l<!6wtAN$pF=>EQf-wO681J1Lo?66tkmi+@5Q<aT7_s%1+ z_+)&vh)Gw9&mx!mD*kFWEW5slv_&&23etYkcm_+X8wKzSNhqMc>AYn2Padg6i?SS6 z!!uqy(nsHpK@D!BCzj<Wju*}lPz>Pb$~n@F_h|LrgyGig$xkh1AIHiyH4zsx@kd%3 ziRJp&{l4N<VnZ4}$^=fR>!sRzP_E{_ggRFYL?DJ12c=t274cbuJP~#IGAg~<^CjmM zI=FhGgq9W90ID<b8{W$^W%@?hoj9oy3!idvI+xBg?ca`};kDcfaW9<+LA>R;jW9K_ z+V^!;fG?ZN$rL5=%BXPu;KWVZexyFq4?A=oPh$vE?%Nr(tm<R7m|8?@C3o2L<Sh`> zkIms~mYq-OQ)>kUizq9$AVt36&<-d^E%$4omwQ^lWkca*TT&v7$s&}76wo{oV4!8B z!64hwB0Z4c*K6Q$Zxd6)wuW>a#fbI7K!i>nkM=qzi!0Z4F#-ktdcVSNB~qvkX-2=Y zandq?_6>>T<#9N&iPsHx`E&96a*jPA9T%H>Y@Eo9%Va>RcOipEjBqUGv?MZgEU6=9 zlvLT{&1yzA(PNZA!{G`Pbf{GBDqbDb1aC`lun4>={qwL;t&614Erb=IO~jM0GMd@P zgiu>&%M&ya5n?x1O$`!+QfnSSZil76a^s3-nmRL;1VHYO{A)a|B9@An1H8hl(L~<_ zWB2{ly6noOe%V<B6Z@j|T2wRuOdump3UrRULQxwY*9R}JZGLYXwl8g}DOl(Lot`MI z4%;sbRA_J?K$5+XW5=2ZJ{h2$P%J}v2@7;eWu%6TZ}TA;m(Y*EP%NuzXV)!?Y~I4{ z0N?l73<cDph^Q{nrzUkBa(vciGMh>JL+uiuG^|ZrvO-(ouQ9>$BKe~e%z71%K{=W{ z`0H!Q^uqD_Tx+OGFxZz+sQq+z7q-<Wtdd!EK9iz-x__x!$}09n@e3<;8e``=*RcaN z@eA2_nlQ~D7&Pm;G0jgkS+#<`4e*f>zO^h(R#HTF%G^BH_%Oe>xV$XPZosR)Bl>m- zWuhw=&6ZD#uQDpj&ibe|Hdf-DMioz8wFbY6W2#OcD%H;dF3;J3d&>a@l_%#v#w~*C z-iIc6NfzG@IF%p=Ljvg7V%uoY%3m`h5$8QjJ<fMfo>J|z^$6@l*}K%}+e7QhssucB zi^T|XX_|GgqLLM{w2D39G|5l@hNf|14ZNu&=$U}YDk-u{oGK05^eiMk?F}yS&=aMZ z9!?il0~Ns*d^I*TO{~<EK)Y#&lua9?<+gV^?Z?q2t((=XJmKg~nu^5KupxK0r{%R3 z2uh))qdJYems2J(Yn|Y{w?7<rp8B~ub7QPhw3L44JZ(c=if~=J9IlPNV8HY4Ha~im z@UAO;pO^M*$bM?J{PG&Vrua@)+$y(xKNt!2#rzD0_g#DzZ^H}}%h*7SLNG%7Aez=; z;8Sk*ol?D;8tVGBsgg@HMRl;5+@tzu)g}BJ$X{8g=AV{r_J2R#_#b|XiS0jzfiKmy zl-Ai%d}nHJCVN(xgimZewp&8#E?YKfi{$>$lOaZwM#$KdCi(S>aXQ))6hW`Au1@~} zj(2%=cAkF5)iGy|GIwTnXTiIO4UT{rYeJiQp_HUx&=j*6jxe2b$I2c~I58eoLS7Fp zf2pKdH{CvRDX@?}T4AI_Lz5bLqBLM`X{Pzb%7NeeyNF&G6ZqbPd6-d+haCsL2L|Ks ze0a4PODG0y;h3Ynr)(ibQ}=Ij#PkST?->)4WCBSja=L=VK0RP8RY6F#niJm+mtw7@ zV$A&R5JcGq<5BYBTRJ5#Q3|?EL3ZlXsm|No+oAVu*{?rPZ@=Gq=SJ7JWxDwGe7@(* zM^PD=hbUx^hEy_PK;6mcO4Zemrp%~)WZEL{hsIg2xT0#21okV2hh1&!cf5atE?<oB z!?X~lxhv8{IWFbbx7DP)#JgQ4zV;vWk_nL>rcl&WmY7FX3<{Vj&n>#pm-g$G<fmMc z3P}v%{xQx;E!KJQ4}!)ZPM<#soWC__?rNe3otbALpF#M$=s+pskD5eWWtDq)XuUhN zijy81Pj)oE9+bQ_goh5efiRAKIbDwE-v)a7qB3X5G_+Izx!{5Z8iuY^rN=oEK*<X} zfsOr^tq>2E!ydTY_~&825by=0zo|-6UM^Qc{#wjqCkDzVjMDj}p(1Fdq-82fWZzf< z!BPnHnFN5IKt!gI_Z@Rn;yZDBJ9=1s;E->(+he!ebN5s3k5^0fGd>(2?)U5Ns>OH6 z7v00R-@M=c<iLyU({lsw0$ph~`r0>hlUY&`<w8Jag5cV*+aP+t<Gygl%hQ_dZo{62 zue^+^RG!Aw>MYy6*Zi584<G0$Yf1~Bz`|0c#ChEHW^43%q`MnO#z9LDfTwO%ttNZ$ z7<mxk2Awoj|KB%WPzH1@dnLiXJ-iD8U3^#n*fC5)D#)3?B^4u(`+wV^2kKI2o}nlu zNwg7QuOAMfVgdw$0$Si*E{QW+Ia2<}<rwT#so3OZ?}F^|F+-s*zmfp{@@`oNO28y? ze%kQ&cK%xN_v7X!BaJ-!=H%Yo+vIz<6Kv7SW(>A&qWqPX?B~zCfcK@D@mna9;0ua- z@IfR>@AD7N>XVE3L(f#Zm6X0lM*LrHvgXhDtIT3XBIPxgp3=MDp!TCA6=Ia(@cnam z_kZ%!HSeFA$k9bCW?J*ck}#$_V!X8SNb=ocnM+Ud@3XB@Hb@JcnZWTp0?TaGl&rfo z-ZYN~D%X5}6kCo_Dyem`pl<@#Y~T`-0RlZ1(HLC==0Jwclmpaiz7uYwkv5g**vEgn za<1AVnS0XL*Pc4;HxBcx*7IkgRySC!26J4j&YxRsWZ0a(FG$Tp5w4U4WUe7*^^J7H zbeCONoPIakWB{?Wv<;Pr98UK1wK5H!YV3Jd`Rt&wCJ6@lMbe8rb2XC>`|}QIJ|qle zg;{vB<d|gz5NvuQdRC=)L@d%OSZlQ~H9-9e_?0DyIV%Ff<15_;(t99vK96kV&?wMs z6B{HAq#@Jt?l6l$d+_E^7q*-8sSI+DO#GJ?=H$1P2*h_nnTOtWo-{GY%0T!*m69W$ z6|eiYvHd~9Jh$5y>}J40I2gL!B)+4=cNbVLFQQG!T^%8LEdyZb-twOc$|l`Vo`Zo> zx9iaX6>>OLZX;NDAxH#Iw!s+rEd%?!1!Vf17uCr!5b!YAvz7iURojM#_`y+*_<ozE zV9AI=hQ$Y4xbx4}Tw86Bs{}%Cm$4hKd3oASzQe^XujjB%{R$JiDMiF;m(+17t>bD~ z;|}L_Kl=MTNAGV}E+=fty7Qh8Kj5f{=e>ViwEsc4$MSPf{hum0l9gp**XR+tkJVmI z#DBYeU><j9s=L^!oJJH-V#5eyXQ2sdeff+yAnAvwo{b^T+-I`Q<N&N95zLJ36M3Xb zNl{Zp#~arZa?o4Bj6wIo{EA}HP^2Z$q0tQ=%u)t}e_FrqaIheAl*(N@YjW$M>g;#~ z%$P(Qs|_Ybg2*MWHc=&4yi7cV8pU#=1Hpur`g$1UQP5<pCK-l(&G44ckAsvxK?pTL z$=*h^VGmMhHVma8n~w$t-~n?$9Y;;cvD{w8*ZC-ubW2MPTebW9eZdK{|K&F8vwVHA zyH?OY7kEB^XkBA+8Ysc@dZ<`)3hJ@o9~XUYC~RoMI}1pGKq9S&t)4#wp}Evk-mSH1 zpu~YSCAL$_r5qX1jI6|5YL-Fmmlk#2!vvXtx)CRxSHCu#Xs#ZKDbkq@9Z<x3$bZX_ z7qw!elPm+`?Hg&;8PT@uUqFk27pVWzQv-K7qjRoP=U<$Tl;z8nGhV_$%%D$~J_v*$ zac0E5)+WPd?7k6!DFKeTzM1EgD4BODuOK{GlxJC~vp;UsR+|6xfmO@<N3Op=4`7Ua zq?2*3n1C#L>}d9lHZ*7t;jV21P-hTc-T~T&rcxQer&E5o?BN_^H1-DF)z#_tSyU|y z{E;t+>q`v=xn1EiY9Z1h3#T}p!PJ{~3wL}P)=@90<Nieoa{8OcZs0@lcw6cNJRz0D z?VsK=j(_?&U}OD{dmBIAr2pHXjKGc_+2*Nd!stqd%wj{>rgYz(QC(9@nnWHk=G<?) zvD2R)VMIKpbO9YYWuRS;*Y$VM1ORyLuNl+CU$tp)%#p>$eHTRX7#0-3s7fRf^jaXL zgkp>tip4@dLKI&njdmZygr5X(VX5x}l@7+Qv%>ap2sjyohW3bQQ#;^kW+crZ?vdZ} zhN-{k%zkKT5LE|$tnz<h)%1FDvNQH|{{MwlR|Q##wZpaPi`#=OSMDqvv_jTU_k}}w zS@>CY{`J>Ex<Kl$bVO3XBNJ(0Ev6t6?5|#^GUX`C-w8iiNByCyx5!rv|A(s9-0BA| zgNziAnd#RcwwS;Y#GH=?qysc4*up_(!10YLgCG?4!T*<T=uQ5$DVtQ7oTU6@T+SPe z9X3Iw<EE7^anGbMNo)1M!W5U5z^{PfhkDI1*3jkQsYN<n-rnvO@}U9&rGcx<$Cr>L zSUw2I-?-gzR_2VJQWHc}QR(qzK2(YS(Pe#YLL(GIL>fyn_jh@AYOCfnH=on;8U-w$ zc8#)4a5LG9eY|C&$2ZhFIC6SkQE*fb@-s7s*LH&Lg^MWt<e0YpRK-sEQZ5h*W)D)Q zc1IBu+Lrv9U95-HI@ozSb{|TW>8QQSS>b39BNeu!Hh4LjEzQUbh6RMS8EQkVGLVbH z!rDrlV(zZ&;Q<g0gHR)JvQ1>1GL0%f>K{N`?Ep4$nHP6|R5ABu1i9|mX-<Pp=;I`Y z=(fEbhnw0mZCKx+x4wG#>Tdl9?&_tE%|D4OvZg=}8H@!4<X`C%LDlKUtA<uQpvjQG zxx7^wWQigNtlkMIq-mHf21~X4Ty$2Ba;+=Yi$-f3hKOg*YQybuj?}*9xXVE@QJUyJ zTs+ecxt>@Spsger>9T+IaV=ETWy3qBPEcx-t@h6lsF-!Yv|=;KB_`{AMyF?Vdwkz5 zT%5iq()s-)6&R|0H1e3Ox^;Uz<u49=>1Is2ze_gWNG(exE*`L~GOk)nA7#C))c)nv zwRuKO+8COsX6eJMyYoz+zAQs^NNaYc`B0oVM+t3s?y#wr4#|za6`oelHEan&O;w?K zfALgIRlM|14A%-<kMnExlYWhoKr8Y0wlX)(<yGeN9!@)4TC>t>cDZFvzknKl#Y|E^ zxUXdCf`!aA)73)X>}oK+?7t?LNiV9b?gd-}EM<nRzAd;adBNpOGoetBKJ5$V7Y}GF z5fcCc%nRM*6}y6g3<mImzz2ndOX7oo<h;X2K#Fe7$CuO>DC31ff)I!|<U>S+2yc`> z^F;`_*67Im)uLVbXqmGzvE<KQ^_Np$pt%p|IslX_RdS3+J#HHmI>Br2x-TS+P;wBW z?T-gMEjOONG^jTS%pK2d<9M?y6Nv~g`=2UbmqxKQ5z=vA%Z*>;?XZdb+Vn-CRi0Hi zz_NK!5Ul<(=2exnxYr%dRbKn7sy^0%=>udb-VmAky1!f0zwMhuNIqT{U?0p&)}8IO zU*o}(8?ilFYCcATDmO=iGBcif84fVK)2Pt!Sq{<?#82K|uS~Fr3r5Qb-SR&A2$$o( z{e^71U_a%7pi2%N@{@2NMji4=>aC`w1<i;$*5Q40wvZ+UP%vUlv;s;t)^^X`qHX!# zMK<eJVY<M4V4!$@1X~&I_AvNa#DzW!Gl=>Dm^@Gr3}bP|e8`XtV6y`FpusOX0rHja zTXYC#7a8F`1SHy8y9QSsktep9U1LO|yBxPR;60K&Q_r(;!LK!<d4$j~SK*;eiedSL z5dCoCpAfJVviNXt?eStBZlU-vVFaou*P_8usEG}0?eUaZdZ;1WWdVzy-Pr1!t=HS` zYt<A|%RCoBO&f12GdOiI*aEIY*Pt2{?Rqy{6qPol++%28h6YC=5-q55DpsTeleW~_ z)iax5up7tdHX6x!JU*?yHWsSMShi8+4K4uaE<cRYBd>8Kww}(iD(JczA#ktiqI-7A zM1be!(kFAdBuja|N(0b48k<+p+nf;pFC-yS2iLz{q&JIyT)gRKBL)YX0~lsc`Co(f zTZq2_^B3H)-||7wl<~s?BLeNj$gV&+5lysEFu}9ol=azDY(T%jXDzzy-Z%=_BUc?p zBvZotS((8&H(?nOq0{%;esdiBk(lzxseKz^wrlYd)?Rk;oS=Y>Ma(y9(FyK4r}*tn z51>C|zNcWu%p6*0u!j3FlUgEal<IpbLg%nv>TvJfqn&Q-hO*3+Hf!){xWGIY`&^b? zPb|B5{tX=$PC2FpX*}aqT-EB%sPxy2utR|S=}pA;@$2|#o(#RLr*^m3;H7r*pY}|a ze`mD+Z@d7<zuBoVGXBRv+mxn_-H)BxSB+j@>?JxLM;1B~JrD`Q4=(^n{1ny{O1N=( z#Ug;DLogxocKr?`=an+o*wir74;X5f!iB?&GfkzY>I6lhKE+{-`ind%A)7oPle15t z`Ch#2uNZTasI2;^Muif~f#6U%8soC3L2|;x14E#*8K4MZ>$q$(e|n}8PFc~HDp37n zE0*}!GC9g<MK4X-?sq_cv}KQIU-Z&4P1;=3y#_hOb3IhWJ{3(;mUlEV`4hu*o+kc4 zN%=!PP{k8NC{dX%0@ZM&frF~J>2?^V=?nCq5EKcY$?{L%`V8h&GbH-vYgi{OCmu!E ztRc4=4tv5r-XtI=r*0wg$`=K4a95W=q%4u;0LwV)8bbYeL0b4sv@6a<G~re6O_aeI zBxSgH^?ERRtBM{l*21Ju@~J>HbKrLb`5M>(K=M@HCH{8fd(1!^M77dC(e+RR06@_K zk(5tAE(-}idGeO?ugvB$)5~?DCXWoIe*zh*=Io6Tz`d(oC)F9_uLoj@+_DW>sLHQ_ zDGi={l&yP>%6n)gYJQ)^!ZgPDZqzv3w^lzeK-gqsI$1d~A+Pw#$ivAu1IX1uNB1o? z=GN{2=#Oo(q9nawz`&VZyyRJ{8$B_U=0Vu=<HexbIgIX{7{&eC%mGythJF8|Y5?ei zpJp{rF=>xB39zV$KM;MSS;?N$(rRX1d1-?#X)Tfszh<MT4IbD!J2BK~hF-b+{pkZ$ zX;)k0%7$L4cFo52`FhQ#_vu*wX6wcyyKKh|Qq=n2`4(R?SMcbS_$9k!UHL?ap$DSq zjU7>kWwxFq3Yga0p=LAvXDaHSCeNPesxt$*C6A9LpQn!5V(S(5Mi;*n_P9w(Di;1! zTWj3s4zO)&?`)?AO^O%=%}GekxyU9F{Q^6|k)n7mND}3o6|S~bUMgp4uD4-C%)2K! zbtaFHta9VmjDl_H1UW#iP$UP!QTt6~yYwPrZi%)_^=$Z;d(_-0<#BCTW(_OV;9*A@ zbDHlK61AM7gakZ})Jobuh?G2ci+q(F$t%)oZUI^?GG!f@Jj}v!gLTv>vtr#Cm_^nI zn{8obRJKftw%%PZL!kwY<6baHu6V*WH2jnrjYlm>y8d_!s?M2~Abod*A2iu>41mvW zw167NX|EB`BEG9G53O653i23!sGq%hwcY=rC@46ZlA?tAy(p+@M4Z!`mNh-UZ$pYV zvfKLzizgF3<ku;1MOK@23u^&RrhE#bBm5YB6{NY?VPZk>V?GIGFm+G{Po>DM=hA|E z5Bfn$1UM!M`htP9&03yrF6#oni)C^2FOc+2jP5pZ#3ATAHsz=e=s7wvjw{Y<+nQ~7 zwgJzMp02DfCY?=f-LD=z-}IaJg{I-aQt1uYU+cVoDo2?#uS3|V;=xeX$+?*9*030G zF%cpCv?erRfe)$35m)Cr%eAG1F@rdPhY;2WB(-NUxCzPhZ)k0Yh09z9v75c<r!v-y z2<^(GMXI9hb#l%)6(~l7$Rm~)bdqKUu$$cB4#Mi*Zgal{@e#XKD%kTw3%<@iYkPY> zNtphyGkGE<p+cvlHi!13r7#FN3aQnFr^^si+Y&Y!2Fc$rnhyF-K{Gf}e2$_q6xs>D zsfV}c{S_x?Nnvn`>3RT>vV`dFh)##O)kKpN<?_$!k)KJAf1RVJGn%$X<e+c@bG!R; z=Q|}nLhr21ymF-bupQL;<h=|*SJ^ta&K=!OejS_W1A1C7-5Uy;mK)2xcp9@~_;4M` zt=l;}e6)3EAw&pXoH(ZIKYM%_k#T=_u=Z&GdUmdV!)rtE-0~>gHt~Y+X!Y{rk-mOH z2lBbVUwFBH>)gc87sItcg1kT#RqUp9Z|@0>^ZDL>_1f_adwl<l8aP{~^Afz5o|R5Y z-${>4pG{9YJQ0xXB&D7jq+T^0Ypw9{Du_;!2QQ>!`gk)@7x2-Z{mMj_cI-;UaqazV z={);ijJ<PkEn)gCoaDsT2~KR=wrx8(v2EM7ZQHhO+jep@bMJgL-~CP9nq6I8PxU{& zdspp#pLeZit(BX|BBn+nBu*o?#)y8X$F&d(>QJ~3;l4E?D!z2>s9z}x06yY}blx*f z?D*#Co0F?Z_>xrV-u|+Qnuga<Z7lx-Z!&cAgv(2e`29)6GKfl@K77le!{6rKT@0|I z7rSWoCKbByis%;}a}t;bB_3g38(=j@Zz|M<HoAk5d0%oxD?!UOcfx+Uqh5bygTuI{ zF|f)U_LXR2u*X)uWC^UluW9vNQ)7e6hb3C_zh^y4d+5jrCKBR$frUzoHZ<Pj*pil~ zA(9KJ@dQ|vh;-+x3LRpHU2l?7_+ymT(I_}?ZiI#|_w0cCskm-AeZEac_)F{dTAh^h z)a#p@3-Zp4b`}r>LiR^M<{^Z(s!{XxXad(CF1Yfb&`<lK$L7O3@VW50DF@xTz~m~J z?VS8NbDV2Q;^ott^R1WQB8~`U<|mZ*8%DGYj&Ay~m6SauDLE8n7rQMf_bG^yDnWC` zM%@#fVIii|XaxBa>Joo6pp0f#epb=0n^udM9V3o~3ORH07?BETljceYHSFty7%DR0 zRb*wo_@GjOea&#wa+tflvh3sAQmK%}s@&qr@8>w%09o`H%Q}YV8@Z0VfETFPX>KZp zH9T8-!)qp0K=!;l!0+gWPtkiIl{+Zaqdg<*cF)kOfwa^1G}Ns=MDYEjzW4vfsn_<i zog&#Nuaki=HZU)d^X-g(wren-?=HoJ46~71G33Q@c9zj5V3nsT=9d2NgT&YBi9<&~ zR?+J+(zp7M1W`ZOC<->7Yb6a7++cW9+M0^)7kjeZ^I=@P=GdYeq5FxkQFJu2VYIEQ z#?hTlmX}PN&3bIWdKc$z6I*9fe9>}*`sBBuxVpe2lDLpu2^%RsJAS`FGQNLQWrO9G zGFA)hKr3;BOMY3St$Fc>e;~P+eTa<`elE1GKty?~clC^TG4NVs6&EpCBf)N`e22!u z7n}&d4bp#Vkl6l1)HfX)8|!}yUi~BLdxIJAANgdl3PyM>zdSY^EtZSw+P4}%3R;>- zVGHyE1;`0W!oIj8q1ZYi4X0SEJZEo!9B_6R+u;CqPw@I?gUh?OH9v2%PDS$t#Zfjl zL?8*Mj0zCL2t%!!W-TR2H$7Tk$@FicY$32V_n%$$n3ok#Uxvv!E~HkAEVUDxP8ZwL z%eSk*8wL<grOYB359OM=+dlpBsXE@tfWkwgvNXp%2ma|lLY*h0^4;18NGz<lBJn=& zs|=Mx<b%@J|K5_zDShr>t*&4V9*PlM!O$8aYa{qD4#1Qb@eBY){3CS}3{waIJcMG- zVd8`6c_7{}A;gOKm;DIX0^G0#T9o&;EJDBF^l=KfAM5h*TX8=;?vL});EMNIsT24d z{`T9tv*~9Q*kKl@va2bH<_?-=75ee*dIM$o%@eiYL^t>M2SZvkzbvoq5ZaNX9Z)Ut zbitj8|Gd&}4YM|ckYb?AXSFGuBOC18l{5bjjKCddo`-Oh>#Sj26&eDk=XL)M@dE*T zc1Gqkm=I6;;7kvpy#PNt-atK=^z47w5h93;Ib{(dg4UC$CR5feEKsZB%5t;AuLkYC zsLTgd35clUNhP_jS+lSAh~^$|hvkjUEky;Ey`WOw9Hl`a2msK(b?d6a!XOR7Cw7_| zz^Jub&kr+>uOCMa-KK-^^5X(AAh!8>;-g+F_#($M+-H{wSc;?rD%$<zU8KzV1|t#J zU@I<HS$=)CmwNZ6C@n3|`{{x21w04o#f^~m5yyhugSk@1_At>>0FC;G2I)ei<}f;m z%6ttKG<Mfe8Y(qWNS=ATHurBV25=$(^?cD;ivG@S@9C(HtSyRSUK{&fBBq%0z`?${ z)3vgG`ppZ#GmYVAdF9HKLFd7TNR*JFMMFp|3r|CV#!nJLc#-D^7|4Xci6~p2s7;FM z>5@%}VVtK*i6MY?Ne$m7^9?YE`vT|NHn+Wz3eURud8*1b#~JnK`+|%H(z~%d>~gfM z&MSnWD=_mUKxe2qPIe<c{6#u|LXzL$B@rrMJ>b{q5##2uuWFHdNZ#?g>`}Ml;0X?o zQ}&gC<sYBqWH_waT(NzC?;Bn5_e(xUlX5Z5j4<DMk814w3~O3EngR{GfyNF=IQ<g! zG(RfRmoRLFZUgtYFBy0*><FVi5n6W8dI7Cx{F=$<BGdU#gPob*edy}j)$FXDtO*oa zJFJa!AboEDs$55|06q|9i$e7BqO$jI)d{hFzCZ@sg2G)@cRWA&Q(Hl5F3CyjR$MD` zf0evk<by7>mz7j8D&o`4NLd;a<zx>q+V>_<8j5|WH7UtPh)xr6vr3i^kHF^Lka8kh zlGE*{fq}&B?i%Y<qz$d{-5y_7ShVKC8Tk;sGqo4mRCW*JR)T)i<(}ZmHVM2K=_{6? zK!%;o>m8JLa~^8)={XywJZ~&eMOAEu457aVGQS@>#AFVWQ5#KF<y=hDUZQZ?Ue1wb zA<6zcTrBhnVE+jal5chF{5mNxZOm@Vz|b0#t1goR8Q(gvU>eio*BkYcYt<L?6Xd6+ zP$A??2pK_?O86sUFN#hAwU`Qk0<{R<^O|~zabZ${vlyXe?$>Ft=jepjFIz-ykSy?F z77o_F*<ql~#&_b%jS7MFdePlA`s|7vQ52ski?A!-6X)1|(+ev9?P@}tz<rp*#*f%C zXpNGr*qjShl45B9HTaV%#)WW?27r`u8h!vipJS?%G>AHe0BWJO`AFr|7=_tqmS^hz z)x|vw=JZWY78g+n&gj4vG@K|wXTy>JkS+O+5+H91`F)iT5(6YwD1DB~HcKNp!IFuh z<j;$IUv;|sAdKSgsyjT%(M|}}ax9!nNkP?>?Y9H&pD|<};Exy*Gg`DnlDsXHOuB=A zUW$;F=8o!Q^mKu<={o=;N1ULwNUnl#QJx+eNxZQ-7}*V72Uu0}&Bn>CRyMbGIVt{! z=Tg#ASnBR?fb3xVhn{iT)*iUl&Bfn|Qi#2U0*v$dsmw*%3>PG;Vv82A`Ilr<EOoA> zMSo9-^GD*6+`ZLq^1d^eEhi^XQHyXdSWWhhBgwvxgI=NMb|$Z3cGc~-Vy~o%Nv&ql zhUiUTRv$HY(eRnQ8X1Z2l_US%8i6+(T#D=CWj-e_r4YUrTE`~%eE7c^wc+ASjv~KC zS=dB?=s;Tr%IpgmK53FJW52Imq8hxQ?a6zAl}CjX5oN7L3q|~ZOB4z7a7{rVIF?rF zh-l(nijIvCgR`RBxjn}e?-NRe$>yzr$vxEZDuX%p$J1m{v)<J(BC6INUd4?Ba}*Ua zp&x(snu82*6nkpJ!}Vot)L-LaKinnx3m&w*BFf(nBu&;Re(9KlO2hZ-i!ty*2g3n4 z6E#r$Ra1XC_L{~BUL460h^bncZJw@gbK6iV<hsD8o{oL7|3y@FGpu^GlElshp!ESt z8U<y)-Nr&lyw3tS)K9&Gd6Bc1A`K6`yRm3GWcuN?lGQ!K-NFN;LE0@l(QdItuw**| zvibKaXBNT3M0{B4x^2+an%-h3Avdfhc@3vBUxlKj2C(r6N2%>QKUUU;&>4Y*712-R z$(yv`g1KB=q4<;hXe!VB>ML-FN-rB{1EQ9!82%er#Z}q-KlBG|bpNS8VE*s(OaD#e zJ_=ISXSl_{UI(g==+~LkLT=Pf3NqeAj_Vqj@xMjxgp|HE(5zEO@WS%v=hZm#n*;{O zL%mb&Lps{~mf5Bv1S;Z3F3V9r&XlL5$@pTJ*JEtfb_ME|WeyA`2(uq3f~R+vj(apf zE#c`WOWYU1_dQiZy^i5Ke`A1WDNVH8uCe~fJ&Zxe$o{orans(<2K8-U!J`=b;T~EU zG#IC7YVAR$w>Z$~R5-R7Mg#x1_<cH4Z2uZ`D)NVWsAuE}G%XuqgeZd0E6r#kwSF5) zVH8ylU`$4@2dYc@2lX%vVJ3*KgFwj#A5dt6TnzqeT!fZ44Hwl!J!ImKn8cC~QtV&o z8eqXNb$dUQ{z+>p@-+BDsee)rZaSY08KnQ99!k!hEkO;TKU`gmXxzQ#G-AiDHU{+! zF@LBBb;}{w`;q88R_`|=nS$BkU3g1%Jkpw#{-8-wJD^r#I4B~=SjC4LS^6+EK*}Lp zXGd&t9#=x2chgEZT{UyJ^!KfjX%tk|9U)eUz4moh$epm2cYiC1)Dugn=_zQI{$KE# zwOsx8KEA)VLH0w91kHSDQH4Siz{`MIf^;L&#}{P!(O*LUy8E*1TTt{YPQb-kaP%mr z0GFat1Ho%=tQHR~59OLOrIMmT42IvS4b{xmO~|x_K&XLNn?0ptwor<L<hcYwX~fN% zViAt?I#C?V{XUfvgq=dL!b>#@5A2VE;;&ha;6m%`^5cNZcSQq9b~J%}GRAu@0u3do zP+6O*T&JP<?Ll?AJ`s4dD_#u4Y-^+NL@d}x{7C+Z{)t#5v`n$ANYQi$fYej|W~Tjd zbw94*oeDLuc!nbU#ImkA{$oh0B7sENURb8qa)f%(5GqJb<jz7jimRpNCVLu>OinvL zJvW#GZ!~C<Ox;xcwT7=c`|YP?;f%p7AeI|W_go{ZU$T^jgCaf=Bhf<$^eGsdrd~@F z@qStbXQ0-sBWQ|VlpDD*bVP00l~&owWx-*;1&zULLj`+g1^UbU5u+_VW@a-i7x&uA zp|c&Ld1I5X%Au$pWqI}LcD`rK>fEX)ru}NZJ>AgF+<AVn>M)LdML|L5Lk&urM#rC> z$Og2xid?%>1F5n}HZWm<X6a^4l0h&BwfX*HE%zRRm1(x)mh62mHFX!;Z(y?{vRB_J zo3Lr_b`l$Wx*IL~qv6~rrby4hfTqvE6!q{80?la}{kQEG6cTa3HMh!%vBnI5U_IeY zGDT0u&qxeD^HDc$XOHCJn7N_xt!M3oqmuc@kjBwTSb5eIZO)2>R65Bl=7lk}sTa%f z=1SVVqv`cv?CYS?$cLKSd9l+WiLX`<Bk%36OiiKZ0dA~J7nI8q2Fx{$ty^9FYsWWj zYYS^^=PA&9XD3hgt4tVaZmFPb``X=><x{V!dNW$~b7-*5sO9rDa+BWrD(58(S1O>5 zrQ-}n>CaXzl&rwRXB%#vpQI$Zf;mdhJKg?+FMk-7B5s^HsMZA9OYZ62j9(N(P8=E6 zrQJ<9$`9Q;s`c$K>At|=y>J{E_Px7-zu=Asgc8sw12qfFsd|$#Mf6*7eBV@)AS#^n z*gT4<y3Wkm>cx5M!_DIZZR?s+ug$dmb4efjN0xRaSv8k1L!YK%Gd=553HD+XBz=2h z?6P;E0CQ=rc=I@+<uKEuOX?neGo@z(DU6b5%Y`;%%blJvkT+(_DV<W7mDZ{V1C^vA z%OfAB-u^ke{P=?8B|LFs3P%lR<!`QT`mK{9mB0qCK?pcO*DR{V^GKB_mbNiH_fA-{ zv`rNcs%QfuV9IPVlCcO<n0HrYzlFlzN0|x-SkLHf!5_bIK=;SkPmR9sgSk^$GM|Z> zVDj`Yo7Qn+BNCc+s~bAvd|I9Cx2@ae{birAB*CP8w&#O!XsY$T@$=hx`3{i5ACTyD z_l48Q;!oRS18a5w1HG{m7m|Il2;BM5WpsD*nN=U_K^YDa95-z`m}|_K{?|w0O-J4P zp>A&<X=e4$YOKHL+^a^=1btb-)1&YUI9SfY`Pet;(naz6eB0&uwSzQoEVnN!sU9Wy zzTUd;GM`JVMjmhexyC0E&F+ESgyB5r@wcP8>?eJC1BO=KGwuTvG!y$OUUHv0S?YpL zSKGVRS%WxM|B$!eP2j~OypG&bhxh?YKfM-ov)A^wVWbZ|?jJ{{isd+0GJL?LR$h1h z&t;C4mXY?~bcO#Kykq*YGyCTUl1A9n!okQ6mqyq^&%sF0$iUjr2$Gu{(%!+&NY4_| zW$jX9+diKe-s@SXmtbNbgOCsp`z=OdU()J|dU<7@IKExaBjq4vEoQAHxncghvmH%y zU$=)j^il!`@jEVQQ)auF0)nrBBhtjUvbl39J*tq=h+SS?{aU#`w6tKsA~-e9tkc&i zUtuVcrqekMq+3msfB4{Bn)V@*xjymB{y<8^3+;Iy7qZs$ykYq*UnrMo_GF_#zDQs5 zUbr%yMi8UN`kJxkg!IyV&aS{#FV#=u#;e3pqq{-$jF>L9r}-t0&C)y}rOD<XZ#gcF z(7xT+rjTdr{nxis94k|EQdie$&EQBWqot9#<&fm?E(1n3I#O%bnv@23=`cfk{SC?O ziitw5Oed>lxLox0+zm~<_C%9o^>y^-dM#h*7S3yxwW{Fvye>c3g`JA)e6FT_4?~jR zPZs7{Qas>yD!ln%U=n|wl+}F&hIXfcO|CI)28y;jwrRSZDZN=Q2CraPvhYCXwL2)m z+x5#d4VWl9t<!YSG>LydDn;gKy?tt$<(W;qO<5zA75U)=wbP$JO|W_BBx$A@*<K-Z zk|IVY<@66QWy4jdF!{CTp69{2JQ<WaU{oJkUcU9?`{!4qx9{_LT|AR5{Ly2UnpvGx zr<O|3+|;L2#x&mt=`n5z)`*5Xlo&%_F27=UG(9><Az~E?9GW(7K9uJ&4*{y+#l>%g zG98L?n^XD8L973UjYZ=?s|syREy{}*l;Vys_O@8@L=E?<NaD?}IBQ+BBm2n`7eb|K z!++S{x7zFg=>QLQdzb*=v0&jTd{v1f2G-(}rWg0{KVWtx4esyK-o4d+2T1FJ$$|H+ z=v%GY@bz!(WIO;i<9cb<mEZtUU={lFk&nZKb@W;>V!3~r*`uUKk||1=vNP8J4ka+G zD;nl<+Qv2ELsb@#A&;*$K$XlML7&mhq|X^f7-xhT1BH{IGT;oWe&YX1`P_^lw4IdJ z8efZggS-B`q5g7GdOL6Ad(HC&E~^+FtswQti0axS%7#ZUnK(0=g^<SRG=o8@17|RS z!B0vh#obHAL7k42*AN{_gtey5TX6GQQ(zR_Rp=R2*FBb0mYxao2aIvswAu(}gp?aZ zZEpQ5)u(JoQ9M?;E87%kBdQGw#(Y-;Y!MW4FpizmTSUvJ!6qp_#!M7p**mAWmJ%TE zavx!dk3ndV!HNvx|7iCMc7`+Q>MN!}bR@pjm@VI(;CkN1W~S{gbM+Ea{a{`EC}%Zf zSh1h5#H4SpIaC|2A5(c$$pY<arkC?XAO7y!t}f5-_LOsJoU8m%hYp&w!^fByK_zn( z3`?H@h0(m+q8eTeM<NQWHA#phFcm*%{_(rB^wtKQK<DWP4J05_4yFgF$R*z#-WJ_l zx?R7@w!X&Su2S~Ln+Uc-tD6j^f3GH*Bw;O`Hbm<ng}GHRH*pMalqCGydQquBvy?E? zFOw}BKpGztV5Phw^LEvxkC%0i<8@##y0E4c)&OrSd<{9HyG*=4e$!qW&2q!dW*^Ld zr!4n+AbtckV|uV?&pY~bdJudm-1yAA^oy}{4pliHz=77leFop##L%Aa1_M|^f@oMO zRnyQ+O@rMq_q<;YI<I@b$j@z3L5sZBN^(c!>&|8i$Efc+fcDg%LCcSxM!?)L(B1&U zIQc0Vb3M6eUEln<h?ibfc4%hwx>#R{^Lm})nwfIS_){^0Z^M!!*!#BiPO~+H^1M#7 zHuwHrZQGfKWyM-CqgJ{9ccMyQv+tK@A*hOR{h$G^jIPgCBp+l`TA*SK`>SM3m`9L9 zp91N2mArl;zu!@sAMh_#X<Pof2Q<XRaYa8b=wl6K8e45Lti<xXdWDJ7T=OFN=xUXe zl6*L01J8mV5@7bX3%A+hA*FG<8l%E=BUi`i9RW+MN9^FxctYaQtxMG6S#H9L3~7W3 z;!f{oxk}y8n6-+NGen=<rES1RU7vs_Txr8To5n1I6c9O)#&KxTg)c=#M2jcvqOy$w zIBa!M!s+G*1J3}7zz1KObJXfLo%<5GSZ%bkFb4izzY*#;2zf2O<o{e;SXkNqU5xYp zAff4KX&L`N)j9(M9rJ&?`YdW_MIScBdS?Hq)(?ax-}GaB5O8r)q<pk+Lq2QLed%II z%~(V^u_A`UFS@769P2r3F?G;qA6#_WTwP1c`t@tikO#+$=nF@~XA9VCOJxd&jMGK) ze(A*EaM9D@a539PWsSwh2<PwUiI$Q{6+MlGCykng^*W9r8X&_sKNzNFpmU+i9OQ$s zletw$4(1J;mXW!Y$^4G#kWVFT?eK#I&^LKN<0})9ARZgdEA%<Xq?*X#&KX16-!<W5 zeW$CEtZ<7cPk|j|{m^>`!V*MMiL^zw9}ua|Al91(MDpxIW`(KrcsM2e0|Y&U7#P_g zoLzWA;kSeb7Y#xA3#-Q0kj;Trok)rZB8$o=oIAC_<Rmb#aVg&@K6cQ9OokYFUst2Q z$7FZif=>E|3I&;cfaHf0qEI*rMnU0^HrC6?AcN<XqpnS0l8n=*BggC~!=duP)65U- zO;KsU#WfC$Qq96g^i=Ii;0Hr#mwgdsl7u1-L(#KUIPv)u=UxKmRvN1nuKC?Tas)cx zi$9Fy+V{Z^mH{*!Y$)0Nmxpk<G^w9uM-;ddkfNUrF_HJzNy0%2y=IhdkOAcf!C}8H zI_%GVXD5*4_Eb?=36|P{<Djz%YJL1#;n9Z;U@cQLI6+wkXKwbxPT@(ShB4PtU@6!d zY6FH<S|Dpj=}^{c{QG8W2tp)WWF1Z734<X`kfLB@cTouUZdHAm=^%cCtj(ZD>s1jB z?$b?#F=9z;<w(8WoB>&q+ni5xyE{IYpTaOJS-fsbIe)+EbPwxK=W-io*M41hz0PNM zc|6u<dtR$n(i`KlvaF0_zF#cpim_wdWc`^aoLVtC21Pm|c|8EGong3b2JP<he%5=t zs6V}8Qs%`3<-vB3qzaOW=GX2&Wn9|bMH&`$eS`fPUU7-emXDAeCMjuozkGjxa{Z?5 zOuh1YFJGSDME#_}DI&Sl`Pk0p=u-V^?{0f1ig|Fx>595h-G5ba?mpMq_P+0Wtj6I# zntjIceDA*tfA5yG<_}d$Cvd|nnke*w@Emss5ACrSe(A0kb8Ql<3YHSjWBa({fL8sQ zO^2LTl8G7|duh#0y0dVTuToB{&76V}*3E{Yd)m<5W7``m?N!{Ba6)A0+tNJ!_T5){ z6B!O?d=kK{uH%gOer<PthJX9ZZs*>^F8^*IAS@u#FH8^}6fKM%`L>e7_(y=AOZ00A z7!JDniu?QTr;W$gGf&6+etEmjM)&sHyTPB+@phf<&!ekk>ysCF2J0Gh1V4BJG`%D; zJE)}gzDI&MHjbgs57qYR;&$)$?>(=+x$lE>xa)3HoVB^_ZqN2^ovt(M?WgZRF|R-4 zwp8TR_OMU=>;%7ojM5Zd`Es_pKJVwgR;q!AU8h8yByA$xRHyvV>L#-uIeNJO$iMHM zPRG|`_Qk8l|C%Q^U6s;EsJS{WR^b5t6}Puwpk_vTB1YQn-tG~jc)27_#2~UPZ@C;) z);I@sYNT@Dk_PHhCkXD#+Hq05uV~hNgN$h<87n86vzX+%9?#P)hUR`p&}9cyc3q+E z4TbCj8i&aMswzWMZf<C<?2~FO@!@}6+T;miOFTxtD!q~KVNA2{1gW=h7wbG*f_C6k zdMUQzS|8e4F!=_jjcozegl?R;&>htcw3l!9wKo!~j9u@8<tO7{HLyN9hm~%8+u{b2 zK9GzCM|L3-rLi-iVzIeOlRugZuemZ`uSmUUKb+bytA2IMXvF31<G8K0Nr1#95oXb) zuWnLp-rywgBvBmEl9j5VG}>;C2B-%YWrCCy0~-d!6G>_HMMN;!jwr0aU`xu1^;uk+ z3shG~I+r`5&qofR<HM5+%7w4d02E_U<I_~9PDkQ&xNf5A(uI-d`+jQ1^%oj!?J+HT zbN0s}Lk*e5Y}nt}8Aw@at!0yq$-uC{o!C~B_gvOhN=cUCSFQk=7n>kmFs_fMUFk`c z_?(SjjAQgnufTsx^iHjq%PC?kA%ig!_fH#p5g$^ydsx)1q*pD6UMll%JkzaYf2n~j zWG6h2sSv1x9sNgPAy5Z1%1pTae-*BxQv!C_arZG9!3Ug#$9QaTqyM;62RF)1_#Sid ze-+99$7(>p4n1x>Ml<Mup75WS97U@H?6Bg_V>E*g*a?^MT46^WMZHQM_C2T~K_fw< zgCc^Wf+B^nVQ?bpfBp<Gql|>}F_Ql(D)RXRKwy3|D&ENU3V^`<=KMd!C@0~4%!EK) zfy6lb43}&oM1oP&`~YbVr1EetXnmrL;!^F6W)>d=IZ~v+`ZeHVh8jz4$51vE+Z;Le z)c{mATd|Q^GX>i=EjBB5KiG<Fs_4#<_gJn@)yDy)eFiABgT7IbOXv;P$yd-W)O87$ zXMRV4WIJ9reWe77{KcA=B}{g0to;&tpjwAu%KoB+Qw#oPMRH3HCV+?qcu8epRw9yU z!t<oNS`}mQ)Ge%O5AqEeA88BlQD0o<y>uP3iuP|qCQB#+sd|n@sBzC&_F;^)V%Gyk z5&5>i*l~)T%UsW%vqsy@!c3~kowI-6%T%WN&n1Uz&-ytTrzGt=O|UmBOD^5{&nV@Q zocyV^lN!j{#oocMqIH3ehtGUe4xrVY>f0uX%q*|OOIPcNX(m~28;^x0?j3UP3GV*b z{m53E)xtFc?D*7lzzrom@DirS92<|qANGh=3+Gw2Pe%3`fqm%`%Og4$n(SoCZPXgC zJ5{t?w>`FFCn4vS0;{S`LFrsFK*|z=J#A+7U7pvT>n>`PYn7dzn0n7qP3sQMr>$VZ z^G2Tb1=&arDkZZ++!Qmh1lPpVU=kw5GyS2|rEE`L_QleA924f@Xag-kS9yZx(4#`< z6gd2Jgj)nGv{`7or5Ydqs<4}-=5wRdGO=N@c+*TdeJ`p!Ut?!5Jz8o!d774%o@#q8 zCouyX#b?#&fGO7I`|a=mR<1~rqR9aLPCypL+@gO%Iw`U=6_b+JnT#v8J1hbW{lx>u z$G^0*PrD(<sWD}L_pzTlL^O@rf^7@=in(kswd)|0WTByPuk;5=7GD>SAQ@cea7-2w zC3w%eNAZGy@6sFg2+GPi@Ktu7|JTIHumnidIt?*{-4RSii46KhU6uS8F&h{^VC*Pv zdZ2PEeQy$a>>&h6!eqwup2z4|<%BKQ7@FP!&Yp27Zy+nLoB5^?LZriFxcO8pFN=1l z8}TsD^`-c;;)2;%1QOfbigK|{R|c0-O(bs@n6v@yfWuN2O-nT4^zGEfUM15W2Pzx2 zx@t$>p$6-Gmq9aOf&n<jdDb&fJR;)8m1x;`;^5y~woxQWx`iw+l%Fr2KU{-+IwuiO z$SO5-N77<ilwQrNDqjV|khdX}O78erxt?aGemYhYPy?&XVj~W^cu>!(vy^2!1n)d5 zKGO!=(I^esG|b|<S(l@$-e5UoDIl5GbQx#4?zZI|4^`^k;buH<oH4}%a6G=MU{-VR z5x_wGFesF6&#J>sX)63D%)K`!m-pNirS&j#C@0I5s;)O7oaI~;zV^)l+3IpE2YJ!n zi=WK)gN#Ja%P+^!1DJqsHnyLwej?7gGucQH9j&k}{kLpNp{+K`cmQ(rpKtyuLfh`5 z69#FxD+iQg2|J<#QQ@0}u$)jMW40>zGNJ>Qu0SNC#5jw}QE8}3uEn|wEbTTta%-={ zUScy=vT0WHj;6$)hs>aW$?&Jh?0<#uLlhP1kP_(O{4(F^bnRQKxp6ce+i(}|0%4ir zu!iC0#c*t=Z(T<B{e&QSg8kT`oRWc0=4Icza@)vAczFfBwQyi)t=1;TR(Nb$ner@e zw~Tb&UJKiBH?n(X>zngA-H|?|oJfY2U{4l|AArbwzvUj<6CtqytJhd3RS`2fEeXP~ zTy&BnPqo<A2rfJnx3^<U`ngvV!m3yb4NfBH1VZA}uE%Q$p_<-Mh&Xf@iH(BdSo5fS z2Hw@&J4$QjxIUPM6@L^b&F5H2fYFk1hF=A2F-PeAVZMA!Yk=i66E(nqIUnSi$9a;S zhKJVvj~NW(syJ;P{zUtAo8|IaJudVtk~A{&NY*Ril#H$n+3+TSQvxRB2BecSLwj`= z+2wC9$g0wvJaeg@cAE7t{Z(pci3@J?ngWrGJoaJ7e0x?NUoM1bc!emW^!?^A{rd4q zjU<VB%k3DFA7Z`l#k!DX;A6{l^>YmggLaA}!`2WfdG+U!dgEBDa*vJOg&&1UL#KB= zMp<!apf6rv5c{hlJ_?khf7%cahA9o9zt=0A=DlmlmS6~4o~Jo7V$BrQ<b&)y`^YoI zTu}EHb>F`mETF{y=QfL#j{e`bS^vWDSQ!87QI^f0QI>R3_<xMDfGf=!QbQ*XTj0CL zuay~ET9Z?g6ync`7Wwf)k=A~BxmzLTNYqpgRC(6=UY(wDd$t*a24uGSXWsYXsQ4!v zQ`+Gpg8|xC{gn=pLk5;cQ$U74HapvB;fCzQgCS6H325II(pI4{HmZZaL2f@$hMJy} zJSm5wy9aj?BD)K{>C)`9_dvnJ7NRYr7bQ)O2Fow+?fwNMQ!BuXB!UoDaxIDCpH8!q z>UWXpj}T6996YDV%55C-4qe4?Y<KevkgjXPK)MD^4k_1@iUbO*hp}jE)=|@+k&bul ztFb7SDeXYG%{8`(pZSOD2M=cX(k?-eH;)Uso49Y)7^?wHj{O5>((39-b_Rz%Y$aFd zsD7}#Nml4PowDz*fXSG>{B8jet+!0xF{4-DI(gE<jXikh6FkQ;=M|KRcZ-0>=S`@x z^9#c3sQ(AHh81#$6)ke6=Zxk0QDGikEjp-&mBsz8mFZ%>>)*Nc+IeNX;u9!!WbGR# z7#WQ%=9gYO!#@VwMM1|g#5!2BqpjIWWEuUXBt^<ADmwx5oy6P}tql(Qm!dZOZ3em> z?#@s^L-!EjNPMs#m&w$f`1|+a`8whBbAew*)WF=5G&!p|uauK$2Z4@6In6Y<JrHtm zjU+F{qiG0!hv{K<ZFD4xl?lkqRp}zSS)j5=kRn(}5OFLqK|2%CZM21y6r;s({CYFV zV1bNtwCQvmdzPB%vEd~I=eDT~opl3FO2v9s+nrOa<Jg#?0nQT*`=(|!=5s|i5)Fpl z^xiv3bzExO2Tlbx7u`X`V-B0KmrNSYknEHLIdmb97PRYzDoFu9SU;AlP8d(dFxN7I zct1C1(XKyAEI|cmIEew%%9<XNIWG0@wu+{^?Z&W_v=fxs{G|9UHdsIIaR?JGLpHX! z{ha_d&}%0<%z;Que}0x>t=Ibvdd|Z-5WP2PXt^2Qz)`u04=R)ttPw4eH~3e)`u;bj zFqJ}-@%BfgN-uX@81y?^7dP3}e%?nMz_W9Eg_0dSXH>CI!4>?m!mJMx1H)VaT1eN5 z9`qr!*cIm>O2HcOGhH4xuLEMEG>=Dq79=He`uA>s6bM-~zP*xYzY~&Bq*iF-#+TRh z_}d9#>S(n}fZ=$2im_U<y{72QWo5#Gkipu?Lzj#N$5gLJQdYU}+ZKkVP1TDX?F7w7 zxAeH9vX!vT7OPKi(ih)fsfnoqWO;PIXn+KBw8&|iEKE{2;i;+Yto!T2pRFII$c}Jn zwPbu(%z`JKR%7@#XDUz%4}RYTO+0VbH&je4=nN97DV_b+IYFr(f~q6*7n0eeMx+I4 z>dwt~u?D&Xbf#%IH-pXuI{7vKzEa7O;70k8?5Hn!24J~S8MaBhbN87_E`F)l2EVhY ze@b`t<;5$=4Z<rOG(ejD<fr=(foo#R@0iqXBv(16BOD&vxUD;Il1jIiz<Lp*kLoi^ z2Czc{fQ$6n5%gls!^L{0+I}kr7Qa!L*v#Z<&f#F}T$*;NFzEKV0<H5srz*o|algs$ zW%2s3V&Y71&J$+wn(>={2<Pora-d<;>92b61&uBq79VMuU}IR>?rG`B)#r;=Yh4K> z+vo9LJo_hDvu5(oE0E1j-7z({^r<6M7c8$L3;P<el7I_Nh;Sf_f8LI}elpHHRGRy) z{-8poKQzs|A1zHsTw|_3VDmK8paGt$8>8R^g1ZRN4qai$k(d%6+zAl0loK1ZDGGA( zV~wC6hUg2VO~D4)c5Paz+;Q7*v|Cm({<bU5z}S*#6s+=>2Yx>{O**n?a7&aah{Jn~ z2?pd%`Lm9-ad6|-i7cEV1KFsKVYE{_lDn{^Zd+ejui=Vf$0EVB<2InKjY?5jJyxq~ zbat4qXSE-=s#z2whf{$9<qD$V_KCY4kaY@H&8>MB4lz;b>C^HN(rRtaRi{ps9Jq?9 zr0$#><)@ZOeMkemVB!udC%}wL5z8J8AYmv=S#yj;R(Fi#*?diEI7B#9W5u6(%e8te zjRdPOhI)2W@P<K$fpOLa@*$Bs%|C$MG{GmvO_!L<bFb^zq)*)x8D*gn(Y1IPpY|oP zp$<oKCH-8GekBF~g=JwSwAMakL;4HPj^Q&2&TLFG+O-?`^;O5Rnd3{2#kA{irKJO` zg0j}QTi*z>lM(MkA^$<QQv}ym+}?(zRIzi!IPy>h-&nfjUOztvqU-|2(X#ry?@I@} z$#b)5Q(OP(6FxAQH1GKpJ?xVz(nAdWC31W21rx-#w9y`LRKkpIGw@g{*XiiI)x!1; zM0~ja8^GqJ>-|5hlC&)Ut|I+^f|2xW{|-j}_mUV5t?GjxFtWRwKYA33CR~XU1(1Lj zv40f=u_xp+W`GtnL6nFuE>+i~bL8tiW6tt%W#~#gd?XWn;vu1p?5;#rC%8bok$$jL zu|Bk+MV90UI(LXn#L1VK>VQ8jq8y4-E@G=~Oi;1u$Q3`SvQs)CGz<6lwL|-_&GZrp zNAXz0I<)<SkvIuPqN&+J#zM&>L>VzDtvE8Zt*a5F;fBpzr1;f%Ht3yAuf|Y&{Nx*G zvn{B>P%3wtpO)?5l2nR+aUDUXueFUZ{y<T4ES?k_G)`K74DDA>ZrEiMy-}HlH?xuQ zFu&s%+p9AKxx%tMaD>H~3~<Yzcmpxc)ALTB+=?ioLoo)VAzrXDM{^Zo&X=chDWbb2 zs02|Aa!nNFVf>VMm5Dgq-#E)8yr%EcxSdV?4+$k`{<Au^Tu4Jy%9!CiDAvxj?C|SD zJEH*OL_IYJ;JQdhLqKB1;^{-Jl8Mc)01f0!`p}%Zi&Fb3pJt=(y#|YIrkM3IvUG~D zzx+n3SUi5o=}N#O2|9M}iG(CIHPP0e904OZ2^YLV;6q2Q^deUHkmlor&@#z0q0;?H zB_KfqB4VKlL8FRw>!t+}pV*?Y08|gv(1=KCaOtiA6(>%?eSrAoJnt7Wn^S+u95F<> zZiyDj@M<}O)(eCMOX<5ZVC`Qdx)Fe@&uBaB8!{Cz7^~NXr`~JgVu5%|)|*59W~e6{ zk{*fVZmia9-N{gRsbOoY(CykisD!xLTF5$bQbjR{3H!jWPbrh_arf|X=>6>}InCq! z{<Jwhe~-F7MYH}`{r&MoBQxFY^4t~utRn;*_VRe|&G~(NPt%=uxp(^7Y~Y&O)z=>c zxmck7>z7&|Q&y4z3<^}*r^nkt{ON1>>8r|hmj?@%H~Xid=k^!#)=KtPLxOy%8N-D| zr00Rs9R0FU6#cZ={mbb?eKyzbbvG=7EzC^-hh!8H?ncJID%<%54p)*9R!tyZX`vcZ z6Z7*Sdj@R@uh11Mks3UE_&jT+y2fb%6?vsv9C2DYJ%q;zzvou*CL?W~NE|Y7E|C%p z@hQNM8ObE%F`AHl`o0N04bfrKP~3sIC-G=5zc+_8F>Kt=hH|Gv0$P*%1W6B%^i(VZ zF2i|Oc9R?G;e@Q6-o`EMNcV6idagq-(w^n2ae$j3xR`l;>`!}w*KWr$BIn@+YpeW? zi8t(VH(&N2|C;sUo@(e8f{Q1UtyrsJdSO0s3@!!#-ZT1q(m$LnPfod>aUfMVHjsq? zmKg)DqMk`PqK6RQP-plD$vy+gb`VOilL}HxN^;OSODU*T_nH#b<`aEPgC4oAeb9rO z@1RITHYKF1(t94Ns%^op0r?T)P>!y=<RDflrC33)R_4a}eNcxT%IX9vR;x*UrSpMD zsgNLsQ5@33Z8B~s$G;vSoSk7~5J6Z0A5NF6wvlDAv3CMo|EkZ!hlLkU0tq=$-_HcD z$?pZe0asnLSh1p;jzVS*po{Fy9W5Or6cVY)HT1XEB{C|Xq6WEEiKdshI%n*CA^rS{ z2OSas7$Dz`G2!pAL3_LLW+AV%6T@5OlS;{nNs7v;6!L$^HJ5|>cE{`>PV0`~Sk-ct z<4JLfr9#<8uneSI?&iLb$A({Lvch-;{L2@#HrcF%0;ff2`GTPx;F;%mp*X<X(VGE# z{vdJQi>oZ-N+ap$u>;;J`PkFqobs_)=Ix9;{Y1rq%n``w2!YxOG8G|sPWqVbwd5g# zSP{G;EV%Z&E+3O+L@yXauKPjY{}t0lQ@Bz3Epu~gvL*+kHYyZ=GV^Q{Dgg3`@WAed z?qsCz-1y44t;>${cVYb4Mw|s1&m2QQzdqL@v|cFQ$Yhd83oR~%Im>ofZ4#<Ao)w4f zl9VyLn#fnDt=%}K_@&NLSkHMR+|05u)Kq8rVi9ZXg_OWf(_(1|mH0_hK)Gu_LDA~S z4fObz0s<twPSmFD)#yn9x5#)Pd*6r8EbVlpI=}kZWW^A@PB7AJ2eMAPBw#i|_TG2| z=A5462Ww1#YU)E2VyvQ)bRMO=SttXXgwm0wenTOPc7XV`dD{%*Xfmf28hSR{yjVmu zR63$wl932miszHkmHqwa%^)2A;oqqs=-xZWS}d37j9_|I>@<0bLi~a1kY@i-!yM8g z4<p1f-DK<yYgR5+BDV1R+6%jRV~3`vG5WG=epx^XcEj^EP~5@Ah_t~hdr-@32CB+q zqgo0zVZj(m=Zpzm%U8;&;pGgQ7jfw&iJM5aFzKVHBCg>zw}`Z%xqEfpBrc(;3uxHK z6SqoshEdq~)gJ$;K93LexWP(#@sXGgOHxoV5qoZzNe~AXVnv+uh(3eRrX=8cO15MQ zbeksK^`WDnxcPIp53&Tf4eA=?hAl_3t`A#8LfplGh<rv8kV7MuG1z*{b04Qiw`bpV zAD7L|V$~QA(G@%O<+OR+amxvD1Ba?k6`2RulgBN4fmZivvV`w!h;N6tF?^MX&-K$+ z=kD+R0#V|&OcLIis`+*6@3-aZ@8uzY(@2TYUY5LRCSd?xX0Ao$)Y!4P(IMcgmtXMN zo$l{-re_RIp-^=*PRqt!#lCa5PKh5ZTh$*YAP=27bQdjWUcW!fEL70;Uhki;lW0JX z%-y~|=BJB}X@+^Ui>kY=fwG%<qKc1ofJR;3?;@|utUF&Nz3;EqpT}3a;+L<z7~Zni zX|_HM)*=X07S6k7sgW!6*LbY2XGayy_LiU0Jw5$zoBfes%{f?Xkz7y>QSYcvs1wp< zpR>=t6gs~R+i%JqFDnM5a<oL-d)jf^W1RV%b1(cZ`?eS^x#s`l$$rgU+I`ye`c)~N zC!@uisSp|1k|&||I00y>a(KLKTz(LZ{K|G|?by+DT-7dZKZ2f3CtJ}e!(Evz`2N<^ zXxMd};#fDWMT!hsV2ORN&Fq%SXUbl4WC<#nlFZ)`kcgG#jADY_+M&r1BK48<o9HL3 zOr3>Cl9++1%pf#0sLAOttJM04h)34Be-wgnL%PqyP)qq2_?Du)5MA!Plj0C2bJ>HS zh|v{5t5p$EFTbGuY=yp5W8uJDwINK`K-?G>i95>Od}y%^w`?{zKX#?WLq6zw>!42` z5H!HSkx5`qc@@;%p(fK>T+&2ka?3-*OW$}RhjDFBW4AwIVj$SF0xgbd1`%&=$&`4F z3x~13qr46|=_7!##&FG6PfHRAriE6*eIAxrrl3ft9qOPsyx}z#Nk909=n-2+G~*PN zgISTRYLk+;e|33LOdgh%`0PfRsX$0I=}6-Y=WtpQiiY;-*uGnkAnf^uExoSF+|O&J zl^<YCiEffsK?pBFcA>wGIG_h$5VKO(QBhPV$zpRl*@mjzwlU53w~R+2_wJ_X0f!_C ztoB@{|EuVE0RS9O@6Dx0bv%5*Mz}nXBPS*A(b)ZkQjK_Oq!MeiHbEr=+Erp{2zo|s z0UT?&W$!)a)G&4H3)>E~^PR!Kh0Ct;l#>~^cq&Bi{LVUa+0yS@y9%JmC)Hr<uLBC1 zWQdy^u#6G`kb)D;DX=pI0&=!gyDGkqMBp`XIG(p?TDOBs^CLQS3VRvoX5$soIkiyx z3C;b)bmM^>p~GL2g07<^dS4g~WIJ1q6ww5Ba>8en<RS-_Nfz`;sV0<jd<Q7y`O^YD zM+wxLxNCkf9Fs7AJ*g6=dOdQOA&fZ5;cg*AGoUm^y6n~2d{R9bH53BwHpiWA715hj z(1F6G<jGlY<qp~Wb$wcLox&yWZ?JN*9A%q@jQ<>pXCQ(fk>&`<fA9wDb=gw&(1^TM zbeJu0Pd8ME9lP$rb~XXWT`>3Z08Ob1i~(hYq>k!1&?iU+pH~ddQQqSx$)A_{I3_SQ zYqmc*GInB<pl%<OBPl87N$<<zjqfrG3G`wQvllShIG-~-C#K06%oJ|jMf)g-uV`B` zG%L{X`D(nDfRZhlXopV#cb}f0O-K<oC*BlO@c>ElOC6IC)dg8}jrpWSoe$TSdiS@| z5mq^8c=2zOdULM7aZG6fy-TQj^-M%3k@tCjhBzrXWt=|31an9)JXJj1QqFDealT?u zdLiSvYxi}C(7LgWrH}A}r{xIOHY1px){Ol&A(#tF%BY%5|DwjvJ)-oAL#t`NIUuS3 zHg@#7zx!H0G&0@)OlR5e9$HUkvHsdh>W2RKE}o^`3LJp3S=il}=?%?W`wqS00Qt}l zREQ$1$B8NFR3!!)wm2gpehFSz__8`Vy)3<E>av73S|R?*w759ecdMd86s$>+W)=>p z^+2p6<O%hxGY+CUHX*?%2R(R?kL+F86Em_AJanzwj(nLPjrufVYq}=A%9fSOgZdA9 zEIQ`@ghVnk{nzsx|9|(@d?pEbLZZfX0G39iX4g~9>VLSeTC)GRucrRXebrE*DT5e< zxk2bH7jbld(|#H&x){wJ^~ZfxV_Kw=<P-M}9~lb4B|jBa9~ojdkWR?YCBO7}iA1qs zJ6hWfumVJ~N0@6<hGF$;hW1VeIet;|=%4nhf*PH2=hY~HVi&QEW2F2DMq7qkZtvLc z3aaj>zC)~cUrTZJ(YFA$C_U~+nay7&dQd<1tBd7sia7$&y2y8`EhQj)Eq;@-AtvoV zP{NlOy;=jrGZcU%V2wvG-K0X~^29~UjD-fqR!v|htPv@YJToyut+032ABMRU)|028 z{jVDLISe@APCaJ_W=!Yk=;6+JRN)=_$*Xwo$Ul^ULvuL^JMd5Ob*d@2l6Cr~`?bI< z1$Ut6kvccH;IaX&=YXBrV8{7aHV?4&6%$;iP%1owczcAZB#~R6ZSFT^EcA0sjDC2q zrzU}XM5}uRN##3~LbwWWed$dA+I5K@>e2h`SqNx9a|}>IV{VL!Zy-;=VFI-EM;ZF* zvJ5$Eizl6z;J9LJSw}{^!$ul1l8CJ*G;ytpeDZ+oq{^*f$=aWjoHq>n+_Lp_qJ3zC z2`XR5NiwJk!L+_;&+K@T=(X#YpJsIB@g<l`H2q9&jjhiJc88Ait#OC3l0|m5q!L`t zZE4;y>(b`I-m|}Rk#czls8Je^hExM<?%%b+zZwl1dtprtLx)H=3KSV65_l{1opVoT ze^N`*BE6q*H~D%Hifv(h<4xMzn|o6)|6s227l&Gp)nk2hO5)s+S3cQvVC1)vAw84t zN!2>-zrH*nJM#;llOz)Ofp8KC;?FAf14-v_3PgUb6m29s5s%W}(=+7Rn+DZk=~AR7 zOE4rKIYqnjnl+L=RWEoWit7c3_u!1#6+#j}+qai@{CMn@5Ax5OI!HB!$~Z2X?>e)B zGeKAmeL|+4&!olRGIB7k09*Kno8Ix|j#bp@7s((cVDQUMSdvj&S6OnYh+72Gy)78V z$xMb16<GU>0Wy^!7#1ZUHNxmP^!;5KI>9DcKxEZxsMfnKxl-e_#6_&sf{pd5(mi%^ zG23*2F)n><m9u<po7C-#Y>Vxpme+z~d%}asp?m=o%R+T}^bd4@JHEYL)=uf&q?usZ z-0uyyKA1DEg1hMA-f+7_iUL^lcDx)W#m|$T>TmqEx%3uU{(^HmUw+BEK|nXKGaoQ1 znBsPfEvkQd3;1l{2|j~`NwR);oY@)WhWveziP=&psfa*!M?a}zx4yuTe{8St{%bKQ zaHEMw&;GsNX$>c3v>xLTMKKf1-kP7O;!&s~mqx$I6+%*H;LlrL%+-TX6kjoo{$p2( z{3QAAj+dvLz`T7m=>Gdzc+UB&o%w_RqmYM;jI9&2)<Cb^^FxEP2RHX=RyRG=3lj5p zUwebl6UW{MeP-zc;Q%lX?m{-nI0b_dy837#`m`d@36e;e7xn>(kn*GywJ&h0+O1}+ z>6JhZ1f(7S@S3GzedOC%x1>(@pOHR6yzZLCHNN8%tSp!bNp_G@#nTeT68iXp){Ld7 zP{-AR3J`uFi)g>wN^yw_x={-=P<8~qg(5a5iQqp=(m_*Td)XCr^qo@`13~Bpar?Ww z_T}aJj+Lhh^uduuUF5fhdX1W><3{RO2&^>Gi;TC)@@?Fv4}7Fl-@?J{%=<7Gn;5}# zEmHbjr-Z4N(xL9B-~$BeqYi0jO#8sGv=z%mwvoBDQJ*b)g1#Vg0lHr$Qa!CeXb~yh zetxY!TbjY#d(1zYm=!bI*dwvOOJx>*DkSN=PAusO#OA#jyV5x+lRFr?5~$!4@lYdP z0!;oD^NQuaL5gz0tr4d4srE2JOW-x|{cs=JSL<X8MTAu0y&WwR$ac=eObWF5z0;-~ zzC<;O^ejnf=J>UQ%yJk|4?xEhS{v}$zo$T%`x!?zMoz~Hq0xJ!chl7krxnV9(?!}C zIiBI`l#Gs>=5)B4vbE=0S*=V}!(KZ^W)H2R<+TW=$bcvY`^qxKOMp|Oc9v1}ZHxIm zyckcSCm>x(dm=$nc#wC#y8*(3fj(q?x=Vp9ew;<7Mg@RJJ)?El%5n5S@^W?GkZoCo zGJ269^y0r|kIv4O)FB^UJ4?O17mq)W_<y@TJ}*-J7}BN$=D7Z+m5hbqKg`85urd9& zlZlr<8K*x!;$7z|Hbtm*#D0MAguVG#8fEguRz{CAV)TF10}P|c<cUfdzn-;p`O*~+ zMUb9{F!=#AFZS0r;c7%PBLy-~Pb}!zQ(xv{31J1c)haSW5YdCAk?j%bjbqufHTm$Z zCkRf-qd~4zlo%gJ+r*n7l}jb8ZVw5^e@7jeUDBPEiT|cJ^i=b(37`?fB}!q0M2~*B zJJF|mGat}RWWVUGNf5N#t!T=Z(J6`VYlnj+@}kV_jyzaG@Rb4D?Pqna66uaEfeAvy zKFRfJ$Q2UdheFTITmfIcr4uiGS199F7=ywBPriCDA1{Bkqi@&LoJhuzsrK$QdW+oS ziO6H}rr*`VEoC_J3-A>bSZ-czyB*>-u#zuu>)EuF-`<^5i3YQZyH<+4Z#-6LuCSTg zAWzUqbZu{HlM3TMRPLB@xo&1Dy8}Aw@)r_~*c`%cwp9^HW*H+FD-*Yt42xXjS9afW zoS3Tq+Y(oZn`nwv8Kk7fD5hMpP=L<=H)4P<1kX6I3hW#l&Y<Q>M9sJMl&*{U?GBmb z@Q;u!9A(AqU}YwG=V}f}6}$~U?ejjjb)A+K5q2zJJYc5GbVU`)BAC>69F+wyUeHe) z)Oa!0Hf6=>L&u`@EltDFtXzf>f4dc(Fo@$=fv7}<vk9szO+4Yuk0>%@DvQn!jyS-# z4wGG)qa5Z`z<+|aH5MV4qoQkoK--r$;)k7cP!~Kici^?EpO*<T(<j>k70qWugi9LO zP9v|h2vejD%KUiqzbJdhAj#TxX>^*^n)b9cJ#E{zZQHhO+qS!>ZQHhOo2Q@m+vkh@ z<B7BPsi@x-YelSDdEJ?LW%Buh%^0Uwh}d~7DIvkIFM!s5RS{K=s0~9U%ncuk=EFMp zb~CN;Jp7plE}P`3+%hq4UHDaB^WX!w4|FZ;Yr@&c^X#>sb?A5kImgIhaOo91TEF)? z(md}!ELqo3iYsaUvopP1QVE4oO5(t8T|&6bj9l;Z%FKv-{F@J2kE{)v-bt)#VE@P# zt28!FRph&gU1+|8<e>;QAg#S->RI3D=xd?WH1(<LFLZ5MRRPYD7S1tLv}!U0D%dP! zf@Z$FazIcaB`;@E>;`Qa!RwjeWaHY_yWTh=IF76F0E5*2;z*~k(S+G&kGbOM1bKno ze*@pg#3k0|v1VoOdUm8uACKDf%^%_E1NjNZz%hNz(`U`o7tt9O%)Yd}!yMx44fw=< zcHZ7nzNOA5fZDAg)ZrBv$0c2EdT+Z9aJX_NQ#9XSxwC6nB1~lX;XL&>nPrp4W}TKd zg>ly5=e%TtHsi8>hxR@p7W8>8w56}E?Mn8Z<q;HdkmPy*N??sBM<eq?v`G{M*h$oG z=%V{fna8ODdL50Aj_a3Ak5N!al!1xz>gF7h{DNBESXu2<8B?Zc{Bo~pP0Wv6&%(|p zj|WI^{rzP2HHK3aM6}4zDgUdfUTci_tiWP>L~(qbb@HaK-^6WH;_o6^Sy%kJNRF~D z2r=blHCGaytD7G2g9+H_aFM0cr?CcLT)BK4>WGicb3BbpK1YbgjE}cYsS7A-eaF`l zx9<(;wSYAAJP?+X%?t`b;Pc*(d?nK^C^mrM!r`(OlUF~G`v`uu^sGvZ3SD;)FYa%K zOurw0I3)p7@uC9ktt`ZTL(?RP*Np`<nc1JNAD{QPyDcz*T%o<e3DUG4*bkl^Vr<Ox zB1*YY0h%Z;oaebztTnUt))o^yPw?By3`N$FQ!azPv%4h^7Mn%3YNU$W*DzIg*np2> z#CcA-?CU8E_WP@QR)A;ra7f2-4tnNc+uFV%cWl6I2lh(3xa<|;N6QP^^iU@q0Kqr> z!uxq}-HQYca!J+gJ&ghwG3YTmvXsn0vr#v#{EaheO5A>-Ys(~P=G|_4hug6hg6Lmg z;{QDa?f*4KFfjeEU*ZR<>elHZXy2`!+cQbKCmN|c4VGA?Vsjgd3reFx2t7yuNPZNX zwfDD=Aao0w=PWDSM@S2}qqa%bEuHfT&U4M5n^FL4A_-S0u+FLWlYC-Yxz4K*AN*{W zxm0I%0)@!SB3useF51gJ|AnP^mYICoM6+kE@FeKWBwcjlQdPF*4A@U}c$HAjT0aFS z($NkR+UAbFO&G7YZ6LjzcHD*0z@h)ddq}ra`*Q=9TS5_j9WH8^6&ps+aq%`kru_+J z$;+qhL4$K-i|ae+Wobg7N$Jm6;uXxDyu!V+$-R0A3E6RmIO7_Pqv-m=)K5!bs|K#% zbf?ditoh52DIevLOL6F^k-#LolHU;|s%MRJhtR`cW5j)m(ARhMhpb!sNyKn%vkI$( zYk*z_DgDYp3r%^(WSj-pi}HTFiiEz2t`Z0M_(+3&`BpUhg4d8eHCKsmwQ#j$E+wA_ zVHj3Wtd&i3b@Z5nqRz>Rx!Rftk-7Uvz+5*b5*R5e%K2V#x^&xVAE;huS-5BXMJW8O zA`cD~Q(02~9dUBTQ4LAGxc8dX*wSBm4kBQ%b+s>#hexyGYAo6jGwrSfT{dWY<<+L# z(z&q^KI5Y`e|VQ;58}tTr4HT;L#wcC^JVM_ML2L~)l-n(TCUZaVX~^O$9bNYf~Yfn zraDOvGXw73+mQ{<fx@aKNDHw!WtQj2dCYtgM;7y|2{XVu#YN-tx7;SwGyo|i2kIpW z1OrgCN{BJ1LyQU|8e=F6L2Ts3b;hZWw@KF{^AN}g?9CDMnL38ujW2QnTx%KRc|*-9 z5C{63y7940zq(1I=Y;mOFu*IfdKlw&s8ZpS`T0o~v2ns846AfE;jKJ)g+D;bogI)j zxqD#w598^k1j8dk2%{+eQBgSut4UD;3s3|1TdZlaP3tf1JmWn;yth~wM&*>j(rvK2 zUQ9Z$D)s`EL6$oc*1>H*jd4Ot9HTiok1DB>dmv?WEU&Xl*<^6)Z~*&7dFLVcU{0%Y zHgZqu<Rg1*vfIPib}k|bgmvi!in08IlFdt`X{~p_e%2tJGgI0FS!RgIJAwo^s7Mlq z5}uAi?d1Yf0JK;JwbmV8HiWJdLjVKKs2@HnN5+uk78XXuGJS$iK|WkM{X+^}E}{n% zSRPK-5tA9LnO+=$7e2U%d&aALB_w7z7`f@3eYBhdB7S+nnQm84W$C7t6PLr-sr!eR z6XhN3Dh>Hshuz)7D~9790`fcS?=&k}AU-))J=rBR7&!;f!C0iSZZw3G=c78RWLLHO zNe;|Hx;j|<{3uLZCh#VHlbo{Y&7Vw8gF4A1tFx%BrPN$2mDFM*e*kBawzP_gc5TgQ zKUhMRLw~NX5K;1=2h{Wx2IBi2{GJ7NR|)%djUtLp4|ZDNqV7GJl(bD^Doc~xZE0?G zEGB-Z@>ia@abnzDwq$TPIr2y+i>j7LwcGW;HuXNm3`@Nhv{(EHd+Y{3qp9f1v-dYb zQO`(kPeA}#SY3es3$U(`mLSWv08p@lV}ebFNtZH<+M{>44Hm9sQwi5Ka=tNSaL=|( zj5aYAjFcoJdUgqBlq0NLu1%N%Lo{26r5IQx6GQ$};m36D?O67d>fiB)2C1Wk(5Ny? z3n@rp;5T7xWC+%niBO2gnip$MJen9Ha3wVcuF92$@zGa}7zNk%l9qWbRNI8_{f}A) zrI|y)xAV5U%9!$Kb#&@`@4+@?y~1~n%|g(i&uvGSWJF&NSFEcnldfcE^+#{$E1Z9> z^STada!=F0$6tG-O`ykVueztLyraR8{$jn@*p`+%Eu0eIy(ZdA1CjgV?u!`GKIJua znOU4!d(OjN`=es3h@fFI^WMzpiX9f|f!4cW{tNUaL@Zm`6d|Y9ukY83&#|7wMEGkb z<d>(?!^7CRLpm#pRr52oSe9JPzd^xw0}u_KwVoLi2gm;v_vvVv{@1-g18VBgYmJEC z{g^wQBRon6nzQ=pOwh=@(yMh~wIco?f<>0OS|h@7=^J-vQ!v2^hU)3hwI`hd46GUG zc0pSn21$}ANK7p)uQ!jUZ_IR=1-3>J8S9h8km2(BM507`eZ)<5Bf%mABll_qrUu0t z!rp6T=3Uv$FCBqeC<Edc9`aQb4PH%mq{gw97K+O!Lu=YZVnu(Y<Y`Wj?P7JG7N(k% zzdClO$B5dQGm31<<_ns;Uaw;%jc6Xn0tV>BiL*2JKfc%V%?Wcm(%#=ro5&AQ`}A`E zhGy5)8yJ{^ClxWa+**+-B<$(2tx2#(s~xGzu%6~B(Morn>tH~ax&Z)WF5?kd1Y-R# z?eBiDF^9I`R&h{G7=OUaclZWN6LQ4)3qUD{qzJ=5v!Jkf6JVcG%yGyQv&^+&kOI#L znE0+%r$|9E054@3FY_s6*o-MiHB;PAmo0xCHI<qlFz8I(C=<i9juaK&W~8|ay*~CX z)}C!R)qJ>(D-LOj!uS_c>HS+5a{EO?ZOsntkjxM1pPbh$)6AGP`<$s2`1)-$s$4PX z4~(bySxmgQ=7_yX)Xgd_8jh3d585^_TAVHt#|WfWP-yh9&rTSPBLppzoehD^1TlCk z3ZJEgxx?0(tTB=iV_=yZ-OnO6XO6Qa=oz|#r8yRC2NitcG_eV+of=_*$6VpB5XQ}M z#ClzK*`VWevfLdl;(Xx^0BOcCLipc>gyo8=E75;ek<WvVFFG+~3-uZU`{C-vah-cx zP=#2q>7)vRIF)^L&?f>s^J5&vamU+_nO?$Ho%ehTAF*cgtR9O{(~C}`kC>!&_M$`p z;HF94rsI=A${^|$boL0HrxcNeh*N&mLB3f1JIEfKbDt!gm&@J=9-N+x0A9ggSUS6i z9t*07#A2TO9t)v1!H+LD50{wR<tszV@j{poOw6!4l0w@o2Q%>cTZwRU1hwRGE>H$Y zKBPp^09Ay$eRu=y$lQuh)-zq|d4K*ysjA?YU|gf-?7G3mi*JZY$vucwb8i{)T|_A4 zQ44%l<Mrw8W(DJNxsdL@Lk>DG=#3dw;fp`zV=IBSv4C7I+?~PTgS!s=JLCn2k15W5 z7gf;S9J1O#Im(TW<RpZhLUE-n`!;DAoE|e}0;1{LyeJn9?H4%6E=OTW8(7|_{VYA5 zMSWXq_T&lM0K>lIxR#V{GdX%mnM-)mnG+i|E4Z-m-7mhvowiS_w<~?HKGCo?s!Rby zd@-7>e8kS=c6@GU*OiwYWA8}PCD>8gdL?paNmAZSdj6{c-7>82$WkUFjj3d<e6$>6 z<3j?q+~@b*b~*VjTN%W0N1~!A4lE<lOxI##tE;;KDYJ~*^GcxxkT%eGYe5`2WLdpy zl2}!N->Ju{<cY*vexk?FXSl-coU%Qdyo~O>;k^WJ;ruzD+aRI_yn?X7Os>ei%%=du z6g>ydMDB@=_cs{wx1nczac=V?yRaz{zqz52%luAlr%-|sD-z58qeNlflq}=cg;IV8 z6Fp>R@_LEce`=r&r$4Z*RbCs8Mt3^>iiv2D+Pi}~A_%HFbKcR)jOa6p+TiXp^rd@K zheN=hdoakaeL`zvw6tM|SwipXNOx;Bb7wZR*o;xbxE#k2ubwo#4{;*C4zfU!iDPq% zn?^Jg$ko~DD$o4n`gD*CKjGteHmAiG<q1JM)b4+s>;@Rwu7F^DgpDJts_ivaVrsO} zBr>y@x`Yz%qY7=D73>fS6^^Su(lR+Ie6z6ps0a#UnDBMrog_rpXfV6pA|w-G9R=HR zlBWPH!pyQ@6S?!dHW?$PI?p+|Kbm@-Y~-9qyEz-DAIonzK5#m+Ww8+S;y~CNO!Nw* zCy_LYXp|xF7UW()BV_f##si^})eYZVOA6~<UjCS4Z?<4NjIvyoWfoyzH1XEls%93^ zUtj)dx#y;eLOF7-0_tdh3=utw#xvQ`@r6t@SH!ArFwY{=UF{Ewg}&*U<87mhwg&Ia zt2+xOMF$4cdZzTas#Hf;?K4fTQupVcghAmax3he&<PgoyG?}nhaOLU+8Uu#(QD(;4 z*pNTa2~$Ny*x;e1Dy7JC2lJCm<8Le-Cs}tO$R|t~jz$tt8bCZYJD(Eh2L0L@&Pr5I zeqc0E+@v#k%8qX9$sTS0fvdh{b4S3NgrRL@_R}TD$AOvgnZ{B(v>CHyXU*0Jl5{k% z)qAKC>J8y<iHf>&RVoVLW+v$gQPd>*i|E-R>^EvVT~<%VU|z6ar}%1t7|W(l%Sf(? zIx!rguUPG2IWfh#hn78SiG*0_INT$3Ap5%ltXN5Q($zJ-GaAc9*#|!_d<wiTe65~f z`baw&@~cXQm?W`l`OrB99HmJ7wD}O0_{B$qqN3Z+uzc}_KZytD)@eLlt)7J!4(-oh z=~zKY=ue>S`trY`&t0|o49oPu2)D0E6%5#>t0@`hgXd-3%}SaK%;YC%B6XCNqN~Pt zkEsaf|0KZk!WnJJA%Mo>S97r6B{5OT4pd5(OpC{<-b*QK75(G{LD|cu;r(1nJA8Or z+*X#UQ{$X)<(XJzV)x-S;l0~vvO75nL|Bb=<B6<1F1Qj!wpkS<QIS+%OtfE|TB+Y8 zqYcQ-6wXkxZkN*I|MiiBmT;jhGH_32bIb#1f%VA^h3#G9PubkD(7@#f2<pAhm2&0y z%Z*%jnmbX~AHql0d#^EO!Rn38@M4{+;y!}2xzN-|1O8rdj{H2vdvs$9k<9a#vTjBq z;M&TWlI^$Mz<}6B8-H}THg^zf+w<(jy$$FRqN8;w0DnOE>hDjnNg-c*W=EL~@v56W zF2-<v+p+Z}iKM=B$N9vaIT`Kw*AeF5#5ESC|LR-$pQAbs)Yh!lg#NMl*H|O#SUz=* z4KYRfgPW!?!Nzpc0t@9?;v*h}Dd;_&v5#rWwXYls3WYrmpp2}voTs8s{toRRhjXVk z;?AD%;xJsDBZ-M~HBQd@Cz7hv2Vb<kF46fCDd-5*n3@xO2`#yXhT9XPI{(Fw?Bc6d z^O9LM?t8mTGUE9BW#zmY{U2RTu5eLA{*scp?hg9Aa(h)Ajsbl2ElJ#pg9;5XqvxvO z$?0(jhMk!<ulJqd3#wQ#cn&cGrMLCTNU8<*vR5)eu#NS%SDL$0$@%?1k(GV0-|<t_ z*cBys5aK(eQV8JGxYIzhpkUiYim}3fObP$feBnz4geHS2#bCVr#a7%K9BFk$ivVg{ zHMCm1fc#HnrQn8_N$w=)H^VuKlQr3Lt?T?3?(MzZfx647E)uEk0r<_NQzzqXs+VA; zwLDw%vfb<H^q1MtAChN!{4}Pb44%c2*c==O8#WT!AS0?+5i`T4*C~><t2nn-lrKyf z*{~c96oEhEnw!Q;R>s!5>hbh5Yz;#@lfZ^jn=A6Tf4c?Pc=UoJcrVCS6U#GN9WxBi zOb`gmStN9R|1DVnu@Gpo`J@dDaQd_b1(2jrLkuoUOU|kIffapxWT5Q{c#WQi8lqiD zIlCJ1Ds_a^GQ-FDg-A8E885|1%&bC`alr0L<|oS{;uX2f)SRAHv{(27l_Dm5P^Ka6 zV2&Uaw~~p0?M{<rkhn}77gHtT6`PVezs-&E)T|1ct`;VOiHL5>my_*Z;><v;!L1Oo z?1xe&dMx0~pIKcX#`33YV{BN}v2zfK0M$w@76i(Nbo>a&xt8GX(Mdw)JF=~fia*Zd z$5e(_CUu$34f|6ucEQoKVlP{sAQVUuk`rPFk!80GYN^ae#d`>`QwHXhu%HL0nZ4Fl zt}D;c5t?)(9AR2tODqA^$^EyBd;d)bwaQLKf-E&0@lExaP^#)&(MRWOKWXfO%XNNq z7FhR{H2!H-Lg^>x7>HMma07z~O#9n}vB|v5VS9-)xOv_|hTd2BOZ*zMa&<3@D82hO z+fR_AI?v`tV(Ugz3~wg$bBFG+%7D`-Irr09iw7s=l2G~bquS>9l#9_T^l|PsCo_qf z=l;(@Di!@|Kg^Pl%s>{?=jKg}!mS8j{CP)*6MWUfP6+P5P2|Rg*lWw?YeeCz^_n+N z=_IZ<Wy0hPXM|8B=$x4lgz!L_@`Fe~NOCzRvV%y!2@&bg7_uVjw^+00&%Kjx3|ts2 zWq1Q;Eig)e`+`8{cm_s6K|yE;^V(HcHXXUs_F$azRT)1vCvYZx$?D&ZX<8Z7=5<L< zdd+I8Eh~7yvLSwf01-w3C8nAaQWE<N<zN^$W0sYjz)AmD(9vF#@rA0`XQ<E_rTcJ0 zR04G?r1J$6(P8#bxEy@)VVtyMR#6-yWL8O<qsN*T_Cav@>C_a7S|XDmrDrMxa6f<P zB}f7Xfw)F<f=N=sRA(b6vZWsZw=(ulUm>((ZtyS&_@dlx46~{|8ySz-CSvq=KmP0< zYd-HA+axq~F`Zm_ctT)+brE3=$N`gkAT+^07A^GC`N4aZ&tR+(z=XE6u{SCxT8NWt zyt^en<)?d3@#9BM(dvDKt|2B$U#%MTp+}+CxNeFnDRI?l|40T&NnEU*0;#r2zH!8L zTvlp%QdTM<A!j+uLM=Y|eT08qb(2!Xd0{E%CXv$XcDx;z<2Akbp~TA5>BhlcTDpm| zj_R~v-U6J{C}&$01G;$0y|2uPk#X4EZmCRPBuefqVeV{ZfEX@>qU4?ql%TLY$sH*B z^jy|89sG0zZXh3R%I8ZBp#9Ipce0n_-BuvaPq?C=q$M#C(*6nJ{SOF1cHl5T;tR># zk#%c74HxXBU+blVBwYP7E&0JPN{Hri^suZdZqZbFj`JbT#B+o&F2T#qUi;#G7?;<W z)FODRGas8nWxpjbcBnu-qjpqYX(+~7J7x{Vu@BODo_=ulbs-o9hykKll6-%T@eblR z5)2+(--9nk!~t`HFa}ZN1urNnihA4whA^&cH}Vh4_76r?L8FqEhT5mj9lr<&a0C)b zwfE9+E?NNt+)bXh+n~K!a3cTrUnzw@c^@jJ97Q$)nr;RcjgCB!(lvvSTPd|YtuQe# zSe3j(q2N*LERQ9;+oF<}9*;6f-!3*A!lxtKOi`*cYs-7Lf|L`Pn_j|WwBrBrrGV!X z>m%wAux8F*gwE3ZKF*gI6p#=2h0A~uUB9(*Xa3kVX2HSnJ)P(HMHR6J!jf!mLtX&{ zc*=KrXfFZLitf?W_@hBIl^=7W7hjd}9yJf~KEI2WziJ-%Tja+9O`r3UKORloUA6PQ zNmw;L(gwYf1rN+WMjMFFzTi61h0<VOs;ZvP;hs}oHv7BrzSAPz596sx!#O4MG*f>4 ziH~f3-le9FYa@?8ntn{9`UH89)y?=fWM=*M5Uu|owios9(qUw;r|RiV0z6$;;)iB& z^?H(4Dsf*>QyCK`Z0H6;>9{q6F0WvGL-9tt*b6+kwRn>-E>y4Jqc?(`ZKCd;wHfN8 zd}ZtZDye#5_`fApHe8TZd{GJxVu`Sl0s_w)28u6cY6Q?Abu0q(&Ucb*%vKIYMF>5) zq!LU_GY>CsKJ<|Ri`%tKB4~f-@|TYCyM#fFY<U)=8idkrb=uK1HTQIYpEdz#e^mh7 zr-|V{&_STaG+6-es82NAY?$wS>D&&6($cJXf&!ud=mU8H*OX-gGI@c307Gn5{aR+e z9)uY<Kna4O2e!@_D6dKwk8K!@z>CjM6-gNwT{a{~rntu1-wD4b(3TN>kR4A_LUyj* z1q2~TE-wFr)lU!7Yk_<Ld~sn_U;T<a*t~So#GMTIRK2~6pyzjIjxG-!hFL~VXJ86) z4x=n^-jcNxPtISrgbz1&!Eh$bxV*o!IBQo15|B#RT8K+9F*9JvB61VON%BUOFH=jE z1Q#in4qL%~6+%Rfk<LKae_aXMrBhMhmkUxGjNLCL#ib@+I?J)VpYLa;lg)Wsa9=|d zrV3N|W!WgF&TiVrIM%I+UCaXjXl4+trYs_Oy?Ot%SB;UC&eEm?@2c=Nz`r!ubq$7+ zZX!F%^73{tE)YYg^Ui12(WS1&sy~52Tkx-(IwF(z=a6`)pQ_oP83Mr7`P)@HFN26T z9o$KOi3~r;L8Q%8dlKnpF4n3#zuom;-WJdpt{5i{kPz`lZZ<?bt|*8MRH(wR3$_bl z`7lEU_vV2rMldAF2wY+<gjdg6WEmZ{4v{JUIAWWR$BD<<`T0kKHKLk*p<QvHSnW3z zgaS<P=Y=>JO>kAuZcQ3Gvx;)n+sT=m;guc9_Qk=$Y{VQjnmoNNQlk=;)cSMnW|Uis z#5(w*q9;@&@q0=e`(7&gTHcpZ>z3<dO>S>+EyKXPP#UUC0lr4ci1cC&)KvO%1(*dT z1j24)U?q(F74rmBsp{;2X3b$s<VUc+k+af~(dpayG9b1^%47Gcc*{aho%sE!aAecV zrFW(gNCa8Fm3aXQEXIF=zgbDdx5P+zNA33x@~{j1(&b54vN`*wc7S=XaUC>SN_QGA zcv+5&%8hOg-&1fvfPmky<CkXBi2L;Vlr49f<q~R^vF8s<6J;E<HCUyU){S{#d%d;Z z50jr!PN<YLxy!mbwh;k{LqEd(?~@!R%%go9viH1dR;#G9!76%YF8#oWQrIL0p~&gx z?MGF3x5c9I_0<(z;J{V+tEcfZwH_jCM>i5hwm#*y0K`VB6HFo(<ytR|ZiQ}?E2p?^ zyNr4a<74$=cjvv8EyB%lDSzOr`2)&{*jpQ<8|g@Hh3oNhP@!9utfEc2hX`~yM1bjz zh0q%FghBk8ON<cynhiuzp9cnBr^vU47H+9BXG<3smimCT5aBha30{u&Dyok0n$tVe zkGax479~R_AVV~hfjN(?OG;r*Rubw_z6pr)s3J+(_pWl#Z%#>SDH54e>_aoVKfbXu zE2bF4RhKo6Fsz}S$+~XM*(E;D$xvAiOS{9E*JG@xm(#`^(G~+}!Q_ESE2HxkQo?dk zZ+X=$rN24?W^TUl)hu0@+H(9LbNBoq23GNI=x-tS5YznFz_S_1DlRc#gNn?TwI!F( z2BFLPpm*`Kn%}cgVfO;ZzR;+LlMlhn%!NbzU3?Mkkfm}0_}S(CS#;sHIy|OtKJYzg zDB?BoDlLZg@u+H;Sd6Abzy**TGK|B=j<)?S>HW@kfZu}Dx5mJxfj1>}j<r-#;A(*e zw*A`i&|`|@dSbPa=|y?N9%Fbv)|u~&3GK7F&x!b|PMS@lO`W}UjqcJKKfdVg=g7dF zJ&mVINXsYgh<_YzuCIpXeU6Df0Xf7aDW+{y%-Stt9gcPsF>bcL$<SBN62gn$B{tYX z-cU><Z5F6aVqeQPywFh~D8@CxrhKdu8`hPklE#&}7C3Ertv@%dTdiJfL{i$C=&vDs zLa(*sA^#h;F#Pu%;{T7eHC7gu|4VGsGJhk|e?I^7sc_<3<J4e=_4+45>rwDe7&0jk zudi0j1+aRK$?bF%0<t~pCS~Idaui7YS0}C^uDjfnk%6(<^FUu8zihS(lB-52V?m5~ z10JEmD56?#byCbqXq;aO3ombK=5Q{Noge?)VE`!p<3S<lZUSl!LyQV)9nYv{6?oZ5 zhM8|#3)8?Qfv5N_Ww|`7LG0(E&jhkJ#->@34kbuh8C5rk;k+wwnL`VTo#cwEiaMA# z18vFT0p6^Q!S!|C0@V^QUK^HzZS7>aZ>R-OmY*DW^bM2t9+J$!4R1<|V*yrk2wPx- z+Q&W(>|O;`GH}ywF#}{=8Sd}CTAD@Rw9MMczO{8}NO|a}lXi@N5m{SsMU6>PQ7c3& zq5daHmNF4$q;b+fb~tl!!VLZ#)i=`2;zOwflx_T@o?^XIjwk0QS--wQC*!xZRfYu6 zaPhNEKl4IGIGE;QJgaT{@?3)yq}T2-7P3V<5{U^?pu$XLzSw=cYp>Yd_S5!7*BJ6y zSI{yi90qdzXi#w!#-kmG0lGG<N170yU{7+#DIRUg%gV4{m5yY9!g*x~lAB*H<@21w zj3$Rr>Mv^=nSk`(MNL@i7Ga8rO1??+Y2sC9b6)Z2pBelc{W&#@ZVBBwKI_UlmcN23 zZFr7Brw}*YY=C~%Gem=kBU1e4G2>%Wo1H8N>bYzLaNQ|@EchMZnB#0}aDIa3`uV7~ zyZlx0LYj=310((9SNVLN>&hipiZ0vlLZ;gMdOb@YK-Kn8NGTYAiuS^Lw{y1rrPU5G zmRy60>9LXAaX(HAdi8+hip-pu9ml=$9uQ(c(dngUPkF}{pchT$-5WG^MeUrfJg3M4 zJ$BXQik?(myj9&xnY85n&a^Xd$~~v|!e}Fjs(i)q@!A=F05{jR@isPbf63;^e${6B zHg;ORakWDM79EX9uU8B;u)3+!wLqBQ@_XC-g_@emNyg1d69HSPI)qsu3o;8bHIxpC z4T%ZKk!ba2Zk<sk<5|ODS4O?RDus53w)Vr3_lMn0*T8N0#(`7o`H`q~(iYWM%lm7@ ztADx<$e!Wsa0!(dBSsw13YsM6GGkG~?<Yg&lk%GPq00v<JbbRT^Ucl;&3BEjw>z;# z$Q>@z^u-LZbfU3(Rm)Q*>)Hm(*L6)t#2gx)d$wxG*rS6q0z{~Akm@hM@yo&K#k}pI zB;)*%K&@4|shN6t;BosclxlO@vjdAgI1XqfQL7Yr(sImu30=1*%u!N!)yEXm%Av<@ z0?}xByO5$r<>K1Ji4EDf3FoM6_y<$ePeX0_sM47_-W8p8t!_pPIWs3W(@%GpBJ`@N zT1{)F#zRRWA7rsYu}Zm;MI^QlqVQ!kg|0{IT8IVa#aEcR5ZR%~%i0o<>i6^75Jutn zHVVBz+lR(Ug3F{(8-}s@R!Q0FD1Y%V=CbC*L!FQh=L`{$g|Dn<xP%?BommF-*wom@ zTuobZNi8Rr5*ycAIhQypEg3^C<1C~@ka~_YDKJJ;rpNL}9?SxG!JQ^A_Ex;y(A4yM z3>fmeqmeNIGwK{0<~JNg3&davPz-;c-grB<;4p6Kbmh>IsIU+eijfBye#OT)_aVeD zrkD*J9Ptkh1-78stpgH~0hPWhLszf7<9e({==~JKD@FM!w14s92O0GF_)9s#F?jxf z8~ZdJXTHXm)z{SkewKBrGBBulu;6>Jn3U+k=ebVv{E58zjg8HR!>NY0g-aR1<yt@O z>NV}k^!=@I7!}>F$}k!Kq&+Ok(&33@S(jI496t{UQb#V7Eg+JP<b#RS%u`3(9n8I* zr)j^~$*|U~!3=)z72Lc9348Cnp26>;<|zKFv@XsVU8*$C!xg5lq$#ub4!s$3nuj7x z3w>TLEX|Uv=inL#fII%R(xn{*Y3x!wLmFrw3yV^GzIPXMYJnC1(@#h(=Y>+g_ZU+j zlkq-<CLm=x;XBu0X1N(bNZ;cbksU7_GE~UYwv623T^;=r_^!G?+bMA6JK2%r6zZ*; z=QXA^AFh<$ZAx-;9@40mR+pt=xTMByVTN`*<w$ngM1}=P>|pEnd50m}G8GQuAewsg zsw)-yNDQ2QZOe;tFt4>duWBOia6ihOcCr7E!K&A%N4q1(i1V=+fUc60U@m9Rt7rl* zn9frB*$H241{RhoIA8|zKy4@>eCnDGBHu=+D3MloaAGk55J)({=TGx)4~vR{ECf9h z$4P|v^yie9e|+=j^|J`aHEt|fHclwqOO6cO#9_&cBp?tW)UD<a7arxiUQCct5F0e( zW^FWQH$qGuc5)REK&q~Q%>ag=@8;f1<KeK~;DC31S`5%~7ujxj`>Q}3`Yru%1AR%B zdj1>U{%bD~3-kZlGqj<m`j7F`YpGgit0Wa-K=PW_^nxL^-qzBQ4SOhFmtgsDK2Jfk zD&2ca6DvVvCK#4|t}_I$W?A#x_oE(BvI;S+{h|Z?v6CBxh?ZbUji7IgAiv)v(}0yY zjj+$wE{m?`4Yltn)Q9mmqlLrV&_Uz{oQu&cZgKuvXl2qsZHAJ_Dm%vG=P7MY0c5!< z20u*lh{-H_SI!99;wEu7E%Qibeg=UYWL|;KjilY;TZ6EFT7pd=zlT6!9c&>ZNo9ia zRl$^@+IV=V=BjJ<Uxyura0+%tg*ckK8owZ$-{xRTDl~izVss;rV3fGqK=Tp%IYq`h zQu!~drf8`B5J2t7&pvN^%bhtVTb@;NH1|c3sd@rpb>$wNIKUEy0`?0D+AhlMKf}`P z&b6c8<O+2()BG}{%^ucQE!31u+yv!kaUn?OaKp;df)=QMJ9)ia^Z{yJaRzv^v8C!x z<VWyM@1vwNZ(=;kyO){lQi<dOhB+I?)?620mYywI!t9rmU{Zc71a16s1DUnm#HC40 z%HJKte7)ae=O!82&bvh_<Y4>mD)@GM*un3IM4%z<i^L%as(|Z}6rKRrd4nRdh?FGx zd278U%jzBt*`wm%J$-xY$3nqQN5-qY^TP7LE8Rm5TIg+>Ez&eNI;_wT*T+=|nmk$F z!fI{NhN+5fMId)ob%f)wLhzJiI0AEaV~^V_tVTz*9Bkrs5VgiU7kb1H%}(tz+}Sl5 zGS=))d3b>Bviw&F*Nq3SK*xAdWMiqSD{&z{3t{Xh)_{r(S}EQrB9l;{6fhw|B5H5h zi4IJ-G?!=UF{r0iV)Eh+POe)uo<BZGX>PDPu#*Ls**h#ucl*ES)2XbEbdAt6HRz8R zJoW#GyR`HL<`s2Oo$e)4-S^P>$E;qyJAbC7=BmNCj2Aa8JhSUiNWKbZi>66gf6NY_ zK!T|I1=({`RhN|_4f;W#-P|Moq81WofIT{4fY(M{cph{^^cG3c7(XxRx9CllRxs#u z=ElwZsr}_~`|>omM9hNJ-<Z*Jx(C!ockFFQekNUCzc+cOrOqK_mDlPD?lxi6Xh-B3 zNW`e6uhOEqEP@5D_Im6ya6q<ab8y*;rTM1YP-MPcZ)Kcw?F0@m+D@l8=Zs~qfYWU! zK2qN4<?vjC9#KQ}kM9&f${+jchiiKuLD6R)a&a2z7046K;(gSw6%kdaQd%MHJLo>f zNF*AaA7Q-)oj{J0fm2Nai#L;2J!9Z_Lz{$I%1O!Nyt>8-OXkf?l>)mb*UH!fAGejK z@|p%b)7b(Yl3di1SfhLr&azEy<GBn@B$}hY285&OgN}EvOri-J>geP@0<((gv+4kV zSjEiwR2zQ{ugH2451S5u5#brX%~`PhQn?OR<$$tFFq-^51+Yt)?jPpY!Seo-XNZa5 zUy5<aZ|Pv#Qs&S`s0s2h4E{=Mc@Gi`43t~Q&kg_cDIb@T^M&&{Sf0NhN`(XLYoA;} zelJ^Dv*MR*>gD$^0G-!XX_<`0LKRyvNMDCyiDc><N#YG^s+(vlyU<*wjb@t~!833S ztU-~a&`4HFu~u<YS!3tZ>rxM9j?}G(?IS)0(d;wGO%G_c5eL<vaq=-Q6kP<@IGa@- z*Y7YgN_YFv6Kwg+@}lN?{+c)MwC_klejNKaZ5ZBZ9fgyxrd1bg)a=-l^)l|T`o7}_ zx9>Y<`K4Ntado8NuSmK!RZ2me@tgVwuLe`KLv{q5iz72wYe#DpPo~R8)OtHjTGfWc zecDciKBmTS%)6qhrr@rW#b5h+3(LX@6WWl=ajj!1Gy&%q`aJer_>GffUuSdWTl?NN zkGI3c6<Nkl7gvR)Lx7qFmTyYJT0?Wz>dvgRsm))1#^&1#3=N@f!Ya1wqzDoK0H|La zl;c<vJqMmE9YVxuo4PchPrJDze=QN{*$t_&5kpQZ6hGu~CdA&n5}}E_F(+oB3@p%H z1A4UdL|q2^BXc=sw<Q87yZj*tdCJorP^`~Cilol1%3NUc*cpUe)zD3L`7qQsK+>`j zV<+ATwxCe6;-|JW(~y(rcLsoU<`b9-V#1J9)nYEtDcp$hEB*eR_Qjv1ly^UDbRTJc zmcn*Jc5~`Tg(Adp!LZ9F+P*E-G#-7qOa7T87`d~cZto=xe(i<>=418I8@a3GIgYwz z-x1^gWCqGz%Ql)T?dB8zi(0{hqcLh6@ax(Wfn-^$h7Tvt++gnqxy*!t;?a{JPGt51 z%LWgQL*?K8mHgqphGdowRCkDyZXs)b&e~rJt`!{ucb==_8DYc?$>7h7qbW+<J9ym3 z*eI9X%1V&Nr^i$$&u@q@dY<#WLl~1SgK!+`A2{oamrUr<PB!j<RoNEU0mMfx^}il^ z&P5<t?K0JeJ-9;CSL*MqgrCkrNU%Sq1%v#mAH;~ByC5s`vw@VrL;{o9F>cJ?*COst zm&nH*X$;f{yn!NNQhfgfr0Hn>`=R*%HTE(wvHouly%%c#jd0B|az%Yvwi0d3)2!?7 zqp9c3U3I{xNa9d6UG(ni3&$E!+8CC?us9Z%h@Ee__TV_Wv$b(R-#Iq8x1)3O8doTY zNs1GUcTLbMD2R}gj3t;cK<Nl)6^o~pRJ1_E-<2*ZQJy+dY^0$H*LOHTjlMJA6E-%= zg2zf9MV61(kkAs$ASFluPL#sa9hZuZBKkjstH5GdB4608Nh?}MTlWmiqLv^UZDpQ% zlRbiMPs}#V;L^;?aT5aUq>ex!_G<KCL;VmVWEJF&B&#GzH2s-`Wm!Os%K?SCz@r)o z3%*&CFO=-y5_qG)cQ;Rn+_yMN?mX<X0cuJ!7jCmDvU>a7=ZCD1C(ct);ygqEGn9=; zrWZ2%h>pbjo!<7{&GQo(Uyh*k_;iW`I0J0OkqdfSq&b8<9FpZIzroeYQuQ#9(+x;O zY%t>Pd8mS9wC0tT=X7aHyGv;869Ve-d}qQ*f)!|fq|Z-`F^-gzqD0`27!QiRkKO^C zW2z)lvx)Z#w~?~K6MYVMnI*_6c^!F7F=TLPRAlCKYjBI85jxHya587L<XGP1Ej~3> z`ov4w2sfp}Rb*06aeX8Te2;u1vD&4<b^=^1EzOi@CO)q`ZZEz3mVzL23u87Wd=4_N z9X3)R&C$;vZv59cbqwR;pR{nYD*JO~8t4%E&7Vc+33o{`-bn|iMNkOkcY&%4D|)Fk z2yfGl9qTr>SP}a)iA860fuQSI1`;%bv?1kpq#?y*;8=98xsPyj;|fEGAT-Z5dZ!~V zvb65(+^~c{8{3C~)&DS={UMBbp*0^>QI6T7X7}|e;7i*$+eHU$V&)?wu3do`6@?G_ z^V1!VdL=y+D6W3xo{GBau2<t8Vvn?-)@Z8^M-)r9aLMnTRnsBnuWtw~h%^J9tpwPv z${Vxvd7vS|x)Hn1ysr<!g}&91#rVZhyC~+TZ5pLHs%KjZ(uXn45#J$m<Mg*^3bB+W zj?e{TN0-iOb-|~UI+#I$wxer)WYzI#=rUe*Ta@y#E%=cNKdgNqsjnhqVRv0_cMsNQ zc@5danx&0W2vT)8F)`gs+-#x7T^BuC%$CwQ8n*J_R(BI$UYL5g(vaQIWO6%}o_{wI z&RmT9$>MHnX8f+!l-1_k;qLTz#={h9@1uNToO(kmRd24l+@ggckiGvWrnM3!$QrEp zl}+=y#Ew$Q4`ht{{W<b3xq6GrcZIk4otbPlP#HVyY|K65%sLzoCQhZ~-_lu`5xv-J zvL;?kE8_}2{SR3qFKdI~z_qmGzuRvr+hz<rn-)c!pC+;z84Z=BtWoels038+1v};Y zQ4HfdjKHB59ft!9|H|&EmD-x5)twT~CY(zu`4WSOBLfgHdm!RYd56n%VsZ`HLMkqc zJChe2=D8u2vCqey1bBgiYwaLjYUpb8qD8ox7e#1X;a}jN2yt^S*P}h^p=Nr<`JGY# z8wNNLYKOmD^l>82zawzpm^=G9E3{}s+-y1rII|u^!RM|z)13*kU-J&>s!rxWVE;G? zhbCdVw^0xaG7xI#vg*TLCkHqqT`e8MzF=(0`aegB?No#ovlk3FHS2Lzukj9_Y1qQi zu^aOmajWCiMVmM3Gh5eU_cZIXJL$u%%^<$%nJ(eBtGw>vQ~1%v15=#a+C~MSINR<5 zMT0gui4t6@94=cQ<KSoD;qy$g`&xwAmyGu+A5te9Dr>PDy1uRLd*{K^lkk>uRao|0 zln34cO8X<sWrV;LcR3%Pl6Ip$iAe|gI#yuGLbl&&oCYk41-V6*LTE!3?i`;xHS<62 zpN8ryzq}V1Fg!%oWPl)5aD~>;@<mRE3M^sxCl9wm8h@UmbK+R)yE8;gp25h78fbK7 z;%+$BI@L%05b`VTQxkr=#D@IHnaBqi$xDd#%PsI1+wd3bz>BnFSFNA$c|lA?DeAV) zFgsXV+mLSBkgksv%H?Su4O3Y=M72|{tdc=%v70^6tgA~Nkr0+Gu-1xK*&6`1*oDo5 zyPTu4n(YOih$;fssCm!vtoSXu1kV7!D*{Lh63_%xp60j2t=L|(zawLxjMz)?c4=Vw z&=MpiaAN)8Eyyvxn7Y(2%&;5ArmwTBofr)_s2M;$`*L5He}<ZnxwcJ!YwH$Rh>?A# zIuBD8SY*AO4{;|>?oTBropwW7s6A7o6ywkR8?4d(_lUCpf;C1Ky8nY}c>gn(o2VdZ zpH2hcaYyceOwT*Ryt`U@Aw^|sZq-Q4&*PMeA>vCg(RC%}A#rVU0!DD-^zhiBNz#fJ z=G2qS(7XlZ4<lNSLc*D!f|$=3h9t$nZ|V!10*RhA3n17|kHG-`xM^%(rP=-4qn-ZV zQ0tieU?|USQX}fm4Fp0UXdz_^L#vV34h2gb2KD^tgQu@I-6pIgLdKhbT+^B7dHpBn zkEB?$o%mCl$Pjq};~xh-N>K^q9l8j#LS*MCO;``Zh_TkC+frO6SEDt{bVa8-aKdwo z?8_(5MZT25k3HABr@|90_3}c0Opk)FRzz!qJzy(wBGV*RK(iLS5dp29-&zdmd5p7p z>aQ8TYU58FsIWSYedMo3^Ctlg(U740ke*1fpQ2h;d?;$SDK>2K{&p)V$$6kW8tm}- zF_F?a{Hoext6565BWN7PNY_?`i3Ia0taCc?Qw(k1T?g4<p(*hJW+YOGKl9#1Xs99r zeoT3(Hii66nmTY<bmb=;*z074gFm~+{E3r4HVWM81{nz48Y=^{YWS>_=(^^>WPO@v z9~Da@N73WXK8RBqBD`C5u{O5+#qHd4ynaZz59PkMZ;|1?{Fy!hwZ`|0o@j#`cI;84 z)MP#Ks_KnM+{m+CvTvbAn?;j?Xb$ddWnsO(ugGlGHVAsn_@Duk32D*%1SLP|^SqAF zfY-qCG|}AWEA{0hxd1Y{;T}7WKvt|5Q%zOcX{m9-O&z8nD>DRlZfm&h)z&s1j&D=$ z9e_X0>HTldCEdU2+bm4~^<e(b&*g@i`Zp(n@*hrQ_?r{K-qv4}oOM_o#58v{CZ2FG zfox<+6iF;NJKVbJ31kqZjUsKik<zw6WMM<ifIIR44#-c35UxhuszTB3(qo$?NsJRL zKNHa{D2z}L`yRN=kUFAS<woMju+sxVp5f#f9+s9A8<}as^y?qut8X)Jq_4&u`D`r6 z<SQg^bszZqQ-%1<zm4;VMCaGL2WB^Ke%&NdBE~A_1*Fl7Zv$^|EUVq?a0o&a3p1JV z>%tl|1T6kXnhq_`N5H{4G<m&TtKOC-X7~({xsW@WEh66&7p8>%_r%rgl+{2+%!!PJ z@KNKBAv?$pa3}k(2IZbHfP)VMFKP3MVzUXsg&;o(e;VyHA)fqvus&kY9{2aeH9UKR z@z2Eds_<41hm4OLrvP(di~}_3Z;@;b%z#L>JE{k~_+ogJmCl~vs++9!BQB0`kK>by zJdAE!3rytWy&BhBVCV({>N5j=!dB{^iR&&-OrGEuCv_=-V1f_T;E#b->eJuq#5FTs zb>8Frs+<$PCl!y_CXI)=0$K!E;NV=aa%Wmqlyqa)v!omn9u}G?l1ZqpwsTNNj_TfS z$6V-?b;>7blsSInPWWn<jyeNJ$0@2u25ET-K^UKt3{8r(6jm2s2%sc_G8)O>MmIrd zpAqDDzf`EbIPHVq&~F}^i4DFCK^NN0==<0-h@hiqSykL{hMwwy{fsZ0KKGw7-%}S1 ztUtD3D@-RJ(6oZ%1{7qBR1&DZMI`eJ#=JZ>2p0NB!wvP>xI#5qus*~=gQ-$-@}w;O z-r>bV`Sdo=Eh<ILgW)_WsceYO0#idS7d17&)EALo?W8IZe87{J<XoW9PbUM^ki{=R ztVGT!TknTS@r9?>`E9R9ip=0I3Q6K;J-%PU&z+22PiGIhKN1jlk|b;s{1OQdrbXqy zMwXnu=*B+|8{s0@B$kJ`K+oF(eLlQ5P>{Y_Ct)K&{O9HXeb8tiBkkAroDmC7gt=%o zVtdwo!u0CWm*)bDrfWu--YDabCzI;j0ZSER*5MP%S_|Gtz?Vr)mHIt3Bfr~6V=-Xd z`;#G2y}jfUV24c2{fc^%J1jQZYpPdKdC)eE28@;<F}YQ6$JwTwyyh<}7t*t}w5mE^ zPIi~R+TRX)qn=xIlby34c2-6fZzD+~qN`~!xgDDr2bOy*omf(ODR+m5)>@CY1-f;| z=p)^~_vZ_Ah_$UhBxdd!ZuvhHgO$5ZV|Yg9o@ddxPyHUy>ILgsAs6m8&IFgu;p(%m zBpYde{iuys)$FwN#LK~~L!327*ky8V8)EBj^E6goYpo?+YI2_jdds6ILeZOEeKb@b zX98bcrkWqBMRV-b>d8=lsBncW%*>L|1*0+Ho7$`K<A-!>_T^0LgPM$usUtZLJtQ8H z+Ip{}S$^rkDn?cyA)MSLPy)!`QtuN0`{g8fqDvvZPEknBnu|zFi0mW$7Nz_hyN(oh zFB>3WNBu@B#s{V+F_}kj9}?G|G7E!HW7>h*IneTIUR1%e9O4ACM}vqhhYNPSoxQ^) zF2$lJ0|Ku23~i5B2@e2vlJIR7@k~5IY*O5edO$GVqTH<zfwOgL&gYSu3IT?szyhna zM?w}czhE!P{PyslCP&slxJ3ioEF0DZ(*JsT*#$}jeJUV8d?HbI^WD+w6~oV)r^&S( zg1u1dcZPd1Te1gqygr8?p`K6f?_a_YqS1P8>Vn2&feyzz7!&D!!E=^#W}A4|a>AW+ zi+g9`PT0!vf*IYn7xeC$6=v@TghKi@@83zKNIB@Rm3sm{m53$o{`0rwBlAQ_uVXv3 zeNQ!r0$TY^Iriesq4Rn+oPiO~N?0++LFFm9`zPwYNCXWGayJ~sgYYT)1vL7PSoi4U zwr%~;B+j8NB442~JZtIP5G`xE<|`}FP=NrMC1#h07ZGYJ%zpUp8`0h^SZ7cjW$EsN zrD6-LzOe8St<&+S*JplmrQ}?*nm+Mu(PO@rE1%v{|9J?v)L$hr?rpeeCr6sBUzlGt zv}dCRj?<-T)dm_W?OT`C>$1@8ZTgLqN;C|&O^^EOb<kGdfynS@{iZ`TIYAgNjmw_* z>F1NJI^{Gz*G)CfSGPv&f7{L)UyXFPj3`;hoZz<(_evJL9|)s_Ai8~l2d7Tvtlnyi zTQ>iQ{aJ|nUdgIPx{z)>@%=FVt$mlzDpkf_!xb%yBpN%rFFK6sTRXHre%676oib^* z<=ge^C9O+r$OP!uBjy?F{@5v=+v2aCKdPvIE5gTsuxF5xHI)rp(pyj5<iFT=S~ohg zJ2&y;eoGzDYgx|>X<2(l!4=$DHIZB!(Y9{9TA2eUV1wSB(Ygq0*n0@-bIV7U5x>5( zc7$6EO6#s}-TfGoe{53>#(4YllXOkLtXE-2Y1pcqNAdiQTg;jG?Pd@dN(0yZnOl@M zVf0^d`Cs;%>F8Mg*EGn$ckuhSR^j=id>xziS7u$5tI;%Gl-P1^KGSq)#K8pWA6O17 zFe}#H8i?FoXe@B~ZrJ*kDh5=~aVR4E+kOD7sXE(QpAQ+s{m}^JYPV0BLTJJYVe$g- zMg7VZZLkrEP_wJNV9-4DHF|mG-r2TF2I7QlpFLAAn#xROiKwAB9(IGv!>3R|-FAKI z@%O%if&eRzyRS&FO4k=dKM06yZLHm_K>p(hzax6S*j<7?pYIQW`Y7>kpPdPqMNB~H zEqn6fbxlz^QDQ7pgGXExqNlc#<L^NT#Z{&eO1M$#iGuK}LFVlz?aev(LzlzM3t3_+ zh-OZ3q4EvEwBMx15AgZ4d=!}AFNzWf-P|E_2~ggQq2fvDHYy&00D@m1FY?e0Gk6>O z<ZrKTJ%SMB;ruE`xM~mMO`55wZYN-{GkPN|aN31}vaQw3lg?hB9~<lpjlwe1N1*0| zDR#hG#L}P-c>Z(wSbHi{gvc|)u9tv?^YXl_s!!)1-!`+xvABK+d*;?s6mk6C4)v{f zryuKuo?Q!{309}P%-utIGs+%053>`{*Zn!ssmb{ekOD}YZt(IcKAMuA>%(%29aRxs zKGp5aZU)d{eO-!s;Lb<*XnnhNEi-QM#?UlqLf&mF3973m@!gc%dcLUQS=;dMF*98m zHY-Szx<m0wjD=vPE!DG{X$KR@f)RaVkcFTsps~F_L0$x;MvH+5La{=>D%X`)cVQF= z>FG_%4UL1)p_3@$LVV9CHn?h}WWH{r%eeH$#W;^X{G_LP(c>t*+)!%%u;DdJ;%=7i zR;hl`=CguvN+rG!3&f)vBK7y*p>$9`FJJ&iufDf$ZSrtnKu7(UXkI{j54wNc)S040 z|0ALY+vdaHYJ2H@%?WOvxth&qns9Y7Rv8_CJsRi5Q*D`?xd!nX?HAdMJbm<}<_aWc zTFeBMmQ+;Vl{m^|+S%Zj?s(a6xzHG3@`J83MbHtrdeN)`p<T)}0cRX|M$=cx4@WO8 zVkV7nyOX&0)?bfiLaUtEQ03^$ELnm410%5Qop($oebq~fynH_I`%+QD_iPHC%2W;p zGO+;yefQQ8wAVG_9gHy!X2cwo=IpWc=7!+=muDB9!wmYiNb{D#^?$M1pzUff-0toF znv&I7bd4!;Hh>BVV)&mJm72o%x~N}DW(6$XE`C0uC_B%p7#qqmmtLJN{XdMobC4%Z z)Au{JJ+otb$F^<Twr$(yj%|B>W9^P@+t%6ZKIe_+i4#}6asSs{(a}-SRb82t_03Pp zc>^_a>3Qy2E?vyW;;n*cuiJYn9@8x5)7#r@+xoS+?b&zdX$R<LSN8#&&{{Qr#?0V5 zy7cR|WgmJ-v~lkQ>)w~Je*4w1sPRBQw}c|%^MBku&GD6lLO@A?&?@V7u$f2uJ+ZB` zpRfH{OG$MC?Q!kg>;&a`@ZrW5T#~Cct(p8B8JA*z_F_Btv#b3<v45|(x{+0tnqR!p zdap*_T||XgPblcMiD^cIRmOq~o#R%)-snrGi{WNc)x|F3Y;V8PeaW|ZnfnfUcsJNG z>RyqiJ6c(-%}en6ZY=`pMcs+15F?92(hs8u18tCxGg<*KK!VJJ6q9Acb2M+;nSZ!g zX2~d7<!!~X#q8xc$H4gRWc*|}${wb;M%eS@_vbfZ>m}c|&Bc7@Mzz`a(=2)1E(CN) zPB>d4xl<0PJ29L#CR#S&0LxCckLeL=rHqO()=fS72nq7;cV1!N=hl~+m3jrv0<+-U z;92K_*slGRO5p{){Y0SplxIKBn)o_L*bfmAVlG5`I9!<d`<clMA{^xebigeyCxbzD z2RE$;{_XrihFEu5SUAJFx~eyeos+~gyon6tFHX#u=9YaH#T&+cyuI#Y+{PP8e23;~ zV?-ci+@>a;01AhP!*NgUyrK|GMTZR|BM*tp@Xw(R3d3tzK7u7W&9#c^Tgx}Z^bG<Y zKgbbgkPh(+m$#pCVBa2-;yc#JFOJCa!31Opu*2%W{ALlOE-qO)kl)Q6Wdql8esC}T zUq5#UY+tc_kcdz{@n1TlQ1}yrD21Uj&D}uABA3Dl_h1#nLHl^mP%#85qctv~P-Dcx zi}*%sQLkK*3e>duH9BEHFBkhzl)q0CKZHFEN4Djd+}AccpYZqXoQs*7VAcA{m+`E> zS55^$qKlfWI&=iuBlH{7CM_wDb2KIoM=>|I&vCZF-XTrYzkZDvS4Lme4i{EbR=SkD zF<17%oqLgwIPl14^JG(k2ZQc=lxA?NW)?*lyydK2|5(%@lBRB``HVBCDBuKKyrx=k zR*S$&ew^s8yH{#JBNIpFDfX417%o|<$Vdb+r<wrvNF@et$P!i7vP@(WVv_tsI%lF~ z^~&XyTNa?|tz|oMkj8<_TUWenfj=KCbXnq%FpKpueD^o&W0i6Tr%pJ|lXe}(bg#Hx zpqd*Kr(tQ^f`L(m%7PaD((<sv;0K2_Ig`k-?k+qJ5rt4hBGZPEX+^iab;~oRwJ4|= zGF!c1d}3Fg&}*^c+w4P{Fn~>7cyfxc7%_6gnIYxFz@&*VNK@R2C*YdPra9ql-Dlhg z5ZulRH41&kK^sYUqUvwpO4?lU%K0zPfs3Cx{~%%_)ZQMNFkY|02ZBCSD&OVY1r}i% zU4Rk>)xXeM2^B$!et>5}A2t{o=m%!H5Po#4yGk<<L|-9HW0DXQ%k%ZugmB8y8HV-Y zyz?30lHxW*Jih{n=UAWf=fd08{E3$MR|c4?gP1rNpga+(G6>O?b3mTfUh<q0+Mpr$ zZK>v!(RLUifQpGhYGojb_c&GhH(%l_fQ+X$XZwY}?T~P|ZU=j_q`R&Xwp@w2<@GV| zD7z&urwJZbucu6jcxrr2r>E@9W|ppM+*_dGpYX@z_iF`nMe5Y9Xgg;!IvfcYqc_%0 zdUQ8CWWRQ&L*3)-;<7o4oMsXwhM>b2_@D$vkRpHa`NSWn_=j$8F}fqOMb)2V4nZ#z zKbY)^Km`lDh?qi)io}8JwhLM2d_?$j-hU%g1Xf7c?F66}A?e6dl|1z7lvCRl<&AEC zG3VUw{B%Fk=T>2Ce&U}|kedEC7mE2`LT*fqe?^!7t$b3;HaVLO>FY{guy2*wT=hCA z-ga(7hGIT_qa-<-)LEFJ*End`%E9Th?)nTIPQxw6*Ya&xjIc)Sz4~bteP@Thf8g-o z_<TJ6rv_FCWl|FO@}z(vniO_<#9trkT=d3mA~9>a0;cRVCgQZLxx9)X{oEsUP?tya z`Dr(rR{nCa%7v4}Bdd0vSknBu&L5rwHW5lVV-AW`=5#$-zm~#Z9%^G4*pdQ47)=SE zv}%0)nM0$$Ngp&u0}Ucy_P1*Pe*iKw!Byk=s23PbG}2;}zjh5ZiGIbjHF7cijb4CB zQ5K_dlY)Ao{v~LNU}a0KHBb>D{{l0S49aL`^N2{s*0?VEl04USM*17P*sZvqr!NIF zkyy*;Z`JV4Qe=$1x7iiQab(oBegN9ipArsukH-%G!Rsq~9nM5^=E94*1Kz~B@AF1W zA2rAOxwEm`w)|87*Csd&3`|~qw{D7Hh{A_RN*hx|lCcSkUO2J_2K}RcQ(=m^@PHGe z>C#KxoL3V)wQ-7C+&h7RI2DL`J}TC9C|*w#K~w68MUxYUNjx(|{Xwejs5NY1@9Xf^ zM3iV{c05L8?;L3Cv7MZpAw`%ioB#+TS2k+QZFA*5m$U#2(LD9LIa~OSgZ8=`O4&K4 z^*;ZIJLPgOXyU%HmVW6YK|%Fgr(TDn+X6Rjy_zjjoWXj(>krPbM$PkdH^hOF^I9+$ z(U5Yp2S9<n{i4b*hN!IC0t818M<7KJB}?!iin-GH_3E)EV&Ch;5%iVXQ}^A(p`A+A zi<*|>_dH=ZT*H|L0T><&InJcPU8jm?;{Dy`UinASg=d6Mk$uo5dD|+THM?5>ZBG~P z9iC2mwH0xK=EvRz%aTLgeqO3Ff<0>8mC@|*#(K~z>COG79@|vOD_t7hRO@z|Q2!;} zeX~2BpULfZq)R2r1y|Gtb=!uc#BL;Y*BfzuuAGi>Mm2I8go?%eRV=hQB*>9;6C0d( z1G#!AW0m0ccHD6F0VgskLB5v4$)}z+Hy`74N?ktt=5%LbG^KGXrC4T=xl}Dp>#?QJ zVF=@1`cDUM?P@{d$bJ~SFk`5{6!@TdqoCmGPB{E{6oG&8KcT(kBOSavUiMdumMi3n zCTKyx0_-IcgqX1Cdocy=ii%65Ar;y8VoT%}i{#jf<s6FTy?&>Sv=uB;v{g0xsU02S z+*w@;m5$;kktQ&Ui@ZqA2}jqvldQVgH@(3U&_vno<zWbH8mJJ+lMH*~Y-FMAwx;@J zpDb?l0y46|FDt<@!hZ=T`l-lriQU}LLaeMZR?Ehj+B!wFat>-c<BG0>SrH(VHZ<d{ zCaTMZFtFJ0*a5RmG`qsBIG9)TH0dC|VLPu(E~S*VF!FS}t_`$P(^WS9h}2U*bxQUw zZ6uOreh|(CyhU~8W;Ut%xIg6m;VB_}j+Hy2LZA$O&lgqEIo?L*j4!7YCNfr-LAg<0 zv>~Wh5e9qrJR5rL;aSY~hm+^Uris;`rY}chTQ@}3heWRg9bWJ(5JEvi27+ot66;_; zxd?n{Uj0nCnz~xw?;$kYSr7khvFLUSj2skdZVImjVK`e}z1waRNR<#H8E^QSV2FLq zM0?M0G1=T+b-lgPmu>!Bk2v?yHhmV{z!9^po+ed}LG}aCUKkT+szd3SRa>u&-SZe3 z;zx&k=!VVb2-iq`=W6MU5d?3zh5xM8!Hy($vp|z0<VF}bi7;r~7%U=A8!dELb?gZy zGN>)MzJ<WtvDn1jM=Am3HbMllZRGoc1RR4kTUSitjKK)z-EM#W%|Qp;UKnvnK(4b2 z2(j?axPka0oEaJ(Y_-48x0yekX#HE4lA@FX&Qi49z>NNfiELFpcIT><mq>O97Uz@w zs)C01UO{R8^|WNuEc2Je94ara&w4J#kff4b)UHyeXdqwm$jryI=gCCetf5+d;>q`x zW@yC^mb)~|CLT6VHRqGd-%D$Q0Co2jT~h*<(DA2_BJD7r&+2{dT;7CaXD%GEh>+u1 zepRlz6#1n2StJt4mGYdczoP^#VE=WUH2<G5lFI6Qrd1#lDQ?nlclaY7NSjez(Sa+8 zA8_BC`RU+hZU+$jG4sIYto;?c{u-azW%#&(IB!AcZU};`lk0vX4lWuaA`hAzfQCEi zH`72+I&by_Sjc@PlwmhE#Hl%?mmv)LbFW~O$a%&IS%QQg4uoQ!AkqPtElzj63_oi= z{Zw#0wl6#*N7g;NN>Ny^1_0*avwB2~`OAxz|K`L*C@AHHQx|96)tlq`p2%SflERGQ zb>^1`5G>b%(AAdZHW5q=@c@z<%lE4-<l9@X{zwDKkuS`utv&udY=`Eqf?8&}X<z0M z$JixZxSlepgTe$5>(tvJBh=&)cYBi95L|Qbr|r}sRm9h}Qw_@CYdcn5cC7@XyC3IX z?#sho=0&?|sbYR5TMDgcROrVgu3=>SK$1Sl3({jMt^(*KR-7Y$TFQN;)2HtHB)?U@ zK`|M<7TXW@4P<hGDcL_(W+lnHRsHncE}73>VB0r*J|mL7*j*dso2`908r0jy;$8`a z1&ue2>Ig_#Usn_oJt&pBnwNWUoZIJ);8nHl;v(CzQ?fTIyAjq@)zmh9N>f-h%+1nV zy*Z?^h1@U;TD`Zi965_`wjz+n*@OqMF(O9U7WvKgl2hucYukStkm<7{tN#G+dRtn` z>P>2oY?rNAhq&1A6*lN4wN|P%{n7DA$4F;0zHc_pTxF=gcg@V?D-kV?S&oQaGU(I7 zxHsQ)^v)Ss@UWZvXAC?^iEY~=AZz_s@4MHLrzPLSt5aD~Dchw0z#kYWNB-zv-Ijk5 zz%Vf}{nskh%k2LMU`Ds^shZibB{;Sud9UWseuUMmHx`Pj!&TOh3gL}69ki~NZ5K+6 zCk>N!uF$bvkS&G2<qLn2-F*=MfMf?o$jkTjb$vP{n-3IAOrdS>L_ibMnh+30lSI*} z30fvH^twGddk+}k93j)u!0VM+9^VV1#`DYm>FzG6He#A(UV6IPRMpfs1JyhPY)Sf` z1Vc~vr#E;6HHWKrAT$y@pK`4&@c$gYT)N(zul_b)Dfx@IGn@BWkff2HLrKCIEPXZ- z^u)5??<$sQg%uk7HBp`RVD?w?@^%Zx`YVPVx|Q@F7bZ$MglJNnrGQlsx!97d@~`CO z489P~azsEn0CK^NLX!cvS6=~nP~dqq11gAPS$Ti{iB90397DU06)jy;q`LXk%^n>G z<iV3Yq>)$6WIb2A<g!d`uR!7Ec7vSo?IF#yt|t4<p8I`!{*QpSPh_;a%s<(^WjX!2 z6vvrTB&6uM=G1DX!Z8E9)t3o=A66}E<f69`+4CUpn>OKomXQ2z(9JcQoW@`MAV2Ms z4}<n@a$l3HcaS_+s%AT$dO)CSS9t0ogf4EwJ<8S5ilDky556qxO2MDJ7ZE<s!1Q8g zTCUM0kWi-YVVqC6@=wvlafJCaNQgF~S|s_iPMI{ndlgpV<^jF3(u3F8?2(XklXr9% z5jP0r3w@YiM{?{nX&s-WbFyg_*{tg0rQN<8YqOiD+OQ~6QIShmtQjiCED-c}N<mDq z7g)l-Bm@eE!3VIyL#YJQ7*uq!ZjTK0=v3<4Vv;WpTeXS}0^eAv^aHqIraGqDwl@Yl zRaU{^V}F|2AWjfRkrY3*$g9t^rstX%hM-qvQ;g`$-)%^?Wh*sJu*n)un>@(plQuIu zgV<ppHeIMW2g#?38Z_Wnd3}eRfhQ{z2401Bg;rL%5!QX4p&)OS|BP+Lv$3C0cnWCn z_$gJao@(g6&+;3)0kLa?|KfA^Pj$m@9zi)wNCpKIm=G)aK)%_|*>e`{GR?b@q7ifx zsk5+Se5$y5JF)MUo}b$;Fn@xn4uS^vCp&`R5k#xI`gX-a*Oij$yJauLywwuhnXCF& zU+O&@B-2g_u;#6-0zr?y{5<X2^i}s2P8X_RH_8?zk<)IwSh^a_2ckB>HR$hkpG;Cp zTvr!-W!{a0)LI+wV&l51f5C6`j56)tUR~K5mCBe>zgrQT?hbSw&uk4@s-?J%P6*F? zXkP8L@V1Xf6Z=}%HlP7E73d|PiZoY*m(9xWZRwIR)Q&rAJ*FL0Tj*fx>~dpHY5CgL zS6r8dtm`0XWpqPWxW^oGf6O8-;$4E&C0j2imuNFEX{&Wno-aIYvfHTXhx6MeU3Abi zccESm)Y#UhQ~okx5`_k5XUYp#6p|W?BLFW72{F%4R>Wdu>}{hw8TzKhV(n%3RTcz+ zW&EvD@O}an+7S?Vs0ANdE@}8F*9w{sR5)U`<_-;pMt-jYVt}E82cV!w3WRhZ6p)3x zaIeIB0|R2^TkcgS9B9uvMh9Y!{5!3oWRhXHMktl8wn1xLUx5GLSq*cMCb(&$aOtxA z1#K5Q(|VnT9QDG}W?;BT%LQ`<6NSuPa-^}5n-Q|jX^)bR=056PW=|&}!58fo3wHPb z);x($X}nda>nhPD)Mlw(PSpIatv0lLl+p7=bYY5={AYJX8d=SX^2v%dK)&#*-;46m z2}_<hPpyUnW23&M5f`GbKS8MZ_QC%scd{Gh?5``Yw`rs&R;~+&b;?l3xs|0gWv8>I zR?B%gSI(($UuJpu($rZG=!RQL%<`Ppoa{bI3iH&KeEij%nJ&!wZETm#dah#ld|#c4 z+JDrs>8rZ#4CR24G)>BBVd<g)w~}D<`~c%@*Z4L#2UxVVmTE1id@iU&Jic8(mtmD) zvwRRxWiP1g`KNVF@gu}yf-$tr0zaz}3gGL9%VLTwtQ0FeA9>pY>p}5lE;xVNbDBB9 zGUe=rpT$&?U?gsUUs_m65xnZ6rPG&wIR?7xk{(M{Bu=s327?BcJz6G{g>r)BGf~XR zlp#+6@s$0~szPe^&v(a=Kw^zo$TWbO-$$ZGZG4rRNDkp*tlzFt+u04_nyZ_AefmUs zIQ_Z8bBL+(M+rY%(NHkJ)d!?VPG;~rmpxK`qI|z=z72zv{JYNLXW$|gR;r<bnXcGk zc+7-Fwj#E7hT^)(#EGzp6mir-UQSqd!lDsn1{2SPZ}ptX(7VQXQA6c(kqW`UC~PVC zFWs%rcmYzwquN*>r18vs))fn3(qp`ckfvM1d-^TM-f#&HP2u7W2gF1LP}n%SSH~qX z{*}5hM7|!Ot5CDl^7xII8`WHGSvwgK)(-4YImAnvku&CX_i50KZ?U+dqdp-g{87bn zYGNncxFRreUY@vp@{wnHr`(tP(EX9;QhRC%N~ZXIN^*%Yl6v4_h4;GwTz0zJ?Mb(T zWQUCtlXta1kmP%gIG|Q#AGo+GsXz;c(Z4gFwF>o(6qlWEJx^N<WZx54JSF5U5-$`s zBFrc)el#eO^CkBF@J6!2z{mb=Bq#*!UQZVrp6e<a540hGL811W=&+uUYY1e+(>2t$ zt`-9b*fTL}JFUA}ohJk=i>Tx0T{vN2u@@GqgT`hUW1vOUp=@$XS+!ck73}VO`eHqo zGh1c#Q9T0HgpVn!YaQ^^i1a;j=<R6bMseq9%jRTVU34+awFogVxXoty*9N+(r|f02 zNeJ7y$7wM;Baf@Xb6UmgTps6~&uy)zB|x$Y=aMwdT+)!t{;pA`QH!XrNxSdkA$N0y z{FZt<)%I_~aI~k?(X-`luXuSNs!Xry<M#vRet!ugzkj8FF8J@nq;4iH2hyEL_P(h^ zg#A1Uh1^k7UNY5f%kDb=3{&#f_-FQ`hG4I2hGBmos5%pme{+FY{*BPi&ir3P7dEw4 z|KgC){;7JL2vR+MF=?$$A%VnVc>w~ATVzn2D62xOnmBRy+yf9L7L__O8nwt5Q3No% zA5HO^Un#6~-Pb=`-Az6o3`>{t#>S*fb?JG*kkFNs!HFh$EW=)p981WWt5|N!Mc(wS zQOfGkwhgQe>RuGRe~hN@P8_KdTsTS9+qbc0t)E^#{)qnvy70#oLL$SljUs(H*`FNj z$|(MVdkM#KqUY7i$vL_Q{Nrf^5P^N^JE>L6`=1lB$BC}255|Gve<Ufoo$*c<m8KRb zVdNtC6Yo@qemfA!YnLfV{NuzlMA{^OH7UM)0<o0)??5z2V1`sY!&HMvhuClyvI&6< z&Ji{&Nor#M(WLaF^rKCO8<)Yo>zAp#^eZ{XMG{6h^EUfy=~9YNl2(*I6CBVGMiXj; zMjKhmblkMr$@cT;UjZil)`tuaO7;4svSzT3zv=|hhKK9)qsSiL^X<2P9eIF-dO*aK zj#E+8pB->0RR}80Iu;wjBLY>#3{Wq<7TfKS$^batJi`7M`nI8JUA`OheGfb{P`yqB zkM|8vni|c|Pdy-1jl&5z3_~zE_xDFV51f>fDS<L2d*_OPIP&Bo$28;@3*yY=ikU$V zd~!@eR)2UJwEb+;r2i|1Uw!yYQS8fDk$*+aZ|Jwvia*G-2rI@YNm@$0duqg>0G4|m z?83Z>2I*W&aWa9T$re&$dQ<;F`WLs*xN1h=ikd(rLPe!L7$6ZC#tRxtxY>w~cro8N zD~nY#IJVVV;0TW0Dc)rfXf$@?`@#PDu)TEfVKMxh14BabXxiYSQRl875(;_I&&&Qk zTK)=vCb?sWo7C@1lWZ^&dsBBkDRy{F-w+MLFcZjDWuPZuA4JC!{>cKT_L^%-l@dvE zK4?jNtG>Ife52)!rh&Uk8r~f}zaT~?)IC$j*X^CFZ(~~@;ckh}6oX(eQ`Ept!^D^! zT4&hkOw>Uu&qlB3!6N_QWrsU^U_i>0g7Bm+i9YtqL6;Un!mAby8=NXaqDLPW2f<zc zt;SpX_)QD3?$08t1iS}K;gO*tlgQC`e`ZsUA}vyHf!u%^f^goI`^RcKUkuykyFP0Q z2#mxmWk3o}_YcL5I+3A%spYi(ctanI-lO`<(vA9`fo0fsIDTUpBFutRj?;QE;z|wo z@X%?B^i5ohjggziQ-nLEHtuQ>nd=(6^AvsrYfy^@aS6rB&I~$Fw5D7}$_221MV+GL zbEXvmhc%;4y8-j9BYI*A^R5<S*ix39bThQ2$PjMnvhmxelUKy2+9c7}W9zaIHmXi1 zSRgeqHucq5+ov&6V6@}>Xa-5Zi5({SbBRgmcH`R;#>qMDoGOl8>CQsy7THkKl|}Z< z)0Dyb!3ZJQFlFeWR!8MGqfYXVpa{ht9cPW_8XWEOFHM=IXM?O55D*Fz+#;!duVfNl zRFhz*{y7N%0=IfeDRC~Ls|MI*wHgTr8PaNLTOk^Da#{Hqo>4MQK)+C|lVWWSVHQQb z;tWt`QdaDo@ek8ttD>74!=h#N^x3`5yF2a+MK|s2HZH>=v`Qda&wL?O=EX&^3YJ_L zRaXo1qG7%p^3r|<sIP7%*AZyZwHQ`;=LsI{PZW%2gAG^liJ=#PLT}m-D`xnmY^uo# z0FFvwR@dISZ^FXoUoW!W1>n#di^?5eBs$k*MjAXFPvx$|D@UC<q+mWS?#NHhc>$yO z^ZCb$f0e@0n?J_;Ie!*;#T*?bYn)1L;gV621S{H0AwFncF<Xt5Q_!qoZX2`KC2x6J z6sK!!cin-ZbXxvVjr)}BmcTb0zPrge0~m(<PAD9pR;n@!vr$Y^^Ipht4OSoHdVo+_ z4x0#Kn7mY-SF&?CS;Un|2;e#lbziP6X9J%k^F2k3;sh)GNz2#HZ!z6B6D<42?<6u| zs2h(aKY?ZR;wYy`l`L_+*py9zaM7pAZ~e(1P4Yw_o2(K*7@XQdm@4$;#N0@HP;i3~ zO)@Yfs9wqJ5w>hd)O@c6zYFc#;6Ek%1SAxx*m^=}Kyd@sD#6l^q}C+rXA>=@YO6TT zrrj;INkd2c*{nu2SX2g=gd&0vw>(T}xeTfvd9vI87$Ybpvat1>WCMowe%cX)oR-Uk zsBt)T325QsBgHe$tgqw$NGwfO?o=jqm-GH=Z%HD0ec6;A|CZY2_%J0Q!V!4|77f)+ zv-wyr2PVUH_x);9`Ffq`u}|ps(jiGm8P12%TOG3tUcfMV9PWX8N!0(wFc0}?ceaGN z^X6Ic2L_cIZ~Pa_$jHg`zgWlrS7Zds|3XHv{MT~M#lP7zI;=?lu#m+)ZoSNS@)}f# z92J3}Nk!g)M9`(!e+c}cl~RWO;@$RWvRtE2owu32Yjz&lZWwiL``w6KmelPc)k4l@ zHO`x7O^nRYPTIJmAwLxisskDhgoc8&sho-*QY>b=t3#OyFDKh$BuAeUArV{>xx!hV zR!%)ksb<;W#t5=Vx#U=_1A%y*1tA}FX1iOWNn95kuDJmUSwSdtLw$6<WCSm*;a$BO z$tbI^5@z6~up$jUlzF3NEvzJaLA(N<N(vriYzCrAXI5MAw&Q5ye<Os<=YeI4kY|ME z4V6cZ9K{+HXhj6OKrV%oWhJSF$FqYgy{CJlBdnw$&XodMS*CRZRaqj1lVmhUjmu${ zf!GNFE*$pNO<4`{Nw=Z}T=KU&1^m^(lGZ1PYk#Z8^55Kuognf6n+^alnr{;N1zQ@# zq;cX4tdwT|pg$LLJ-`iHIY%!Bz$P1}6%68w(ot1|<Y6i>>IeE;{tOO(?TlkZQwfJ{ z2vLq@EiN7bXw`dG(YYZwYQtt~vam+8M`>E|ZD7-{Z3IK!H`5QC3&N+5l+yVG3zI3J ze?;w!itWN7w5+TBUI_}74!$#Cq6I~4f*Ix#j4TCM?#PyMdB9X6;%`~F-hic?2jQ8q zBqO^CYVH_F-xr!gTV2!`H9u>#g=KlYFpG^QMG!_|!R30bQiF7ROt0<D77gD;yF}f_ z-F)%U`M=y!TrhC+bhA#X%pXqje|dDi93;CNRi(!i<N?^G;XkPA6@rm?py?BS$plGK zg-0IsgD`HXjEo=Maq)Vkq){-mWh`D=Qz-D}9UMXL>UUj_a3nZ!L!gS~Z1JQDq}_&) zrETlls>LrapR&;Pz3-9I<yU`q%C%MTzrO!wg_!Zv{F#<7ob-737(Hez{4#v^{un(y zS+)2!%+?0K)pmZrJ;S&Dkt%15{Gxjl(IU0_u3YWz7AiTYX%hYYaOV^(Dc^?8J%oep zjg;76&(Xbq61Q@70<Sn~6MeX!{=0Vcp1n`^t5?IXwS!AvA3ktm{!o3gE<Hbg&Le`i zy8c~@R6E4#w4<D`#G+OrJl0FiZHEs}%_ApG-!9JvCFW(;>i*;P=+6B6@wiEq`+Dx@ z$>4hBTNDjZNA>ct!?mBE;gjRZ8(~muUgAu%HhsB^%58MH-EbogL43xd6$a@6OqaS> ziM-0ng`dk?^@j7JVsaC)-mD<u;@E9O<P0%;iX#gYr<JVjA8QvuoS>(DWEGLbsbBO5 zlt2>+KO8qX2~@I4!ij<GoGn%uxk`mP)_c4CF}rE_5?})Pq1h&9dF29ADV1kA9WLqE zn{Aa1T<kfuf;bsqwCA}X<FraxIs{X`aN#%n)vD4c#)zTjH?h3tC)Ts>w_IZ;*IjAf z_8^xUEKcn!muh{GFFCx%DqALDtn$FCt{Q_n#aX$3RR`R}kfajsVTtw9L54P|a<w`U zp0I$kk?dV?SnjSQ&q5IBa}pM>^2upx1C$R|w-9nI_uIL0E%iaSTVJ6FGQpSAIwo-2 z_kaf8laBQq9;YUp4eauCDa_+KFKnHTvh%;)uZrK?u5h2(5vOt?ZO`2|q0o}iN8fe1 zjRrd+2zcZqu8=9*2e^MTOoVP<L%kr}Z@Z>EvvH*JLOgq8^ITnQvAo2N?SoiKGx#Uq zoLXFZd#jRk9UHm$ur{Lj2%cBrKyRn+a|gjZ9QSN5jYTCh=Um(nEncH4dD~^&Xt&D- zwTKnwgQ^pRWrDS(Mau_qu95Ca*0*fDlV+$m7fRA1448f2GYvnvEgAVbEbZx<|Nbmk zRv7zE1f|45_gbV#<~m#Yde4onYC1kg)*ku&0y0r^t}4z`lRNXc%4xz|=h~uoTBt0b zqrqe&yT(jpjf%sL%3Y8GVC~o>0o?$<4qC&ec$TDHlgtj5V#i&lI7W}J3X^1*u+s2G z(IFjmuR_Er{l?D-?@%;botK5-=a4Dc2&uT}gewdlvEBd-Qo>g>7S8weu&JTprISQ2 zkKAaazNlrQui5TJX!GMxk$v##q$GeNH=t`ZI~W|vOe5y1AMj0gj^&*L3VS6PPy)K9 z164_-bBBa1Ss-hMo$PH9aMf8yk`0;>Ir(;G0;NUkWz4GG56fRc|3F&Mn*81@T=6!o zUVd=R&&F7FFSE^jQtR^FY3EbQ1hw|TvF3xU)or{d)o{Rh=7TMjFiJKEg4wrz$JHRZ z&(05wzkRpXiR(G^PQ}0QPQBjsb|2_khs{xW-<luhbFk$6`oRRg6z8njB3b`feTeWv zFbN*k@h|q1iIwAj+0XxzUCP1oUkBI!B9)x8#nApqcgVubh-B-UyaI`@q@$3-TThKB z!{#m;z*?6fRRCU;Gk@FmehQ)mQ=_G_d^4hRc$rysexEV2+0<O|T7PG~=;3toofHp5 zszu+@!WZjBO2bqjjX>YhNM|!#dByE*)A2ZB0{&UKE`G}5__lC=3E<J2N~(^kWcgie zVUP9nb%C5PgrO<)#&<{6w5NG}$J}bSv+50t1iI~|ki;DAi0ODV=w%h_-S=G2*c40V z-xqpFa@I(;1Op+c;V=mbylWc-WEcc810Up+RzNdDydc_pu9f!})hho^=BQ)yeW+j; zEWNfxm_s=7fwwrnsDXS%B<QK^TWtIbE~4}_wwK2Vs|_~Xfcr1HqQv!Vl}EmbnhH10 z_TWKx<RX}I(&_$T4ea${e;nG%K3uup{C&Ea1O{q~<Xtoc`T(UtUE&ickdamZ*sVo) zlA1b)58%e?lXHCdOM(r|l^wRTsMAVBCA?CmN+n!=+ws)ZikMY;pZI4o$8VWGRW4}( zk4+u>PVcWPwzkgP9zcQ-ZN@iNaB(~+Ho<{J=ceHa{H{Om*Lq~YfbSw5NrmzEA{@)) z8Ah1eRdIs5G7`uD7donNXwtZ3!-|EK;MAr$D!U%lOo32cTwSX158mn-RS+FZl2j1Z zpQc?ldzPNF^%y#|L0UYHP;Dg#)}TGqQk;7ON@$hKCCT&>3EEPpETst}YY%MHMG^0I zbckKV5GdLSkwGx2xmYNHOG4?EY_d%U&X`${c%5n9n}G}Npitl|>+0iVaKGXrgmj+1 zTVPJR>ixxP_%7tZRQjNhnKb>k>0`@qmX=>@zItl3fAz)`d6J!X>GIYs*UNhAW=y`9 zvw(OuS(j>7u}NcV>c&ok={XZZj6$I)00xhlxJj_NR;!>JCc~mTvDDi^JO{U{%3vl8 zkPNm%$-y6fM2)MlbQFEf#I61LR`zgu-)s(sL5jKg43aW1Sc#{AE(HQ-B*T53(k`0_ zBVZSCrx5N8?y?#~ES{{9wG&T}SWfI&Q3`-L4Y>ZDrUO+VzGNWXFq6ijVJh9Oba8~_ zE$M)XaIdN>s`^VbuTYYh=b%%2wpjkd+;Yx-j-aIZ$E!|jKBZd#QXi?VmjNKcOYif^ zN49l*6#thzo2`-DozfBMj|x;AAmTscZ{+iC#d6H3x*Yg=k?62+zXyo*&_eA3kY>y# z)qdBNDEFSZW~%(9ww*>dQ$HHD41k2u^H&hF_c;~sJq=REsIW=}(9$QB>ww@SbJdgw zlYEmdqPy`Hbqll2U_Q>BSS1OZ(|JA&%gWQh?Evj6ztd(9er*P<AU19udU5MZ`6A8$ zZlbdjjx=2fRK3v0Gll65bP8U^af|kDWcYb`VOiG(b`C_gVYcz&AA1HAIdD(2uOTo; z%j_TDd|0|U_})4AUQLGN!~g@kWwp9^`Fe12afpz+Hwx?`@bv0{=v~Vbq<ULlq{=($ ztgO><4~#U#Q<qLYsA0}xC7m9RJICRxWW;;M=9M0fBtd-`hHv^{L|hx>D#%4l1U~Mw z>w}T7uY9H#o4#x}8Q{Tn_Hx`c0$lwk7;5N(b?Is#<eh8?-V=moqRKApKX{9(plRT% zcw^4tbf+^bD^N9j@Z(cc(Je6f?%fc=%IGDTb~92OtdIp_Zr3?<+TInpbU?dyVJ}As z;KoSh2JeWP0-yMZLlY^(P%aR1d8O4}Lvzl`iDJuf=2eK*&F7%jn;*T4;_C8aQt-rL zvmhYyL&bAAN2eqw(xr!FJWm}xjuHLSx4XDop#>C``>+gp=K0;v=xSliA+jM~tf=kv zn3|bersJ`_Ns%7uXlEWaTVpCrPTml{XZD_bX^W#52xHkMdYe_v&X)@2^$OYEO9C}r z3w`sHtT=a}g0xN*FM@hEWsYU90{);@GPDlY@$^Zt`148#5n<xjcc$>07_U<c5_+nS zonHkCht53~)_0fkZ)GEXX-2y{$Ve8tTw!o#68Xy=yV>0mq<{(N4xi+i0|ZQv&2v&l z{SQM{DLd27ehVxL>&!VU71L6%KQB{`d+1nvx*I?dK(c*9uQqAsCtvC2m%f!h1cGA0 zd&fHf<x$O4`;{6)cU7{^)E?xnhP5|7h}9?&M)%{VQA%4L%bgd_^gGSQV)N}x@uv2a zS2D?1RDz$YlvLz%nhL5$jdQ@e0x7DwW);mq-^}0q4Tf_A@;|i3qPE{#MzLg67Bt?8 zqF^&|UZ41mv!CD3$U6oz%*Ky4@!`UX#&5&pjhx`#g9qG^@?yyu(B(&V4bW<ds<IU4 zj)Q}@!wh`|ti?%Q2A1IE5tkhgVZU9p_rC?K7s|i+pVC^dMZeCtfE*qlJ)`|um%gDx zaUa2yM;#3O5iSsIm7wOSx5zb>`l(jorsZ7-IklEH_LsR=#SLFH*>CkbY_^O3#SAn5 zn>3G+iHZHcmFE40JUC}_{D-PbGKHn-zSFQ?!+bh5b49)-cTo&LsxFqXO$Of>`Fu<T z(sytSG7d_f=Hq~%jhk`j6iO7>!60;)d$s*@`d9&qdjcakumiCI#U%u^PNrbMfE6qq zEI8U6afvlIwDCgzcg2D&BNrUe>HqmE|LH({U&QQbY-BQ~F#}@hhwlRx!<E1tcg6r4 zj=hx5O#qSW&#j>=3RKtWihF_t5oCFM#|&cpxGo+*=!$p4Yt0EBqdbPKI*RJB_1YB- zLkWdai}<*Vk^#>U#O6Ls&J;+bCG;a>iV?%ziPk=ewnDXeuWOki`@#U&b`%1m5J@p< zw4FF4{R%uC<9JZwzMYds5+^(DZ}GNbQSDf+Ub>xpQ+MQbHW2-hJR?kNH(pC66CY-1 zcC_;nIWOO-fGQLcYz~<YkhpYQeIgO}ho;c6uqm_2b(iBZ{|^#A6}OH-b3?I$8jn_n zz}j^t_^n(5i+kTi{{uiZ6mX<;mf7LYWFljC6jKVj^*@93K{?6>iV(VL^~?FcgIHqB zV!P_e_h&Hn$=UGl^eo5vBZMZ>Z9MbxOC3FOV-YJJczn+>fUX2$Hd|<MPvh0q+%7!N zsF(7Y7+|YV%m#f|{89y2NxUaD(Ic4jDE@Sflfrzc*wF}Qjv0hErJ!5`o4W9m5pBIk z6*K7Ch_ZB+ih{GM2+%&kc;HX(3tS<T-A$qop+TLjNqLnJlCZfXG^HgJ{z6}~AX{kf ztK_R1gu)=H6iQ8H45L5x1h5d$%pLsZ8P!;}EzalNrkN_J7O{dCkvuCiyzxM`k*b_1 z2*a+ts%8L0%2Yuv5r?o1%{)A{+9EgeXt+6BrMFJXne`<_!3a6hiAfU?;4MmHp^*hU zP^%W4>Vl@Igi>buvM=-`z_=kP4XpLAZT>!!zf&ez8b^s3bj<Zp6|^h%*=qFdZ0V^D ztHX=Lmi4&diXvw{QL?e!<Cf*iY@PFH+<P0wT%Yf02-3QJ`Rv=s6FEJVDND@l!8SU- z&ze^HaQSXji4SuZB&5I`rJHCKyLhU1n;bNu@LPJ1{^R|!O%U>XJ)~3l%8;a#U*mdq zeb(DWrAJ(R`P~Fr9MfLtYAHdj!ncZ>|4E}38>=@~+}&EiJ(AZ4+9-Z2Zl%aLikGW( z1r+uC8$s{)+=3wumF=&~t3o+y0xc0wlctgt>eUVF*JAe14~~aA+4YREkv5&9mZk8) z)mU=U$_wAzP(o^0QXOq`K`2uC#drHZt`>R2S@%jS8o5r!XXmnH7Stb8C*h7t&7En1 z{PIzF>nCOa-qk$?H?GI~+@d-M>-)0qpuUMy$EvF)yV8q}lDFNB>huFjb{t{VNx*9N zLKi=p0$WE~!&dQRimsL3&btz&m!eGAH9*8Z8*P{^)sHFuu-#|Ari0o6lgndGx;BEa zv-imWid}5>7g<!8t?~kvFu#_O#RClX+<X|I>Vj4(yOLfM^vrZxtF|;Ia+sN!(Z`NF zi+FF88I{osT;zi()(Zr_igVBDMd8K@*sqR)%(Pqe+TZa9mq~tGU)s<5(>5rub&u(2 zN6H2Dw8zMt@fG=WPt&?m+PnR2lH8R~A$Wtgl9pAsFn-_|AT`l{Ssa=E?neHnp4tB; z#>dFO_&-5DW+n!X|9179)?SZ0XhrtTulr+sH)z-}MvbC@bpxIaCILk9B%Bo5kRU<L zXmgF_4V}~Xo65CmIo(7HqM6qZr&R<!J}O+bj8g7NiJU(acLHrbrRPTFg8g2kTQ?!{ z&P}uo$$?BHE69r_Nls^|b}U7trZ72aqcE|odZ0EXk_Yqrk^+WLE80N2)w(^KV~wFb zyV(FYg96%37FDZJS6G@#3s&BO+C7s2EMT<-tlEtvEyS<GX4&Nz3Vews{b~SgfcI7c ztQJH3vPpL;MHfb?!WaVp9~4QCWH?f|UOmM0$i{saNp5xvqb_E-zAK4hrg0M-j^Kh` z2hFmpibWK|+qs>TymdCEjFQY4E>?M}tjkjB%LNkw+`{@aMFXzqh>EP0ai^4Y_#-@0 zQqv|zCOIb$T!OPl@kmm`CI**c^#g8H=GT@_f@xCswAM)V>-;9q>FX*JRh}rU%O4Y! z0C#d#dnl<47JFt5EYx9WV>IS^P5Pr1_@*AeH6A^NKjZ38TADU+-9op({Mhm6Yxsbj z(COruKq(NqSrCfb3p_1HYHT!7Smw*N@gbE$Nj4yF*49ks)nI(TdsgrLf|Yg|!r<Rw zvCuri=09MX<V21X$sM2%hF}?A#9SH$uwrL07;tRwhl@u}lp$j<P8NWRLQ%sEQusBY zu;33E68_#MhZ<DD{e22c-ls7@RjivcVStww08c7mS~bE|@4E65W@mw6@3zX-Z@M(K zv>^sqD>^CC9d;66KHqFIcYn^8{aMciit(*q_TKmTNl*~LOf9Mi$tPF0<@<iA?oQzQ z;Bkzm)4#W|h`rA}Qgv~Tn{-dOQ9Bd3g1j_ZJ7W+<^U*Z(n?SE8H;*^_Dt{k=X6fK* z#rXxT@8ts)Kb|b!d%)}N5FbMkh;yc|`|)A@C!FK=>v{N_s6Tg4#ufkf#jDG=>G$rX z3-;&ax6iht@t1jD*EgEPTUDDq?U9N1*VR|u=QN;exuuU&wDxjM-|OA$>tHwhG!#Bb z$_ax7iAR@S-?00YHKxFSNBKKmzsD<J7PHL4w!YQE*Y04J@>uMyNKkv<T!G!%{aL?T zd&{ox`{S|7{_2X~(_{1P96sUu>?{7+zw`S6+?M|Wk9rF~ddfBjLa%`=F<N>nh|x@& z`OUX`dJuE|lK{WhCxaof&-?!AvFojM=JRnfUElv%POtakd!*}g>%)tdl1`3R9PD~7 zO&2EO&YGde=k-&k?^N6fb`NYyOvVX0MEJwah={VD=F2~L9q7=%C+D6TmIzf#BojQa z{C9QFl%HjfVorRxX5;#Tpi>A(h{QR|@TeehURl;YF17ek%YvyTpPSltlm5}6M*{W$ z2qU)T1X=O&pj<Z(LgOLKKqAZdTGSaaA8mnzWy6T7H5Y!dNjT^B(fSuPZuWy?0xyQ0 zwCYLxAGAG+N3=v|DIGK26hAm8*f_~;NO3A{hp9ZBz}^>A(oe@@XHr$QbmOhn%mj5L zId@kKg2WKFK?zQ+o0Vnk=&^>enHeZ)l*z<g<Pu#r#!MuWh^I_37a`I;-&_D24fl3J zQah!kK9dja=O?WqejZ%r{?DYs$VmNUxYv{|za%(itjIWVk~lFgb`w$=Y-nY%!IVS> zS5ldhS*$cyjU_|Pa8tbh@8Xb$_SldUane&`2H=FBc3+<p{-34}xJgqDdVmvl+GM>> z*dY^by5ZlZLz~ryj}E~iWU=6X-j4&14UZSgg9BiKpJbt(ub27%U4$EQ!c7`#AOM`O z(g5|iVTT3bFeM`N{l!ds{20zq2ZWmxvE(^<Vici3xnNhi45<O-#qoxn2c@36Rx^K# zq3h+P!`Y%ZWpk_QYD6N+6abuw1VW0TX*Px}7Hu5vhOFo#!lU+K*`z@*sK5D}qe0W- z2D`27%eTGuE6X1$(`r-A5p?6y0mR6ns+|@tvlg$HmhI}ll!qh+4uobwP|v_=#l~DI zDn86~(!uBMf>3s0BP|FdPAFmY$jA&Wq22_~H;PL&&N@#52{|D~$LK*#9|(z(0LBdG z0QYU)?zMoZ>ze6vE_Hq5DC=2PwQV(h1$~d%{Q$8rs3GbOpip<=)o9cTNC{P%1((NM zrTeD3i}$1?_564phCgRxQ6Q-pHeF<>6Znli>}6>F%z=!M=7%2vkvTB@BfbpFX=%8^ z#nh9yik2QS?U23I(57pF469F0d*G%IF~vpi3R?~(;-ZUCb|5vESpra<jhyMZVKfan z7^H#dcU`S8COskGFHoWDT<@%}pr~<oYA)~@a6i);QIFs&IJ+YiOuF=t`f3Gyp*_P< z_9q~Oq+;9E`=v6B3zMYa@?1+)?|lqx5qjW}OEEKWcV$<h@7=aURF9neuBR;`bKD2J zcTt$=g_g^zXJDuWT%QCf(Oq%sP9zCzFr&>7+bcqFT#jI1V+0V5cO|C7Eb!;SOKoND z`4ZT3oQiP=&=3<M7HU_@io^|iUwfD9j_u`l@emhOP#cITU+2;V8h-YKZNNHnJ1sRV zU|)q~HCJLPZHiK@lOrr$r`mG-T3Y8(ugJ+_S{RLK!Jlii_<1Uj5!lmI7m1mHQ~-6| zrLe_d7e@vbr&UOxAW_gQ0W+ajH3mYSWmIjg3HxrP$}I5*1o);g#Hsivs#06GxMoz7 zZIUj7eS25|NBI!!ltj>=BgGU2R5tQ%<4TTsu?GYCu5xOv3O34njLItN>4sExI@hF3 zRUHjRUp%Co7iqCWXTM3l&O$DOJ;$jAqt2E$>HwH%?M1NXq$Iz%EG^kOIc%aXQwFj$ zjeg*&wJp5W&!rO8D9_ZzpU&neySSKKPIHT^n2*58g&ay-(D%@T<mBtE5V2L928Y3L zUL|sn9Msg&>FBSG6cSTuh1(^n67qaXT>wiN%!JlV14zuLfbJ5S-$M_rmML4P$x)N> z!3*tbV{<KabAx-?7?0y^7~IdER0Kh3<_VZudXS#pN+ZNG2p&2Tr^CA1TqxENG(-l6 z_`$8<Mjo~uA(_h@-ds5;pa-ET+yYy9DaemFqo`EAF#@rJ5w+F1=yJlyy)Q}oYeLh& znT~dJ(sX)_xTn&NZvB@1ELv~fs7I(s%02sN>_%&4i5a|5Uf`wS8xfky&*vZm4Ph+H zQJAty??R58bJ??|`9B$AvuL{!k5C<$E1HCjj%4#axZP4;rC6+BfB(Vw)j|pnJ4>8} zI*z-K`?8V{={4HAJ;N}a-Fp%83bp~ZQSbXszmD9L@hexRop@U#yS_|wtud*@e$1c- zggss2+^d)!RIORhK<EeOQZ7S&Kz0mz-YYLV9eN2312dBx4ev0zqH`w6a?-LI$M4>f zMn5RKJVU+q4#>Y9N><Q1c*x5ha5_qD;wh#YLED+OF_%=9iqaxUW0gWp{Qz$F4D;MQ z!q1TJm#rf41!6DUMM;4oOMir!YJt^DR8N{KsW?8ODeDxwM6Z9<u=84im3cZ-`uj6I zZ5#yc4bJ>wCeOY+=$w3=(BzOnPfT5IDYzS7ppJgdQ>XmB^PX4+6Px80W?azB3$~uI z8hrOOWkN>}u{NVGsx5)NDB1xsUq$hPB6rx#K#J^Hvu1u)zLaj9d766($Wa{3N6P0` z<O60D)oB*aYITP~AGKPp>sQeYE?}s$ZrO~DK`X9Vj<D(xuMsDA8M?dlUc)B;LG~$^ z!M?E>HJo@F3#^>@XOcDLuz40a`wyI&l?9H}X*8{6YzNJ><mn&h4uOhh-vk5{@<tqH zvjySR)P&lI_TnIh1?gKEY4h@(v|{B+Rg5z)(y4YlVJJ$<UuPl-gGl0q9%Z)^Dcd*i zFoH%&c;0(-ZYWVQz|6ZEwBOd+Ok*jOKP!EISo|R<?qK6)Q8yA4xg!8FW1thiHZ<z- z&acfKvD+{nXZndRtzDQ_X(cF%rWF9ji(mTrJK}S64ZL*QEu~gr{-?7B(<tjmY6Wbw zi{2oP)?>2|ls)lLU=~Qm#h4$-%DXj1yv2BLn%;5NQL~y9?+H`#PiM_Jr6ok5`Q{(p z9)X!iX?LlT@#iQ-xoH7uRg;yC&72-5U$pqRx%@yfFs=PRDT6<In2t*@`{)I=lH)?; z$Vk`(J`TH4GPL5wGmB6gzVT4G*_4w=dRs$3X^6XWe;hlGdH?=~{wTiZc&lqI|6Ag( zwBWvXCMo#y$5ijk7}X2{^z}I|n&hc?#y703YP;RPY<-yj@-6;n>+^q(XV@73>z&P| zrfvMZ7}8gs{%)m`DQsi)^E6v?YOQ-9J})JF;7`b?nEkFMiHilt0Oeu->#3_Xb8a~o zb;U?EpUCBRru(VM8JUrV4wv$KlZQ#0haE=5+yoIRM{~Dbu#^xfPQjswyWG`5PIupd z?zW~fgm6}RG~9*x_$Je{SWTo(3eiU05>Iq>&BXnsSrfK5=L3M;*$ezQ11S-zTq90y zU&#!}QXZE8BTR0**YN~$5-Jr(O!~~^ECGp?;T)UJQrHg&5y>mC35w>C_b|o^#f8zF z`-YT>O_dV%r;;vN>aLiR329j8O7>qok~wMj3;PS7JB+76CigAJU5<N<XT78O%~|>- zx5RYZK2In*?r~pSE{*R#HyVryNtKiWRM;f6dowGTA`$%(oL!A;@==R03$>$of3|?^ znavxd&yo;g@|;HD^~FNa^p(0+C+;h{RPk7Y<EqxFnn{jJ5h2}kKr<9N>>(F@Fdv^Z zPCMFZk^N$%ml>=cBr-%WUIgfQ9DJleu&HX~@R4x_g^}>Z!eR-DZh@)6aVRX&0l8X0 zh!E-2o1~_#cC`!mKNRbe0=NxMbNReWx*5}Z-@~LT!vpS7L1ft(4zq_Pr3rod`r*N` zkj&H_P02A&e@JQOSwe*=^fE}RGiaH;mhkpWqi!_c_J0likRBHB&n(GBL&9#{=%w4E zW*h3ax2H@Qo`|7d;HJ+%+9@;^-27`}%q}%?;$2BW3VriMlyC~!*O_!#5x!xN*0UW` zYk285-;W;uLi;lnRez+%TW@Lr$R#^vfMv9Z+<8Np5HEYW>7!+ps+DP2F$Z%!`Sh9= zxmXdDfSH=Ot2k-dLvzQI58V>!?e@7`maQ`$v&<cph=YE)Ww*{gOv$;})dJ{$_r#TG zvemxzJjO26bMR%!9G`gI&##(zvAp|o@pEx!%je~1JpOLG-TC9?pn6_gk0FsZJYwYt zs$`*jt*RAHZ=RqR)CzPV2hyE`Cu{DJnD7HEmd%qtsNv?^rW~=4gX_zdi8-5Fqd3G+ z;d=48z6yCOwo54iN?25zv5ps9OVe&X98eJ)LS!K{2n#Wl-BuCjzMx176A-)DF7LB# zb@Yq!9a$wXO5uvOjw2i3ItUH7K}oI!RpYE<<LoQza7%Gt5FhivXMcMSDjD=c^-wL_ zRszX;fJ1>S22@G=g0PR^nIaSC`~Z|=BAUZfziflTvgA0=Uj2HmcS>uEz{;3=KfwXL zWw)6&1_JlH8x#0w<2l%K3&&qU(g212z>rLkI4)?N@^p(A^+FNT{}PxBO27pOcWj7z z<>D6DM(b3VehHFabM613>>Y!2*}68}GFBO@Y}>YNtg>y}wr$(CZQHiB%BS{s`kel{ zV@Jo^e==swcp`E}KAB^ToH_36X0zrpkMVYqUeGh7(%x_%9jBJu<~?1f)_D3wDDGK) znE(SuGlWkhsL7J{XNIn|Te89Mo=N6v5w$k`=omeNdJ7R&5hiBS?AMqu>E&iNgBr{; z=|(-%ncRZ9DN4?yy7apBaV|Vg<6sCzWnBIo5Zt6T3?qw^HcF2mm!xEIE8Sy-g;*#s zJ4V>5ss34$gGEBDO)i{DgW5LdY`~6gOSR*G1+KH|{AwJTzKyxkfm|}DnV~-~mei$C zV91|bmKr1Dq6<0qJ$`9MxrCYsDN$Cf#0&j>w&{od>h6Z#>>duz_mZ}l9gdeS9u7|K zSB!<0)&htSM7Dx(5T#E}NX@>T6JHm}Qreu}r52DcYCl{M+Y=BP7?$tvls?XOef;P8 z{D5J7z{8r_D29&P^o*x1@0&9ShjzCr#y($UkHnBvmq;Hxw#8!K?=`h<>Gw<=bdH>m zbF}F&h{7s^k35L!fn1f5(=<=FD8h_TyYi%m+a(qP-9=j4TjXLp&4?+3l3sbhi{EUm zReMWHkimZxcX!pL+t)g41WZ*}fk7v-&V#;%oPdkAte~)7olw|9I0>A*7$1Z}<7wt2 zXy*YTHK@{I#g>d~%Op0QFMk8!2T)C&lPS9Jq+NOLSJeZ;_9xg9u#Gf20xo2Y7H{Ty z`nvLwDO#-$#I^gJcpV|3k6T;mW2i)VY(4^O1T$(YF_EwWFIhyuv^Jf+rUBKOAsU!S zu}-h6hIC_&`UYOo=)j!EV1(E5K_;q+@fRZB5=pG(pNXd%EJ{~FT~In``OM7T9ljx2 zMR}d!4E6wmP|8UETaIG?@7r_#Uyk~}(dVW84}IPz`6C%1<5b6J2)CsLQsrrIwSymt z8GI?j0Yn3_Y;wop#*JJ)R@ooR37JU13CU8Z2VSn095QqdML3U>fSi$lIdsKr0d<Mv zD4Q;LLgFG+^KhcOVWgY!6ERRh42m5Pp}#v)>Qtg*T)C?{;*Kg?9FoSx9B-!9!2Vtd z8B8pFPk*yU(gXy^=~TxNrZ12BHtu$B0R1Xf2`w5V@P*q@XTVifRx^6LTyR9BC~tD? zk2eqe@%zxRW;%JneV}U{KnW=>^RUfF`e8?i_*?hT^+Uk~{pp`0LW0tI&qER^eAEsr zT5F*`Y52kk1Wd1_u+lz?VTY$U_*f&znpeIUWc+Pq13;4g`0M%=s)8Rv4Ob4xh0;mc ztiC?A$lg~ef5X#Vwm?@F&~X$<N8!(51*y9Wj!PyKt+L_W*6dm()oD<s94(CzNY3}S zCJ<DJ)M{dn>N(n&WEg27*xpm;_J<g;1Gdn;kF;7Ol!lfQLQo26{Dt38)((bJzOXT> zk;3jHLvDvgdk&5yL>wP!v`cAhP{u$NPyVCkkudZV(upZ(nSmGdcIl;Bv2zq~5lr;V zmi8rfiYX$(&kK_h927s0M~t7_vdL^kWx@je53<Coj3<uk3xy)<-JjcAGp!v+j6xwk zRptEI*f%MD2*2(2HSvzgg~#oJQ6aN|h1q`vLy$%P*5%cdLulDh3yILjhc^LxX`_nS zotWP_FblneRn(4x{XR#CMQr05SlSdyAj<kf%Cg+z#$xj+$igZ&%z{YfyTAAKw>nuf zMy3*9P+i5l5-cjQg9n$oM^2n_iFCYKS$UA9t~&D*UhZ1dO^JpIZ&0ThXgNqwTyU^% zGg>gnR88SGEG7nuV}F8B@A)YUOsaG)Q(yww8o616WnMS3K`yAPaeMWM@r@097GETr zO31p6G8_Vayi(&8XMQ4OsPUL#6vb%?OB~ib$g>vp2V#-g@wK;8(#w0v%gtOdrhh*J ztgSv{3Z5S*CtXTYuocd>Xu-*WJXsV3m+u6G4->#yqgJu(BWn>v_L$%(+;RU=NrS^h zUBf{OH!KE~-SB0z|2#?k8UJXvtMCtdWLXyfegF4b6v|O8uVFfFkR`1825X-OQbq`! z!dk>?NZJjE^TY?a-_}ORlu&=@t9<LR0^!&h)PA~yc6U@J><a40UOKbg6m0*~5v*p2 z*ut%mD|OEAl@8M?kA?JL!xgai`=sS4SR*PSsks8vDY8qLy!~w873kd}h?}4b;47E= zcBAja&g+{&V;X*-0F@E=jJ0DwcXxJu#VUm5x4^+}&tVvr8_COukWGv!XD<{4vcor@ zwy|dPCC3#KkAsfTD8uY2<09FmF30wCVYdRaDXNHseLd2-5;(W!$cCV`h+_a#F7rx# z{o;b6Fxg?te7z9rC;3T|Uw=dg8|X5~(CE*GE`Jun(DAd7$^WsCA4{$Vafl8}#BRKX zuv#x{9;k*E*0bdrLQF58#bXVu@cRgr#G3&7rk58)%rRkwL6>jgWE;RbG97*Q4<(iF zb+SES;rnBYN<M{g4&Ab`f_^qfucjVC_Ld#P<mwkVMU8gf`WuzMv^GHl0RIvinds>M zrF>^%`_FC6)g=Eh*y+Adsb#e%5x6C>m6{)vCNbMmO_TZA3lzjhEI}+&aK!$8rvZpZ zBwlx4o6bW;08xqX@_rBN?<4B%Tibm#y?y+x==T#BQ6js+=|v>Q@s@v7%aOx<C$Y9T zTG87e(Ao4fdlA;}$}Eg?vBMM}O=302BsK9Al=hSyuIv~ejCgoq!1LuwzsSb}9C`kF zh6T`bc_8_URQX$wvct9NirIo)sM*s0b?~)d{IM{nxhkUPxTaV4pA&F>m?j(_D3m%b zW-t;GYjsR!rtqNtk>@!57o=YUctz<4(hs5k52XL*9|!XvNPoo-q`&?6N3l#k%$MSe zC3h1Yh6ei`RSJPWyFpLlk2k$kce3z=h({n2AAbEBCfn42mu6((^ZvF4{#xHOZbcnV z)q;S^CNvjohtn-~-&vaDT_Jh=0{0`#v0?=QWsJ7f=S<4vs~aP9Xq)dl<A1U>?L!PV z)kMAYP}E9tYmvyf5D6v|o+TE{hd+L5N$|91mK<-QN>ht7UW(fB>vmi*S0~*q=po{* zFVgYq1EQ^`$m;k1yXe@pYOAM;3D~Bfo5|=;7{nGo7pogNPy`x?+^ATA-9S+GA)TH& zuL7$yl~y)woy#w*>S=BW+I(VzhZF}yzuYe?8ity3@hl#OW)#&}2VP0Una$S`_owQq zdpQ^whCxo~*%o?91S4-ojc3B%VXYu?1U~xDt#}MYbge=a32xzp%ra{|w;>1y!!o=* zM0KeFjNOLVSxI-|wh*%5L;pyV!&Jnk7FCh>uo{mV`KvaHgAZ#Pd4!QVRb&m~%1(iq zgRVza#T8W2-?Maj14g%YrnBtd!Fl}#06<<$xsp<|)nN_5vqAH*HSd6qdLibXXt}s< z-n6+c(>_vsyqjTFO1~y>7R`LEoot_CeQ5&0BHze;yJcT;KrZg`YI(w2e@%JT0WXoy zzxl~&oqFkJeKD!F09%n(s=y0CxyFi>k}mk2cESG*5>6NG(*U3vl=0V?CL;Lo-c4qV z(sxGN#Q8bfrt{C)TDdpFuA~_Jn0R5Vt6=+Z5v|$5*k)gVTDr8HrBJtEbIZZ`@K++e zyI}Yl+5q>oAj<L4RKIBv5;c&_;QSdXx&7Bc3wG+=YoLI&E29{YbW@BrXzrfZxFr2< z(i=xdBr(ZP#io`1cK*2}t?-IXEM{jii)qodR9We+MtQPQKv8-9i&}GTAjAe6LHSK4 zeI6hUww&UfC4H}7)GhzE<sM&{6j3-}y)#P#7IXk($0mJW=Oc;43M?Ev5hUJVc<j=n zixQ*V<Kaf{{(Sv$p>vaywSoO@NvQhVvCaKHE1S-inc8`V$@r|XqL}algIQ%#qmsJz z|2ufY#G*~j3X`~bG;!55c6N8~o?fIFi^MUxVoCkEtiG7%by2DzW@P887l~>={f5{u zsw`s;;o-wl>QNSS@({Y=yOH>9#VhrM39Y9n(AC6H5W#DXiN#pIt-c?WacoAp#+(?z zh(>?i$?LG(eu>gV>X711YF18^LH!x!v(k*7n9SNJue61@lK?4JNY0%O>FXt??~aI? z3xNJ{{aVM0noGAskL3)3%69*uO*6~>P2bkLCu4bns3cb{vk#Og>G%TIi&O^CbR*{I zNvo7=w2&oG_o;rf0z5>sLNaLAwY&#)$DuQu;mNNsflB1!$sfP*>VK&HhBC}YFM_4t z#A{GX+&PAp{b&ZZO!ihb+LogN%Okx*uipD{GUbAbnXhFGqzP1kJ!v?KESikfdY=3u zB=^V<B1}K1yY>Jj%i44M_^YgG9ixq7`<OJ<O}|{3mbb4H$431M%LV}w*Sp^j`zjFg zIl8jaEu#*@qq!+OIHYD+dnY3XJK#E+oY-<4?p3h-wMU9zmwa<6(3b#-tM)rdY|Rjj zOkOYqpu~#GCcS68GKANfq`3t@JA>p4ym&Ks<6pDGzZK4G4F9n<WlQ~k%?@C$mJb*v z^CZ%l+K93t$+{UxVUA+s(cfOEAY>23qKR0z?sa6pG%xj0cV4JXu{6QhTp8aF9G^d! zf1nn1iBxP|5dQ_W82U*MnKS{k_@W%?ibaA*2ngG$l@vK87oq#MgmX#nXHM-5*XIRo zp%Adrdi6nJ(=t0?nPx<d!H^aXflwYE&*zTMULw0Ru%piERdK~!s+A@>)3&vNJKJFY zIBB;$jXM3mBra{x9AlrETDX7e=AutiAVoqyaR@1hlkt$ydph#?rZOo61jOVflc+Iy zI8ad`-pkw{%4t;qHPVl$6X-|OxqAf6qRYfj-+CssI48Cq{$uUJWS}d_mt6`qA_N`6 zitro%(6n_}2!61Q$I*M82I(KrxZ{beCg|c19?bEqJNx5Rt$W>Fd8d7PVY0fl7eD+s z^5IrE-l*;SX;WohCugTiaDWa3lob|2KUG2|clFS&t?;KN#YvGw{2>XW7|3<5R~<Rk z*K%HFd>Y_L9P7bGk~UoNIT?xEzu@n)UA8ZenSLJiFY8_RSYBzya5axMP>44$by$Lx z7zHp_sq?gok<d=piuHo1T=o*QwfOzc(KjF{A7c}te{%htQ_3K?5Kwzqo8T&f$aR!q z>epm)!<Ft+nM~}VeRVr;sFgt#*2WMk*tt}0XE92utRW;3NJ+7V;Ql_@240;?FQ?wY z15m@7f*fW8aZqjtc#u-FaZOzr?ay^bR9sv_k4sOMsSlM$6U6!;O0qlX*7vKT<Sr*f ztZuV(HM6)HE+DmBXs%Eoh*oBFp9q=}p;Gi?(<=z(T@`-f?2D8}68sB5)d~eXH9Ng8 zACyWkB^Mg+>cQq~9}8f`A_09Qox!g&Z<%C#Y&nRb66<fg*?=JF5KW9s9^`JPF|6kJ z%6^fkQ8Rfg1z<7|kO=%be9b?KGW237ZxSJX1`r_rn}$VLUNN|9<EZ&<xy|cqI*M9a zd5KKlN33Fg%V{`|!<?bs<$S!#WNa%6qat4Uj8wM1s6#bfSTBBlLn%syVY0G)t#XEX zb?xR=*n@^wer9KWtAl~^MkIY}#GDxMy4nntg8Qv&=8ubY!j?KJRkr}7_d~`#OI5W< zv(?(J`M!&#g6po-ANZa7YSFcxPtOT;og?mbtlYdnWC#my<h!3%xsbo|LW%H*kOZV* zrNAe+M_bb$vgG;2;PjKkscfk@UKH#i0%4+aa{j;$VjR+f*r&a&G#juVxJ-+WL+Hy8 zsk#z4MR_2=1PTclHQY@|E$d+}h2UqBaK9pwPAFZL_8t=Mb3!kSOXj!qfiok@Qt?>O zjDYLtNr2E6H+V37FDn2?1qpnC?QJw(KU;Cb10=SHzfo0&RqVC=&V+lM_3S#=Gf8<Z zu`}xOpJh|HCxzbYQUONgz#GuOA8SW2M)+_;%8w&?e?{0$=Ms`6s9yHIipJG2ek<0m zKH>$pfgmM@6~K?<IGB<6=%tL%H#VemOQf7E9t=Ca?6By}s8by-+IgTIp0sX9N8=UV zAUs>8b0`ksk%g_^Rc@_8MdaRI-c%@e+eYQ>!d9FB2^y*mo%R@rNm1R&@%ZkeLdM#u zZwX_t@~zp4Llj<X0lf=FuZL*U{}Fu1xtG>E&_bIKK48>cb!lWCh=#Bn(L-7^qc6Yz zj3V#WpS0&Zx<W%=-K&(P=Cso$A2gT?dR?~PNFGp$sq@>C>3g-8`f~03yQy>{tQR?D zdR11Cu<3<jTqiN_lw+`LZ1o$ZL5t|tD>OU*HBX)3C(JbR|E{D@5uFPTmh9_G%!-Jr z9d7P*sUPvPj;t3QiK*JwBIU)iavHd@C|UB_xOp8Cl(td7PM&HxGe4@XzF)E@ZIg<z zOSPlxYvZ6fh$p~kC}4oa8`HZYcid4QB1CUVJ=k8m9DUJ~i9G4J8e-YWp!(dlogbSp ze$YlO26<7(j>c73hUM*HO55_{Lr~tXh|prL<=jayz&gg1+Wp&l05k6Av>G>pnTlUd zP6sXMKkl(vv#>Srg^kWT8Fd%wvT3T&%6)i|jnhH2Y{+)I?9!F-ZoD>;Tx{>&^|1IW z73-lEs5fw5v`pN>-|il2iKqw-p(;ip!PBOx=VJDNVk~*8;()~H&(%9;TF6WOs8<Y~ zwDWoNrQue$cPW3K68SM4(^=(8AtlL+T$YX0ktH9U=LsZWC0X2kZwnYuTq@iSM&y|Y z*ag_=yW*A@F@e4XBWA)@=s`{v_u{$YVEN1PuGtJ8lc^$qC(9G_T`_szGx^rG39R_{ z-ozr@ZIwcEWzO52>4N8$hwk7hngF+JtaeX*+U*SD)VGINDZto9RngD;n6aL(41eRh z)n=!0-3sjkM{&nQJ2}1D&cHW7;m0%ZzvkP2`<TMS@*mrWU#XATZ;1S3Ib#b_F*qkR z6D|lFW>B$TuP7s=lBNzz2Pt1F=L@Y+_xN(wCjbOOhUi;37){&H;=09H)1d<gdOnGL zo(b)Z4i~*+dw{l2K9qHrR6tHI!M+ZhpURlcenNv}?#k|cVe2^@^wTM`Vbd>6hvmm| zU32$%O%nR&iz1Sc)A81w>o0>YTRev)%#RBVUgp`<?ngWaqv!K7zt9Yu&O#h(bZn+r z-<{`PChQm5?54B?-@2j)S>`f~45g#`_+%HHAbfSsU)DYfvEazIiNyw>`Z+;z2*wyr zQwZBS=UR|H2<7=XAP8Yv+`itqNY_(iu()XvelwOxH;~k!_)$Q^g|?>>!Q5+|XW80v zT84y32)%X=fFm?r1td@n*uUs2K5+c)Uj&&(DLq}^rP?JgvEOil{9ENYXSo|}kyMcJ z?S^do0<AS4WZ@4bIS*uSp9dW-g*^0-r>Y@lOKZQO4`iPTP`UD%9t%`-u`nM)93o8; zs;nO&3brg+7}cBG+NV``B8~fE6<>HdB5Udo-rNu?uMxSDtdS2pOAes69TawUs9VTB zF{-Nv$T)dRM3YjqU(x3G&iA-{h`S?<C-4)luhC4q;GfX=AoAQs&{lQjsMmEHD-FgU zLc!ghJ{M@bm8i9c>>`W+{D&L{q4NZ+?J_}huKkZFRu8S5^F_Y8iilOONtTU`aWL4^ z_~QrNcuKsLkDHjw<gZbTYXP&`h(qyJErx6d$%?M$B}S0*@TuwgqZZ!$RTO!}>M;VY zGr=lyN)~kQ$UU6-iJOjFkR$gf+_T9H%l%_vRE%B{39wx0IcgD1MRATskMi&!XP;)F zB-}1p`5B~%P$E1tbJ{imO6W~>fl1Y(g|QEH^vdd0+0e(r`A_s3AqsZu0i{hfx1V|o zz{vPZ@0P{Z(slmqn^R_sl<gnvNAu;@y02xF2&?IgESFsF?u59(7b!NEN7%<cgSbJw zHPEG-peA=#5OtSz!k6e<sSw0;-Z=rb@f_<Cqy1@nP;|Zx9lP1VqNU~I4{m2wCqIr6 zDZArvL70DLFV2}3s|r2lb^>Fg&n)2mOTZ}XnKJLua_rc+Q_BAP9o!K?cA2p;M<`1& zFgEk$KmoG9>1+)VqyJ8cBI@PPS#OPBpLJl0Xc>BCzJrY=IcUVOt1HJT8{XfnCZ$?( zD9n246PN4+5eeaaCH#KOdYtw3Inm}Gn=EIo$TI<VTxA^ZvNG(l#Ruh=h04yS1C6JE zxIo0!g<t>5oVUSL<*JYPo&|3hM-l`eH|vDJY7`<@*exVv2G{0d5;l=D<EE7U)UEek z1{Rs;)o0}cQSI7gTV4}d{!#EV-4POUTw6I=&Uvw?iARzw#<S))DF^wE8d4@f_Vd@m zcnKE)`c8?b32$OeqQK^{Xa{n6k|YhX-lPZO*@3DWlX6vIO~L1Ixmw+K{QQbHq7zLJ z5zb>lyunC~q0JE^ISR`JV)Ml~ENln5^>MASYtMZacIiLMSO|nyDAOJ{p-**>=Eijm zouuq9(SX_+6Vz9s-+u5Y5%@cGe5teZG&N_DyL<sA<j1M!6#CJZFqUIR?h{WpuKs;! zHYUD5M3ANUOqISv{ZXj&;V*3YeNd-@ZU=gB#MBJ~t00Wb;jVeFk1`pP()T#j2nT|f zeyvRBM~HGDo9|@`q4TJ2rX%_u<<y}6P25!TNp!AB5UBt8hQ_ytSZ{+n5ZZ@=1_1Hf zTuXId)cg9<v?Xnzev3Qo<MbxGX}vb1Yx#O*O%UR=B-D4Pm+Toje6&%9_nS;I|BNau z!A1d*bf<wxCcXcQMN_)w+b4Y#;9|6!i6FgfofHV>+h0Ir!;?wbbD_vqv|LD{4OvJ+ zPnseLwJ8Db7oyK6cdrR%4&2a*=Gh1yoI^%dsoX}xC-|UwzuCWK0eY5y*^^`cnf;F` z$XbdUY{*_GDz5FcV^Roj$xoxnjYR_js0zkpj%X{byJq?g(F@5wJu1nTm#ctSip8|5 z%}E|Lj*c^Jh{M}WAzdySKC&&&+YCDoamn#+3pUyPqbc)>=>+1PXGtzR`(iOIW%r_U zsiAW*WMinDcb-yrre$+cUQaC9!p%-tUYJN+;q_#Y1$QZD;4zH2kUQWZLG1lWZk^0& z)}JlHyX4PeN6Rm9vTdl-Ez>=^H@~*MZt3*bUw)XhCpf6kkkh%`4>HYPTm9B#RvO1| zsnodg!;~7#nE#-1K(PzmM?oA(#Gv-5kdY|NtOOv9MolIa;|VAdvjR*fZ%;>3!x1Kp zJy=42P&qz=FOAWp2*1QB(yxJ`lo9yoB5E$LzIbyE3xAcnI%W)u;}{wEiJEp!vEg<> z#uGW&^l*&A@nU1;K9hk2(Y?jw!4RqLhC>6#OAdx&g%a_110-k?Mx|wqUvyA$djRxJ zeK-rMzF-oqOsK^!`9>O>p`Exqi>I$zcpuPlG^FgRbk<fuQQcZ)hOo}!UCdoz`(X0W z@rSO%ch3j&g`e`U&{4Sv!W=6gW}V}4NX5kx&-Doif~-dCMv6vojUK=oN1!lHikiid z+oFQW8#jP591)H0Y#9Y(EX+JNrKvOKQ7%dp3aF<rt=8&!Ot^a@l4RG{y9jsHWbL`D zP{0p$Ub_3yO9s#+2=&QTc-Pv)gb2=Jqp<5&8q33*z<Shz5hn$)L)R|UFSun+?i0Pu z>qSxG=_@#UZs~;+deXw5IPXJA{_d(d9Artrk|*x6LgU(_AqNOgGWu?_Sldan13#Xb z(Kl_L7=TO??o-ax+`)WJE^_cNA=5=DZi$;J^d~7{EgCpKXSny5=v0I{rfA<*6Wa4a zVL`nfSJJn^lp9pq0Q6y+U>NmxGgM8Foy(^;(?X=|iy^Uu&yXmNLwr+nl(!E?L+x_3 z6a3DqT)+K}?_c$Sx1#C`j2*}={AEW4CLoT01V9WdGW)2F#>)$^XYAd9U-^DT87Zq5 z`h@n3BaA6X$6tp<6w{kOI&#iBT5!t`*;;-<IMnrI$8lWik-Eb}5Chcb|DkwD&wA&K zMhH*zUXUbj3ZTqY9BJ$+!l;{dGC^ftx|tw!8MSwg8b{TK7OxJs&kooNNs}#HADE^l z;vv2q{KffNz4uK_T=9*!uIdjt9AcK-i&5^#051thOamPzSD3gn`N|A$ecX)MuiR3l zq?ur@Rr(lR5%udC3KW|_U^sa8gEbT$yq+|YStztoDD>ypEKHUyI=fL0uTde;&6oOs z!yuI8S`Lk{>$vjUK5lM;CSg|gTte@j;vDv=S8R;b48e_t8nLSoLV~c6uLw7eK%{5b z&23QCL~)}k9gqaC@>mx8ihAoxdN+_lHly*6@d6jDUIR*ynSB$TF1LIS(R`wHrA{Wq zXr!J7O*H!crCYNm7AE&~%hCF*59urOM^B;m6Rr@ZBpv;&T$)+y8?Yn-gdh@3Gh2MP zv#l^|B<9<7VBH=k8Nd3Vo28!xu?zJphk^&S`KN((-Y}Eqr(On?LBM;DLBdcg-0SS7 z;heJ9L1VQ|=2D@VlvHwNx^(hbE?$gfOcN&cD3FZ17*@~DWFyhEjRfjqaaJ%dMmnTG zL(vzGQ=8vVVMVI7iaSdX^7H2Xk+W{De(e|DN^=A=iHFrtu4b|HD<?LkW{5Z^eSk>o zB!i?&XI0?sS4CO^=Z3bBoAnIg9?3Lnv%HCXtsdh{tJoHEfDy5X<Ov-a;vAZo!0H<{ zMF36VG?|3uWDZ$RuN3<Uw%3588cS9U$wG^_(U(r>mK3KSnI*u1WKMK+JbEN9gx=#q z;zSwt^h=PJ@w79ZWCqDr#|PN+hcG4G?`AVTX}&uzw&|hmI4=)Zrl#fXOB}3K(S?_H z(&x47jkCj59?u?+cAvk~&Ad3WGA}VaSy-8E*5D%vTU`y+@>jUo*Ep9qS2Cm?$xu~x z3+b6Muq6gSbya^j-O|AsH>gZd(s>WoESuIL6;&nlz7Fq$lfEyvay#?l3HBHG)5Sn( z$ZpxkF)7gE179d?SRQxEB4EC0)wUo1`8TWm;6C+K8B)QALiEI$F7J9#NJGbq$yE2< z04AnBTnyA6bc*zVyJ8HqAu}Q>{Y>m0rYifHG{jFfqI3A|62a{hJ}by;rgt$Y-42N7 zJ*?LyL8NSn!Il(;!T#90QVWwQ!PLrJN09Gl-19B+Xpx_nj@qg{U4_r_y<h#R>ekA8 z-uSKj?pQ=}85Iw}hGe|3LNoFW)SX3L(;EsRThs5zBa7ttV2=GNV3!|AL(M-df1JFk z9ShEqn82kGe9Tlj)?+~dqiYLVL=HibSbD8==C3gKx5}lPIxsMN{x_iBwKk@1y+z2Z z-CUh&xLl7``WOT5o91#d?qY`cHu|4Dl3K>Qv4}z2HGaqnd?y^TjQpAzQIR7Th2uui z`?tA7J_U~3ZDH|5e&rLk?(*f_u9WmqpDnG7C5YFK^0IH>Ir<#kf63;Itp9xv_5Yv^ zVrToG(ja<v`v2JTU`but2CEIB>q6x=Rg<k!|F;@QB<M4+1Q1cL{?!0UF#hCYWBqV- zQ4ke)hEI-4rkPqiDWcH~*tj_JQp}-&SFG|@Jr%M-Efto~rwwe?cQRiaB~z@EG~}d~ zBJfIeUF;b1k9@kC9x8o4%&1u|DQ^!2BhEk}S80m)*Ptf;lE1LJa~atDJ}^Mucyt8} zC2J1ug~K{EA6_3QB^vm4R1=o!l4z<gdW0m#YGs>}fXq3^B_-oKRTSRuoHjo<5-A(d z_DUXTxca{|t%hRrPB8J9!Tbys&RRo?p!g4E_Ivy7zsl+_hz=!|%yf^#%kThA#$2j* z^~XuG44apodYSDo(TvUTV7(Co3ms_qTOIm}gEAb3>BhDs>7pGOn}qla-yx-h%{lyJ z_BOA{YZ0ljSNszfol@IMFCZ9Gtnc*s%N?<oOP8&JO2Ak#B9RK8-~oV(3U5UNF3?H( z6k#d6aD7X488=h?&96DQme!pxcI{XCxYZ?onq!kZjavmMacn2h6)d{JvM~sdEOdoT z@X7+?%O4g{e$_cl|5kXZ5zv3J5zIsl47*@U%xsszf2v)9E^Dg-X$aj=LUh#kf`Ka1 z#Yd7-HjgnGlq~y|!-{KBcA*(xJ<z_~4r|eP$$>i;Sqo>`L~_j$q{LYbDz)iE0~qP# zcd*so>z2-+F9(Xmw=W0P#=Kjg9wEwETrOgNzdtl~-f@dDmK?Xu8@LqX^9}wd{Euf4 z3c9%G-Cl~$cBbdk(!lP#K0i~WUr>ItJlzpQOr+l!6AIBNnkqGeOborP4E?~c!S3MP zlS^+&3hK(<P(&@q6dSxn(pIga5We>nDZ7zRvy|Jf7JLV**Cobws-F1o@^_u=p($qv z{l29am6U~vSB_5Dikluzm<p8#o0Yxbi3*=@j)T6poQJV<joWnE>YaDLdC!lr^N`oi zqmT+S?;cLW_G_Dm=c~7jiJkrnkRX<zEB8@h3!B>Qw_gc=&3bYUE+Qf%rQSFm6}Qcv z6un6g8zCA|&D8?iAtp-OBkPS4sS9k|Z-P1@>LJ=8I?`^gx)wOqx;|>#u6w@Up7&1@ zmRM6%HeSnb=(^NC-JVjGT58I^Z40F6NaZ71k!`Kih<I~ag->JkQG|cl>bQ{hKv(c; zb+<!@#_@LcbidJQ$zHskUs`^lPC7b2U%0=y4e#U}GoySIbX<}>X3E%cKyg>l<J02i zzdUb+*c<a^Rk`&W4W)~*SaHu-MF3}=Zr-;mk=@^!ZmZHOJ{F*(x+;BCc{7Cam=DRg znM@GIo0Atm#vv<4wf@E3f1Go4OBjDOW|VFoT5W?r3+!1&v<a_{In~=2Yb7h}Z)iQU zEfL-HXmubqt`A@;nQ*zGq2-VVlm+Zzv5~uJbgPzHz^HWVS8J6PWhyx?Jr@QRKu94c zjdB{ny!N4q8>K=}sYPXvbFWM7Rp{&uBZ`^T%&{S9=*+5R)v&R&I<ee%l2Y8-jpinh zuI=NeqASbGB(a*Kg(QtCKWK}!M9lC|ZOmcMRJYtuA`(@~f@|Q~IUkm5n^$77NRt=J zDG81Te~D3FKRh6XH_u2tBJoirHh1$r8(7O<d3k?4tDJC{z?s2dyCLzIwfB2`kia=f z?{yN#IZ@A+4ZcYT5zluGXqUw~#=`CJ{Bmg%ti|_`&o&pza}h)=v~V9x)X2Z;)T$|A zFxpzCI<bo4Np@-|b6B{tO75y<c~@2KfU2W;BUL?<8}r8Otm(HXN`+4}&^=U^EZ9w) z!?;6h&CN882k)b+)JYZvL7IiMszSk<DBx5YavFVxV3QOHN))s{bwP}h&Z2Z@%Hv;V zFPMvEU}G*2uP{&@w`GHA4<gem@RXwSz*b787tGq<+P-xjap{S8WCfR!EIGCDTJLsy zD~#w|((`uSS$$mSt~;7J$F#|)7(;^f-Pjd{^A*%>B>LhphS02q(fsZKR)w-&)CB7r zRq#>c070>=jZ_zmU$G5fYV~Kl!$W)eGtUJ^Qr)TwmL-tbW%!-hLgTX2usP8HZhwYm zqeV35cWI{cv0Ow=tB{WU1S;0B`Z2`v3&oX0gMTQ*fn&_)D&A&kMsclqb6P$!S=>@! zN?-iMO+zltdd7lV-^?6C8dToTKkf6%QKU?QyO8RRKFpo(ZQ^=w;2hSKoj7t&0|x|^ z>DvvyGE(0YEmDD|iQl%G_#Ceho??WaO3h^suhsrhRv;(t$;D=NuJZeX>-#bJF$P@6 zRq~BBniOQ)?_!LyYM`1OKqN)e3cfOJPZS%3P}c4>%C8}BHlYv37`Z#q5?TtT*un`u z@^8(HMeqr_#}(h@5^W5(hs5QYqW(-aqDKfuDxze0fbQi|Pcw|)P+v%TR)8)|X#rSY z+V8rO09{A)uRRBdNdVLadOCa{q04W)a+ij!DD!wyVdnDv_oM_L&a0mT$0s%q_FjIC zvQ4*J?hi?pFo$dXj@RvyJTKGq>l@)T=XZ7uirN`@Vlu6IPNHz3EE~RcKuR;TRr?m~ z@Hc?-9j5rdBz$JNfAeSlv3dGWU*E6P<sAxG;JsgJW~Fp=hyM`aL%KR5aVA()yGWZJ zXC4OQtBR*F#_DfM;=Jup>e)gMK@#y~M!(1E>esD*cH5{3se@bt0F89zWNr7Y*7|~4 zO~dSN0wM87IOwi}*h6QMx6acwJ=RQv>yF+)j~@lB<&5-6odWBtughQ33Lq3|V+_V& ztYflw@p`C63jx$fsiQPPfO@ZXyoL8FdA|UPMKptUn-B`}r2(QdAD*DI-Fz+!wq-yd z7W0%#?lnTv`I9ufwy$6bDz$#jJs@E-QfHgcR9POa1kkI+U^<wplc2!^Q4c4hR72_& zne;9B(pP^n{a%5H6Fbx?$4ltoT5qsS^*^#@<8YAW`LgaH<yg*~Tbq4#JcgB(-EuH- zJyxQ!SP9Lud_39Pqa_sG-oJ+j0aJB1LE~NRn5z+0?l|}B>3BKTcXhXa6lolVd%1Dz zl$ftNca|HS&YevxOKLkmU7W|c8B*G`)@nbSzh<yGG0TTD45s>cY&(^ndJ)<O%ZrX{ zuGPxJ6nmE>l}cdONk7z$B(E(pAc}y+lnRcD@W;1fVVP768x34695OJs5Bex|9#{4R zmV#s=9*;6?bHdv6m|20G?=I8XcT;5x86?>VK5CGOYhDXW2{a`fO_l$%?~3qRUTmWk z41>@@5jwHxA>&yT1WgExQOP&q)Wsz2j|n<S@VmMKrwXK(DzxrX2ukpLgqo4lNlV${ zOUuTP!a%I;)BnqyP&u~oxM4b$UkyocV2$dzOG&9LuEGPw1-=N(E+<c9N>P7*Hh~QE z%%Dl?<;kxPMjB(VGpX;vHSVu|1N+%dynrPDtd*iYEqUQ!AWD5UTOk>4(6Wf#Xr=NS zjCmqmu26C5BE#@3O=BiagfPc<<0HL%7-j`)<PEcVtUAHepWHTgn|mFZ0A?8@93hxR zxd+26jA&tX9SsL02?We7i>i%H(>BfLlvR}W3F~~79>Al}WT|e|6-jzAu}nPVc{$e} zP_c8V#KrC^Id(6_(oAOr%buiV9nw;j9=K}Ybar^~1(L7vL`{d+PJ_=!%m^)%T9{}v z4TL>utQm}5;yrb^TSM=>jQGQ~UzaaA)-@_46wB$vf4>7geixF)*%NkbVCrg^GJ7cB z%|C~ctAym;M69K7i%mSx7+j@<jaheEK35seXF%p$BJ3q(A@aE4qI<V#^oyqi>Rcz@ zPGli@f20n2D9mv}HAP=@GQUn=wE64S^IFO}k3Ao19X@9--cJi`4L)B}wiOsW>Gb=U zrkq=4P-q2j*zn6ztY4NmD*c5!xb>Dzew`Mmq6F<u_dF@$<ELAT>EBT+%~;LugleXJ zA#I^`8GBx5*vZcz<YnoU+rrXDbp7!nof=$@nMaLc`3yMyBaE>!{dEXRIuA8yrRaul zLfV{%L76LjAMHy@Cuxl2Hql6D0T9q0nPYx{mv&NM9e6{1?AD;_*+CL!Il$Wi(`6*u z%c{!0NQ*mJ?P)G&t)3YyHl++FwC+1#-si?)N}sw+P>Fh9F26L&g0UIWB9eHO94geL zLzVGvzx)93J<9$We`C!B;^2gneIifR`AUGWa4+ccM&V**x_7JVEzKs6{wKJ!Iw&@6 zzKI1UP}rw{W9o$I0$vxHLFDMSeRjl~su025eE&kF_+g!?mC~EHYofL!w2+e19j+<< z9_7D9)E{sAf72NK#|XGBH7lE+CdD6HIDFk+T?1yqI09lPTHh2lt@gqT%@)-R<X{TM zW;w}ws<tT3%buI)Laedm1-7$4hB^e{h1c00*RC#(mKOSJ%L&Uf1IvB%57apz0(2Ix zW^OEZLA9N}h<mC7bxzyP;<IN8Gd2^^0~@%8>WAQV^Lfr5=&@zm9ML8UF<|%g2dh?X zv1UY^HX*XqDX)R=JY-7ySggHge|%Qo8jgA^t=KJ^x@A4j)#c|od@M8!R6Wes0ztc< z<gcWtQW*QSzz))$@}E2=Sc+Gb6HJ$gb_o3$Cy-$4Br|Bpj(!Qhra5gNX*SYYW*F(| zCBv`j>*K*Lk}%On60l=dneW)}z(s?CLN`Nj4f2ua0XDQpOLDC&p}CWZ(8N~NhBhcY zpk|oRGY57r$J|m($9;>wF~{k3YmVA|7KC|gu5QAH-VlMmg8oL<##RvQ=#z7Si9w9< zVGrloN+W1S6}G`45KdSkz|`7e4FyxPLt^x~?1R45#Vxhc2?$&AGB{$C>hz|Q@_b7% z*q;*A&5s@X=tiKwWRol8lS||8?bcB9T-AH_v9e7het0hlXt0eRCy+D*WZ5AGzTI>3 zmP)K;qcE{-?wmiUlX_@X^$MyiGi`UNUM)U*`i?D@)!|9s=0Z!q2f_m$G<sw&7idEh z=eon?NNmaL!k*%Ub);L}>mK2)N0T;U1A{&HyoP71@p_Y7NO>=*XK)KJNMLAK;d8-o zykHN=@)=8P#_h1xu)S@TD?n$Xu@*I*n)XD3y=DWa>o)DNDttxp>n?T?OoDw5qQPx# z^q)%?6<{y#1vl5rK3e6|!b8rY!fS?uOM%#{u~8TVEM*yGix-ASA>m?N3~Av~A9PS| zvbl|e(FStkn!T5q*6v@5v=eP<U<1iiflxYj&3x4F(TDHW*$;-6WwIfS6<<75?T;%o ztHcB+Cd0lcB9An-<Dl1}U4URstInMO1^v<|<Q!M1rDV1_sD)^v3*E4QjG&q$TuRuz z7Y|1tZrTvWntohQgYG#0f)L?^g=AY1F(?*S>Se^cCdM0%TZt~d>l{#$(Z@SA(3E;Y zsRD7XwH}MohIqQlpR{Qe-hj4v>dHQ!yeG?$G-$%CJ^m87ik5_F;94kPi!z?5!>W)q zdv`UP%sNkaEghSu0D~5q(x^(2Y-Vt5jWxnp#*mKwVv8blP>T^r;M-2Cn&_O|5;nFL zH@b&dF*CtAc5^|wShUYl>#b;Ehkbq)&pjr}44MN{n;I{WgArm*5SDy&ZFS<paJ=TC zk~n(%>t(R7W&S&)>q|Fq#LSW563%^K2drTG?5y<rQmp3ND?`!Dl9PPgbu>~oUo9DP z+`d*I=tgGV+#a2{A4wVbR2!@l?HNo^3bqsmQBS!Osdv?Be8*^UWX2<;=Q+gP0S4-X z?s2?}qGb_X?@7HMkh-|199-K8q?SQrd}Qh<b~i>SZ~zL$@1n(Te6N{UY}XHCfQ^`o z&Y!kn$XFSk4`Cg<1hjw<!Z@>6KhQWoWR^2zjX@b49MxwL?%l(xYk=YnD@L$RRWS*J zr6M*r+t(qmwjF0O?cS}RAJ<uB8qpHh$I1go<Yt0rKa6T|v%%<I#u}pv`m6b|dFcrf z$#1yfNdHmyr6dcYHqLctwG-`zwO$CjU(=gWa#jl@yEK2Df8J&1>{qbnM-#9qAwUb* zZt$}{RK{y3U<N@K`7lf0i%ButS?qe>O|yl0c;kqq4y#++{+KB1u=9`#<`xcVG>mty zzikeyF-;#H>49u_xtAOx^7M@q?b$JKNpm`hs&Wc|Yp}ay7i|#1sOl`vsD4>T?4oDU z1;%Aeazv1|c~WJaf?d&y#GElBut2H`Jub#X({Bru)RGs9)I4kLgInzVG<5p4qGX-Q z<N7kJ0{8@(NUqA5GuHwl9YGuGxfbu3HQ%0LYk@QM6`IT1!rB74!EWnLCqDEmL#qT) z5T_P~{sZ;Cm3HI0x@wX$H*k)W;D}+a2xVtQRv5Au>vuY-h00P^%o*+M?Cqw%bsDHW zDqRZ+1>6@dwjpm;L@b|-0Um=T?;n%}A2yMAi%8Z-J@hmo(_`>=LdCAV6T#BLeG)M- z3{Db%kPIPhR52mG0f)v_8U7_fF){r2lK=m($M?hkVgLUj-;9jR|1mx7AN~(fOWY6t zXH@h?l4b0NdFHFzi#p0u3x$@9V+j`sXw!y5B@N}E=K8%&S|7fIA$Tp}VNw2~SDcnK zxjVKShM5LU(b!6i^d+S2A5LYyl8GYwEchIO+N5)jDA1^L>o8AD@fN$|GZ%#Bl|Lit zc=sE_E^N+QUQ2b=8UaK?fRc|uwEmB;<xOQ!2f9H4s2`1pg&tOoM^7V&ga@x0(0d>P z&@Pd$pkzwy*!6x-uDL-hc%z{UIh9aJN2A=LWmT)3MDVW~F?6lj{)yAGYN|QXVYI-N zyalbMmpasN>oD>)v^iS(guMtoy^|l<4$5wtVJ8sM6}5J1mUx)iUZQ0r8PtJVB*H_# zdwiuN2ls@vc!}K_?HLnI2yxc1k@`F&;|OsU-H+kCHw(3Zq0Mx?m{K2FDu?)3tbX!g zA!VteOgjVftKt16?=KRYn@SQ|J&O4=8X5;WDzJkOs?+_1E^uv0S$8m2<b!-->p4T9 z{J+8v(Gvanq?5UsE~K-Fb6j2Yqx)NC>Afg7(=$-%@V<UT1!bhK?XEX2m1}w8oE!#~ zG3GHw@RKE3;OGUfojsbvrrNUDbn3U9O$;JX$WqqBrhtfa>cgh^Ssc2Ju>oByQiB0z z9r1J+uUVhrbGL}k0_K)29&5g?5>%u??&G`e#wIc3g(d~TG1H^H(Us)yHLg_dsu1ax z(xn*EzJY*l7U9hFTc$unqdni{%aNR;pDGQ;!C+jj1~z#l_?%u(L#Q=4-d&x+MhslN zxXB^BUuQEBt-l+(#B3`<thc>Ct~+eBKR-@poMp6EKoU5X*It$Tf(5hkihegcmC};9 z{x*G;Gg<vGuf9+{8MN3Bh!vbwrjHuo@aSoGgl8OW>!0yjf1Ma<!A+*^R>kQKtReX6 zPLA<{3>f;DsnC51omRQEIc2Y*>+A*kffk%>dI#a-cz<8lc`@@))ue>%e7{W`?Ooip zz)cuE)_lK&_+cLPj8uf^0FJr7?{(SP`g|=7;10i!#N4dA`Vbs^ZTLieS-l<|>?E%& zhb67lf`j%Le}Ww(xxnkMxSxMVwAkR{KR%KBqg8VIW@75G(6sDZ-dYx}#jcGu<eh-E zt)<4BNfeW(6&t4i&%r?=R>>h7@d!D)%$S`-w4!}x{6ABM+3`QdIpk^o+dxLqK0SUR zF|+uPiMWKEU3$z+;=iVhB$CP1iVf4^|Ca%~?3kOxw4!}>{6k`9$srf<3Hg6bEt9L2 z7-q#gN&F0C<G=g(oMC(1|DGFs*6MtpwAg&Vo$sZ@+`PHAWca-w@3p}7c>G<m=+Q|% zVp_!lnn}N{7U)E5#bLlgkWwb7$%p*(uG{!hnHaFa>G9Uw<?w#Kdcl2?{+h^`$E=UB z(mjtTq+ew{#H@=WK(^X!{-%5Hrk;ccfE!D_J?9t6t2Gaw8IVd%zP7inBe~JMQx+dz z4nJ8GfzAOe7HkFj1oniB$kfMvJ<)5w!~%L@X&tW4b2-<@7w9^OqP)1$BayD?_qCdj zTLWmW9Bs@AQ8T!++R$|;gqwEtPTaHgyUbhKw1G(Y#Mo6pBL70%#}Qz@hc~RScq66T z@o{~r^D;H+^ms51`7r)~>-@apQ@a)Regcu`<8wVZ;nQ+NEjpZyeX?Dm>T;#!zDSPP z@f_}%$>o${CJ^4Oy&mHw266vVQF=L^f-CxT+EfS{t3r{PSq;Tr{Y%vt0ptK#mOH#~ z=x~OmAEzJzMXVy@s2CFvnc)9h(e1b7L_>8lMuYD5ci715<>5l>uT4nC0qeMo0c-4e z1Y}Q(&SUNC()P^VD;lyfBO=`qzUA{h&;b?&D`&q*`-!y|5XB1Jkt;q0Xv#!8espZr z(Af{H$>+bHFEKW<^g~hG6U|A-81}i+MiEm_Q{)SL-CmrzqrX%nt7-W1v<#EL?eg`3 z72?2rb~bM}wd|rcOC!&xk2El(w7DsGNqXK4!4Bl9UW4LXO2ocxunb@==u}No8$-@r zp^eYV)%Ev6H$_bwuSKOht=dA8i?(C4v;W}IlF4@vo{!Qex->qLS=jHA9B0c_1O|>T zCSu;Fe==*>jDc6AL9}D$y;Z&N3!Q@wdrPLG={Nl{?;q?@e!`pNRB$j~z_)M|n}9b* zW@q<M?bZ~hZr<mL(%f2&<&K^$a!loUSM7(m4qh`Doh?p)k_w+S=74zcUMG@rpO#%0 z;tnfygg?fX9&J6fEW=EKF<<TtO)gDXO9O6=haFnB=v%bmd5UEj%#&ItTOJ=WJJvY1 zygiPir6bSP=7PBQR*a5KAk+LYAXnM2a)mv9#}#>R_H?Po=bCM;vm$7`c3j*&C@l!$ zN<2+2g6Ug?JP!;rsn>#2JLulq`_uYG`KwCr^p6Ho)jVVn)jeSinVtNP=QnGnll|=p zuYVW_^7SX$`1|XWnSl786H8oh{A>UWjxPNZTQDB0Qgx^z<lMzhe2k^UT^@}sYxICn zmAf;@!u)8uXdFH_Q78fNV`gnRkr*mQ9Kly0o`k)5P-eEHrDdt9p%M$aj6#Y$(L%J& zp*{oCQ03BxWv|PYOnV{=j1N!}e8jc*1N>B%Oovpcvjmocs=6UZ=woiu&r60pWdVC+ zGb6z<9QMs5_(grw+NUY!xnVJ}M%NJ0YNz~kYxWa5EGT}`#KW!eSG;l5+f*@ME0dYj zbl^#x;6ipy4FE?>`^ezgQH|fiQDbDZab@c==gT%_Qbg!q{_`k^_WK58H)WHI^l_>r zsV_lk$C5QtZur&&TLs>mKu`4xb1GW`$tWMs=%H>RZhFUniL`uDsDBcJWq%MpX%sU9 zSY-vUVVIWO&F5MRacu;|<1i91N6&*?1)cB@5aaJi39;4eJrDEU?sZAksWq2rj&=q@ zCHx-u@BW&rTrV7%{sr7S3MpnsxkyEK^G5+>H?mR!1c&kpX!KS+kqnNLDxPz<83|Rv zuocx=ocbjCvi#TbeRCu&O2(QE6R4@fQW8Ix3W^Si9Bio7Vu4=w*RDrbeO5{XtuUo$ zp=fk8lhbN>Cj594boTb23`<UAlhk7A5^%k40M@nVkzDEdB_2nD#mn>s=2Q);ONw*$ zpaiVC{L>?3&8KcWsx5_#+hlDTy0N09L%PWh2P8GH`gBrj5#ij<{a8=CuDrxR1-%n4 zP0G<ogX%UjCuLq>))_k5O)j7Z&{lN0uXT~bLlW;2Tcb1OaHAybbO%kgvWFk1q*i9J zeFdKX_S-O_fi;sl1aYhlb1ZySZSp0u#l!kYMEEfCsX9c?SSGsNVhvGzlN{eHz4(Nr zpGOgOmqY=^MO$RF(F8B7=5GOf^R)(5H&o}zF=$v^4Fn>A(P^@^q;z5xYGQME?9tC{ z&4`2!D?m&kQ4d=1X<<WjtCIXHp~CXQdOmn#R4}i+`bE`WVV-(hA<bI3Etd$K6azND zlb1eV)xLt-w4V|`0*bxbo%rh1i*l5j6%w`=OPPXS9lB1=s$hXyg~<u#4w6`n`7k=K z^WZ#rNbnujIUhODfg6NDXpyIM)~Zd;|GX5EE6NRmjH25c?1G;nao4}H+i*iR$ye8V zNbeadSCEZpd?Ohx&GtopsTt^Vc|^LPuzH#Yk!yem_jzUmw$BsrA?)^~<S7*z9AmZn zw5@ru?)Pc6a&)&Fn&O6#y;$U9d9?clDEj)uJ$BKn!|5^J`1`xl>Ei3hpp?>;d<}Bq znw0`KfsYM2LZ*C*j5TH{8$;RhOz$M)Bot#zuP2}}0m40RG09wd_29icR7~ZNm0E{H zvH<xAbx~|)!Ul@DiE*~PcBvb{(a-&M8Y;`Pur|yGux@LFK+___oU$ATo6xGgIFgJ} z4;OlGuV`dkh=!UdB4rXWC@Qy|lZq1-n-|p_3z<b=r_!Y$W!?5`3Bi4STY?X7Rs`8% z$KGE0!z$&MFfEzc^anzs%c2qAFupU!c$M?l<Z^hNg*%vfSG>WW<V6RZQJ=9DJzPO2 znSqy0g(pGlFox^lEB;YklNLnBUyb;y=9fw6Jv%OlJk`33@or5&-_Ah9#OQw)dtV{p zkZ<J1s{;(;5PJB{nV_|ZJP~@|Ck=YzNIac!Db0U!DQ(NfpUGlnzuBF*<x2aGV_#+x z)ttjUJGnI>QG{?bB(Z?M3!uuK%uPchzwTbR_3PvXWaS+l#$a>2KkBZPgiK%Z(Phnu z?u|RwJK=CVOjjS0Mpu7sh|bE8CiAfS50CvnjJ;!UZB6^_9ox2TYsa>;W81cEbH}!A z+qSb~+sVoOoKycgZ=Ji|dOoaLwdR-EwdSn8y89aAH$HP>b5FS$oJ2F+@wWHf-6D_o zXk$`&-Pxu?Bi#PyN_J?=|MTO1ugccOat%mhO?HUITH^IhR%9j%%!DENO#Vpxc3xQ7 z%9#43)$94m6}Q3z^I!I3tQ`NAM##$fUn?jt)h}%qL@~azd-@j&$I$+^KK~j>TTDh9 z$2b?{=hqY=v+pCS>loBmUif<Ec{VU4mo*a-NFPjH<=x?#xpsfwa)g81{xPquzB{jW zIF35yD$tNZhaCI&i%VgarV&X5?2&LlhWE~`-Prf;;vOKOt?vz3rHgu(JH6y$(3_g; z{MZ}*npj-xt-e=?>5;*S(<)jPQo;{6Y>#2Wk=<O`10WgVeps7M1N|p@@RP-D`Mn{O zM>?vMq2)-?|2J+fsX(jXltL86zCzBA#}}XclyaDbJ**7w`56wZpkOCwq@ZB0PtW#c zMDM}idTcImu3>Lm&n+Tr$Q90533>>LQftFD761D3+l9d?Q8O;cPg7+IG<=Y&xZZ5& z+?%RzC!!BlOwp|6OoYTfO*-{-Yk6HxXAaAYXjk7RQ;82Y$}1c=+yK;qpBJnTMnXDk z_ugPT0VDH)lw)i)>yWgdfT<q%fFui>Id<GBJ88(PNA1Y&TxZ)A-D^f&PE8130f<tT z>fZ5simZ@#4@DtNL$@z2qeW$B2CrU%(y*orb8&ZSJrF)Fcx3FwTZ30JQG&}iEyd;H z)ZvLtyJ>CxT?zFfw+1n>E>LJ$(28jF+n6}$CO@x92>$c|iBw+Rpd%F`IJCm;beT58 zcp3BC3Sb@5uLXc*-pczCimj&;IOEYnHKr<nFReI)t2}9acgMtv3#BbiweJebkvO5H z<>;wcO~HCp&NdoV1q4rnq2a!it_q*cRBj@@U?|ckU8a3<b(aU&gZ4#pH7`OWK2^P2 zT9tLn(c#OPZ5~a5F{Bmgr?uC}KA#&7A&*KB@g`kS8x{t^C#)P~&YB=cKa~YH;aY}W ze_d7dG`D(qH6Nzm!$ps7qmt6$8s5R*CV~=rJte0>1W;+lAwEG`8tDAmFH_+hoqFFU z!%S{zpyK6pO*QxUS7}mtVIkStIfB6$6FB2exDH_&b{Y==pxJZ`8@OtnFw)VLmY)72 z3~|40dAuP|g7@}*`_-J)=6?1r5}RpN6PiuGhPi0o8MP4+(y}*4aS@om3I4~VSjl*# zZL6e|1>5XyCBYTL;b#T5DAP{CB=rpxilDETZpSxv-{0eX;Lqdz^%wGva>ok!B1D=& zktoFn-U!D$kM|LL(iMCl%+m0bgva%>&qHisE27fst+mTn6E)0@)L5x6Ka+l>=o&j6 zw3rfTyvA&p!#imzN-5=*qDkct6YeD(oUyWCnG3WF&h`O2%^5-!LTN2&OJ=EpRW7#% zNyF{Hpv4OVkzb``q-{(_>1(RDjfUzht|Oy0$BU(5VQ9E9o1|z4+b&5);bz&v2Dg@R zxr&1Uik8rJ*nis#M-&ydNSlyQZB=WPm26~~o)$EN7{#%WV5&zuh>q*bxun#(X13gy zPwU7~Gm>2)+g`{=I~$tV`r>bfJgUSgo(7{oo}n$bYzciu_>x2(suEG2?jAO@^`RCa zsX>xTgK9*lF~GwO$ZQP`l@<29^sm)~vq_$@JM)whQ{4I1fP1yAf}JabA;e|puWSzZ zENhv6SR)>XKkg{WIFD41)8~-bKQpz198K$0TABJzaF<RgJykAj{xiozl})*6McwB2 zzXor#N$a~k^kEqbSsixBdFFk*Tukkuz?sM&sf>iA5#KAhVkknrS?hX<1p7rM^tH(i z$w>C&_%-E*u@o{CuZ%Y1^rt(C05%XoM{MH(8?;;Yg;xz53#S@`Kjx$SX+~jGiVPbb zR;Hgov<CBNw-vmp-NWpng_S;0+e5cJf>TfffFf|M)M824Ne5h`j7WiH&op$zhFN<O z8T#Y>I5gomiaB+ieDu{I5rXl6B{R%|+OD75&znbE7T=eeZ@N{7_3=yEC03ot`+Xj> zYI}leb-l?iM8g$fN_Jl+ATkDz4#uVsn$5orTxk1$ZcnbyzT_*_-`x#s8P7rl@y*mv z#@JZ<VTsht<2SUEP^-H|px=-M@&0HEp_!LfUNf+ICkpxQ=!L7BQBy|rBQ09_X71h= zZ0_f}#rnol@wJe!OL_$XutA%>fq+vb5y*d5x9QF+&d$34ubnvirg?Y1xvP@U(yLSn z`v$x=N!Iw+YQ+98?JI_#8uef5`7i%S{4h39My}sbI1-o<VYq2Ps%4Pnn9NILlK!m5 zz{7w}WX6l9<}bW#94io@T7;7-P7q#(V?QkO`H&EZk_E+2^w}2l4O!}k<^8r45OpOn zSTvI%f>w59!b;5GSHy-RWb%h@gX(Ut%+xJxKv26eJMHp);L76iecIj%&IGNtQ{V63 znA0Q*&Kt*YYGoKft+9dEi3a<I;n+3~qTj+2f)!7g1Y>WBin?9X>@Tei`RKslBvynh zFYLXid}Vm?>^)P)09DEQ9ZFVbCS`zytTY~arwYLo7U^~*sT!0CelKDaJywNCCDG>2 z%P%A_YV1dgoXJ!rPU6oLb%%+~k**Y}?|~d?#nM>6M^K6gWKDU2{NkiVp?1Rxf~ptG zW*HS+qL|+Ol}C$QO;j#W^%mO&goZe{;B-O1^Km=Zts&af`WRQDu3|p~gasFz)HlH~ zarbtbsv+U)<MkY4Q=A7da1uXgLQN`GcbeVxp)Vvz&f|ni15TB8i|TVdK0>6aV(zGQ zjsP&E&h$5gNqvGx7KyzoXgZ)(`hGICjWgxhd8_7=@GE7y0`gk37VA=@bYLCxiG;~T z0+y-_CNz@~ZBptXEmxnR&vaNAFZGKkTzd~S;H=f@aKh{9rVO)0?a(t?UQ07Vrpmnj z&XZ50MQ9-%3SsJmw9lgBGM=NL)dnozR!7rta35n);xHpG*NypvY^vD&$fgA&5mC~T z^JWN5DS?Sb#c*up*rlk>5*8PVze^*0DJ85{15vHM>B-xo$<{taPvXGc+x~jrK3(QR zL}jmoDCf08oqJ5{551n+p|0H2oVTHwdnM{UW+PTG&MGgKe(4ZIN#$j<&J+jgXu8m9 zMO4vfbwRD_-Y=$vdSp+}x1I5A)bC>>+h-CskMJGfmsOm>?eUO#a^V`qFa~#+yDL`m zj)3Jxfr>Z3r!(K#E3m3hOtTsvm06-v`R6-=S;;&~y{%Y44N4l;_$!e0?5~ypm!WS? zfeoJUDV=;s6Zri~l$U7Ry`bD=X(iM?MsZJPhxs$!!me!z4Z2Bl`HBnP%HV>!Whav= z7B6(m8ef&=02K;vZv@Le2(6&If?70~qXioFXCrI5Z%y@%{qM}m%j`iD`Z*8)91u;0 zT2Jr`g4F;d76Y-@$}V0`tAgs<E-xx7yrYgM1Qfcg3tyyG72sRzZs1mI>Xh;X5#B61 zhr5~ju>%%54aY^9`=7MKkF5P;`D|{~SMD+V&2C{6^eT#B8wW<$@b61ZgehwE`hh2} zHoevqBryRN^n^Q`4LF`HTT-WuPfoxsp3o`Te8{}N0)9t+4cCPma1h)V4ZPzq*Y`?J zhUd>~>T<5rC@Qz*6FKZt-*T;!;f+=`5O!mE&cG#;sP?B8&faBT?&ZiYJT(vBm*$FH zWb)SMh(6$HM~tigHW_jL3-ITE9Hs<N^rGfgPR0%d^rBY!PR7E<hPFn=P`tcQj!q87 z`qofx>&Z$ou^9~iSWLY@%A|*L(kz!`7Lz?nCE+Vrz@c;kg!QCWFYm4`57MTp9Zt=M zpEB5Ovxmj80*uhT>GG#iEb|FfBNF%HjUY5A6AoceNJV6x7?Wu@QJ#Y~*y)mJwW?dJ zO%sxgxxSc`XUG@i4j19N0!3X#9?0|2!h@=lGy+WmluOKf`4u->JPj}%WxnV}kr5LD zQ8tfoUlF}yZ-|inB~sfFgiYCnsi82Gp+^P$WECUAZr8#qDz%Cabi=$T$bCyCnSDN= zn0q|yfG;K+Ge&~O-P|D5!fo>5=@du_k=<+eal=C^EWITGO}TTUEpI}+*dY)2563M# z7NBtxHUrW$+KK-rfX;Sbb~LkxVp|dY_^ALsoB|~QEV`K7Q_+f--ltNu<+2^h0UbpZ z$@nEMsjKXLP>T<Y$??1>bT=AiG85%4m2p$^J`8ubT@O#-=^+#APD9GGOnjNs>uuhT zsy^&-WWN?C5A3Q#$PY#dB-#+{?P02xS9LA^^iL&6t+Qk_lzCk~R<<nv=7Rq=H6O@P z>}4WFODqDQ435sFIT)(jjyg25pg(u*XUHCKmE;(%aXfHgXZsWj{{~R`JbL-px8vVR z6)VGk4g5I#3ENx$3EMkXEw!DOR=d{jh?Pih9b>7oOgtrtAukAHHG@JzMHu<+HgzTS z=LZCixt~RE)WDt2K6m8>ffEIUoA#s!>uOk$28A-GRA*>~HHb<|5~!q1Ai;nMJdY#B zeKfBW{Na80u)Z4jq{t9Q3>1kPexEqAG5R>0+Yko`DW!9>&Q0xF_x^*)<CrZY4p_U~ zt`NB1!SmO~i91p&ip%E~FX=kR#(~*e+W;UgR<S!KDFOV)bf(7xS?%HbXm<!Ds=Qj% zwHPym8zW&S4PiSjBJ7@)G`2`1jfsdfon_oKE(`rb`?zG2CmeS(+)alHs6`Q&r0mx_ zgu^9}i34Nqf;x^awA@A*k28RAf*eJDyh;n(yRj4&f#6(^VMGM6ua4o#sZNDNWc(qr z&B%FyazH0YusyWcZg;KJU{!1`SB^Sh+xrWlJYpX2O_0n)o}H$aCw#emzh9eezzXz5 z5ofN-l9J0?-HmEhJK1^2^WbRI1`%PYf_j>xO)%N2ntN}JA{0Ti7s{dZcfPqK#HJ(` zYE2~kK{0Rs*~^Mt)kNAS`@w%DcugGnJVHWqPoSM*pbeH3Uk-&pe~v?pCIcN<un52@ zKn!za(kF<d1h`l<8U7}L_Dv)!en<vZakN1@el8Np**B!6uI2Fs?g~Q*V^kNCk@_D( zRFf01ZSuaegc<vMY16jqx?QdSSi~q^Oy0UUty9)vA`Lq`?zkJwo*77vbLl=r4Z!_6 z_-S$SW3<&XrhiBjYfvU|w@O_|t99Xnp{nFHZ3_9*!F1b^hzq)ud4hgQ>~Be%34^n1 z(Pv{uxyV1aD*JDq4At;f)hbQi`A9icn9M8%4Q&$mYWf&d++YN=V!-W#AeR{&o&eeu zu&*9C{OB$>!=Zq0@yD(}9_Jq=AP)mstCB^v7Xn#eC%?f}`H*IVXZ;lTKxgsiKgs*J z`a<{L2=@7DN*Z`-;drWF<bs^v<kfaU&))czS7LN71Rg;_X7_RbB94zWBD@Ize9Qw) zCHB(pq8gCr(V8M5esP#h{1IjR1!En{-GgkcdCW(;j(0WaLiUG0Jtw63cjzu3k~Jq7 z!)$CobJjnQsLNitdH<X^D^WgQc)o@*z&&q(a!y6AFMJ@1lfq0V0E&Ti;8JadH`0oy zb&B1gbPQ%d7xn7PJDVJt29(umiAXPw7W;sZztX|<R6{=1>);aRXF`cbZjnPS&c_oL zzqiPY>n1~c+*I(1`t8+dJ_}gN;Mg$Lbl;rW#v_y8G)}7?NhHwe65!gs`8qIAVps?F zIL1Q1mSnVMkTIuC$)*y*cRqvEx!vxsmX>y3J0fR%b$NSge|@cq)?T=Fc|PUgv)FSm zxo@$VoU~jGlhq7a*4Z;<{MiJ({j*bMtu_6BAW^Jir#E*tnMF^q$+P<1CYGly%lU9y znj%|7RFMPJhMjSa%c*Ig)eg#ptB3A2XN6!{^h7qmHcDTypA3;ZdSDqyXI1f-TA%7` zyJqo^%ky+v&$3Em)j3+3ePR0XbR{>|6mDW?y&9=o`FBQV^VcL(L}O%*zQFak0_J8y z$RbO0x8O*C;VeaB$bhx*64G+{Kq&1Q*Le8w#Xu;-zd{D!@_@v$cO*bHejXVr#}C&_ ziz`WmTmf*Lbp7-GT9}Og5*sPaKeq1&Yqmv&vQe|-!zzE_U@eHVVoBSM&~gH_RS4Zb z2ReqUjqvN_2NbpYE6Cpfj*oi~Fi60xTLdH9*&I!Ls9otc7+(#JPiBQtgP_v@sR4G5 zjWJwdat+U9-V`c;LOeM3uB5X~Y1St{GEZLndvJlea@oT2<jgH2Pw(hY+3zeE(0hws z^Cs6`5t5HvX1EJ86RjRcGvmjNsHNS8DV0TGFV>g#ZLbSV=U+!jc7+dqe1&J<izGnB z{VTo^5F|yF$S|3uM?wILY)MO+8M@HtyDjhWm(~!+#lhczVaG9h|57j5ek#NNtIXqI z`0tf@8Z!Uj1H0aT@PQUT_(0g3)g#LU^NdD&4+(BujR0#|l6gYPUtiDK2)QH)aYT|a z@Lj7YAT)S4XdSi!dna7|a~Tag(=*vUCS3Cr@d+Zws`39EvXuo9N#x(VKX8%-$k9#j zh`@9kYW4RPzdAQFBvPty`KV9+mP%YP&q8gx^msb^xY)q-&*mVqOw=Hjac9xY_U`VT z!|C=!_a71#dzP6o9t0H%V0P0H#-I7(8o(p_DGy@rHK0{Mxukw*{eABYdEBxSPUaR$ zvJl}FVCt4kVe)pu4?cca3d1V^Ez&;(!7!8(2;gxZwp?}r$X+M1^d<53CM-eBpFK1! zAdY+s4zoT-cZNLTfGGTP8bkoc%E+`_i?$y`FbV3`tCE;=Ac3}#<MZt$eolg_rLxR| zb^M{r2x!cl(Ktt}ZlSx*i!FWE#K-ID^Uj<dW<WF&blG0<s;OJ60--fa2UjD+y#i zh!rE)bj6m=c5wsb(5>qG$OZ8|2Y^0P3*aI<S?^9L<cK}GM(EtpK=R{2zpvUx8!Su) zDgt6X_e9OcwEAH-SGQMVV$^nKUZNjl^=iCqeVsolzM-L!a-u{4(wX7yPO(n1J9|>o zx96l%1VNH)xM*5r$}<6|E`w6H_T9u}L+zxAu>xl99R3rRW_r17Y6~)%!HASAB+rLZ zEP!l7@i^fwL^BQ|+aIJTd#$xhM&KV76bm<9`e=Wzr=k+uHYedNuAWzh97ZtjU~o<& zTlEe)O>OYJl%a6{J(+4%)z<3?<cJe?c~Y3+(i58t+Qz+lFB57QG8)TApG`R*BpHiL zzrVs<OxLCJr4^n^80EZ6unLkbyx1-rl3<25DcEzdb;*o+_o#y-V(l=h{Opq_S}n_= zT0o-W4Z5pQrpU;Q$jFw54Vy8L0~<^sPJ-<|7?384ZGy-ETH-t?44DeIX0mZ2la(cV z3#&}3%SYh3=AU+({IE}=3hI@!s6bbivC(Fh?2Spq))2DaMUmrj*+-7g4D1c_g~=^t z8p=%5<RBvzhefb1PmcCYJgGUQp)C&9>?V8qMz1DSzuES#vR#CVVtuafhXQ{YJ);Fg z*X#!9e&%(~oMrUZRjs$CzaeL&@Y)qatL=Q`rPlkt-o`hn9g?l%<o$0Nl;Zx+c}&RP z|3iZk3oj);hClk>G^k;EgV7%v)KA{~|Ina>j^dm$L%5Lm(<ZC|zQJKxeH=r0fymMl z$jvGG2oTE@f>-?4!!<7lf6WIz7l8*)QAGrMp8dUVS>i*k-bj>mjf4eAm1h*RVi*TA zASMCAc-bJt^1~?y9OXsqC3HA%DhhPq;{Z=?&-l>Y#JC=d1~*al-U*(vhaY44wE0{O z%3P1F_FzQDO&J0Sf^l|2J3!zG;=QEu3siL+#wY!U21P_xP`?^~4^FIW`c*P%aDdME z7fD*4Og2J3(|lLpYmh3|kiwMJGl^=ZY$W+KyN6YGrnx>&X=G!|FK5Bx7h+gkw<t%W z*_m{*UoMHkh?-};DO*7QsxEq@!4Z^DpLS(76b$u*rRX=Th=Bnz{9&N{2T`z5<`O(| z^alT$KM9B;wzyu-Xs&lDDl#j}cb!_YOBb`Dqk<b4%yEp(RIMRs^L{Oevt(4ehp*{4 zJw`*ntUJCWSo5#*l9a4}a8Sr|u=ko9)>3fSJi~MsKGK;rf_Eb$k#be8I?2OoqS%FW zStwV&<|dIWnoo|C^E6fc2F(#cUibwi6h5UX;)V{2>$y-*X%mU_At7S_;X#4c53l#R zn#2<8gEWYNk7!)eEnM?!D%pANtd)0P9`9S|&Sj`{7~gw0tF@M77%=Yq(HgF?ALU5f z)yf)fEes>OAQ>hUcUbj=T59<%;b)KSXkr4tGvW_%-xX~z^-ML>-Nbo%Iq`I}ol*?s zrimJJt;p(^qnojr%`1-RJa-?d&0CvsJ!gq?2TNw>u>J^k80WkizVaU$lo3V<NODH& z&g@p?=PwLCIMK9QxTuu=M^fGAr`7mXk^w*s-N$OSq54$Xs^bTX<2pPBk0~K|0OW|A zLb58z;W0Vo#3TdZMqUY-yTGNdYN^-^mYkOBFwODG^=H~P_-kYJ7cBkEi$&Zu$`0pG z`M`h*#mQ%s(@NDJ7!>?JFsMtbUW1ouY@k&IqQiJwSP&ve{BBl=9~jg-Sp0Knd%PsV znPrB%xC?QNuha8vsa$;Nwq{^SSKw@}4Cw9p;`?C6GH8qKDO|Us_<LXt^G;u?<ZCD9 zW7ksgP(3?=9t%p|lTIOfjg{z!TK*?(C<uI9=bBVsJV45&rx)c$mcJKN`Bu)s6Hnwj zrdUI1=y@>}qdWe-ufE8Y<-e3yR(6*EtGxdI=n6SGnf^ys$i%?;UwenAG_-BCS`fWg zYIY6Z`wwA$x=VT>;szYFvp}L3q0J$Ln=^yrG@$ibg+Cj%Rz(_4%To;<U?3Vxx@WCB zI};9kttJC3MYE<P{(QQ{I7fQ{L7Be+VDU#lKRPWVf5p2M3n*bCI)&WK1}U6Uj2!;) zw8r#U{kIga1P$OnZ!{`EN~gAFyO~_opmgiU4ZVt9-edln4mOGe`X1t_36#sd`&LD< z`e>H8D}u6^hM3TYh2E2bWG<Ox;@&lqgv^hOA<FM+!(YgTRE}jQkR-uIF~pq;On6ET zWsi)Ls%^0XuDqzjH`Vg^1MNiJQZz|T=lnMzzwrk^+SG@68$%KX9|JDYuhKzo6Q&;X zX_M9;E72lMR-~lzSnlh7>rqw4BQJyE@9?sUd&BmZ7+r#N?8~=VW>OU%afJNYvXNH{ zD4dSH1*3RLlhRg=Ip2`OWbU|S0F%%{gaq?*26;CF8RO#XoZFR+^J_T!+P_X$@f8Xv zyzr!kRCE*qBpTdW!br#<>T?Vl8|jr(V|oIlkKbg4B$lf7Zh{)~Vg;_QkL@!GP-Td0 zEyOhi3}^^FD|}qiGq1BDrWT+?e$uBkyW)kzHG49Q*8`YZ9wA7+FuWn7of_d+q<&`X zRCtdkgr>520U0WHf(MpZ3cBAbUzi3+hp^Z>x=3g@-fTm9W<-$ND$83CU8Frxd}Jga zEQ{6mp!0@_8N8_=my>m&|9;*;a@onw%F@lg(CNgdf4}G3&ir(!f4}-L(4o^I9rSzf zcy8I+aoy?3|FWxpxBo*oK%I|-c?Fac3A&&dzj}%mp^VyUJCI1O|4ek@!{O_W=OQ<t zyWQz+TXK24pf7#UOB^t)F`jN74+4+je&{aAlJc-}GsRB+;wqd@IRb(&tQY=wCW$y^ zXN$$$%DmnftC(xiIlsL&2ACAvs<NPJq=ZtV06)$$eV!ztvBNyYnZ|g0pk6#<Sj9LK zT-0yuCa3Lik9wAdmh1qY#WFJg&?dcEO+zfjJ*6lHGfxbfh%>)e(tPfediF00YF{c- zW0)JDDrr-Py2GE~5G}Dob;SKth2i#;W(rtwn1fq&qRCx$r!qvw*#h09-`6H<U>5Fw ztYro`lFJ}YjB!`&>zu0}P^DuQv3PiO7KFJXjGl4tgU^M5TWSAHC>oU;ryczPDIq_s z>1ApeWlsuUCm{;jkzuYP0p_lsgq*Wt)A<35h8WRt)*Pm>(3;Gofs6>7_gZoA<wA;y zy!{ft-#Q$6KXt%LiCkDX?3q|QJUz7?c$f&-;iCse<HqADA(lN(*I77uJ*4x%hnrqR zX;RE*!V-+1Iy0V&cp;AP_wu4mNih@!D=|TImZjhjSNqnXbs6{6#*0rXN}C5)l*U3N zyxxBxoUxmdM^q$=UJ#t3CeFy45WyIE4RZ%mu@+`|0Q%*ToK7l2k85v&KncH)Ila@( z!?$6Yj#yMm6HppvF_9wjCk}UG61ie(WO4)5<6f44knrf!cI&=696yqr34PGwewy@Y zoA_YYjXeRR@;Xo5$&4FOBOS5K4lm5frkSX*X7R?6JKX^B6CP7UG?afSKfl;%-r_+` zTq7I|TIoP-cEY~iY}<R^j=ekdkRfAD9?U4!eZEtgnb3B{*?GpwgW8-Awr1A+b)7F{ ztLN)8XLtP;jS3M$jl=W%yrzZ^a(S_@90hqj&stAT)GWT)AJG!|?t-kApdCTO-&)Ve zPC&H|HcD91{QwN~HDLD93aFqZ+NbKrrE4i|T%a&(CDtRh3MM=Do@BkNXg@tiY71og z9NnxigK3Stq0k57MAh{^4A(LhmA%9K!Lu9Xu(NA(GDKVw4JQ*+OWYa%uq4&eJ2O2) z_rB(vGB-fge)6@>{6r2?|C#7kZ@rT9svUKPpF=r~3b(YR<Y3h9A-JNo`jn&Jw{;(R ze>xQ4hvG7m!wcP!I&q!4_jrl%?Db;Kx#kV8Q%bn~dMThgCbZUZ|BSvcKVruBG-K?; z?B)99c`^rY?PJt4CYZC?>EpwzrHAC(%+n1%>#EkH`^8b^^Xy1^(llEQ+JRK<^6=K0 zENGjV*K;l@V85(@&f6_15XTQu^sQ1<Yy0w8rvlZLSMwlNL|_O0cX338Qt!Uby~b6A zlH;`UZj=gCpz`Et8y!kET{%{j!Yfa+e|NK?+V$BZ&?JI%r(`02ZZvkGknJpU#XKz- za->-1Mp@Rk+*E$tw#L*Z;JV5b&W~CHw{=jI;fWrcc_Of{5^HRMr}yV+RH*(P+~_SL zz{Z>04ee!csy{Hq46VKq9fo<&bJzwe&h)%*ft4P83~n+08*022%gmW9?_dLd_cn0f zfHykxDDe84(*4&lChMck&ISU>o%naBaH93@I9jC5;M<n^HV5N8f6^d!pCF^u2ABzs zDbK1s4p0f&IorvxauWXQbydV&fyI4d_op5{E7xwp(-5!4DYMrD*-Q1}%^~1!F&BPy zJ@Cjn@3q=H?d^zh%V9;r`Z%MM1yiP8<5(0BnScVs4b?kuRf>nM2+x?++Hd6&rerqz zyp*&0$$)-S9hF$Mie{_~UuHQh<_h1MC@(p)ca~;3t!|#UlkHPp@`&|3it$=nTaZZ6 zZ)`sqJ@^85<}}G~MJwdh1G6m%RNLGZ{W51{YY^%Ys*e|;0`kn*nYO}*Tt^=v@-Lou zlaUV4?kCcoMh>I&z+H{}=IGsYOqWXRzP~Lq#@HM!D2{8beKaSsN*iEL@5bMWY1Vo# zJ=>i=?|dGfB?kYpNMU36w=-iFX2$=zz4?DZE6WFOrDuFb3GJ;^wOq!bwT&g00m;OW zsE8;M<5GL%3=05&P$2mg4U+%EtmLWb*nt5(%ko_GWPCGZ^0>>yo<XQUc_uT>E*_*f zG=~;uv}Jmh^%AgR0JHW&XE^nBwy*a=q6NzRY9d8{EjXSlnwZ&cYw%OpsnX(h>^uEi zMBYj`kHM1G$4I%bQDB-lmx?&hv1o|hFpL1)pFt~1Ub2{R(2$Bpx`}nI$>y*JITntB zGeh6?T+l+S5hMsX`oO}I<bRsdivmVwd^Mf{5QJadA1t*=r8lW-nw=b1g(oSH*0v=e z<QEwohzcQEnvjjgPvPMX4HjcEn4iHZj20ar$r7awMDxS3ME<*{72J@N>^sj#XD<66 zjO7~_z!JCqe=wFo?oeK^{BL{4EHm`q9-n=@6Ic3Yosb}p=RPKZ)hP;@2?S+w0gUMV zzF5Pz^=@x%;?+HTogO0T{u2Bn9zjb+stl8StWi3(!sZyFHND(yC-BE<Gh{hiFKD9g zYgVR>7R+rFCcF{Hbi0e+*}8NycLztW<D@Ip+{r!{N5&n!x1`sgWi>S`nn^y936T`j zGjb;imqjIn#ZE~d9F#ihIwSYa>p?EZ{Kw&DM*xBlQ=Uh?uwYC1(4r%}#g(LJ5pbV$ zSs$(2o#O{+696C?$7z^?!JGSThuvBo&igiJY<zVGH=dG_n%87(Rg*-lP)u7EO*Chm z_Z4U>zvU15X)E=BJ&1pScvis;M=74wBr=4XK)|X8B7QNQ)4Q=kZ&6({o=khDe(+|r zO~k%7$SKb+ex!^uW{OyfP)e`{d9{|em!RzRPRwCra#O`s2nitNX5{5i98T22CYTe| zsiPe9Zyus?L`wj(+a;i?Eed_1HkYG72gX<8I3W$CDqP5F&IS#iZozO{_#*{jbqI_f ze>A43YQC}@aU|oAyTSkkFCE!-({H?yweTK=-gqjLD4;o%w^M*iD3eW%2j5fh&d@8~ zP5+({xePWYTRxRW`NQ5uLC8J=R0%X-;p#(um!7u&wLkWTOfjnPY(hQsHb=qQ{7fZS ze2&8`ZCdzS_}-rjI1^)f4&N*O4^t2IVV9<($GYuOX8I@aZ$#H-lM_7Q#D6fB@c+SB zVz!d71RazqV_lD34%Y_``h;vqSYg;Cxw>0fL${oIxbkIimnq9!5NM}HAa9vJ`sQXz z(FkkxEGNx8D0QFClz1(O<$9T<-pTk<>J|mq8O!{w{cMn5?FhNbf!;%wMAER)g-7Ym ze$w<bnfelf(tRdKS0)01*`$Gvw@KQS4U!XYEgQ(_{-0ZK(|aud2iJ7u$Yg`iv4Pu| zDZ$Ly3wfs9K}L*fEhWu7DRm!ojg!N6&>tdqC0)0|$|6==ervoYktW=FkGp<Iy;6}5 zF1(%m7L0Zo3nq$M`xVa{lO>|GB=Pq1H(aK(zQa>`Zv~n;P?FR!L`lX_`;dZD=Zw|b z)zRp8)LiV==Ipt^VTU|Z@7(&2uWZeb$v_Y$V-<Q)f+;=M9Ro*>c2arq|AO9GINblS z&t}OdmwanIoBSD}H4CA5>&50>upa;yp19(3E=CMJ-`_WAS*Pv4UnRvIgnN{d1p)*A z9Ol*P;|It;6|jcqFkti{hYAU~5!sOF`)71MKcg$t`)73F2obQF(E#JIalop?X^A)+ z)Bp%ni@zgR`}FxbE^&Te;wiUvsGnZ^PDBmz)As=7$P=yeoTV;yezF%;sa2!zOaF2T zVD+B-`BVlB0YrM~(jrVLAN1VNejf^Ww0os0`)Cx|EtCj9g2RXNqQV{rM{ZGVevEuN zzKKl6etgUrKeY|T-Z%Ek^E3y3qMIS-e*W7;&-gE`V@6h%|5{afsIg)5LnroLQN2+B z+Mn7sp|6oi%oWgR3<LU!(g=vh{NpFwj<hxCyQ7|vFA?8PLs?;SZxH_XZt@~?%`v6X zi~-*4#^YhZ>ER=p!JqIqC8Bf>SUOUHaxN`-1n9!~?m?P=x>t5LB!~{O;$HOYsp>6J zx|W^wFkeYShjEgTK3YjQHkSt{?kB4OM*>)7080o4UErF-!!0vx_3e5F0Adwn_aSkr zKZpQ7)JHeOcJvp<9McqA$~$+EF$8*jf4M$`ASwtJI7Jsc5IC~|pkz>|TEt4kP%D9G z7(cZv$4Nfjobc@J4l<k}jYJ0)3`YF?1I*017UQh2y;%r6wCo*7zlfJM&ez?!=X<>* z6`%7De-f>VjDN()fv^y#2O^P#w#J9D?ep?;qot4sdN(cP8)sdZC}7bFBVG})Z;^rQ z51Ak#^*oZ4h{CvfduP|?fL>4Q7RvI04q6d>&&c_Hh7^fbDmc4>8!q|%R-s$Tk_jkb zEfJ6UnjXO1<eQ%Sg+a^y)`)0^Qz)B)L?xwVux>a>rW_qckyED&5zBz!trz5|eR>T5 zcY5$#xf*CI(6-1Lbmggv{V6i&S$P|2Fw8r&vt5BJte-(^xoJu5g_f157&4e4`<;5Y z7XG-uod)cuaGCf3ow$``FIWlurQ1@l2?X;KAgmgs2(T5^kP4hg{EY=2{(%u9`P?xa zOPPZDn#pbh9EC(FBdVgpEl%0|c@<d?f|^7mmwO+nf?mY0_`v+Uh73i^>X_5_{a%G9 z=VZFb0%H!jd>U=hQd66+qHGykHvT13#qDWSY4WIFrxVDwPTRjl%<TMy<!vH6eO;|l ztNXdvgX(VE8K3FSl?d+h;S@MY=i-yO!gVRNc5s4HbswX4%3Pvfj#+5FB^uj=A<7;Y z=s>r72lYmnu=3&*En83wz=J>gU6j;fJy}O<KNc(!0}!nE1_cHbH}m!Th%wMGA~#63 z7-;sa)oQL)r<La6-({rsLeBa$znmA+4VNhz(wxEbN#6F{_a(4Wf%++a8EN4+zwg91 zNTNr2$qqFc`LsZ&vQ|Z+ozhHSMKV`x9fhDuuQWWc{kZZ@?lsU>=00Az(ovtY`_A~) zfUH&%G3{C~`N9_fp#qbA<V-&MUCWJ#KRBbOJ>jg05dF*aJ<;^|DR9S0h{5c1CJ}1$ z6_W)OTo_jAZP<e!Tfu+Zr@uf9*xYq4*fxyVjYx#@^l`#S;2%KBT1edd$<+_5Zz0tA zB8R=b^VJJ;NhQ>AdHl4_oU-xZ7E4m2lAR(TOpZc^x+6)UP|!|#a2U+q`}Np}_mvrQ z!WYVxIH^8Y+ZA2=l4Or0B&<NZc>*r9d0$?yx@hxurr>>P*F$qrIL-c!W)BBIf&DiG zE>PhM!iJ*Pz;ZMMThNxB`$ksD+~CsiPagL?%waR8j&nvH!ku{rAyZNEv!%?)R9A-U z$(PsrEscV_@V%xKE#cwsJ(E+G?;hl&qpqWaaGnF#2n*sbPMJAhBw9LLkWu{&Y#Y0( zjl2zPSrCXp!C+?i>egd#vzgi~l;wf9^?gR5x(vZ<iAG9c2$Mqs&%dGw)=R{z#HnGO z3M=z?$t^sx<nvJlhnIk^gI$!|n68sr-MD%%i70aG81`ZVbvtkv1sORFFc<e1HmI!9 zR}}D`dxdW_F+-IEdirtWj0Z-cS%Y<HfSIwk4wc!rzYePrzcXVF`NG*!A^Hw$x4@NJ zP1%K9@%^e}mF6=kXfrH*{`c$Fird_T;!4v*_q+4nq9GrKaTtav??ZdXu(Q^PLn_=s z<C$RVj$rPFVEZZ84Ri0LKWI=E*+EK55*~dYE5?~{xMJmpY6kk<0F5+4sfj85+jvVK zFUia~3AIj19np<5zL1{<J#<?Y>Wh?ahIObB<F^VwK=D#%lX6$b-3=LyH<eUId9%9o zgj-0g#T<=H^-2tl!;7v(H4QIc#^y))f^&#xjh{2H1OSQ85ufj9#SNEazDk-%k(RH$ z=G6NXJeM|N_s)!Vq#<sz(g!&CR9Vo!)fVP|Bj0l{|JONWOX`|(8)^tY!V|R)`k2Mc z?2gM38W71LAZSWO5d|Y0;NQp@&Y3Q+&%cfhMr1Ro<;&n{$)Cn1+3%+&|8VwA7X)S{ z2KIn~<H!EFexZm<;0y#G8Tery-vULD*n<%tFCT{O%BFgBW4ngg`3{;he!k#{;zn#; z+uNrViKG?UZ^y5S$eA45GsR4uQTd!8TnxKsioV4YERy!0Z^H88KY)XO<01G3;3}3q zdH+?q5>5=<_;nGryJZSajP^1u*X6ix*B7@7vut?$wwnWNHPsge)uikzdC-Y=K!QOY zRCiS`)P{YuM?%*NBDh&5`a8l(grb-9%fpX1KS~wAk_e(-kpu6aCL=489=iZwFAGs4 zYr=9RVG>~uV;rd;wZ&xkFPIKKF6CDKh5Fd=f6&OfpN)7_{6q=LERUff&d~%o<iz*4 z57+bpJ%UB}Jf;%m+;jwHT-w8Jo*2dECOg|3C!F67E+HvX2q=0N`h!eAA!W5=EA|q= zBs_0ibc{lPfQcA^yN}WIkw!>zk#={TAtRqoE%$0GxG6L;iA0Q(f5@Y@$x{j?kPg>a zV(J&?xxpucI?|i780i<lh+0RU3a#mYJ-yH|HJ8y(r3OE9E3*Mm6?zs(F$~c+l}Hd< zBbAa#Hm96o?2bhBGdH*isbp-pHdiQ7(CXH1VWBHC+vV%SjS!&6xvK2wMt%c8G;xVT z?t;*|s*-*RMH*4X0Vr*N=$3OSWdYJ!05Np-KXleM?6IB^(oJOP5!cPvBKP8n%Vyyt zz@eUOkl+r4JFXB#dB)8oZ^P5(x8n$H3syT@M`6Z?q;-hi>WU}P0sGpWIrY&CuM4-G zy0ywG?V`!KAWq$FF8;crM=|;Q(s}(mR9RxLKyq5}8i%6PP@1X`r_Ur;HhQsx(=XY| zT*0syUJ6pEfET(TnH#(qk^fip6CHhr;lA=NrAvX0I`y||!y>&mbSGrCm7B(dUjn`N znNFc$Z4T(*XIXmCWZJ#AMYeI-TVw{&Wyd}x%_P;NVS~7$u^{M3IY&E#?F>Db=(_&( z#UwYD7grbCjK@geSF-y{nX99RkHK=P>SxA6B>jr1?qzdBh0pbg<p7m=B^OW6X;v2A zBiJXg5_Gg()7j3$3^*>(D(@=OtC6L7JnG&mjnqv4ohcI@yPQBSbD(?#l#)`0u^AyC z3SGF`TIc25ws_PYH@uEB8I;+6t5?RCC_g=vihjwLiQH$^v4PNc&4sNCyFs`VX~6i( zBYS^h7{VPForE8SLjCRq{Krw59@PvM(=+g_tO+iEav1Cv-LForb(%)7g13Rdhyfa1 z@ss0}8W9s-rY1F8+2TVEmB_=cKqJ#*8t`!P-OA#cv*IKefz|U4N<lzq;qlI_05lNy zY+Za&XKK_62eus1r9Oom(LJ;I1&XR-1&d;Z8XVCKG4BEiKdSOhDJ$e>a^>AyD-gk4 zj&@(+HKT;0lhat0LyUD)Igla}JboUwfS7(F7V+vxFErE!ZX2|}s8!%ePBYH{C}M&d z>N^yu(brrp+Jq#HY0cDOQ12SINqidp)eoY$e`aT4u?0ASmK!h!21*^wfR8jXI!Lv^ zs&Jc+zxWyN?r>uFL)qEe7#w8Ut;~B?Oul~)`*M?YZfCrmWu~*&rd7#z=n=dOA3Pp; z$bfQfhJr?T2jxMsv)C1!xTT1SBoy@+uhPo$+VO+1P<V6TgownGw^wDO-rAY9e}{<3 z2kz38%V4X0VzY(g!-iVGQJTiL6=_3#4cU=6LyG+fo$<_BwO`GoQu=UTP5g`KTOc#G z-7-Zi1l0*-$K>Js5~Jt#!1l2+X{j@^XULwRgO<qJUzt1myqDEA60u_0MHj%}{eCqe z$NbW2b?=;qq(;3=%_8l+JKT;by@Gk5s0CF}D6K|l7W6_w|J0`Z^u`%}VN(F<z;f$z zw<OTLK4hG|mBmv!sYvaI`IGsFpAi&cohcj$Ub3W}AP?`Zj<3dVbDI)TYlAfYrsDj^ z_lSGxK!y02Uhr8%MW9Ww?^GhM1{nz)23!4&5?bIE>CqWnO1oe)hcG?%OC)wUvnXAE z#G^^njJe$6P|R0+CjfH`#x}l?Wp#b@JS($;q({kuYBI8H>`XQY_B7Nvc?{z-a^VHm zLEjz2=GBC_g}t#J2XxiarT!>@Tdv;|<8;`TPpnHp4y0sEQAJa<%vP!vhTEH177;cL zuYe)0Kw*8oG}**u9+MRQ4UcHL!m?yYYJ(K7I9fB@Eogb$O;vomU~7vvtuxxk#*)NF zAMduvvxSJ^cgH4}DE-V*l~bv54-1d&bwKeU&s9H<JVc_mdqW2(ap6ak)mBrbe2>+| zU4`50LARvcm?b*Z+4DNni=08J3<Jh$<m4GSq#C|4)T=Lj>{&NxFFnx*zUy+0>A%(9 z9}LO=E8^i~|F40CQ|jvfh<JX0g}cP8$a$@hyiZ{ZF6*)zt=<w$nCU+v9@2T#GL9b+ zj}{4`LTa+hn*kz0>$6V>^ub@=zOjr7Tbt_cb`vTEiqr&Bc2|jz_yndghX@i08?>>G zBnZ}byL-d_e{6ERjT<XViZe$nN~f+eZR)4()a~VEQ*#w7?5e)Hh#cX_^NIgNfF?RP zKVAXLqTO7LfKVJ!x!04cLjI%g+;#uc+4Xh_<;nPy0m_}8L*SHx5XBTfQMZ^tfHQam z0T;KHsTZ|y?WF4035}2z(A!SCvSdhavwOe9in{?s?l>NgGLGo=X)Y=P<?+RJz(G5X zIdrOf6noWe&HrA$Y?({n@L)4+x1JU(t}1fOhW^Gg+*nPc+M%=v{d@x;H&NaVubb$k zlzOD~i<n5Hf%AambKTdu9Ye*^$5^BFu)eKk+~5?A6ybUoXLct^r~eAjh&3B*2vVRe zPWE;_o^`QR9G^JFr=iWUXWa}B<l%bT&>tRRtKXBUm}o)7*;J-<<z@&(zh#Ms&%!cS zb$FJ<ySyFz+50(nD?VRi=#De{Z4MKgZP`QJiH+__9KRdKs9uyAWVje<S~*@i4(qbm z%T7+@Jn?X*#b>|+AJ6CI75=%FqP^dDh4mS$QEdjq<?Hx#!$0Z0F26%BK;`h%c3q}U zi??IQdd^~oH1oVXS#G2JDvC+q(BQOS%0xKHe&ZBOk~xL}-xTZdj|=kw6(}{$LzY}K zu2Y(<<%E	VebQud5*(!YEmY{{vbYWjF;HVC}eI4WC894>9)GFwAhvo94Z<js-%_ zAy=TPItU763^9x!t^raOvp;t*Z0=l+ZB-rr;^2bYkJC{SWuNnY{WxZSDhdF0cFo<U z7hR2;Z9AUMX7f6nU@vfb<jfB|qp6z&E$w-}DYT9r4*~{Ae+5#S|1tO2O+ONqaMv<Z zMm~2_9w0G_(yL30jWjn@X{LA6YC4!DeCR|BKaR<O0Aw5t@m()U#L9QA(uN##5+y$Z zzK&wFPt72rfCkx~Cb|d>O^Uxw1AAM}=6Z0~e}?<-`oh%FSKnoGoJMwMv{=Iut7T7< zyOZWs@{JxW_H**_`O`UOUm0_dx3&LEt<%-6#`93YB5<*_5bJ6m`79f3WECQ8$Fp)U zy^S~C*WHL5A1F<5yNx|MkgxByu!0Q9c$pkFy8gLAkqi}bLUX)f$s46VAcfyUpAXc2 z@NIVv)*M50f;a~V1TnbzZV*!vvRvPjPC^W0N*>HH<cwpXFxtL{vKTp4cc^-bA1IT! zJ^`_G4`+l`%qJl?7fHOl_uZto&m07gBS}~UE{~Ctl^7AkzE;;PghDZ5JRxLvSmiDd zc7UOZR|xN*Xv0RB;Kt%nM?q;9AC2{jNzQnF%)x@m7Ll+S2Od{&-dQ+8eY`gaDCkVf zv}`UGRM03om_;t2zG%Ip84ezv3mM*h+c=NtS9Ko9vOU}tpt>ZYG>v2FdfL0+{o|sm z%F_O3g4GD%b-(-}cqwFbrcO;p{5f3y)TY!Jfph~6Rbig(yAeWZ*+-C5<%4$3W9!A` zvH_9fU^sUT#>AEZw>*b@ivVr@>Zx%&Qekb_d&K#lEU-rN=Hv<O;d`ed)o9CvoUM#v z8ur-aF{*}k)(Gy70<!nXZHXAL9)XIPNvGxZnQRyeGbIBW#vV^_qBZ>?nuwcafRMG) z_GN27XFZF?Ms%Cw*}=oIJ^&`xe(sZTGiiy!&I(J%?7D~0U(auAah7a0b!KPJX~tQa zJb(NsEqWZ5gF<%)gEjHu=e*WhcQoaC(+u@tMkspAf1PhP7Mnh9M%W1U{)V3i0VU?X z<dnrQ7Vpu#?6Ae<cRdw*2B;3jI&KAIP!jsu2lErCBTmy@1YlSQ!U1%(4fTcv@aGNc z>+Poy4KPMt<I;A~9rmcd5UqT#*Bmaz5-pI&v8K4B^)!`gImgS5gLF_>V`fRqHBIhX z7{{FgU{+U#>|b0?hpfu%bpj+)5JUL%)TSvmrH0`FLNA&AZR^B-yRJ3#*Ha2kIFN&C zH!p#?BqAV!WcrgZrV#Kl{H`EQ*?qUe_pM;=MpaH;ady`xm60G|<QWlz<UG8y!h#?F zQ$GN0W_FgQCp{NL>7C&5*YP7fI5aun;_hsbSn$1!ne6-EhTu{bcI4OYoX_(j*s^w{ z^#mgx1+9NDt~BpA`H6I%cVC=-YA*8-$}r@k$S$S^rJuGv6L(MCGYPL)XOFxq4&88@ zwU}V!2bD0v!}Zf!mrcw2akV*2WY?%~_kKq=IMPw~;ZJNVjs;eCEsJBA4XHocUk_Q) zR_4ol^t;Rl_rV6aF<$V4zGo+42$c^VS5F?dZmeH;EF>6c=%}{&0G78soDE2j7zK+W z%+#^<4nXaJLj#BX3h1Bb#MH6asN#<6s@iI`=xpeF>r3++3x=~%f+Z4kIF_6|&XvhY zc&Fe;FoLLHHLa$c%jj{2(f(W&jPjWKvuC2ulO5iD-w${fbpTJj;EkI!k&l><W?_GS zvTd5-e;xE}@8#Sf%}G0)BlN{1;P}KRF{PoC+<doBhD1U<f4f1~%{-IINxwIc?(;1j zjjR0I8sPt<G?F&9F?BK{U}R_huZ6rz8k#?dO_ZNC0Kz&tW|;amC67m2qxk}xV`rWS z7DhxBiKsPa;$bCb?RU3OyfTSqH~H3bXjt>8V~<xT-IEQ^MVIx*ymcq1zCU`dyyTIy zEqAa2K~afd1j%hX@b&z0Se!{@d2ein@C&?sg3QjQoTviVBwhyK(_EIjHxtf~$x^s& zI>@^{7P<FJ1maMTobYPrS+^~YE4D8S#LWmE<qIev6vgw~!SEsK6WGmFS12Mh@b!$> z@#;YUVIO9t*tW>Q3Rp9jo^Y_vS?GfJk{O8rF=3SCvCQ}<Mf9*eT8WI{hdJFJVs+{~ zfL|aLpfCu=od~tU0R%L`B^)9cg<1l@F32bWX(7VZ(S@Ye5OBKyz#2d}!qHrx5<e1A z5M}jR`XA>9-o<!EiecbC(q5JA_}dquL?}KiSn#6*`!7tQ!_Kif{KpKG_npTaj$brE zQ?A=0V|q#8XaW3tn|xi2^t_)gE-rd0zNafc{KuRSrF-cEtKx77zHo3e1!n<)2V4|g zCmwQyOb4+YzPVkeikCIE-f%x**l1O*bv6ms@-4^diX@`Zax_SUqs`3eD=R#5u1M1Z z%j3$iDUD~YolTZM)Bwx6YuZLTPX&WC)wKBNz01)m(Z`F{>i+5w{#6l3pv}VhYeX1^ zzUd-sweW?cbN*wW5_qXMW%xs<w?cHS)d1eOYCBSl?ue$WHB)Q0YI?NWT0@1>rfJnu zWav2@wf!uIr8AVH^`ao$<h2wOD4L{C@H8WLK2@9rKhVB0j7wuyr!tV#cIz>L=nL9n z5-4SWD|XCU$zWG|meN#w=E5L{%qvSdWflY!M67mTJvD<d1NtDDI7?1-gfjVihqS0( z3e}&rQosX=&4B<cWsDsHN|LmjmP&#l9c6C0op2xm8qRviR5>*Iwn%{T{-#&5FQddU zTlG|$Ih%x`CQoSiuS*N<9u1ZPcTStolx|{%uqF&Xwo!7JX;pcmfh^4e2tuDRohk(o z7{*)fpD(0fulwaz;_LNgwY^Vf4MQe>0tuTf|Mz!{avvW93BFC84G~{pNTR<!a4T}s z&yF0SVQ~C-L-BqeY|b{p1+E9`*C$LfM6i*a70nY<75pZQ(=5{|o_3b3XgsAkX_v<W zs|4<~so;SKpdjLaY$ejl8=;I7O3>>23tNSy&*th;X6F8`ybc5=!Ad>)#a5s_%n=Y5 z39oi|Ag7f&R}WQ>T25SXyWE@5!xmU-R>21BLN!1)CA$Kk(_`)&Bh+?qQC--X89oki zDfD8_2+$Xh%oky2+4Aci^59ZUfTfmoegyqT1e%P0R1Y1~>FSksi~RVgfi%H;`>Oyj z0F9`CjRDo<f%K#ql@uNga6U0&rjiW0DPn2f8mjx=+Ug&ehR{XP2FU7R?&C%1t7#2G zR~|glS}%n>Z+L-zX0*l3=zOOt2s!^GbO;9Nn2E;FB84tZy}r{eBer@yqOpzWyo}!y zV^(LofA!LaKdl}hQtIkf7$mZ`*DtO*t=&>xSQh-db*7)pSWd;%D;GvY<o*|9?-XTO z^X_Y=ZQHhORob?*Qk8aAR@%00+csC)cBO4~{`c<FXLp}(^!RRK#>KptV~)AvjfnM& z=h>B!flXg=CKy$pxhbIFNwbAg2G&xlXO%qE<vjn;CXm%T3x1ALqOoAgLat+$-i&jz zEvUHuRLEbrXwq}$ip^!)nBLu?tB0^u3Kpry+wJ`sDNMLRz8PdiZE<$a%l?qSgh-+< zT*L|5Kvv{9WjjsM+9)OBi>cOXR>4#y+e8d!<y5s_CQb+4sb`}|=xRp#zV0ULBHU6` z96=m{zEIi)luSWPwMl4%4C8-_$4G>caIJdC`+=u7)b0b&JC!kFc(8ORQ<y61c9d*g zYp3lZuwqY5&=Kq*p!k@D8_rJ#Gp~6~xN(oq?a-L85->y{7x@t?BbJo(LN!i8IwqbB zcwME7;%wgu9L{qj0wxDv&;61pOSRJyk^Fm#6r`By`~E7hI&lI1)`lo?rZ(5EUfUUE zsXOKqkJfd{q=s%)bfE*ViUbXB!o(pg@F|~oJXpQ>^aPRwnJ3e)x-xoeo#*}XUiyX7 z<Fxj%#(P2FwzfH)rT=zb={9TY*6y_6<Xxk1us*#WLKxi<;Xd>d^a(~CBZ$A~SJZPx zZp=tGdv(z;U-0F37@3K?jt~qnl=GvwAB<>zsAE3iR~Fa-d6!1=cPe#HGz;h%lH*H% zLD0bKqM$(DE(|+S!C($9*`o_QvB{T*o7+PQ)?3R2IA4Db%)pgJ_#*4KK%L!<Q^#8k zNIS8NzCZfwh@oZ3LJM;wI1~CB@t$@|){h2(^aIR-m=+w@zl1bLWbcp-l^NszR2Z55 zZ3LH#<9|nR*_r-z`eo|7aN@Th`}|h~w?2e*U^mtmnFzD>JAx~`7t$DPWN%l6{DZ}` zP4e@1PaXiKd-Rcp+YuZJDdi3S_WN+?K{B36Xx>38sKcWKG#y%aJw!7e*%C^iR}A>r z-@H*`rK>Vx%d0Wrf+tD%^xHI~q1;6;lpwn3JTyn*9Fc&BHs3z1tsTWhJUTy;V955| zq)tQ|D)lQ91TkZazo605S5A8y4&lijIfFtXUDGq;U5wz;vu{{-36BDkapl}aIFbn} zH{F>N*pgB^f6-V|S+yu(@}Po6Xd%^4e`9dzTm_tmzoL|h*z3;p+w{+Bz+#7^-C$5G z<1s_ZASFc02-CP^2BTSz9LBDA^U*OCsdlM}+)~f_Ust_$YBDCzuBs?1AJgHft}Mr) z>C9<BmstWnFsXkc=YT3tELRLt7#Ui`k~GV{L9l8sx*_(DL3^cn7dX;%A@(TVxI9x> zr}*uAzx;&O{@omy)w1$-4XcuasgqIlI<DfUUkCvIUF1%fIG)dgN#93>$_6vRl0v2p zO@GZ=wsrcBM@hsGco8i5*2%8vpE?tAgYvB9uPgi8Ym_P5)khH`0LBm@#Ps5~dxrIh zk*Q1<Vz~9tvJpz9wT(JoJgp}HDc{s0r{k|@j-9l_i8&ooJFu3~IL@kpDSVQZ-JxPp zKtmteE5NYSYW8@FeZlzjPNF4dA>$W@Z1f;)xbpk)DFj#%x7YpO^XuomcN#uVG=!Ku zV}J49g+JGnca+=$Mr*1QkJ0$loL6wSLFxoKy3^9<3I@MjT%SL0jb9zwU=#*+->wKk z1`-aJE3VJsYP=sQd%Co*^FO?}dA(sNCSDe;Ioa>FbMSpM^$j}PGLx5=3G$vkOwtS* z?HGLE6@H^s@wCFygas?-7<Idb2@~m@N9@O-{>IF9g<O*Qyr2FPqzef}pC~EXgag>_ z^nN)nFpR*5n?*o|XhE#BtgT0_Ooudh5MWxO@u1}5#`@((n0kkFCtq8O&~z%#G}LFv z*3k>c6zNTvnhQ+b1?dy39cBNVr@ky$xrla^yJ!~>1Hx99S6Gia$>;vQ4K9I%%V&HE z`r|D$e+xw2SIe1@OYQYPeGJGu`Pr~On+bU)UaUTELau@D?rdBD^%WT9O6%e8$6IPx zkLhH2J4R)}M$EcxGscjb>1jr$zw<Lr93_h?%_gEP5?eUU?Bh$NBM>81!a4yh!yGJj zq<8<Lskb4W;P`GzZ1Gl$V{KvDJY4vPyp%6s1$p0}%{x!0|NL?Iyj$JPh?wwbJFkzJ zM)<@3esO)Fa*D`s35_eR3VAX{ZcGqQmdrBf->5?3Tm|&xqLE5Cu*-<4zyNZ8p-@x9 zuq~^hqQj6QXz&>U@BaC&mf@p+{inaV8S{AJFh`G2en8Rkx>6r)a_1ZifJlvW8pBdL z4r(}RE-KEoi6uSTH@~F7+*y2gA#vpKGJO|JHH#)cX0DyT)LKll&s9B<+NxzknRw!` z9LI>bFwuFYmy!yJ28t+DjINcGmres0mwyz_N0!L0%fGMyNu_M@H)wfS6D9SC7j<cA zsTHTJ%A`TtqB)qvY`2XF+1i<>-&nF#ao8qMNg4qi;cs>1^1?0Fh|PZDxF!aU8qTOw zW2?NYa#a#B`V-KM`rp6>zb+WgRO}NU<dH<KRb6CuML)T?l(pfcqj(CPac_|<Uj!`2 zEK(z-=Y{ku*=N|-AkzR1!^nIJiKjN0;_PBF$!u3v3jJdTWS#m%4#px)GkqIjqlmTN ziKtd}OMMDq9K+P4Z{@BQ!v>1OAUP9yUbJ&GQY>N)aX%I~n=@*O`?Rdn&a_LY>Dih* zqz8E%q*;n?0!ifMSAJnpCgm}0r`=$pIf&g$8cx>o3i6B9PaE@37L6m$H7)ib+F&sN zP#q}HtV1W@=$F<TYESl33>W}01hz}VDjD^{o%^cj#3s5<`YG{Ei>RJ#*L3lA?w;7> zIY%BDh8~uR+wCN2IUe+udNOg;45+8krOqOlaDO6XL+qdiUPQ^y0g*kGf3EM0X_h8d zvlG$?eT6*kK3jFq{B@19$Jwe2w1`#w01UQCt@irzRQphe51=ok`(TF;tWO;*pN=f@ zi?7hz!<yJ_itmk)UyP5gvH@fDlt?T6eKBQaLgZBZc<EU=s2xXRBs-Kj2QROSEL}et zYc~5-;Z|)6*_N8=T$=O6tmBg5@hN37q0AMioI}6WWj-J$%|XAAy?p(4OM$=}i$nzD z=!AOziqF3IJ`#2=Tv1kAI?{m7mS}EKETmdDaTpU~;HPLR$+x(KUu&?)7u~Eozm=sV z@@9s1!*_EZfITl2jIQ@W;ZX@a`k_Pj6lSfc@&{h_dqxE(S`%toiBDy^`480ww4=)M zBxWT-lY_<IW*Krt$Gcua<?We|8(d24T&F5hOh_CuHxj=@?cY$pCVbR2D0Ur6$bLOX zrEYy+1v|Z&Ne3qy5i=`t_`ZjPzlvRubj;z2S!4_IKucagluBS?ThQiWq%?26+0L_D zA0~*T?Fp>pHOa1y6adk%o-^%By#}x4#x2%<x5<ZnbGLlhFzfCsoV=T?NG6?^9TAZh zSl>=Ppo0q#B0EeV58kKg^|n7-fR8)Zrr4H>piVvd16$K|2@ak^a$wPAHuXTl!l}<N zaBrS`7s=pUBgAW)yCZL2Q5o9XxzlXWFz9zIv(NLF$BKxQi`$_^yOD%TFQVjks2K&n zJ)oX(Z3tSoq9**_92R~+Kt(lSs%8%&)ra{qVvClb@|bO*CqfAY_pP$Fo@F>~c`FY| zf+!4UvjgBsXfZcqj}vq`g;5o0``e7wE!tE^#mN2xt5eP}18bF8F0Cp$`O>dEBj%5d zx@Wy?ZMN$CaT;L0ade|N%~+Y<VNT0hO9r>AKE)kT_M-sf8GHMWMLK#L<Dcx4^q<s$ zd_K|peB)3hQL+M-(RJ0M(3gJHaHEQCPG|?W1f6?C9wEgH>Pa{>Q~4XlfypIY^49wt zPH{~eplatGt#tubx2LI7j4Xl*=+X56lXRWvA~^><*nzqxkIZ8iJ<Bf0a;1=Pz74_l zGMn6LAI58s^2sxQV_Q5A?Ywd}<h{UZjtMji_mFv&hjEp&hhyPSYO27APEj@XYS!?n zBKhRPCNcIFGW5%W#MC3Nl`sDllNX6%^gPRun*<q^)vupL<jMv97nWyylzK~Eu~b$X zXUuon`Rc)iyp0QX_@}CO%8SG8Q1z?m0@id&q?wD)!Y|$A{vF}*EqyxSSJ|Hzc2l2_ zAXT9I|1fRjWcw!qAsg$z&dObA={aS5JDi_t49yJ;DX8L+Q25N(xiaLNPbjkGSuI1p zB~Yox*C1PLh;Q3ZFks9au9FKH&LwY#pd#&r$Jt)wWHuYvD_qzgJlOcr_|w<1(`_cQ zzu^7iM%swI!?~C#RQA`%@N^6)uHYcIxFZL8%RTTY=jzL@CtI`{Q^y+NCb(qOmS=BF z?~g-;6l`ME3y+CoSV+^Os(TDgV6L{XiDsW7L&}dQ4XXomk9vO_>qdWK8QD@uEU2}d z&SBBR`N!G+?zUm4gyJ+;pgT&7apF#D5jRt%l`}vbab9)mkGl>uQi;}8ig=bSTgSH2 zU9X;)s>jgrGDvJQLtWMtE4r-61Y9*fVJ=e91Y!rVARcL<EPd?XGRGzdO!d&6rUM!L znBPrh8i3sYc}Qdg_Y%pz@@IHuHP>c{)-UyE2sNyLCId%G6xZeAwkKQ{mGPhoCsL(` zFhy!eoOs=f+Q-<15H#jX_V+5`q0e|_!$v8kszSAiI+!z7f@2`oSe0^~Bue!W&Vpu@ zAQs<b$Hk;K+svZmC(<6#<j(+oq(HN@5l)y4aq0k}D7~A$2PEQ8l~mnIA7Re9c_Lr+ zd>_4S8xkmz*b{c@7YI1dEVa^e6oZJ=IPv#Sq$g+$e?$s^QoN~>=J?_a^e7CtWM(n~ zd~=|@%lY7m92AoO9D3N1pV?b#I#KMkFbHFVIKh~UgO#)|k#Z=oaQE2~^G~>HE;Wqf zrbOLCBXeLpME<@7WmhW3pmdY`<FHN~kkG?n9!{ajX36Z)dV_%ElKi&W>nmC=ZP6A< zf(7EggQR+pgoq&Bq_=5QKu7D|Ae|I9vi>`(-rMdEV`uiBtO(vn2$>h?kN|zWuz=mM z``?`#u;8?y_3rH*H%LJ)Z;S>B0g#~eWgCV?ZJ2C!^>nM~QoVK4>+^dB<i4;{xCw;B zX$IL!^f3HRuhWSW??Z8da!GQF^Iy+B_KyR2%||N=dJqhMz=RNz_jD30v;g{!Za3%0 zVs{=rF2K$Y4GD**O{23AwVs}Q>GDomXkNk=3LDS&+wWW}gq#8&SR2pH!%-LOx>FR3 zw+zcan#ggF9NbNyS>wF6&$Z7RQ-hm?S1Mk{K;-*CCeb(T;H8lt@SBbU@uq9&-9Z}A z!|2wHCh<l*@^tJ>(HLO5q_Q^|kPEaaHDXxtb8CK@1yq6hZ?4sfq9DBH11(KG!41!k zgzu-nIa#mBo4b8!daP=3gFmrkj(fLM<zCKgze*qs+c?&EAe%L4C2OB){e1Xaz20~c zyA3*XSW~CasU&S7Ija#@E!;UW#fWP)DB-Jdqc^MC6y)&>xoHTthG4fE+|f(Q$vd#? zm$*qNl31@QoXFNVOC)L;ONQsQs+b3#-Si-b81xawDG8!=$8t&(N5LNT5X{5ml#ZDv zL{_c~MzTvu*?T0j+`hEgBE4+MLxoqX%-+3x%r6Dp&~ZhbXDpzIi1sTO*hOC|nZ71f zw@{(Atjg`dlW=Mxj3dP1v=^k5rw3ofjJuOs0cfJ=zBooa1>jyR(dr&&<AK`CpcGHx zho?1Ah>l~SK63^!k<d%m`y>Q+ez%hl=e3Q6<-4bl<9&x|94(cC@-zCpg@uR*w6Ka* zdp+?D-KOAr?97FXo$%i*%W}8PHqydT#%rBcN0F{vOw!}3v<iFeG@6Sd<w`CBDJNsA z4Bo^1s>SK!Jt0cfbW=DCjI0$_TD*6gj_*ywuJx7mQ#l4~er8pBQ?obX*SqiMfA^dn z(KF?v8KWtVG5cm$wd~(NZ8wjvfXiI8$9XO$WcP8&wOIKpnle-oTx6`ag_~)S6dih* zU7f}O$mp4BnQne}3<0!zx*A8Q&<>EKY}^&|4I@XsdWS15BfQ{fribO<*rbZ0KIDHI z?YaI5gTeOi9ljS@|7-VrhRHB@CY6|6Da93khr;!ANrq(vR+}s+Z_t@^Fj-e?3kUAw zinnugcIsE=g;~HIlFGqun-AYR81jCDaAd+#hSFKB#anO;=yFrk?7}tFqu%m02yDj! zmRuz5fuZzN^WjTqMq-|zdnP?1<`|u9!Fk_3bibQb8|G9i4*bhPA=pjgNDGsh%CvcC z`@%b$=kjT^wt+U<Ich-l#f!ir{YYz8OSJ&935fL-oc~2H=VxNP(|{3&c{Kcfn#1gC zmAEq;n2s#mkOD#6GE$rjGj(tvy-k{}G?cKQ{4+bTI$dXrxAVdY!pN~j0H9XzmFqI5 zeE{&+hU*dzVn0I3f~%b(GE@@5>(^|onK0lSC^Md82?oIX<En$SDeoM6VA7<G@2A?! z7-)rRu`Rejb15h&<lCS|2ZLNnu6^?!ql_0}!v0$<ju9C;x3(aBkWUI00|Flt=xdm& zEMJv-dLen#u-bZ%YS>BvS3{M9`FPlRY{~KWTa7F+N-q2{MiZQe;$G!5N}B|1g=wSg zn+A&E0%M%Dn6G0y4k8<B+sL1);<(-P(%`B`Bs)kCIpBh1{6}NwnXj|!cvXi$-rcjG zmD{a7efwJa+?H_tm!h-q!7k-Zjk3AY&?6)6RDpP(F?kOPaFmuYnD5Xxg%y|!bTTKo z2$PX)&6MSHZO3L2dVOTDMOq$hM}1rGM!{}-Cuh<dbt~QfFW^}>)Y{#4)TPUuJ)r#E zV;6T^sp_)ti5XFPP>F_^yrx`DU>Z&Z1igWX)mRz|);8Y>CTb?q8<D*JI2}V&7tm_I zW??1uX!z3zE=+>1q}39Y9$rs-O1y5X#4V_$SbV1Id4v^ibCq<awjoJzTCvj2%uN^m zmxd)xLzS~!VOWiHk+L3AH$^jLg9(d&_$4~%d>Kl;bd)n!3cOvQ1#1;k+7Wh8G(J=D zTp~Z+y&P%cU!TH<K2t1(1)&%4fDxhtc6G`4^msosPCjZR_`x3o86bY-P-0q|9SjQ@ zXp3~tPRrLk&WIft)}8A5r=by#7I6rF8cv<&{gA?i6nQbE$dusTz*z7g@q-*P|1RQQ zyqsJG0IQD_Ilri1a$avV`$;4+>UovOJk_)QC5-7P8IeBKISi)DqEhb0p|y}Q^-iX9 zftsM3G`-2j54nrvYMz74FbrAYor8QDyYHib^Hi=aLG*h4ZoZ^m73E8Vup3%1&~cKk z&|Jh-oPNXnS%It9&iyzn>Qu!c*@!pX^?;|;!I9RlCj;cW4^=GbQ}b`9m!dUVKyDQ_ zE0y^!l&bp1yFcbGu?0X&Yfw!tbEzvHYZ4WQDiU28)l~rM-f2c?aDEq3Dr@+efJ?h5 zxm!dp3gvPjqYtAg8U2!1H7o|y87e!_5xbQP5d`>#(2N+T)Ai4J4zO}zm}Ka=HJw%N zcow{VarYTd4VvOF*JMRJS%rI(pT=AYRWMxUmpP{#@nz(Cw03H!@Ceg(t4^!<fe!Wj z1XNd)z;ud38uy71N{3UwmgZ0<Br>K*Q_t$Am*>x{VS|UEyqo6JFHqCu{cKXq*UHbP zR_WnXBG4=E(yPXRMFvr2+eh7S&bAVosX>={@N%W`Jha|KI6U($F0|;%)+I5PBHfcK z+!Y$vUSgy~M*}pizJX5JdhC*$%Va1V-H{EuJv3+c0MNoA)#FtwvaabO&1Gig+<?l| zK+4|mWA!^Po+PX;rFQNgcQyj<wn0jk;Q)yHfSa4zCBZKJnwF5iti-36#IKbyTiY<R z#!vT;Zg1VcKS6Cyr{oMSQbTsLyhH516TcFeI@xDv-2iU5j_ONrN<NIMI9&@N7VoUP zeX(vVes7Gw-z-x8cU+4&+0cI&+&Q@ZXEgc$2g2|zclzH3_ix`T*S|dgIi;iX9}2^N zZvpooPR5F&Fo7I^w18_9Nxsi4F$Fr=MsmdyPl(@My}`S+HE*c%SS?%gi=_<=;QLr` zX*klUu7GQ>#YK!kqr0%TYN|MparjcwaFAA*$V-@xv_&y(nUMW(Ric%!afI3hLE|Q2 z0w3BLv`OR&FH)L~E0!QPv9qb*DQ{EK^v%an!)qaLR3E7mqr>nwk-Pc6ond2m#i0s< z9E!=ZARjeOVwYF>XClw+hEH5pB9#O>CTLULDG7SU4<x@v_R)iW+sfaCIOGf%wyMt5 zk_GWHcsNB2(57HC9f`&T;WCeqsxD<{qcl$TIB50bvhr!`SiDJVR1WElO0&R@Of=l1 zNs-Es8&Ts3`xmwjE1?o<DJo4ZD7pY?P0`Uq8XJ>m(LAMR?<Eez9Kt8No3gSoqIAjl z-^geMiH3JJD$?IKRL(7hK3CF&vy<#B1;hAS8D>DDmlC%yy8_h|D<daD6ogkqM$y2a zSHMB^`>MCCX;xQ<r^1o68g|q|tSm1);u+UGa~0HAEDD+XEkRiEgl+HA$_!X(V<&t_ z+N!Q!HAIO}NQh{OE=q{#gbgN-D{913P?y3fO-2Rw$8${e?TNM7vVS6}S)uv@Z<`i? z<E>QwkYx{jdIW_9O0z}tlu)#XQn)c9s>8(^vifH8VA+z1h0I!!kp(O5XZQlUE=sCU z(Kpu`(=w+=*_i7@vXP_EnHDZZSWGjxZnvex*7iRCvG3^lytq=NvXidj_UM<;?fP?f zv^b<;u*u6!{!X~vZChVT8EKb}Cwg6v4xu`*erb~d2LMyDNry{&>CKV#@%im?md)?f zaXiDxeE3t)3xPjzBaKhvIYRrDw>izx+d>^yhl?+5V95L;XR^co;%X9=884sT=w<VX zb9p{yqRQ*Ub^FiL#)Upz&sIBWJ!Vgr-nH@bh-2Lw231PMx|=zW?PkO#;zY;U6X*Qx zFFR%1bH<5x&*!68ji))F!gRh2CGp#$?tae!_|#P9<d657n(FGl`@^ku+{&YKL@+lI z9%SA)p1iElEUK(huYT`$zg&5H%0kpS)H2kyu#K>}FhClQ#c5`lQ}O?&)8=#pNaMA* z%=~|Kw0JB|GK-v&0pFcfr%y5RwQ9X{A8)~}=3~Kct^14d)3>0fbE7c|vBve!#)sw8 zg^U$qF)eB%9Pvg5XWyJYv3dh!J=ead(d29UYG2H+r;szuWd!s44!0K0tCDp~&0h?R z+xk7&zx201T|L^~QMK>A=64c$jmrdjFL~(lcATi6KzRMB1@#a@ORbmELi+RO2KSLd zm|%4;6pM{g<sl!agq0De49!|Kf?q0@;|XX*;Na$`C#c1t6)ceNd=(m>2cPykNXN{O zqRv|BGAAPW%H@q{91fFixuQJy^2o|O{knb*9t}vBs>giAQmW<jV=fHibddwm>@6DG zpesPl;uQR-zbO>cj3~JWF1Np7K5;E=B*HiNxe&L+=Np6s-vB}8s}`cB0I8OnV$<Q} zivx^)wgKzX{&|>kR?+1bVwN4^f=?t<=wm%)o!Q?RoNfx8t^mnqUI;~KD_A+A5nm-l zj+A@EN8B%Ol*blAEQ^wiJcbUkLVW?55%V{q9F&=0)wB%g6fHPM#amgR0V3wT5ENa$ zo1|+!vQZr^zBXIBp*ogEVS??@1+Unn@UT#O{QLWjRwT7Jh;ravU|sW>WFkr|L;B_C z)$ecrE+nt7?1N=_BwkGA5=Heg-ipwuo!93PM&~$waV#Prti-D<wReatIbB++S4@>o zVkO5gq@x!Nv$hO>$u_Nsp=WBuKpkbR=_J0Is;G~d#+9j9jLy<Ta_+0D%4hsnJ@**3 z%y1rC$_Elg@2*`h-=dK+u>l>J+OjuW!_*a~#0-)jIDX6Um2H+KDQ-9S*7ri+iU4G` za{-1BU7_s-Mj^(tOcY(!?G>x^c;oY2iN>`MS#mY|O8E8if~AXKi!ImsfUAf)&NS;t zG39$(c%Q{Vt9;aZ{37I}U_~10PW`f;tj1i4+GCFX(^*N9X^I-Ioy8KXxSk>#`AsEs zvZN|`G@1rcu}YgJ#?MnCWGxEDVG%)?3xaVbAW&fxH<lr2ZWJ0upr(P&q;eDpjrt5} z0B7G`Bv0aoyo6NwU`T);<OEv|M%;l!fFvr`lKpI(X8x{2)!$}4tcL{IchB)Yp7WVH z+GI!~MHxueTKAgGJQ#x*y3m1p_mR>`@ke3*!3CWM>zvcCKQ|XNdqC_Y7Q{Ya3r?3` zTO|^SWzgI}I(rr;s#H`!9HpmBBStvIO@OrH_Wrhh!bvkd7B(OQ`|%GAvey@=MVgcQ z@3-_+Ru_t17)z5cxFLj2v=v{B<_;I?5DFtmgErDiXBKaSM>Q{HW~G7X2}T2lUDA$y z!j1T_qYNzD&{AL~Vc67B@{?R`)lhjqHT-&z8<NbEcA7S&ZUJdH_Sj`sCAe&F_bXa4 zC>BO~3*iCwFLfX-*jb1ac;Tng>T&&0A(ViXNGh!d7TO^f7!6Oky-+ZJv5L8BX|b_@ zNRqFWG@;-9dAe0S`A2RU6o@h*g!U=hDbF;t$9^PZF_F{K>|iH^_ke}s0_a>p{x7jt z@Ow07L8Xt}62)+B&Qw(zX_xFJ_GBjd`rF#v(?c{R*vfgH-w^!#LKmLx=qK1g;Rk55 zgHjQ|Lpb7!`D?$$8c~z!Dd&}j*{5;FjWz7dRORQ{uF>`?<K&^)J*`peG8xGosq(!2 z5q%Y5ZD$r(mr6r$QF)Wc({szzq14ZkZiEl|a1(en<Wo`v>A&$Xd9EPQIGG4FrdY~t zm|L69f9fk{0yCW}2kME=Xv2QegA5J%dP7K2@P=29bWrl%@22)_Y$gC(PANeePD<v{ zyKjM>N5hGJBWe^TX~xgc*x=dWoTyx{@b2YZ?etKV&Rx#qXV%)uq;s2}dzw@?(!76` zjdH&ramX)?3*0V^xh9o$+ScQ<X_0MktRj%I+Ga+2u2<i+$Vqe=>RDw_uo@OtIYCP_ z-P}<@*y;UPr$F7vDOQoEm_&$sjrj~Q&*->dH?<5*{8|aU!(Ox2hCQUbV1IMX{wnDj z#@Rri$M0en^Ry1VUy5DP5p9e)5Qz6`ki48CY2%DI*rJQ~!j-<XKI~p1m??Xer27G4 zbI$a(q>&!Cs5H#FkuoQmQs@BZs*oR=grcmMJQ>K-GpR1R_!9WzP<2Hog!ERA@B&DA zr%HJs>im;Bh%6XE+&YBH9wzc{m>BjMhzHm$<sztw5y=3*PH>Ll1&qa-{jrz=G$onF zoj^2EHc7HJBHTW9UjB?qyW8a>S^~6E%p=-*6M-PVmsLr$b7M*BLI{b%Y<B);vKarG zN~Eg-gTi!nWjO0B!TFfI%n{{Jg}94yv6x5GUXz^?Qw8;T2WwtH_c-KyOk(rP$KB>p z82P$7x!K>ckNMzKMK|pS)vtBxli6EAP?&?7r4&ywKanuPQ%@d#xOn3(;vZP9-im<$ zc+oumrCLX!xT+2YJIGm-eUX^b8i8!@%9=_uegP&eZS-b4-Fl3_a+NB~Wyz2fPc{Op zVfsl?l|ee|BOD9H$JOm|O;9NLx3Tw=bGBENFQv&*_2yAk9<HR;_018DQB5v!N3C(J zS{Y&+qgY#-0@d}O;EUw`ssAw5=H&jL9@YORg~;^pO$k~u|2c`!eWp=656f*r>>j{( zzr&WCz$UM&lf{wX&KC)#lPOt9qvY^@)j=eb9{ZElr?BmSB)-?tt!~<m8c!F3iwlpB z5HUMS6K{|zE*^Y8LdXd1TiWx@6ZLn%@P-O2oLzl(={1aTfM#5pDDW;WAXamD&d;no zZZDmqVT2Xs;le`v#7D{<1h&)~W)7!Dq`2z~VZ}48ec}O%mcsj{8r=E927_7H3&P4n z{z0f!K_#V`tZHMEt{^D-miEl1lZqgTOMQn*_pg^_{|u&LNSNV-Tunb2baHVEt_gk& zFznO_1ugz$D@UA>^x??YJKHgo<c=q4W|1#>5jV3D>TevKghx0&Ic?B;MNvX7ZfMe9 zJ&p+7t<_x%u_~wk$j>aQl@LqSSVsPfbD0K@^SRGVvFr7eX(rR9tySE6)la`3F<n(W zBVkho+X^KvI&9gxZ6?zH&>yc}^qZnzU+{41Bw2oa(X)=}$Bs}XtLg|i7PxE{lx377 z9<-vhXcX6^#^ZN+`$2bY2j&x|S4ZKOHCwvXZ(gCE7&2W2u|t>>!TJq+<eom?-w6BY zw8+s|oBcf~%RQZ*s;l3=!^e&13rKJjV1#9R@J2j)(0O>nKlV#>JXtYsm%dx20f`&! zJ`XyT$n-D568EQJ6oc+&l~6F~#)-Os`M}OVjFh`!<?u2|Ff0@!$=EqS%FJ3ZWndaX zju|)$0^A3|4_<_C8<e-~_u%HMLy*WzFDBKNC!a}~Y1*-sYLbLY%?DDH>1QwdfdlxK zk17p>7~cqXg+Z=nU)`C1aA8b&#adK`w27pKGhFS5uKNN%Lc$-fv)D@}ibNuPCGLkR z+Egy@SBj@$Cb=SV^zUErg?;cjY{^wD3@MqF_357#`G`>)hYEDj0x(a=KtR2he(Mv9 z5vPy-=r~-#8bx)kNT3?*%w6E7eyNtX0{rs1H^FPkDj_>@kLK-(S{f>pA1fJERuIZ4 zq8<2U4DL-ck=E59Z?xbvo>$#&ojjK~OMsb>N*uHZ*zn?rC%9D!WnJrRiu>9sqe4rU z&lL7+*|6utVQvghUJvO^Jq!{!Ga5!0TIINX^3+VTLT$;coCRD)%0S2pi`KZ}aR|>p zCXTVuGdx@Xw=CA_HIQUv{i<nk6V3s}-LtDC8YDBHYg8Z4!z^*KbqtENKg?>jBiTtU z2#n~U^v6;fUJuJ17%=>e%!H+?>WB$T)C|?@SXu%p)sY98hs+95NoFj~p106+u_P-B z1a40tsMvYzPVy}mdfuDY2de`&K;Y=IqfPp``RS#NR<!<c(0_DcV7HZfK?)7Sv-u^Y zqtA{fCPMJN4@5v_^t9_RtraJQAb-5HMu`JszYBRzZz)ZUh8OydWyJ6*a@c%1Lvm?n zGb2hFW<rL#n`FGE65e+cnXTcbvF{+Td_CvwU_o6RoBUj?{@JT6n_Y=U`9wQ}0w6){ zL0oD|-5p#qb{hD}ADFrxg;hGHZNh4FL?MCZK6W{EH&(BEBBf=Dkb}q_F>oC1V0GP} zwEA6(Y1wRtGK_66t8)P$r&_He&RW$G=a>_xzr`XamRzmldHQ%DFH#-_dg#V+AK~X= zBMQsAx?jdbNYF)4$Iq7u7aJ+Ct1&#|OISOsiW6=s3IgVDK4))Uwkh96raJSRQ6<{< z)8y8}RNc#9ZKojzGWFWiPxFcGMvG63^CH$ly<CfC9lF+36&*R*%A=h;<vrM^C{=P% zr8J$L_121_7t00#r^OpA=-Er8_(&I6CqzYSb9%?gA*cqYZ1XaqEy?EIuYeOnBu7hm zFSGg<sqE}Fq{LCacMWSVP#dG|sPN#qsPKn?q3{d|OJqswp%ug%yFfS;@<ahF7R7L6 zrE{fNKVzz`14|}QaGtQCE~Wv{!zX_Tg-=9K_$R^HW|O+I{TLAVVDORyUVjJ_lTe~p zs+rylXDgx>Om+&7&Gs{f2hOYv*PGhGyWYV2Ua)mA)JQBQVh?x<p{6WD5y!VBTYG;+ zu&yg&dy!IluDWGPVIrDC{vJe|P*Tm@1BfIWpT_H(2oTZ+d?54D-3=5|ceVRJ+0-T` zVso4-6jQQk8>;uFUWKv?9MOH1!_2{*h$DuVYliiA6XrN^*KckjGX)oc1Koe<biFn{ z$QON37&s(u@!@Zxe^IzD^L-)K9eweH0Zm`?P=Ngqv2PWr9UC41%EDOzBi~rLZGWi% zWL}>=6peY-9v6py0sl1IF#N~D_dipH|EutEF#Y?#i?uhMG9-}xEE@=K8xFT`JmJ^; z#}JgZB)2Hf5>^sW)G!6+M`Mrj^|ZN<K!>CRSAX_xrh>SP{@D7sFy7sv>Fql?9~nAd zl_>^|GN#t5ZG}UV&>j~WLX$$FQ|}9jB^Al%R^wqqM&7kZ&^T<6iz8oeY>#3?m~C43 zNi!eb>|#$r?#o+E_lA~<q@oZZ(Q@u~=l7~h{a`2UC4?+IEMcEZgq(OdAK*q%|1O2S zp+h{+$~n4_x=dtT0dI8AwvT6UUieJ;{ab4?1#vhtlKv7RTuA_u@d49}N;$J;WMU&N znWb2~L`7fxdm~`>{KyuN%UB{P8DuJXWC&`+8Q*!ZA);bZC2P`?XpTUZLhSzv-)Heq z7<0YjDIxpYJ=)5G31^;_y`TK@M#_sV%%2c+(61qvtam;nm?rTP#if|V>xVEt6sI-r z>Y<+7NGFsh4n+nG97|<m`aJcA%uV<7cmzDUprDzi=gxK;aQlrWjBqCpOVW5|nn*=b z0c%GJlUZA=$kj(uAqcJt9>rReKr@}M>H(Kq-|<^yi{pjpar0hQ5i-~YVtnS2w`058 zY8|M>A6fb=;>k}Gzn+V|9E4)qmVJZ*qv+O!Av^s5r4<MsUhxbe=D_9bW?!7*xWZ^V zT7w0ZMn+rZo`rIn1?$U&6)-M-Z$H2+d+O)W`xP<gi~Ae9bgqfI!n7+42sG26o#y@^ z#|xT>u}#?xDUfRq$s21QX;ke5WmE-!ODGZf#o{nKIczmsJTjOdTVJ!0hkcQ^<pUYk zhWxJ|ff61x6Tj;Q9&$9V*oJkzi6yxI+))(<9)G}Qf?{Ks4T3+?pvr(SoJH=dCNUEj zz9qtM$ve8KsTUyT>RiJnNCgN<hrn+mv*Qxa6<5#kJ-5k@-Ht#Bp5ok(sj?|44Ahib zy5e2lC!48Oy7~+k{WE1d@`}Z!#3J6AVy~|KrQ~HPpTiU9y}x821|vr49bIy-i<jw@ zjSxY6Dd`~*5+D;e>zui!JHfoGhw=jpGP_ilp*iTu2bjz0tzDD4>c5<{QYev+5aRh_ z=v)@dilEfNU;$?+#93KBtEunzQ~V<9-IPkQV+RakrC4F4v(l15sU(PV!BA!e>M>TL z6t{$66$oFH)}q7KjaQmP!U+3wZo=Y{VG9NR;l3<+fu2~3%%G`z$y;qQ2@40B8%PNb z`yXGe%*dQPQCnVab><uGIOoz&)hSPJVmZ_B_UGUeVLA<F-SP(l_A9#jY$R;GMprkS zt(>;<qIF3<ka!Qu@OafG7ob17wn0Yl#n};P&?Y%<OiOoMBF3WqVSeqNUN3mrl>)Je zgG4APGRJ)psX9LkVyi|j|J<$<5{Y}JDy?P1B9DPWm$e>b`eRe-{)bI<6hU=VKvmM1 z`?j_;04y6KZ%^%)hJel|M`rwZ>%cZxG?uWwED(bDB7uD-oP93HP$q$?y?NCMr9JCl zv|(82uN#Yb-gR*rB>JOmzjE$*Fyr!de!?hCPc&moplty|zbC40T8O5n)I=ZqSQ_0e zn--VR)kS@@wIbNJ&nn(;*n4@8{z_CM&1N|%L0_-Y{%G|As?$`FJuLepxz<S<<;(bH z<)ou^{M@{1lq$<4J;7!r<Ea)zcEp69ezuar)?Afd#$<#NqLlvf=BfnTZ@*i$s}#Nt z7Y_|l<K5Fk%9w0}xl>Ofg9!)~)SULQr4pBTKc9+qeW}mg&pWg%xOi3j!Z02fGU}31 zn0usem5x~ANP&<e$(L~K`Sl-`SiG9qZWBMSly|NX7I)wg#9OTt7JGZTk>5*MRK2wp zZs5<;znAds{_B?+h_|Sw^s{Y|3+L&)I5awLseQh@)UWI@pQ;`d^`hc7CiILV4H2$+ zuG!$+fN5n864&Nov=2iT?qu&3%m69J0GDv}S82!j$gMeNQuk^DN6C8sYm7G!8C^B; zQEIqk?o`65(UC9+MzP}tA6ML$q40kmu@v{eA5mjuDj*qRDTWJSm>FzlKsEq?%UPTe zSal}vnmgt)-!an5`<K9AH7_^vg<j;27v^Vn;$pqp`e%yn_)&xAuVyBl=N&6^2(K>{ zqoNN_FEbgQK@Efc9$==W+1h`sOI-iw(QtOA|C=xUuWV6czt+EPQD?O7WPahh9Aqx% zD3GH?)O*?Sxr$~K=;h=|=pCPL2u+2}6?mS=)Q-<v8Jw*Ce8|Gp@rY*!#zp)$d=2Ue z52OzMUe;j~Xf5%ToCnd;)++<A=|4N?hxZ0{-PP3nipD)&%joq_XYM@=n&sf+7?#Is z#Ec7xZqetwE|ZAGvo`pl>iasZ{X^3z--zoeAlM)a91P;t4`fIv()?*d*IOs^H~oLo zwxz1!GLUm_{NT6Xwi3c%KUO-(>oAg-X&&#W7u3CEO2RD$pMot0`@nvM-cMDA>E+M# z|LFpeFAEljB)p}ergQN7URKAGQK)u-OMIeu`E-5INP#QzSfVwJR4h02jrk7%mdr?h z#tn82s5QA}8p&Wy+#7sD<_+=P_HAxx5H^u!+pt&Jkot?IGfudi-@b$;-k6!im$`e} zXDjGZA8Jzq@B!i%w(ChD)NnAP;UubCx!@qIa@;!RTR3hHyZZch)b4!NTQ?nvbv;IK zx=u5dbmr%gJ(}^Rn=G(6X|u}80^|*<CqUU2?xQ`+m#_oLm>Du^Kx#YM8Z(@R@$BUK z2Y26M-mf@x4+L2l;TI`$nFLS-$m2gp<^<LgNe$-LsBn->t&S0)0m2%2(D*ow*e<_g zUht2?q6OXs_~7x8(w)No07<k!k^IBw#PyH55bl4^E8o=C`Ci{+{5NU9gt!&e-DaMw zA<HI#V=K)$Q#K^|XNF3cDtWoo=LbP7&=f3HTH&ValXxc-9~b0y-;03nV4t3E04L_Q zfnKNklxl8lay+<3i*VpKa3GXTJRVHrY=`F{G<GOnf<_iYEbtG7mV<lU1m}$aeK$QC z!tC#dr!(gSRf`_77FhoQ(;QRU)*;D3G08$r@9x)|y~V{LLQJsN5#X{nm2V6|z~bZH zD=Wg%^>z%fglxr*%&H^qe=&XloP8k?IgGVYz~4*%GVaz;5(P075|n(HlMnw}rmd0n zLdi#1k$%yWG}e;`#a^z`c?23U>>7NV)c?$P#4<_X^s{S$tDxt0%+2y6CFUg9nB=wX znaF_%wZ#+Yun@j<6_G*M829x$S$gk-)4zQp8Y-K)Q*6W}BJttPghO3He{lcEwNL;@ zub)b&>uvNJrYyfy$&>~khn(s=<gBqmnF>2Rcf3f2pKhf%H<SS`@1}4b3eeCxGm%UP z?d6Hc5BUbmBv|qrkd{Flu--zMN9_-V-$i{k2Iz2yz0y&AIy3Ya+zA`*V+#1cmJt^n za?T&efH!0scp)oo9jWkr98yfpZ+Dp(Zsqmi4ttrl3QW%T;VIk)k9Orq2IV!v8r)Ig zL@TMD1LB684bel~&^O)`uo^ZNb{Q#=a*l!tZ<28l`WGD#n>GPsB%2f=BwLqsq2x06 zomJTrF<QIjLaP*8t&?r+QWq>n-Vl+|Z8^Y({z&}HpqcPt^2bKYgOUUZ=|uenFfj)4 zd#%%J2Zz!4eAMDX*)sV^M;KGB;G*r-4BL!gy+G&PnjpV=$!c`-JbHGRwBFcX1OQ9X zFZe!!AIBFuUX%?@K0P6VeXig}yc_bBGH3KEl49?|!9>w)twGEP#Jl0nX0k45k+HsY z!NgQK+CyXA_v@!g8WP<rCE5kJ#Cg05%xj+IDDboiQ$3VJ8HJ@b^wcr^3Yvy7jDgZK zbR}6Hc5_?NR>pb>N)<$sfq6&Tq#f-SMU)6Cka<X}&6es+uNl)+=u8#XBP=oGT%=9J zp)s1YTr)Eep|d-KjbNHo2WspM<HO6A%~A~q4I@-BzA9l2o+r#>$m%YY%jn}dI?!8E z=SAU2m|%{<0lo8!0d~5-me8%2Wi4Y~OMeY*j$A6Q=eEl>xV$WA=+r;HG~fA-l-BrX z$^QA?&Ghq`O;{`sH3W&%(xoVLkO%Cu<Rg<0V~B>&yMnBvu#6g`;$PQmPWY9Sdv);9 zk5yJ$$_#rvvjFNhKD`q7RQrXOa0pEZt(g3V__AmW^{x06N>C8;sIEtPOPmX8;d*(i z6a+h`1kTD<(kc=6SR7E$S5W1}Q^~ET&zo{T-`xKSy^@1_7}NH%ci&g{R9}!1xi3Ku zU=MIJc@n*H15uDnnp0z%1Q>lr&WS7flSpKXw6ie<CXM9TKWA0kV$4~nP=d7_LbK7s z!Xw_*1A3D*bi5_QkGjeaV@nlLm{UEE(WB3)@BpVJr&V}0p-7>|N9kJ!FT<2FLd^VB zQJ#XOc2P!TZF~h}P?aoV7n|JR4)Q{Ol|cMWN^_N4&<8`Z{WbjnUA%p_RSN-R_JxL= z(;J>gn+hq5(3cy3K5&>kR6zjCkeR;mN1hm#_OeQa$F>&8FrAZFEB=}4gAE<bvP7tF zPbiWVUv;lLV+*~{p|8FE(0RvYz{SjPOlf8BWX}1$7?VHBam4epNdkK1&$nT1D!v*T znj7dH!kb2TR|m#Zb29<Pw#95v>q?VflFjBIAd$`)TaqbTV87;Yb=m*g3io3S=&?VB z<sKq+SvDa4pqR-hJgvK@VE5X<Nn4~KbZz4+6q_{sRD)|_%SF|cXwle=$>S-GGyPRn z8JrqDo6(3x)*j+#NYZ)Ex3)Up5wltCvsE1+FJL#nC?H5y(ODEfU7sVCJ~wv$BS}OT zU?PYEY!X{y^nGb{$9t1I-_{}1`S`Lu=M=~nsEu2VP9O16Wx*n1@j^5}g_81@JQ`OK zf)L7DY9U-O->wrqiN$dJQNg*0t1`<v8)Afe;Y7&6ggoXU_S1&x1y4-UDA{V0ScJzT z>*?lxPu`IX&FgXq-%T!t$u{hMj<9l_s)GOJb#tw=Lgy-Bps!^#z;xj2K%8LSFySZS z12aACCkrKEMS!qHl3nzAC0tP_W=+M;M8vC^+KYmVJ*-%<ct<#>lp~D{fc3)lMB~n` zzAmyQQ9DQj06Ndkkb^`_@R#3Zq;mgrxZ8$Su)DS;UI+Jp#;rroEUWpq&774=Lo-x? zrlXChPUkxLYDUW+Xiik<k8+O<S*}pyN45=FFwxBD{iCoCuL<{xub!xkksk|?$+#EX zF&WT_*wsglPO1>5bmi^Mi!Qc6vzGX8$hNM(PrGJ+yvdLAxLL9DZ1o5T81{R+F@*#| zCrFkZ6B(6m`8QLi$`$Vzd~s4guYaL~BVIOqYU9K4yoCd3FuwUFpOB<CX>w~5kL?X3 zeZ_S8+?aTfDeH}(T^+x5Eb1P62Ko-G;sYuW4cqZ_KMkDh=l43mp)&@(ZhtfKaJsA; zD6}&QlKZox+R3ur2@~R->p0u9RvT1rU=dzWtRi~6m|v`Cr3D^6xQ`5cfhg}z5B$>v z;U6)8ob3NzXri_4w8r&~0j#-hWPFrWB-g4x|H0tLMlZ!>&zc~`La@vQtzvu}*~W(W z)U!PvPt6ewCh3`yhG8U=)BTaRx#%Co3yM2ZCHTHnl6`^0aEmv>@vb9kc)$})%omPl z{A{v6P8Myl`D_4(yR|y$7c{iLWs0L?OQU;76?KH@5FheFCU>x)zHIlgNWz4QYYKeQ zK3X&xN}#R5xq>y&!3aU*S$(5A>CJ@If^5MNSu$MuU;%5Lj-|v9a$7(~k0Z$|l<p*M zXQ*Tzto4j^>|l;;41h5wHzgGXAUSZNIwLo&`tP8C39sx18=@H*wgH2hqaFaufh$Sw z&yZU}HN{!4`wsO%sD`2HaBzGzQ*jE<R`5_{5)E(YJ(Wx_2(=0!94>x{nw|O!b7e&? zF8dADrO6LWTA}`uzdgS6H@^8~&LUI(V1m`M&0xM`l8smG`KbOlKG*4qQ8(K|<GLW4 zE!V>ao_2a<rF)1a{p%AvBm!f)zB5v-eCA}q2iRM+2@rQ%Z(Yrw&^dn6{!m+{`A&?* zC?<feSGP<ry{lh<BFV1st{r1SVA$YBYDl0%?qM89E8~DcF~O3+;SreF08D2hgme&+ zXiUwu@!&@|3YY*8$#N0<N||somqA0iF5aQoM|J5QQQXOERpQ1ZU|<8{t!nOY8rKUf zCH>k&edFSFY+0G^Gqu2nqp04bpF-^tSXyWqf_ufAP_9TfohS!&94+|@G_f)mD#BLz zz;(NQWL&vSWwx-PJUdUe7py}E6;do&WH)l4G@z>5{se49EP<Ot)f(f5oJqQhy!5s) zzI#y|W>75t+HOYBx>)jBQ68_)y+r92X*^su4|IKRSIVT*R(uh6-tik{j0xVw5EH`a zOx+6i<9v%bG@XElU?Y|#AgRQmT^rz1YW8|6deX0mJ8K)*E{}l?s;m^zE)DkUn#%Y^ z;A-v4Uf<NK)&)L=Vxpc4<h$?VTZYn^gscy6(h$#sYLXueJ%~>1Fb$gU6k%va!awXB zoU6C8v)*7XYUi&ietaG$#Ca~Aylm!qKDRkJIJ#C22N*r=9lWoX{wXVY2-yV8nkA@G zT3}{<jwy{?5tKod^&Xab&GO&TgKQuy1c-Z2>iJ8<lBc3CI=CTj78?74JwZRU6x~ z^DTDj-#W(XCI93_<3(sjUZo{>L?n&jwo^W{k0D0LSzqAcz1&X4rhWUeXaYQ<RHdqk zKv6uhR{BOBUuc~nAu54rGKh=0FW%?+&p=FEO60EAPk>=qICe2d;AtLeG27i7s(b!S zUqpB{8K|cU@|q=6Vs206OJh&e<Mo<cO4okC@~!RqC}%`a3pu{|s9+R{`_XIblVq>~ zfk%UJh`E@gK{t?DsbrpGzB^FR8G$k)_LR$Znw+A71;4K&lgeE9m#W(ALpluz8J%ss zj^SQFge@B|0<_m_PMCkcODs3@5#o}U)?2r)9|k54{ct~ZLNzHWZkA|qN0lQgrAJ&} z4CnXEpbK1?YmV6t*H)aUv4o>xTPl|aw@5CMc(y#pwVKsDSDUKYN~-GNH>Ux_{@1Fo zDuIRt-ZY#Aw3{{{msp7H3Fwr^E@iEryWaMKzQibT420{q)9*icBg<IxWLtD+MkTy( z5?S-Ygk%>Gl!`vi?{`K(O;Sv^yrMn9db;4@FPnxl-0y1-6Eq%+1b`0K^KAUZxWo8A z=`YuAhboDBUT5cS_TEiP2QH%x+ktTy+dX(_krFuyo<68yZfY`7gO(QeO<|y)VG)9} zZ}6rPIers3X02Bq)%Twz_$z<92t0?jX_ci--0#d-cVCzZMq2C$b{vB$Xks;nU6sNv z&QvB!2#jRHQka5uI~Oo}AJg@$ZlMN!TzC$a3XG30kGvuL6~*-4TrMAnJy#NUPOXsf z+TJgk<`lPo#hFtNhaxGv3~up-nVx<9QC#YE@alUi=jYI}Gj37UKnnE8mJ5%b;)@9o zYD%Da&x<5aV!%lL@-H_V5hiMwv7)d-^%(JYbZvNIhoNDw4-n4C1uLitIF&82B=gc| zKa&Ka=G+Lg!Lg~0&eUWcF@j3>ht=SZBGj}^naEa`&#VIaal#j|r^dC~4XiV31zAE? z$zamp6cj&pmo%<@Q`TpWbBMkw+!A1LuU6%Dy~N&kdf0Sk>xy?g#jF^R_;ECB>w3)u zuLExjX{KN;wK)bzTFsy82756EtCj+`x}ij577|W%hizi>Q{{6K-zXNqV|-oKd8g9; zG(Qu1ch;QUJ%V!pz`b~774YA4$?w4-RR7YaPoEi@Zi+vcKIZjEfXH?U{{mszLoEEK zg2~14e{Rq)v$OtdcHg0v?Kigv>GRTn*szx<4_PJ-h1!MDH>Fjpy>SAM(O|A$(Uct7 zN~W634L11W3EzNBCLC|wHrZzsb3K2w<2ajl3*XXa18aqg;GG4#(_8NMzz<-Pg;ZT! zJklKI07x+Ak<`gZnR#)9I-CCAtj&1S?|3C<H}z1M6CQ8_D`G9D7iVG!y)_Qrw%jX` zcU)11p*#YvvLOy<0|!%vY}np7T)70e@>PJRI0ao&Z8!!&LlcOrEiA0r@1qCtteC-P zN(XIdKGRWmeT1Nua=mgYlJjUeq(@2ttdP6o$xngqDB?|%t&RLKY2w()QiU^={}*HD z7$Zu<ZRxgcp0;i4v~AnAZS%C<ecHBd+qP|E`n#FA$bB>UDwRs5{#VwnU2Cn!e00OS zv=}n+H9CYV8G4|A9E5S=Lu-!y%?fcEL?>q7A)eYGu1Srtxm>KmGnS`AzAkPJb(M^` ziJY|@5?s^YML1iXmbHHbXxkeF&%Qd|*b;2VWv#wOp9=vi^?IrTB#xwh69KpzcIFt? zA}3;n5{G;h4ek)k>?r@nCCT_ciye3@oirN-9SvM{+H&mMbgaugap5V%_=CF%&lAf) zRsm3mmxs#ZIcy!(2<m(MJme4{vEBGX%H`}eA;W9NC1Gqm_j5M0yHiStAP(W#O*fhw zZ<(*K6C4+Qlx(rPs+4~KnQ&ma_9VP@S8t%xFI;BM1!Iqw&1&q=u=7x7jn+2IJ#j}J zyP9f)oziwzaznhJ)<DZU{d&7FiqT$;>OB@9ksm<4A2di1K9Za{A{<b#p0qIylECs+ z+sxc?@UPB@d^_b6FuryhA%82ngMGpY8tfPdJb7q^P>}Ya8o>!~;pfLksft5|X)o@K z2!+{(h^C*4^R<Y>(vusFLQ4<q(0cZ3wJrfY&(mses^=pshw?ze9{>+^<CQIcxo9)i z{0h&<<chL8|IAuQ2Xa;=iLfqV8wfcs6Q7kBTzkU0Jjrk$H~R2}Tt{1=E=wdl850)% z#ktndvZ&VqfC|j-m_5dz{En6RfzV>Yu>|8ZKTAA2#6*NWf`D+OlKXaPdwiz1n-jSs z4UC)R_6j-Vs$f7&H&_vL{ZcT~xJ(9d<We<S==n4cXXx%DagTh}>Nznf%7H_W1DX^@ zM;yBQmJ()u3CXHLBzvO2hmm8|kC9fSCV*lrae`_AUKF?d8@l|gI%mdddIBm^;Go&X z6C_nK@#2RWl!8D}R$WLhF1N5(_RzC7?${!&0Ex;z=66J*b!LqK?|q(KXYy^cjuNK0 zFx%#Q0}{i#cFft?@IMH)m?E--SvU4qZ*JV|Y#Gt(n1v|c=dkz$MioRYiR(xnj_EQi zqPA$YmHIy|$y#Rw)2^DVaXi-SIWWTsW#4|2s|);ks+?+Ce5Efc<I^Fb-O;2L9?%GZ zJR*S>Pn|L4j;AKb+k!EYYZqE-Qkll8x8+|b(O!5bH#-6aMUV4pCTLdlD0Xs+^D?C| zOXt+rN0ea9kmKjS#9=BjXm-hW3;L~+pmIi+`AX?N0_(Q_!bZoy^V(6qD@vOoBNv!O zVer>+M4g_u(qQ>+WX@1^5ZUv%qlw^^-+@gw;&?V|XbrkgKSn(?>A#27@%ziGb)jEt z_@LP|_-<`v(qdb@U-^54=g9$h-O(!&^W&(n^jH(04MHcGg5rH!`K<-#4zdw&%e_DS zCM&&$Zh8lcI&x@Mt!?x_eD^scSL~|p*gC#WmW6K$^60nCN*+i^p<`8(eV<R0B~Xoo zc2vJSfbjq1R;@mRcEadT-PrYxKLb6h-Q)>>+Sr#n8cU+gDAiHkviLJgsoE$rnl6s& zTkb01WO(N(<(}a`7L^V<wurTOTMj3Q;|(BV44T-HJx6|4Q7G$@c>a-hXs^9sT&>;w zhvn{zmr<Mxnl*o!pmC`Q(mP+T`t}J=N8XxPG|G+Va3`s$;yJA0vrd9#T%B+}`y%R4 z{(@d=zJfQh^xD-oJKM+JxxiCtICA%NbQXERji&aRjxd%;EWz_bK<Tr25Mg)1`lI>K zBaFd2j4wv9cGK_@7ZcI->{*_)d15nq2hwX%_yteoS3mhbXbBtpfBy;n{|P#9aM1s^ zsvE|CKj)w!X^S(A*mbWu!O;5P!qe7<jR5lkNCJq|Q{yZ~h%vzJfz;1PA*ZzS@$SX4 zQDh#8C^{GaWZYcTT=bT4<}r;%#X9i!00~_BOB;L)gm76v&6{L5<tzxc)P~A^gcP3= zHVOKL7?#Cwut)087-lj)d3qZHW>}u2m`tHHO<>u2I^4jSWjO!h2}(g2JC2p0LKDk~ z;!|UgCyVICZa3-L5)`>3Z+|sfvuJNRiEj&3mlhjTyyPZvV0GEH|8Sv3QzNroqV;5H z=2XoPFtV*BYGNx;4WgqHC@Nr*7i?-;Gg(=SpwqnUFEwk;{!WT_#oz8$4V9SW^YsdZ zuou|=0UbbQaiO|Y3|D^1t)#k+&O<GgByw%HfFc#^Sma2KyqS=wSVH)+05duLABcI? z#$Iu6Ha@4Onjo$v=ehjO3MK5pTxHfuzY^KGl))Y+1r`MsD{~Q~hJ$W#gaY6C{q_XP z`P>OGkz!^jaN}*^C}G9xIY2WQw@SE)Rkd#?6{Ry0IaANOP`ohUpgieei}vEv!0S)q z)xpMBN%{>c%f<ssjR=RqZ_~y}K|{*fy3tZ^o~Weo+aCo5nT<AFzz*3#watSa^bSW+ z!Q2<MB7iiUpsAo*7_2Q3P&YZCq%fy1UN&+{UeW=uqJR_2)hgZ`t!NJ+^z7)xeI5My z5Z@D^`|CFhB1hyNkD{DP*xJ@MDs2*B8`BN#zr%=W!N?&^q)ex?vv9kxbPVtU5`39( zzP@68_lOlsR@jH-^ia@kbvxg#F6yUQkB(E&m;38Y`*&Nhg+h95nt6tScO+s|Yo=jj zPgJYO$Zw9IID`Ekwz=7jT3g{Yak{$NGP|vp`^R^09#yA9`y-#`AMM)TBfq<BUi3dy zxwyO_i7)rwqTfeJ-!E>YJsn@4ENpCTygW7EH8s2Nx?4WX-A<+GGkR=PCH^j4*KE6i z5`;;<j(ook4w3|QbwJv|Swh>1_Hq7U+f(gn@|=d-?#ilaKJWJNz3pG!jT|p8)V5w9 zzJ~MV{W!cilw705xs5U%6bE@GI-w?Z)tBzo#)l3i2ldLa<@|PG|2VxHJoF=a@ArD$ zk4-^8KHT<o>dZn3A%TO6J*A((81rDnfN1>N=ZDA=*qc<KX18o8=|8dszwec4U8<m} z5jm-0q7ne!)RcPIR>6@2M~;3nEXZXA*(+2JLX~|Jkco5<?YoroIe&JPG8hZZ`Ud^& z75aKIz@Zox=6!A2_2{*fEB5PMXc!0P)ET{A95UQRf;E7zCM!OT1`PfW<eS{Vqjp|` zrorlH1q*mVaMnbcVA(5Ts_+gAM8$h5q8oSfg@K4bFnupq8cAsC*)Z{+_EJD|L2y(G zE~F@TWBCVU#fYv91vyVIDT&tdzm#}8L#}D<fBHc>qSl8q8RJHIk3gPpEez3_D4Tbb zpJ+`Opz0KBN<b4U-&50e;T2pMi6lt&yeD$xUN;!JbTe+g+16s&<{e_w)`~OCzYv%v z-|Hra6Jv_W;Uy1T6Az*%L&-~pJ{#jZqE{;mbm?86nLGJTw#G9J_yHSYF;B_xldg?u zUzV~`3+-w;5|$-$-@RUWO=Qr_$RLy?M|QbDk(c9KDbwV>;?AzOuOk;+r8VwE(;l*7 zhBe<SyKkqy#13Q<WpLUFug_vZoCCNBvSwtQMi)pFQ>3&RokurF98)H=8D0PDMoVV3 z5OEQIMW_{IRpd9z%ZG&gT>6&gZFg&z2bb=&VLK<EFVok{n=%)l?YIA%><W#uQjInn zV=_dwV`3QKA+UZ{PWP{4yfup5TF_~Fpzo)@83Pz{o<!`qv>n}r+=O?m=9PKpSdjX~ z%EAR>m7|#s*u|*2_e48NkSE41ZD_bnL1S+SQ|S~{id2$mq*XYo>IzzmN6eLZR<VA_ z!yS_^5N{~gi$v)MZ}>CBhDpZRYaI%fH`APzt?W|^X6`V-ND*@7>%F4iCQgwLH6p_e zYih>~L&oXy9kcAKa}blHdNHRD{GTKFcsw4u@>+zp^gKb11t`PfDZ+l%a}2cVCb84M zsZb|l{g^aMctK4Bwx)Pt;YKeAaub9ffWsyX@+TM^tn5j$k3{N=o-m+TAXkT9M)=pc z$)L;P!CA`e<s&UkN}B8~nr3j2r#7RG<&#ALBGxGXwmRmPbxcCA7lOz7q!Sq%&{9<A zk0u@ss@S+|(<oAqfkeb)tg?s$n$HV*ZE9dG2)tz&{}R~}%<uvsIRH+2HhfceRmT?1 zZ=95Kleurhh{ka?qOsJvM084#3@iD)!Y-u5!j6A1{HA#<8Z;yaz1fGX#nkcMd2@AA zJEft4GtOKjR$0Xq>pbfoJ`$@aUR=%ep^3Xw`*!=*c5tVOslT{$?JRc-k_snBpt}r} z7;-|>P4uXY5^jdXDR<j6;C~IQArUh_cF&0Rr>$uLEt-kO=)TV|8MzCDpRU3D20{r? zNe;3T{v@lnX|RcUzb(d5NMp9~Ncp&>0x?N6(xuO<gx9de@gbZ;DZZ1R1nDP~Lj*ig zE3dJKVH$2NL2=|Zb|QTe_^FMvSI`okrw~X)V1;#iO)jSbpV&;_%n3`g$D0ZnlX$BH z>Ar3<Uv^WdWhJ1@5*;mTmJ?uDjax{F3bi(sHRi?Xy4=yob>i^h4Mo(Z>N_5ln|&up zZ?3+EQhK8_M0~H2Qe;S_0vlR4=QPHq78M`GB_$paHN~ax6J~CMoWk3=%|hQkzEK<j zb0o%<hKN>jVI=c4>6zA?ZAWIpa>97*J+Wu_m_?4^v*Y`Fbx^7_1jY4ti0<FU30XGK z_rvk5*z9mrPghcvhXhlDjbeqle>zLYYiWnuaLyen{_{q*xng><LUKym;VRxSCA0lt zgXEZ&!*#UvUyr`Qg($QgPU9t0v<?acn+$g*AjO$HT{Z25zFZj>WKVk`x@nb5iSfEI zINg{s6sV1yHOy#~WHC5DS-QI^`G8ObFNDZ9As<ff+LU~oEt~mKmwAs@pdU^hieB{c z-|%YWR$jk(9B#g0O^gZ);G6c-DJj?h^^|@UE-===e2}jx)Mwe*^sG{~XlC*<9&FO* z-0dJfj8C)I;@zqE@Xah+fBASh?@Nwx7IXYDa>A@_3Kw5rFrlp+69;DiDt=B7sg_54 z!${7Ju#6Ts?4_tRiW$!w>+6_98bzBc`J<R+5Y3(KZ~*A%5Q&^*Dz^@O4=MS2C4S&5 zH?|JVWCgo{CdbDIvS6gHDM>ONg=T|7j^PY6_Rc=F(U2vVLoZ$K1nq>4mJhcM=~ON9 z4Zb<NeDx0#B?kk`KWrzMS=s*GWbFUwMTnb8KNKz~alzgxa>-!5WL&4AZwUUo;zT`= z%&lpI4fFo5UW6ng4)bPxc*_sH@X!N}?N+Y>A^q#Q{;m0`ef#5HKXKVSHHf3=W1XNs zD1DIz5g@liOxKmNK`>jfIi4_YYUFx(i12fTP;JcdUkP4qnxz$D5zNyMGcvv#ubqN= z#7`qSg^6NwGZ|H!w%dlbVBXU_GZ>QB`IxPDzo!u3F*oQs<&T%)T<96{w6@PAAvrAo zX(0MY&JYkI$e{vhdokX(rx&=Q%!>#VPjepL`bSHi?>;K{IB=gsJ8$XwM>DooPZLJX zHn3y1^<x^z;KA}N!W6)g^B6&7dfl%Ngng|-m+itac5858D8nITPL+RBDNqct_8@FH z@~NgKosb|;35PN~6_cMhm=pxGI9S-Yx!#r~k3W^JD582`4~F@v!L+>hUW)T4otIEy z2`=1|P$Fc)dLZ*c)*_=8ol3>QYsA7`9HXw78*5iN7odD~SI8>0V#LJ$iC?C)*~(Jd zeGEuZo|_OxE*mspzD_01#^x!LlXkJX(^tNJ20vSB)iSrD__Q@{<={V^Yn8N0^VZ!H zjmt@4;Vlt|;G3%BbyEh<$N3l^&VyEw1anwqq=?B6NBpxG!t~>QM9o5HTRe(Zr1-u# zy=wzI52_4GWtVnOus7)^QWxtHmoxrf3a3d06_rH#yi!X2snR}aPfbC~@gCpF3Vg}z zAskTdZiahiI06oqsM%A2Jj-2NIufusGR?N}#+;UpM`k!IH-QQ*`lICc@utG*mrC<X zMCHe_=VX<YI#GY=_tta=N@`*(m;wDCp%Hr9s9JNtgWmCg#=MP*`=;v;8!xHQ#<o&@ z_RGy}qD@^IpfFtS>kTa5=O=WKxj-;5<Suki`IK{W$AfM{%T~+-H>R6lE$25)3?-({ z(lL>9DykG7eQvlW@;n+Ozn=>G2<uaO93&wkIGX>~@B)I|@JZ7$v+pa4eR@?@Pta8@ z%j6}s2(O$l^$};Z+C#HlFgchl5E=@Dc{}&nKfHTTRN@Yf<LGGgYE~+R0$c_n5D2)B z`@GKZauYu(OmZ+|uT2Fa*s0uGgjU`!T)^PGbI$6Y<PfVTw{Jl|d)=Kqu3|bg>UzhS zT`U14+YcD3c>3*J!Xr#2rF70hQ}yJ~|4P+0OsJj(S$2J%CCtLE87O4S`=VUcQUA%B z%UD}aYZb51LvmUx2(%T4qOBz=Ew<X@r=hhQxwD(v4zfzS5NX>qZF)K=WB@<v{g(b* zwlrmKR{d?vm1m7j5Fh;u5!tt0v$|0+Zuj@(l_kMFU(sNn%lwQEokIUJhGr0c8i}yM z^^ysLe-)>Q_^0XVVV?_YALL~cBX1vbvB@k>CS5PkEnT!oAoWA-rEFHb<YX?ao$nDf zuMBi~1H;S_!BCQfZTQ%j{MA_(&1R(oi&hntXj6n&;}}x|`vwk7j=oQ!OF{P-o6MyY zs(9PRT9`M3U>}y?Kr{>{4;OA!rO+0`ehlU|5>p;_8pGFRN2~vdu2ZxB#_T~xUU)|q zX_9u(#_WE~uWvFBgebyak@0wldkRV~y*OM$0_5H!Pg0XKh;Xsm>(i3(9BPGOjs9Wv z3Q9Cqk&`wWErFAilLY{v?+HAgZ)~-N3=E~z@Y=s%#7+k3BeAZDJER9^kMHFsG?YXk z6m=H8E?`RC0R#wRh>e}EhXDPTg@@NflE+d+=WB=)NN|mVjqY|fHOQ9Yi5LYKNkIRs zSugOZL15;6yC9Js>i-bg!3hu;K1d)DMUfn;fEAhSnR!r#A?k1VB&ORAYj$i4FVGy4 zbI`%stt`x5lqaYQt#c&ZKo&n(@Fd4<Ipk3PK(Oq@g@)ZDREa@^zLkzWK>l?&rasa; zZu^Kbl<BIXYm`M8OO6AW=>|AE%5eBcG5GI23jf#R&hr0S68<eOVXwp5kC*VB$|=!w z&-mxpu9sCtoQw_4flyiuFc7z)l|^L3>w6WAl>hD=w1&#G?K96Mq1a>-%=<n^A8*0^ zJ$JfPk};ZtAxeg=T8Lh>zB+9$1gma6sI0&U`=7K!TD0`;_BGdpsues+QS*Zu=;nC` zF}a6LYXkp{#ws0o3CPF*=!D_%SIGzFSRdhlF(Tw+hoyid3eC&>L8R66E1eS6B+VyJ z{wwt|)DtCnty=X5nm#H40WlZRFhsu;2|u4bA$-DXuibIfMrs<q<VMxIpPmtwU`x}$ zzG9uL`ulo$y3H^C=*~p!bD=7M@Jvpeh)ug7_zC4musW^Sm-<$+Gsyxa{0WGHyS;%B zYO*M1LH8i7al{7l^RkM~J2>_9Kg&c{yKst7X48yly@mcK+-wP@9ZK2c)&k^{NNEAH ztX|?(v+JfKpHsm*^ZO~h2ws`lysy6`CnL|;PeR!lm=&r+{qCiEMwl~g3$K4KSOMiZ zYb)Y<uPzYiHju3e&O0A!N*OKkne=uiuV-1>Qs%HfS7E64)p7+21F$90H34q|8#@j% z0E|~PhgOIO<*L&6`dN2_SUXlM+Z}Fo!p`*Pe++-bmRs_hkaniNC<QW@cm=FA2D_fu zqy*yP5%^dc1b<8qH|c_1ovp)t1Em}S|Kn)E_)nt++rMum{DBtP{=jH|N;mYj$??~& zI>(2ZRgnuSvCGLL1|ZDLtr7o-B^8{#ZM#0<lPE-4i#N@phik!^njC+)gyo+@h+d2E zNsIDz8FSA4<OGH1%f<8y3Zs;M{~?}r`sE!H-nSol8XDHiG(^&IlDusq$&@WuxW7DT zRnO?2wWR(>b8a@{^yC^5Py**qa^aGg;;%`S{AqOd^!|EyL^~-br+so&#Q%U6d0=M6 z`rz&6l8Pv;NWL$VSAr!b=Qbedbk;K*+G`Y1DP}lGiD_|6VkHM+LB)i1X$nM>?^gzJ zQU4GDg(4J#1jf1C09XVdOHS2WHpSZNv43OEMFG+Q^5*(*nM~MyOs7U*z;xOg{tM`W zN0oCG0)Pl5PT6*+cx_QE&^B@O^~9}RnQ|muo}#IRu5M#ZYZo<yJmmgCIeAaW-3cRb ze~yR8m-iVB0TqE$8|`iC0JKXQ`*4&DUJNcg@RvXmLm|~2+n4dNXrkSI?c>=?h$4VH z4I!Ey9#EGqz*x7-=a7!_I4fqK)kI3@;&My5ws@OZ3;;SV_ZKmE1p#L^LX^GMs#gx6 zYnh=Pd%muvFO#J7DhL?JAeW+SeG=f^;u^A7Z=Z6a>J&f+}T2T@R}d=sH8eaHY8= zqUL%UV^g*`c_Ct0k`Xe0+!!SM0Qy?{Sb}Ub!3U1<6m=U~uoipJKf+jj=)e{1eHzV~ z9fh=<K9{eKeFZ{4Y@pv93pE4XkVSzYec{iQoq7+9(3YDKJEIz0On@HJ81g$<-&RSJ zV|k4AggL6bV5FI+FU39VxQaO2E8ynlSbxo_c*{Q)VG|W_iqGvbk_Sn1zIW6=Sx9k) z2Z#953k7OM`QPVsO_$wkjkoDL>$t>C8|#VHOpzGZS98g&0m|L}9691mltDUUs#-FQ z&lT!^2Bf8TeIHJ~J{;1S>VAJb+)Y%ynDQ8|x_&-g2$qL_cC)tLzL!sK&}~vnZN;$} zMLKn|wleKOch8-)l)gbpTzwoaX&l2`+?o8DMB^umXWyP}e30Z)DMkV>Utb$j^0J8{ zbI5okFp*Sq$F*23cFm8Iw$9?kcC@rRzq5TBUf|1cvXS^#G|b~mb7mKMsG_F5vo?I4 zSQdMf_HSmEK)5?N6uWhnYh+DAl4Ey1vvWEPmG8d3;5NCnuw`XQJHeM9r-`~mqMQRW zC4vG`_@a0XKSVgd1~(Kn0+Qe?9|S56g%1MiMTD=8oZSoUlQ$%F$qt!65CO>CZ*Bte znst(5eV{F)I693sYzkK0eh)M9Cx>D|oD@sk34YF8|3?Afd^BdUD}G?ZO&dN^dvrFj ztJ1DeoSt)!^=-T$oQ8W@bdC;;J(^s)`Rf|q`>b(P1t#J!J%6*l^yOuqHCi$GFbfBG zF~I%b;(yCDDRM9?%s|7%fK+C=)PhMll`f4m8<9JgeUKYtmFXST2IJxNQ6~h;B_BR3 z;ebv?+i_23UD`+W-tTA-kj&SCtkYl7AXL}UAlP6p4Ow|SoaPN7Ma3NyrVZ17$B&Ah zx=RV37Kh>n$0qWvJaFFSG@s*k{k%p%(4z<DTOc}G^Yb0zNJ8O<pd_NCoAD=1_i(Pi zihF9fTv5%CtB!j=>t-KMeN37&mw>AU7y_-P>p$8EepyY5hK}|gt->R}6sKo_#H32a zEqy@tBJM9_9p-@IUM}nu3yFH^71a5Y&$~t`4QUNGTRI*K1)KE<zs!V3xSa?I^Pce^ z@`lCZu*&ZGNt0vukVlQv%lbpJQ5kAA)HAlP<W#JnSCsM~A!-dO^0oVcPx9e>R<n-t zYrTBCt1QM{XH;mo5u_A#)sndzhC*fUjVU82HpQ!uR<ah>*5qL_(2q6+58c^AeYNM` zDyvt35riSD2HEGT7f-qwk`*mS60-3i#IphnsuO1LI9a%H-sGYLh}<T4pbkDs_U8k@ zTihd$2l@@$?}1}0i+<ei#RR(6UQ6uY@1EF8@YQmY7s{^4hJ_5Jl@#an*h-E-_Pfqr zqr|WI?bz?`3Do)g@y&@%BO%~5@jC05+&;&E@*;f$l9-{*ZG&La076W164&naLj ze9kIJlRy9n|6Uis;ug7O9nTt0wem<-y0uaaaUpp2M5WeVd$#4VHa=Suka@>1r|LdS z>nB)MMr_~frW~1R*Xx}=NKr<}K63PBV5>*sRN5)Usx-=6pQ=;WZj<NRKv!+A3&_px zO48L#HJ0o5u7L2|v^I4(sX(Ayw|%`^GEKF0!N&`@(L6C@Q}4v+aZ?8Fo0mhLKa$I) z)%U$$*Qxy6{bHzXE7p4AvtirbBFTedoEnPt13~Am+tx0$!k4reJMs*&@jmBk=fbe_ zw6+AYDy!b}Ef~+e`KK|B@gK%C2KFEJ`+pozbRy<fPR0)SbRt&zPR2sUhPFn=P`tcQ zj!q87`qofxYn>XJt{FcTyy@y4#2n=EHc4)m`SB)Gx=qr}6lPQSM%2)H))v2nqwQ-5 zKronahSRPA#$*v9?|j=X#NMs3{;l_V-Kr^_PQ$hN9}cg(YIAm<nB-}xAE9_hd7<m2 zqtJ<!Ow!Y26vX$|fcq0AG~0Tk|L}^a>(#QW{4Ib+&g5m3-gW`0P7jd?GbyjUk&ENw z?ZxHd>N6A2ykYFZym>V9;g*4;i+5lr$;Z=de;DYRC%K0WH!TKIrhw<AcJ`-p$T-Ol z2FQ9X)<U4nQ~(K$I7oB081v94H3T~$!%5^PVwSB;>dAvr1N&wU{u4!9hGUgN2r9fm zDTWA4kzMiI0s-AAVv?^AnH#czFcxD1YXaF3+;o_T(*O1m35K7+xnlSs0aeLn<*@eu z2MOr%RWQ_JSD@vmj``dek-*lnJ0f(QIN~xJ8Uh;vX6iGNJ|^LA+1B{u<Myz5duI1H z2&kxx+7Ll%CV$JQx!D|mxNz}baUdbc6$6+))%MMekVwqTGT%$Qdz8##jv08<dH;{8 z2f`Qgq1tVis$lcm!=)hu1)owHYtImxcy{=F_6SwwWAbvdBE)I3(9x4i4j5$mUQ{jy zsVCN&Jwq#;Q8R@=W721wX!iJej-M@t`mdu|AeZny8<NqrMzp`;R8sn;d`7<0Embnq zA77}@R?YPZNMTB1{D}r^%EJ-Z_?mDM1p#foS<Djili58cLMpiW9ts-$Iso1~L2IWB zdO~F~%kmvD29EQFQB>>;&cpY=6mj%%7m_zfHycX29eIzU09B&g9HBBaapNMn6hj;l zLuRen{B*lp?V>p)UGm#-(wtN0g&ny7ILimNGR08jJRB$!U@FWR!$0)|_3IZS4;Udm zCm^wt#$__QQ$95Azq?zlJ{aL<L6GCm#EFfq<*=d%OYQF@L7>cPh|8x*w+rpL<iO$Z zK~)S9Zn5-rBARjHq3Oq_8f0~&SKNsZgU>7GVQ)D0;wH!41uWFu(oxDiFybNOik$rL z`A}on`{=!i#cBXz<OBOJ0d>`of_JNz&y5g|T;!!V`m!BKyuyS;zE6n^ff_L41X;Tv z2q;8f_oenDs5EsT?IKk3d$|8}9+mpxayIy+T`060P<@Z~fYdx{v6x_}^<<jw=!_CT zZ3x)O$9?`}1gbIW2c}+UQsAvzmnLZgm8wzp;u>-0!ENLW+X-AGY{H_oSNm&~avsHV z<LSGUcHJ|u3}>l3oK}hLb4t}K`pxF08L;bXDWQ+tgA~RYXJ*p^Gc!3_0t69m#M1%= z2}0EADIED5F(BZIav}cKk=ZZw@}%<1IOVhXH++<^T$6qP)(G5OOWYVdA8L{$C9Ln7 ztpab7W#Q#Lt~Fl8KRVF2N9pbp>>*JWhWj}p>}kjVaU+EFFRgO{l)aVdjI;Hy^xNee z3Gr=6(^<5*+COxTiQ{c4nYw1A!)#cha2Tgl*u5-{4Lscl1dJresKEsH&~M}~yFsv} z?s#bEPoxDnvDVTL)eNQw@Zo=n*A#yMUBO+#<NKsze}*-0l;CS!%r&3|x;HS$$yqg# zgb5RJ-!xHsxxRa}CekP$IE@|GBGP+Ih9UxxLS(4iJAi@W@AJvaIKYsUlF|{7#UgzO zs^YoocT~jt1gE2Z94537zc5RWG3rO$EnMz>$%R0TTt)Dx7uU;V{VLgaI`&N9qQZ|2 zp@Yhe>T!sIOV-AnP_HCucHZWF6ay}xch}(w;Dt5oB(sktF|+@gz#Yg0?P!6rFrOK9 zMf6zE4g&M16w}P@swS*8DKxzP)pymStmHxtUF4=7^(GIwU^I_8W7rT|oV{2ehdH-n zBrWlm6QQ?Z9cJVR!Tn75%7G%2QfjrOeFGWyL|TOgoV0cwTFWj<cZHxwFQCr6TBl^d zZexYnPXI)2Mns8`SUFG@44=n(%ts7cacQ{Pk^i}FR%s7;j*uA?rDA+H@^RZ$9egGf zB1m);X!)h1xu%Ua)GtxpgjEzqwCBW|JqiF3-`fGTuDQ4IB|JR{O?A*Io^%&CN)ebv zI9c_DXZn()gsw!uNiq<GhYsV4#++<XGDv2roB7rFkXku#OaNKPp8ge8uv!5@uMLf) zUB49IMP9{~y17Nw{pK@zS&@$Bq?V3GM}^F8Mji@@|2%83ki@wtD3WHKJRqDx2Ry;M zg-$eri6<rMUAO6QWWZbDinm+%sj07t`dLj<?t=7O``2o2{d9i=bGvjM^_z*~c$@j_ zvYE3f^xvh4!pUezDypmfs;dd@W23Cl^1clYZdf3^_858l3n=qh1WPJS<KpD%nfmnK zD7jHDra@=l<ir6N;~Bvb{0d_d<pPy>OQEeRF`~;p2`ExuEtEEr(i@LAe7%kf?f)dQ z%nbjq80Yw54gH%UJE<Z4ucDjIcU8M|Xb#1{FQjft)+F}lYgLsVMF~dSFtEe_>bX&n zc0BRD4gjEt&(o50*w7*Np>{=o_j^W5ta%>o-^$3xD;DMJFd0)MkB@hs_oN#T6F&_` z6pnYB=eo|4{f*_7`gOq2GTagbUOrwup9Uwwtn?+GU2()owa+-oWaz=1_UqGLs0Ycj zz`hhkA<=X6<75;3Vzak1hx-PD;#$&}<GDpo%nodr>H6(tndo9}APmaUtm~|x-@kx_ zm?lX2nlX1HHsw|;#RC&z4_(=$al97>R8)v3JNI|uEopBubU+P?&Im<c+#wNfPkJuI zTmx;{tk@bB>|Yp)p`H`~m=fF=IE<%nn39{nGZ`$T0r*pkUAN|*PzZ>G;=*h`R)4D) z!%R=JcsgT_Bh#{(-IdYN-P6<3p?^p<1MJVS`_$u`o3S=?ncprhA*|qp<ivHu^sK!H zAVnG6Fw$5Am~;Iz#7MOWGe$5))pd(MnF}7EeINf&eJgNUJgwJZvf-zm!Z{JwLSVv= z%bknN4N~@<073aDVAD(BP%m^m*#pE<LLnnFDzHR;M6Vq^A^IU7eKT5r4@iTv!Osp2 z7`x;F4|O_-lH8o6<+jWsN7&d2^ra&nw3UU%;Wpv`!$J#-OSiglToYxo`I@H68b+0E zu5N24N;xsCp%CLArH<pOiFDhqvvSyafGCd`BbCR1v%jiA_eZ2=XTpKmnO{56PM@5U z^2NAA>%$^x+<gYF5`i%S4n&FGh^nKdfx_cV+{*YS0-I0l4NMHAY<YzbTPfY51`**a zy3$B7tW;NoBE|2%%0E9;$l@IcW*TW%N-=rz%qAW0nEB~UM?FVf%1Z16(#L2PLL~8w zOfMh+qGS&PCqaZTe4;KR4gXEJCcf|l!#5Igc|%uj-X3d!EZO&`?}MJ2fmxiJ6Gn1E zPDoEo?KeF~50<9i2Hg{V+~taWw8Ed{QehiI=Vq1dp0zEw^(hY9J}}xAcCm{nXzCL- z1TH{nrrkU$mjXH$rN%+HDGwy$MB1IP@3xtzFV?@%pljmC#85=9N|pJki$zpw)fQ^! z#8J)m>giEzS$`lh!&4GCVs6@~Wfj>-5M#g&qeW%%-8PSVlZvMIGk%-?qIWJ~HXp!v zE`~SPx4v{esD|?HPG7Z5>gjE4Zy=w)n5U%qbrBug_JM?OVVSjv_WVqms?#P`1Lv$& zk-TPwL50d(Mj51=b~vsQ;LCz3`t`|})4rnY*Rl4;U>TJijr@U7C%xUiRMXPuHqLZS z-0`Yl1#u{=QYifdecsTYflvx(U{@=6hL$%H=ROQy{<%$dVgIuazRr#8WBlxPDu2aq z&J6;U14aU0$ZQsFK!Ly{0u#s*afzgf2H^_b1*2bPMU*YoGI<qjY|7m_4~Ujs8GN+z z*5CXA_8^%F5No{6LGs;!%3afDx1u<aO~i5%sa6UcO!JY|ifUYuH97aoqI{>UD$W4M z+TPo|gjfbB;&a-A9HAE|{E^jVw*FFr>*UzOvrRZ!lo|weu&f;NyJ+m2bZk~8&uS&g zmE@Ha!XCP;kyX^EPNT}$o<D&vJ;KZRu2Pby@rjrwi@dpXZp2ojycPKb=>Y{ntJTkb z@eK=Hy$%G^28Z>s?<afBcqEu|%>b=^1GrACyBJEVk}}1XZBgEGE<lCHf2JV+O_<U9 zqAuiB{^r7-1MN8(#t~_^T-dJ4J5b0Ik+Sxyhc$E0nUi*4G`Q2#hoNyRX4us9Y3||j zw6T-bhbK#GHPUvNt@zmX;`VUy;OJqm`MiERYjt(e$m{NXrbK4icF44tZ2$CNK;f^m zO$;ep!o4{^e)AV}2qWEo8czikbg1s!YQ=W|!KgkZ$zcK)2I=#)9!9Jj`KdtNFoqep zPc~YJeSjFTi-rDE6kmyN)(hQw{{?T9G;=TL@T|UBdS}WGco!L)cF=91--Wm;D)lor z(6J9BO#iA(u6hIy2p#a&NQPuppt*D1)?5Snqrpxs@$?w`BsHGukU7JRjKj5goufNz zF=R{6UQG%{#oXY{O%+sIQCN?bdb2Xh8`>(f^2DR!8bbQ1NCaL)u*{rW$ghiY$me|$ z9PQJ0{EDaI@GEoAVoZRoAdRK_Jyf|XE70}fKSAu<B(GlCrYF1Y)*q7eP{K-Fdr0Dk z+*t$0R!pt5Ddh!0mG&tC%@0`odw-z_D4>W>Mvi$3^X@C2ZHR+{y5=4M#ZPUpm6CIC zxK)$%S>XSMw>uZM!HxiAJk^&yfGCvsl6^E$Y``J(-NX)jmc^cVFvR>mJA0JOq?QiN z;PV{R-8_B9n3v+?UD>}qID2|?aPWd6!p+&t{++>)t)sR18{WZ_2Ul0xbE=%T+XJA2 zZg`kaw#b>QgNb<h&;G$j!Sx#V{j+bp+@k*H^|(pBm%=XCHlA{OGVYg<{P(aR;ZI@r zr6q_c&_T~f7agu;*KC?jAKD-b_2g3io2Td_>(x0~e_0LGJH;2U?!ogvDL6X^+kaE= z|F2n+@xRQHOl<%5XY``RdJM`aqIXX9i0FGE=YBk58j^;&D`FFg=I?gy6%hz!Rb|iF zJ{T-8%g<+C`FYTZIeO5<Aw$U7*;V;8GNOG4LQ4x4364dJ%n=QUcp+*KX%b5ak~BvM z3>Bze<U=jNvhWd}f@Cq~Uk{ljahU>yQX2b^+_H@WziGpn1|_P(ONXd+kR;P`8V7<6 zl%>X04ArZ{%f-ZK#HSck9FZLQuu^q|3{A)-M;ROke@z&6or#wXd8vt6WcdzKOB+<^ zCm%5^k((d6M-k{V5dxG7d64!2m4YZd7G(Ad;lxiFf|U-Y>Y@EfmA$1#i>ZxQBDoPz zN7V!clGea5gw<58_W~nVBZ7gZfWZ@;aS)fIB2cFU3KY0glF0ns4~P=`$@-z%CzVP^ zHcm_+&p4MF%Z{l!gk?0E$SubrhL%hnUvYpjA1ATWx)VNU5#`R9aj8n56MRZcoU#HA zx4<3q8_KJou2%(=DHM7~ReGr;h)e&-<X%lY`=0wKP6Fpw2grKrGjurdl3!ZpSqHrM z6!&#L>9FAnxYRKg?P?7s9ZL7!%?5i#Z|We8)nI0a_z6Q%F-|tduoydI1)#A7Lr8x) zH3OQY18ld&i?Z9V{s%xLLlz+Xp*@C1cF-5F3xpHQ?zIjLoMuTO;lMO*9L3*dwXq(T zCor0WShb*0gJ^cYZj8ifj#uF^6w-!q6f#^P!<m=-#tl{NkJReS-LwVc8jxoCIx|wd zo_2ayuSR`!WX+#HUtb3oSFetn-^*X$b#*hpJ(}Kk_Z%{5b4(8WKCGUPH+5b3cne?0 zSFeiATO?$K8;RWf6i<OjGg~v@V=Dvu1+U*9b_CWwGhKY!+#LS6z|Z4tJyh#-XJ#+! zW<PI%RVrScchRL4xnQ)|=EE8C!Wiq0<ITHnXYFn`1C!L!6817V|B+kZg7w{tY25%* zG{4)B1xH<jPa6tA=DSFO`y@Bq|8${mJ%AJK>=Cj#MX_l@Dn1`rJ)ws!yD(;t65%nu z{1XB9s<*x?M0qK+ou=66JgB;U4;PDjY{fAL&-<sZr6(7wwAe-Hku_J$yTg>RKD_+W zcpHv~2oNseqIlPC<!<MPhz(b4cODm_($~@MsM`lY(M2^9USa>`uh}luJoFAC<k{QH zR;eLD>ug&>ZTQql)N&T`v@ln@;L6_%&MEp^3-SSuMx!ONOwDfRM%GdrxVz?M!h=fc zZ^yMaj+i9wUE*`$vKM|3GL-HX0%?B?mh%TzaZg8O@*?~7mH;4qsyYaFvmSNf{ZTXE zq#$3J%ptwswSVO+bBuMvELhOr#Ax8H-Z8XX#9N@bCZrQw4U``KqF#bRXd4L)E?{43 z*g_rKXySCGCvZHPWyp>Y#9OV9zsCgU5M8Y#a(0L>Mgl^U(qSCG`A`#L4wllL0Ce%j z{FVk_gG;1G-Z=@z9kckehG6ZHWUz!g>0Qmz*)Jk(@*rHJ*Ud9kQ*1-a|K|Kq26Mi6 zvUGWTzuNG8vTk0-7YsXLKauRHcW`F^;u{}KPUm^r3jgA_7BCQduFNT7<<tP?R63nx zz+cyt$0lOvrO^bQF^g$&OxB!q1M#+=g4G8U0gM7gOHYtNJjw}v-16z9monpN9U1UE zb+;1n{5$)^ZG9R%(JBZib4xL+sdg!sWZH8gAPa;`tJB%W-d!}{iLp*9m?=hUot|la z63Thkvo-Vs5a)57<!6#tLjcfMZ{PyNp*jA%6+=7iF+(y1B-<MZ=n;7z#2=Ko{4#P{ zuyU$gfcb@m&b5<j<^$|<?>WGd0TfG8);N!4QjwLr4Zp#$Ewedm$i6n?(Bm6uuGoO7 zV|@TN#(W#fj#pG{_ZqP1E79Kly`Mutjq<F1VzUQ!@^LwyGR<2G^9^Gx_(~D>;5;S< zZf{&G(aJte?3q<(GQd!&RJ1W@JV|K``bb4ZAQ|jPQLQvIU{=?p6jSg=AC%x6>b$KK zb5liY-AhNEpK4DhDu|Pcs##1-hb1McBo==2C)j82!}9)4<ixU9wH(W{_d@FMLHetk zW;<@FaZ%W@E7|`rX4~N-Id&UCb?owujk?9t%bnqan*d_|>b76h{MqR3l9Hz#b2;|i zSK724&mS7~L3%@ZQZxL<+wu0vA$3bjcV^PiH)9C>6CS<0kYi6$(Dmp(*q*KUX84nY zRJ_rob15fb2)lxB+Z(Ln_3WNJQMg9<Mz|z$CI;wGI9GT_-L1)*;4!nkrAHg8^f-ch z@VPopBXBm~l@DzWK!*?T!B<0!hBGE?+>n69u8h)a8>*DUAu7o=*s06F%;_4cl)!#a z`B^~>*wwnjnBemXEGC~FD-}28nZLj0P$e+J@mFZT$S!bnnicV6dTWEXP1-w+Cwy8p z7j#)<zkKO{HKQ1>rYUU>{OhGYxd#(*E@&`eDJzw0^zVgsH_3(`1TTl%_K@C?F6AxF zK!NOtrbqfb%HfRWMWdULyIQAq#T41w80<0Vq?!|qv$4|sU!+@yUOF6WEee6Ve`%^Z zY%GNDBSv&M8Y5h8m+Utel-j%^aC0&>8k|j<Y%CC+YPw|Ds)8p~(gR122fF?;s<I=# zfD=5kYMQs(8IMu9hFyu76((fors?LrQ%JmVA+^Q3d}WUfjobcti%x9F$}RX(PJ9UQ zKWlrqxkP)LA=Ui>*a%F#u7`8b1*Nl*ECjJu5Cn><O!#a{whiJ@<M*emzdYy}Cb$4F zGzy&elmNC$%|krR4+Xx5FgFfy*}}qKp-}T{x4n3xfocl}Y$2UoIDL??g!94am)}ZE zs8EX5+c9R{p0??e)vr<*&lu9bI*;Z0$|XCG&2|&TEl~`6Hd9+B4ffV_(YDw=?64_r z6a#;s3w{dq?bAuRNuT5g4L?eHRr_f1VvMD!P@2w|X_jjB{MB+Vbm*|sh6WA|b8AW( z%grjIO5&)3DyUK<4WeQB=DXo3jP;gXQ+?eEH5PeMGcjs~h(9D0OOC`>rwtfjqY)lX zkrG($kdK%{@%<8Yo&s;~HuB(srF%<R?>5%3OPgSD`-DTJpXD$2C8#*m-b;@5dgwig zL>zIXN_}0kLSci;af5UjV0OJ*+@D5VRU$ooAF=Q*YCA4Un%H)}`v$dt*24VXYZngs zpF%}?d|LwxC~ofm9Lj#ulK*zSz@^5eV+JeE*Hw2wyEme16QzILK&bZ(8kciQ(N7QO z<J>RNns~cL0^kkS=Jju0$Qx)7dYO$47wsz~LjoU<?Bi!b0#I`{tT`FaZuU-e!vss5 zwZ!yv$4Ul}AChuCtXS>QM581>KI@}@FFOKfQx7^~(P-p>%!_}sU-N60eGS6vqLS7* z1|VYOOo}w=Q54XG)Mvtd8JmNL?^6v9mbn`f%5faF(0xkhxU5*lxMwvph;)XfZhf|7 zv>Itc7)3SuTE(*`JnGFXEv#Y6PuNYPXox(-Y;r$eUkx+j(Qxgsr;hx^oR*i+C@8O` zv}TYEbi{l~8qtwgD{5nPd~~H0OWxJK7112n>i6%8eb`SA_V>%(5tv+C@^}4x4~PSD z1euVjnlzs8?2G!p>npMKIUlsl)QbY%nPn>`SR!%itjh8XJt&M*4gTT;ecYnQCqaSl zTny;T;^sk*rX&qZtT4z5>o%sTM=tjhVsmPEBOn^D=GgjRUa|u=fAp$mq(Qn)LO_kS zl7`$EhJ@-#Xo-kI!y#L(1VD*{CPMTngD{A#?o+Wmli_*FaGm?*6nbZNIx?zbD}y|b zU)%h9OdmxXp!*>Xk{@w{T4x}ECfT1r^Q{G=%sH?`|4#K-P#Dm`=G~kCQv6oVR2_ec zvV`P^(K;L}sDk=fG)fY*66?ZPL!*hex$|Il45_Buc%I)C);9RA_#F(iU>h4(`S;X} z)j@-LmnT`omp%XV^=2X~Q@6u;<J5?igU?x%tT-PnUxY2cEFnrlF@MIyp({y;XeC6+ zWSW!`lG5XEmJW)>hT1dc0j|Up9zx*nK-4od@s=a{U)fnK2|FB+a1$a(C05OZvxDpP z>KWQ|+lnjOlN+ZQ&sQ1u_3$(%6(9T8w4ht~Ga^Yqd^*8jhVkKz#R|iODr2N+yqBn* z4QTxmo*nkx=N{%*;HqVF6$-m;EW3K6O8rl)CDa8zn+}bc?NwHTXU$SpeuqD_5Vz^E zzsaTX2MjEAQ)v4I`IWl{h_5=7WpD-?V=LhL7FafsfeUgZp&w`Bl>rZ328a)j{?QC^ zU<}r5W=XJ9dCC`&p+`pjHu}^GR<P`mnau79n&FEDsHKa~%UIQ@Dx4F2;*`axzP>G0 z!6~<EH4rB^cJ<3L!W!Kz<Q3%8ECF6piKs5)mLWd04&t{re>-rOXM-C^5<Hh#m9Z2s z$kd?BE!|yl^v^01`|8tboDuXTvL#aEP4hOcvjJqotMkb-0K)>@!ABU?sY*<z@nk-y zF!9GVfm!Vmi8~_l2J@9Nh_9VUJ3CiOzH&x-$%My3>?gI}e9?HN*TqZXjJAE~gW*S( zk}5DhYMH`fNDy9C-ues9FJ8r;$9=}2TX4S2wtOEVP6s4A@kZ~bN1C@cd2lB1_SVuy z;kQ%0i&;%N*>9?xz|i(|o6t$Mk&9S7^%q^;5(FbEmRw&*83P~tvwm09ClEVStBljY zScqYStx5IL!<elUtz8EXP_qg*5j5EIEP#^|=-~{A&w7w}*(RYJ|DJu6c`&sszc`;8 zca`VuS0Q1=;DoU6SyL33SNGx7j=HQ{YUsH&!)@Ab$QX(@cJAKjMBUOF*wi^2kL{}P zywjV^TqmUcFl&wa{i%OBYdJKv4t0UXDWvUiu*pqvmVKWlf?OzS;W|f0f+o{j91_2* zy*VbQo`F7GcH@4w)Y-8%vZ9kGjZLUiHFIW!VGxcgPDDod7!WMyZf*BUbGyGIbJ^bX z3Sq3-v_TtV76~b#f`n~5Pbt5R*rMV`bV|C~mS{|Uu7pDXw#u&_i9U7z)qH1x7{um& z|7e1aQC@)~XCsytK-{ev&b?S5;b|il<im_EJZ*$-aPVHv&UHF9F?JfS2N$2@tEo5I zp}8rtjTSb6SF1MS8j$xZL>`M=#K-<CVR_1JIAdGkk0k;n%Io;kCS~O#TNPSv8?alX zfDMkrN7q+1pz{s?=#(!k0<?lg=1pdV9Iip7yD`(2w~sfHG53|N(m~0alE4f6Ey(`v zKZ(juJI((V6=sHiJA(f|P42U)BqX<aKPGolnSYtwHGfR*!nrF_Kkz?B$sd#Zzu<pj z$wsTu&oiODJ~iZLH(uMVamOP=Q)J*=)1K3LTl<Q->_EX$uQE=Tc2OXPaPT|>VaSu2 z&$PP&--Zu!x4UV0^lBx=vI(sh@Z7W;307?yBMo7Z#F9y7wkVHZSBP-~aHUF6{z2&M z^TOAkq8Af8tCHZ%A$_lTB<M2y-a^25Lyo3%@AaWH(mw#2kTZq&Be>qM`M5=OrT{x} zF8%>g9bbO>p{sMZwhQDllb#jep*!FqopiH46O;ZB8@uQZ7jzde9e@>mTx7(^xBH15 zu|RunoM<{S^!)w$-Pc2PW-R!8zM+)<`}^_P3}m9aO2E&T1!P>kKEEtfB&$9fEh9<f zuv6}FYbl2sA<DqG*%w?QFTCI&mZ+O276T;M;aPC0+TUJYV`m7zc1NDY)3^@bB6n}g z<&6%o6Y+C@t(XrAP?&QR{b>M}wG-;EIn8nP2AfK&K1eX(E^mPX;774Z9%EYER68|Y z(I-CuP~_O!&zARs{i?Eb+JeVmmq^Pl2)@=v^X6fQK6G#(D;DQgtyQq+oKh);%JBKh zXx%9u0vxCoKw6>E!ASfiRw;X40TvX{2vTuGZ+g%L{#s5_^;B4=0Y8)kY4Li(WHc$v z-I+89jX8aA*Gm1ck+HZZ(L{|0aZnEid>E{|pvp8v85FqPoY(Hk(v$4y{KDmpLXRR> zw=UYnujU4SKbtSgIp09_wc6J>3Fs07FzF1}sI;!NS!9~*IzMl7Ezt;vEaKR?IX<zr zcjD0@#+D7~jrkCx)<Ed_&}md1JZ*WU5dmRh@!VHCzzN?dhr4QL<9p?~kmN#|Jw1uf z=5|JEXS_YELQCU76j$I9+{z#S$aAq(Mh8i@-xE4oORXZo;5@%!Mrl*<C#Nb|@=`J1 zvWTFIRavzUuVz|Ph8(sOXV)<>*L=tis)*z^X^*MdqRvv=YIlSHBsdYP8RgmaNl#Vc zg2M2J6_`0S(NiN|n41U32D_X}A>G}j2kxDrVcBB+u!}gu=0Vk$G{<YN9HEX?!k9pG zG+WhnGk~QEo<+7aM`>Ky73l+Db$-j@;HsV%%NL=IdV_BlyU#p%F;69VH@SX)&qGOK ztt8=_Bk^kE=HpUl+6(V1)(ii{W@tJZdKoR)q&s>HPxnd?oIk;r_#rs@a|uoUz|+0O z&c25f0=v(ey|)j;h&rc{aM-MFT9;i%F0)=%|B_jbgbQr)RJ7j~3&%Yc!OW(niFYDd z*OQITw$=WGC;r`Ydi5o0^}x3=IrrM>ZjupeVh<9oVMxr0MP$>CuBf?NH;VzfvTYXi zf>pJIacg2oOu49%%GbbfcH+_Wh`I2D*>J{Wrp6*NV^ZNsl*-nLNCP>`>Dji5EpG`} zQGv$Y!j@-%H<g!G``tYh=HiM%)^Fza>cQ@AY;&s`CHrU^t7GPnpmqMy&)P%igl_L+ zSyUmZ!pQc#OgUmAsE@4@*KA*+)T4)nUW>U&VSkhP#zW3_$LS-nrnQs-lg%<G_Nu7& ze3>;kIsvo?IS%0G*jO36(0T169)V4C1}d^gNkQ!l3njZWVZ`0ZakfT#tC0M6^1eWd z$FKI*J9%Zt;2kcmc?(b@t)a%;%hO0xO5OASP<D<%wsl*YPMx%EJM*M%+qO>Hwr$(C zZR4bE+qOGzRd;no^cNksBKD6JYyI1M$DDJFHQwh@U9p2Ui4acC&zN**@$^v(5zI3r zxlE(pGt9;s{;mr%;#9D{+q+<5cs7XHUWF}l7Hg_j+TScg{dA%?&$2!nfGb%iI83K7 zL38<37hv~iP38Wgr1&1yznK~XN>Tvqq*TD{MWHuld~TCcZlJ1yYDBvJfqpx}xqOQo zF$cCu-|7Yi<YWK8YdRY{(|<1%{y*JadOCXc|EeSy8UB60_oAkJ3~@`8caE-n%&26P zkU}8{I$%6{H%KdR<O-Y%J!$}D(wV{FD!ub^$VSh!sFQ^=%ji|&^x<e`-IkGZLzyhH zcpM@pnv7zqy?$0cDw(AL*8w3@5xycQGYJKfWTaxhAPs@k*r#+llM8NE<OfX9sFZaf zdExLEXikNXq$_1#2z;8v-Op?+<QE))G`+%|s#`cIk2j<ub)BMJek`Xjl6*Xt9G5)W zWjwk1H<PsEXSIxyKnY!z?JJY4REjK4vY{NnDCBMK-XKQ4M5umzEc738X@Ro)TjD)N z%G5A&9)Kj$(OHC283hJTBgODCMK=klteVz0PiQDbg-c|nG<E~%0&&5UYu7o`EW}b( zj$fa}D->Bu4kgeW*Qvi{QA-t#>eaAygTLB{el?K5q7%&<YG~a9n5lb-besEe{%R8J zlHq5!%&LbNJ3;=cU!eg1`=v%F2cb=yszP9|jgnrQS-t6RB;(bmPnDWvQ9w-Xc!GRE z4RT)SM|?`G!Yy`T2$%+dp#lg69$bdHEC)>zj1>!_39(AgM>rA8NgF5(ku@O`&aR&6 zX!%2TSHtwd((X43JwZ%-)3lp=(`5aLS^ilfNu_NiHTj!&U!G7alG+jz{8L<I=81Kh zk_nW_^v7TqWS|~lifi!$^1zEXC7?$!Fdl*4M_wfS3WKm?${|H1WawxBdC@;W&UF0N zYmzar&b&2>MVIyj!lzFkya48O++A^_PY3rrX_&UQ?)lojUUz&yU#_{{-rVqh9C)kd z{eEw$`Sx^p&v<9m^thMia|N%l_HlWCU*GmddLNj)#MAI%^$LKPfb^i?8aUdqvr~CK zz-KImZPt~|@nYHZX5Rc-|6G2azdW9&-SXZ(YZ-TOd6jjMMD`SXLc}~$clJYBhBt5S zLfJHUIee(l-Q1aW<8w%b5gCm$PKDixPbSkZo<R+ERxLN|E5G7wOn0$pj|k6#Q@qF4 zPsQGgbOnsbB3Ye3Q`(eF=p60d+a_rmw$NY-sx4`xiLvwM@d}{3ko%(B{5tmew3}lv zfli_?1WQ=v^?cr}h+)t?nGn$nuEPBT3%NN@Z+yYv5KI_NubGCh6-^(pmRZM%{YQog z>*EHV(b5%laQV-~3}aBhT5hQ|z({HVd8RCn;n&{RV}~`TF8&_l)A9In_f6Lpd<3m* z_vUN2tsCL-LCEw(isp!-?bP@V`rgwx>+@p;C{(s}&&Nl^>C^esvder0T-M(BVbA*H zrHx-<m-q8hfl<m)^Y_zN2y0VUm(a}D74O>9<z2>mkIbgFf;i(VE{)yPRjn?K4gO$5 zkn8R>?lbECGf2Pw<HxSVApZ=$EBp^{7#t@MW{+R54UvQRT-bgZquOQ|o+EgMJ}{cV z5jyV=IF8^6dVeq<){d1}Gr?-GAy)i<UEIfJh8%Da9}}>{jk<|V3EJbv|Hmx`;uL~5 z=usmv8bN!E`0-e+;DeuA_R2Qk0qBr$Ora46s>dRFl5S67LsHzhm;&{r?hK$vBQumu zxkkba2IC42K@gUWgtXx2uO30-=?P>=e3WV=k~c{=57u?pv#87wSVXjHD#99w<@<)~ zjaR(D3dI<15=ZKK<Dj}Mhh%n;%B3{~>-yT%dwq>nbt^iWYo_lQwj#Rc58js))7bY3 zVv_SDD4NS&f_!T7C5cA+^-Th9P>&Oir25Z%Q{}Y^xgz39#&F1IDwsU+u3aAYf?ldA zPe)hQx!o4u0d(%TGzJ+Fg<x9PkW1~Jn9KXn#^Qy|3t6%K)X25{>iP+8Rz}k4KA<q+ z6FSOq!>i*!mG9UIUt%y@n_fK&ye*8(Ww<^MfOvNwX|agjh}-*Y#1e>D<!IrY;n)a! zRZ2RIhcJ>3`J{jP)*#2!)4Xbk;#bFux=rrq5fW69caW<NQE+9f)@!kbampf@#}cOm z!!ze<X-WSWF5<2YT&z3Y`6j-S0c$sd7>#TiE~eW<XjZwlSR<^mo`Len9~brZ+zlv^ z6A9#<aa&QI*Jo69;15v0CqFH!Y>_DUP3&RHK(|NM^Tqy+EEC&Xy>FZ^jvqj6ORBB0 zK-~{Y@fyukU|Jt*r#+Vb)qy$I{9F-FKIu>V%muuD7S7B^S|^lvt1vEt$#&n){Lzwi zO&J=FxjU~$JRAu9NPhSogB0g)3nv<;Z_Mi<X*A66`H;qB6om<|h>*6N-?T8P2mrEH zE5>C<8c0ptl>-45s9HExGAVS9d50K_c&36#3eb+3()5E77<O=h7IF4HVPJe}R=dOA zctlvdi`nv!Z9%DHdY-@OZ&)r6D>n(dC9!I&rke#Tgq{!e*0O^?rIhS1CT^=@&W+v{ zi1e2b4tg@8x*R;Q){l;fg?yD)c_W^4|4!-I=(*x!?v;@*qh?kTuO~W9!EENv^%V^> zG8wi$@QFd?MX>id&;;|d=UZ(_Q(k~$ZcJ^i4IIm>qWA@6LRw8OV{ltgM)$7o9EgN5 zBJK|Kp099$7z;2ARv39X!<tYa7AHokxhN)3)G3sk)VwHSrb%^8Mj9M>N0E5vtMr!! z@Qi%!_};V5yPt-<k#0>W*niw9@>x8G=8fV|X>F+<f2qM#T!UyAt|VVt2Kp|M2zvxK z*4|&RXkRR6RwhIy%mhV{0VWF+$eus`(-9Dfs)@wBB3%W9y0k74F;-BtaMI~F*;%8I zW$KeJ^81U{i737oOBO@ELh>^Q3Nm?LG?AA`j6v3?f<`Qc!cLeHLeq_uzKX}1jJkPb z5>id0QDKVYU+>7|ybV-I3lm%j{5eH;zOlV!)et|P{XMi+HZ5-e6#l%;fiwETj@X4j zfdm);K{G00Gm8P58OZxIGH-C1F|)n=h9WKk=qW<A4?Q}6V3P#$So?r!+RmE4S+zG} zO6IU;DT@kh_lCcx4-piCtv736fxL!I-5<%29T+`MLx)PhH@Gyt+Z`Kgi$shn49#SJ z+iA;-<el&*{Y2)%Fi`?Yi4}m!M;7Lj3VyzpoIvB!ogXfG!m_kz9FGs(p?5~4y(X7O z@S-t3s#`l<Ub1|4LiOLfrK)~j)u`DgX*u19%(k~8U2V8RDKXU-wz*@iPc8@d8bv=D z`X&9s>6}da{_+G?Bl(!($luH<CGXS%!_i@#2-di0)qaF&M_$YESjKk7_UUsZ={j)? zh~BgNV&A`Zk?C^}aHS_X*ANS$z1?pkC^e1Nu)=5K%@HoEsKf(~gr~T&5!1So&LI~H z%G7zFAJ}cYO`Tl?CR6l)5@Rb}L;a26HslVa<zlbu#WWKoH?gY7?Z#+4!X})J+e7x| zi55`E8MVK-K_7JW^5x}EhpY=$*QLPyB<AP&d#-9@7oOB8t?Dhb*1L~d%{C&cPPMQe zc{=?TqL@m4{yp?31=TUd*KvfG^Q9wkEW1uE(g=zT2=J6e8ffMGEJ?0kk9Y)$^|u3$ zIm_}Y2fwtxh1ud;mfiPEwqVop6u1Zlh74%Mi{$htz@_Dnwtkg^%cD*98|W&$I&%L7 zTful$w-M~^pg>KO$E%RQ#X0b?b@6t2E@{^5WwepfONTY-9cTHo{?61nlBPI0oG6gk zL|v6MX&+7}T__Wb_Q6PwC?k}HXDvjSN$yp7eu7~wge}@b*|SF&h-YK>L0mn8fpcC@ zM@t^08WDs>llJkZzxrHzeCL8w_Gtnj%BjF>*v-OAsGRwj<0$dvVBC}Q`xM>b4mCpz zEG^(%I+|Yb_Vb>+fy7h?j)6)dFcFS{aoX?}-vK`{+cT0K^BH*Y&xE&R??}5U?}glF zZOY=gVRy6tUKm*(L%ZrH7_Q?b%SY|`<M+n6yBW;S^T#>9HzarUcUdqR?dbl1SpGu( z6MRc}H~0b{hN!PmrZ=+r*v#MqCSqMpecddSpss*2Da?DR6qF1i#b=&(F{7IkW9g;b zeCfI<`o@iP`AW&j4A%XW%ZXwR!3()>W?00lix9tMI>4P%K8SnI^`Ms3I5q{F>A&0s zyQX}Yz8^n39qvGt%ROheX`q!5=ha6(tUADqM+t$qaSsq-|I|(|#>?w3ZDm*+1M~_v zC)Y<(P<uiTx2*#l0RH^|);yK$0YBXQ<7d(y>5hdOG#djO2(hQV&M+j(%DWvYSS(xJ zY{t41?9Y@8RTBdnZEk>v*UV9<-}V^?TpnG_zTqkLZ~4|fCv)9Lp9@z~#SP!ZNph^n zOR^rHuXKbDL69$iB8hw46w@%kMs?o?M!7G8H3wgSgWCW`xRT%hZ&}1n$MO%MO9nb7 z=6`!^RsBEx4L_kv6Wvk_sNtZUA{&|C9apW<%keE4;tZI<fmSla3M6Iiug~1QfE4k@ zhMdwSZw3g&wpS@|BMWUVr4Br94Vl<EVKWfo2k-srTkL=&dDoo$gJIK|MrWNa-2H=& z!vQnOilm#oN;;||iz+1QouqItht!%>p6&83iXz&|<y?NM{y~1%^?WkCG(Kq)DGA$T z&}xbyO_lwzfg29-lLw!oXN5PHXd#FQK~n{*ZFXEgZ+$_yYO;n7dXUVAN&+Q6OMNhn z{1J>iMNCz(`o-C@=q1YDbCkSt6OT3AaofjTmhTt$jw2dKs?!iUc3nJ&JDT&SB0UCE z2o!X<3|*M9BTBK3DYydTI>IWZU(RAEQmi|-${?3r6!|yv2ZcX#ZGAqCD%y#62%^r> zbDG^dz&aWTYixb&OkDP39wEII(*yLOaEW%pW7}Ia$4h#FBSTbx^t8;LaZj6U@fzL$ zTkPRnJjcwb+VvrIpW@5d+}P%d=UDV3h2}&v28&=KtmKtfODIaN)`a4cNA5RR)uXm4 zz6?>m^7(iA(tk_ZwT1P8*nZq2R8tu}d*u?=cF)x*Z>{5Zu;=)qi`T6pvx8VHXWVRM zG8{i&&1i*-TqrHtHCM|SIJBbKlWw7t_(ghRA@mbv-pW)$V401Vp|$HBDsAdpW}%K+ z16PMN@p{BZ(Yawd$)|wnCrfS~$}Jw!lrf+3Cx`ItDjnw$#0{2ft<I=7u}6=j9t+t< zVm%7TprcIE|HYyg;KWCEb`hhEz3U`+YjRBIPr?^?NHAwNf@e%c5oEQBpsq>MP7Pf` zm@W3DP|HHD#U09piFA^p_6u_^;yBsMe*8t&d92sp({Zc1&Ne%Grylj{M^A^``HB_Y zx|Do+`%<pS29x(z@3TT1^&{tb<Lt&17oELLHt}MfF7bnURW*3ie{7+6)4pT8V6eJZ zBv?mq83k|-H|Yl&e;}|?XXwJTOH*FTFLoTT>D1|&`0aGQM;(-sW}RGK$wBhbtYEgi zxb)6vp~+Hh3H3IPfvIwy*tzk*7$cMis|3kX``Nv35;~1r)^~lY&c`{(Mur=cOBodC zJ}2@yRC7Occd&fEXv0dj9P*KSn_$`H=8p*x-IJ4Et!jd$ym)IIF+QRoSh7+bPQ02_ zgo&<)e>lOAP9O7EkNj}blU^4WS@DMnz&GKiR8)>h+bu^-98Sn={qk+^?cikJ*52CQ ztzB(RgNmklT=9DP`Vs32?W=q63jA7&Y^a>Py-p`_Z8gDl)*D&T>{d}|oqrFU<oHFl zL~?p04X$&ruD#j#>A2jhricg)gOslhL?>TA;LbYd>_tEGesOSjCmarJ7-h;Nx1ppi zw&|0#r?LhduDh*618V{ON_sf6xW3u`rfO<hbUyTO`i)wV(b7}3rK8==S%}$Nthar` z&nRo_g^o8SK=s5%b@zzo$ygfxrd-jfbCL8MNH;dZt<V}ekIb-)J8Rp$qHbVU-J)*1 z(za~DWlkumC>{Q2oxqxC47xt;X<C(63%;E!G$5pmgM@22%7}mf=u%(8roIO2);ylz zCHWPNuih-(I(L9*SQ}tX@=`v$2v3?-@rKL~K0=3Owm}Ud6Xybchnw@-<xwUJayaP+ zxOa8h2e|s~kx7<TB+_9T>(8oTe%*k57VyR<Fafobzj?ulnRkGI+01;*t#P`~-$>v~ zYQ&FsmwE0?U>GQ^%iAceOAESNrE8W8W-Acv=aFZV_O>Z9)CM8iz;C6Ty++Hy5-9t8 z0AtK2lrR4ALxL2<L`Xm(Yo=wT-;>h1q<qhvjr*FsU~%wRgj>5mDi4D~0Ei5biDIkn zx*wB2S&~QH&EToge*N>!GUoX+WFs!qAG`oIb+|Ld5x}re!NuF$fWayot^{K<V}*0F z*Yjkd$spxJ5i$AVqM4Pg*NnE2YK$|K+KA!9eTbXNx<#(tgyHa>>uf0lf+1Eo4Lcns z&>yrs6~@8z03ybLZFpPi6AF4EqDu(DsC4I6BM*TH)PDqxNQNj4>+<Jqv^0X>?xFKW z^A(Oxp3jr!{bPUDOk6YgjrF$&cS57z4eyYf&Pq*A<$jGdE$yhHG_fne8z^^nd%~%O z?M>8`rKuPq(3R`2DAj0Kb)h`c{3sjb4eopM2Uz->xNgqSuf^RVH2lh->5`;F0)dk% z{hG<!IF@Iv6isKk?`2J#5}*kJo%ORpNzJUtZi|{f)65+=PLoq9q-Ub(I9BO6T;SGM zE^l@#XAjLwGyTw-zo2^AU#t>HjO5D-XR2V|)5rv#qe!sNvxCHHm0;#ujcQCv-pbm9 z*Nn7KJGedp#k(>X;C8lPc}ePwDgki!l5o<uy>u={S%q%T;ub{z;J|_L`n|&+Q{-Rd zhPm`$UHhG8eM&kq`om-&`P(ec<Jr++w?0#<mgWe5`@O&9-Whu|ToP;n>6wD9-4w^! zslxnv;P$|S<Cwyjy}Kole2~J%=i7>F8dSxpaOfp9b<)-q-l3UDToVWZRx}qYX;#sd z?Q-S|VXVth&MZgVtJ-YP>TF^-LBMx5&uWvti;Qe%PCnx|C%W|ZEa^j#>47=xKW$OR z|G<TPS+8HxpuY%Vb8D`X1eVmjz0Nu6QJLWb+CEpZkVV{n&gh(YoG57{O!whd198wW zb^89WuQ@Nw{tH9=0aaVxe*aI$3D$qoJv0AgWB$z)%;x{qJ+s=A3fzLaTBR3`8e+1l zc-V2_YWV*gCFV#@+rOT*xx^xn|767Pn|aiUgRf{`JYP!o&l&|5xHROTHsEbD;Fu*! zjOGss7t+lsh)@=Z#hccJ%NXPv+PA;J)4xR8L4a-Et$SL<|2Qze+I|doQnQBAI;hU) z7n250$C14<*l{w2|AILDW^G7N#ID-;fjEdsIXRv?TNC~(SK4>a!IAyRGSDX#Sy~(O zq-)WLNw48QE8uz`jX1VnImS{<uPh*@#W}7KSAhBhaqwQ@`++!Q`DqgVZ-_(R7?@$N zwZ8)0e1vUFoa6a_8ZLiU*W51-Qhl~Bsysqa(d)O=AJ^0J`&r34GQI$TxUjCzQJyoZ z;koCbZcNQ2!}O93$H2y!QySXRDbNUc8spUdvbucY?)-gkx~|Xn3&Q1=kX)@{jK@X( zD8!BQ6~u8Dv<#WN0i_9qu+pz7Z<a}E<%h7fFFfBLh67(3(htL-B%`A9sroYR5XzXc zlF>aI44LJ%p3<U$Is(8b!A5G+FylNhY-NA0r@!~htroy{PA{zipdSnfz0OdEZrIL> zu^(}e5fzw-n73gJBPJ!SjN{BV>{_b9bW!pO&a)3llM3`T4Cutak=>O1FJ3G+ujC+z z6<lgy=*pERGbxr-NX1W+GS11oS&BTmC!Jmz#Gz2!Wc^XkX4*sPC$rdrawXx<hh0<) zVQQg0VHb{H1~`#@YJD%RQ+eN?87+1QS$hKQ%1jtfRM~-*?dmJz;fZx)S&g!{bHjcZ zs|h^ii{_gMWL6#N6T87kg%dkXQ^wPx!!OaB4DbDpieLc+YX}|f=4t6~D7med3o~)X zAaru<!U(1yV4&y(aYDX}BlZ+y=1spkrle=rVq*6(%B!MFXI!N0Zn3(QKhxGv0KArk zQ_=i)Qk#CzOHS+1!Ol^?MpuPkY>d*dBgw4Z6KAh>^L(@9YO_TYTSJgof?~7d0^%2Z zz=Ysgb}W$mWOmUN1Vog-6xm`I_hZabSN0cLwa5H*9TZt;Z#o`mNiJX6109=qIC)(? zv7zOvY&Z`KUatc$@bK*hOD<F!L10H(0o<9jtxJBjXf!`hfG_RcUi~JQM&|R;sNwg; z9f%OQvz&*aFr7&E9}i-DGWa4m^OzUK^@1wu5AJm$9?O{0Xd7R{wI<OUh9z7Qtr3^y zVVf5b8zCl;X)o2=!6Wc%7STU2P&@c|r>fwf-A;2lt+M)=1iwN=F_SLUek1z-AwPg0 zuwC^`tNL`m#9<bQ#qZ_F>68;bawdmA$VHx_7hzMLR*3Uc5))8PSBQIF;7#xIc++hq zl<gUT{YebO$t?1hEsgD%z2PWYy+2MhNaY&~D7BGg%$d)3(HRL82HQinT~Ld0o<ndn zFqnJv8yA(OsXsC_pc@;HR^j5NL>tFn9xOZy_mf``WJjp~`6#n7GA%*~$Tn37PEO>u z@=OB%<K6pW{x0&iaI5U_wem7{VPz%p)e>2gR{}Oe-Yts{%S2jK@;iZ2XG<w*zf>D% zW{D<i{ocjf#wvZ-$?Ykiv+T1R4Yr|7QqFm(2~|e&6itgZt?E3Ni%R87-zYh0^bB9I zNoBOzF>8IzXnQ=uN}GSScWbRiJI#r1AbRssTl8qfn+nVRsKmhQc;IF!UG8n|mDy3c z#m#{kamPv1wE_NIofFc;qILVsI(FE{)m@*&15ITN|L?87?yUlOxYUgaMJ2KU%b}ry z{-)x$ss81u&u%}*CvJ!BTD4N>zz*?&`mmM+8={6Zmcz3gPxOBC-S=oH=Ok;#hOe2> zAA7lZBcl~RbBX!KM&pPTW65xxX9Cfq{`(&+5nRyqIq!uOI?$tEo*bnR_-hPwPz=hq z<C>IMo*AgE`{MUw5`>mB_5^M4g;%AS)w5F=Vwcb<Au{?scvhUf?Zf(a+_gtl0oe!i z`j-SXf^s}3ImiLl-_0j90g83?4my+vg*@v<?)Y!N75Cfg4#{y_+k>0>Zvb^yTDE`O zR{lH3`hSC_=-K}#1cP<^pKztuvg%D-dL8@*#6i`hRlIlxlk?gs8!p`MK9&;1(^w_! zZ!a`rv0HOVgLpK_Lf;`E6T2sBy^BrP6%WSuPs^tZX2om)4T+;HZ4W>Z2?^R6WbwVM zs!oR-qW&W&O!DoCu$!JVw&`pm7h{Yd3rEebI}VMEyLB=LZn72Dvapn!a0C>w9FV?` zy^GC@#np@R$ljS1qDMIi0^zonjfpAR+7|!qEjM)fs?PWP!{L2@f<6pSU5}E6o}Ux% zb_)sfoD#RSB*B=gRfT>4K6MaUD8Mg3j|tF5QZcAqDdY-rvp*;hMq>1!U+{y5ZIQ-P zwcl1UL2ytjx-kD@0pW0RS^10g1{dZtd#d#-vcXpuD8IUD^uLrpRk(Vj2-#WBwe|7< zfwMpB2HIt|>egV-`FMMO<35rRlC#+lGQH{fLm=D`^=+);`*975plG4@LH4V@%U>qy z>6P?4(i<HT`Y^n*L^T-5n{!?@1RxZF6T0)~vZ5JXb7j%$1z2sqi7ey%l^Hv>z!KZ# zIA;R(lwewmcInh<wPO#GE^)@fhETGcg~g!*#ES9%79KD%o#QaT*Wf|Trane~|4!R* zvWXU<6P1X){YqT_qBA@BUU$!;9@vnHp!kMDb?x5a!-bEC)Zw_VH_8?aq|;8TIXxA2 zMWZSB(66rbVc1EA4~0;60)7{QT`K`{roT+%m2NJ}YB*$NU;wJ*u^qJzjKiQ#1uFIh zP;2dy0~L7M%@FU=n?U3|`s@YRU@=()s8uUOam>=w1OeQ`6v@LD-_^6JWDShj4_R4B z+f0FrKA^g@xlug|?f0|!PTjB@I;Lc(QT#(48RRmQ!9~HV*q{|MJKWV7mDv`xN?Z%3 zmkIWlAlWlJ(gd1{%<tZey@Vlu&h`(r55iu{^Pb#SoEm;VSrIhgssa@|g%Ka>f`0%7 zM4>2{f(Xt}H*;T%6;x4lJmzDGpdF$I*c|>|Geld9N2|{OZF=<4wf4f+Iz;;Qibtb^ zuS0sNVz$%%1>3_{6Uh&<n4p?2o)1RxU$#dzk36<~Avk<%H&8ZX?CbqZ^x=+E;izYp z=x&wMlgn}Q>#ZVE;OG38VxT4FQOJ;-&D0fZ9x)iVxv+>jbo7z;9rmYNP^8Q{GgnDd z_)@ccct#<VN01ezdj7{>8#wKF{2y$r!3Z{O^8Bqo1o$f8d(%JlTpJtg@DU&@_sth6 zmQbTBO4P~+$o@s)fdfQ4JM7Oy08%@AvI_A6{q+=gNJ)iykYN%D(u(o#VV^M$I^!** zDBHoe<&?*iE0rrQHU^@%X6dbnyL5{fjY=i;n2`3|gX*}y!H7$JAF5wc1F>U8{HPnJ zbkgsmMkN_@BOS}w-*Mq*{1osA{f$&X))%hcwim5J0*MyEDZ@*Gh*}HPtr&4@4ST|> z`9P>v0x;DT)W>9DG6Rzma;lZMV)mSnGa?99F#vp<vUxG+e!PoK-^V27XffuBzt)h= z1Cv?26o>X`S|ZKmOLRMMtO=KUlf-Y!PaeDGibsp*^?Og?g}Et2flI+2XYCV_$lF#L ziJ)QAKp`W{R>Mu<L6%T2dUA2vqp3ya7vlEeip!2(=1nibGR?7h>Ug^K{7cOqLFaGS z5p-Yyp*hmcR-A-bObyZJ_Jgs78kr5d-Z|bK$k3%pI0*>)RRKxP%=HF1#J*RIarmx@ zVzHw^rfx^|q@AwXeM8laSePS4di&02pa6<@6Qt(|mq2{9kYyJLr4Zq@-$F9YFX00< z2*;@&h9NfjU+0NKtR-Ph)omf46Z{o+$};w4rN0;^2JS}alK>>i9`-qeogE<uKIe=0 zmGSW<msh<xX`s-ZOVMCdmyZ1u+4Y=15}EMP{ac@|&?JFC7s==6%z)5>OOpSl9T*AG zkN%X*+s<<>UPi}oeZ=&)+iQy8>n4BtTT8VfK#!(YaCEs=$QyoVx}hKMP9+-3rMk)| zi7eWvFY-9jvg)VVj+Iy)Z8T~b>k3t?r?#WA#Q!95&P`C!T?!4BOJb3t9Qd)6Qmp4v zs$O+azgE6br;e+J9z&_8IDI(@_}T=s6lSfRy5R-hXuo;7J|1>+#^HRrzn|T_&i6;g z4UOtyNkS@=&Fd{AYcmdaeK+iTXyaW!>BN9!ZEoESuqnJgAn=<?7D8stXi1Pf^jRK# zdp9u=ej_A(<XRLEjo?YmRNeaAcFpeIpY)kY-{__LlR|QEc~i83WhP?)$_&MlT8ZES z-nPnz@LNW<yC5hd9-%XVc`S#3O7Sssi+{xSCjSl5KD{J!2cH)!e=0)n)2_oeRip-I zAV!_S1T&fOmZCTPC5Kat4zl}B8SGp4IfdYCg46-r(}zXo;r=?V1RUxMFnhJQ;(Z5b zYnX);G`|%FRG=!)(~jaS*%#<Dce=*D(+Sh?^tq(0z0m5BV46mnrcPRQw^x@*eDQ{T z$BVGoV-Mg2mfUe(dITg+QSm2frBMHOUrnWk-RQHCf|4#A>rhs4SO@MGTp8^5+COaM z^#7;}W@G&yP!cp9=Gl<FuWN34Be(?{+sAR8T}Wquj3iH+&0Ny@9XFJa;mS6hv~n97 zzP)0oSEF!BsuGZ0eg96)&Xzd5M=$7IZwzdWN0}5v>FU(ZK*<x6+>79G2g#Ecl@Nv# z--?)Q)yXQMd!lzep?m&d62cD8(ME;9fXfAZ7_oG<PyS=BGU{Y_$#g#l1}J`osA-H& zh~RMR#bEyh_-SgVV;R>pQsCNx!fn^CFLnod80lJXe;VdO&p;>$BRvMP@eJTMU?V*0 zmJVMV-tlb^jUz7no~)!{(wI!3KM~><EZxs5U(B6I$RA8X_8zi6pIZcMEGaoqs)}$M zmbi(tAh{sHpIk{_xYEskVG?>klwR~s+^~@N;g5Ig&*xX+|D#NF_*`jk7lN0KXMA_H zEgKQ%S}pfWvY~AtW)?wP5$*G}yW)+RXL8uiZZBQs-dN?o=R`n`rLK!{v#|%dB~^7G zi;7ipWOgwKCIr$nfZk(mJfe<=;{LrCF|MiAwz0NZovF=P-N_^!KIlHxt^dGeC(|xA z?8dUVPwkZ54LA|lvtrdnKivVNWIL4XxE=*t>57N*Oij<AL~idKXaIN!iGT<VKD?5X z4#WoPFv}p@nv-M(B)hM6>{QN|j(uW)d^6M2y`Zx5Lrqv|RE`Wo)Pqu1-e|_;6lBqp z7^JHrJ@EzK7UQuSGZ8N1L%x@IfK*`NI#m!SA=FZ`59;Hpi4@AMMD@RfFM;qt0O!X{ zP6LRp>BAvAB^G}Sfwj`&KZ=*Q5f7n^wnbk`uRP>sg7l<90;L8~72d#-ixw~<^T*S2 z^s%Ri1qFHMGiHBLdKqQQUU^ouaDJbu98&S4hbm(zz>un%)VJXy4ky=6FCkVGLugho z3Mlst3|$gXLY$in6vNBcu>YJoTT=VxL{k3tn&?1Ms$F!I5FlZAZAoVp9E@Zp;K=*5 zD1HYbqiL~hLBbkWd3CMnq!KL-lyUm(O>}Ov+)iC{+iT2XLe4_RQDhuQtQv~G>RNUa z4S<Y1lvn_T!H8Gm255o^B>_|}>a%K`v{IO`$Kq-dKm7}zA>P?KqhdhN<~N|e5VJvy z1U35GG9H!9G46_c|JxN??!sqDn+ky%KHB^z`ZLPnri8)Mmh}qyBdlesjfsf$px@C3 zL4PFd1>aaN>?z>e#ZbNddx!%)tm<Z+5IKE}<LP65VP`d>sEsV{ZjBdjU=G&s3*B*L zYK}UtO;)l_)w-|Mk}1mHG4tG2gUT_MLte?7{`<7QuvW8E&^c3ES+GSVf%wQcjfmEo zqjCXIia_wJN1CkG2NmJFqKq+ZbLzOv3+!0$Wl%cls$)-4YehcOf>TVPAqX>C)8M}9 z)A{-Guek@$#%f)SNKG@`MaOQ$>{7SatGR1q*ZW-b^HWQ7^ENK-MW=%S=ey>>q>FaP z+7>tFm8A`=sAfj9ipHUFqf=uOCnUI@$DDa$cxCCBy^%V)w=`)2shdA1BY2UW-St$c z@-wWYqX>3-XXt!VD>5veSdjVeECi<O&_4b`S(C<tx2(dopI_KT<nx*ST1Jkbf6>~o z6{LZoIh}LzHW*!-52|q#qWNiKZ|ZRA+WC0m&55)brxooceFM8SSaLihh7`4-Gif0O zXMR{+V^G}u+>RnsigT^5sGzXL?Wh1mDHUF=sA><9=bd?X(+Z{01i??P?X-fe6A_{8 zo$^YfT-@IL4RM|(PxcA3SG%m=RM!VOvBoc8q<!ctiUmM|G*w=q<cmIWeRMI6GY^S@ zhyow0;O*~+g{UN8h=fiH^8DU~ln;pBeR_Jy{dUJ1jz3Z9zJ7wq5+rQp^S!@hy|pDs z(Bb8i)e1VuCa?hKWW6|9YjL@?EeLG6?Nsy0f#8pMW_0>gnNKAfsly75py=T8hTLzS z*@JERNG{JuVf~a#7LSw&6cO^YV4RwEZ$6A?_Ea6Q<Yc~}nx%!=EIx~~uevx<uTV%S zNv-;faX!N}Gb6xc$x;LjyL}=HbOM`?lRV90U`vq_)1hnM4}Q+avv~WD)O`6Cmh;#& zj`U@UL9jI3fV_pXTklr~m)jC6!O^y|9xUpSO3SM@g$9n2%>%jveIseC&=wd80JR^G z1mSz%pdmLO#wA4JES|pXs7L?LRPc%e=Y`)r*stR!?Y^=zWDP>PW#HTDT1&nQtoZZ0 zM{WL9fK^ufWuV*1o1K`1%>mYF{JmyTut=KW4y80THj606zmr)80h|;=Bxb7A7pASF zypY1oFw?}lz21&$c%_s=Qh^pxiOE>Rx=S!ngjc8q)mFnXjsqH*wl~YR*9WHHG%MF@ zx{qj5F0;>*UOL;kpDmwcDSLZ&<MSDLIG@f5JKGZ*B~{1lW#`EYkC_V-9N(L6zsScj z?s0h;%DsU}ek$!0?Xn#)@T;`#9x;~*w=%`7ks#+5<Ht{z*LyMtguBbP4eSfAtY(5Q zxFhkre=zp4(=+{350{PQe-NqDwApV){J{mn%jppS!=$*#v#kTIvWT~Aa`
l>^8 z=QUwyR#6uvZ#ci7b0U{j97e>qo?H@uiz_;O8V6%TctF8<ESu1lm`vBC-XTL48E!pH zLD4BFxbus}5pOwOb=|WQdfLkXACldMs246Hg?TkLN~+rBU!GKTXTV>aH_4c|-)%lv z#4rX0D)g2W3i{7b=V;4Jdvg%ghI1?2D?(C?b*-LVY`Uyu4A|&;px4Q{^(1nt;{J=z ztC#7@YVyrFAOp6s6x8e_4;b(7=0^;!I@VdDl&GK-<90n26#GTy@QM2;-Tb*A&Z^5+ zp!;_V21$>rm)q^r`}bD2+pD=dBLPnVx51YO^-T+!4R4c3+w0llqN4!$(`J80M23wX zR2^eWo4V^$+Gh`Sy%3|hH!F0uF2Yq%E_#v(eL09hBg=)y#71@W8z7|X%0*owsPerH zMiwju!&jIFFBP+ycolkl6Bn%xw3rkSvNJKwq{-i=?{>>+^}q7?K-Zac$N-5lyT*jF zC&q-|bgW41OOu@0FCOjc+-)h(^*zd*KXPe*=vc_VNQC@Rzx**H0suaQWPO3@e*M{E z5Aye0EYR<*y|JMwK>>d{ytlW&0y6GH?}h2<a`o~s>#`}fVuN;DKvt7C`yTLhBj4dF zW$`o)dphfH-T0_2aX06-XspQW0R}i$0s(&rj3psQ-jf$Q$@7%}>CC1?d*G|3UH>-Y zn^B6gOMBOs{RHOY6JG)C>(<b7b~Xp3W`j=EA6GMW2LQIM9CC#QeKM~llI10Ddwy_T zDs|{R1&MD+JdnFPj=ywtnO?+3DinA%G}}(xKIb;eiKP8Jnm#xp)U@`<bj;80i;_?& z_xXA~QL`P12zJ@VyTq3VK_Ja}*l_G3Q{`E)7y4?TW=+-Gf#+CrgbO{-0zCp6JsR#_ z?>(SL6;VR>o9MBa_W|ef-?hYR_s^p<1T~X!CkJmea%d7a5zZ`f6U{mE(G_r&>y!4g z7uo@DU$${WK)IcecqbT-|GZ+{jL9&7(P{rMLn3j@F(|r+CjL!5yUL&eSLj7ZocOi0 z3EKdu>403mw!m&j$0nssK4@zTa{K0+J)Z{-07dB=5Cvc-A-T1sS!fbNXQn3siC6Rp zA+`1r!LjG|u^tGn>vPRU%z?weGN{x0Vs~0>b&*4+^rFtiYk8w;me;oj)#W_w{aQDJ zcHVTlE{qiX8PieO6E^QZD*>2liqC-HWX#Y*_2RbU32ZJeG3<Ic0AjcvAG!0}8r4Fu zL-*WKo;swG8vk04WoxYI7pxk_Ma8nFv(uCJA#}^g*nkQ#foQ&$76)_>lG-ibUU26) z`YEaPJeP<ZvM=pZ&w?;AnL8|XnZG)Z=EyT?l?(KoA|zG`!Gt#Ovovyvh@p;4!T6|x zr~@Nt-S;1rK%br|sfADMX(#LF!Bgth10xiQV;7Op34~Om3gsj6W4wETnvLT2yTp0& ztaZPNXS=$9Ez)I|jKOHtS<9@$$M%BQO_cV9jZ(F(Xl(2#|48{BHFHKi{B<oX?U@6u zo!%a?yNN4uX3EF&3)%W1LK!sYrXt_8WXM!$?q3=`^1RC;Nep$S5g~&-N@mK|_OtrG z#P=5LuIVeQ408McO$`byEUwI<*mimBIqmmhg2NIZK~Y3D?ZK80=O`ui-=z^TuJov6 zQop~8oDD0hD%JHg@<dxTJ$JUrIL4fWPelhNChsQKqQWQWWxeTP>n0pJn#*vTy?y&| zhy$eKS4O>*sBubG+#Gs=a@bN}v8Pgf4YW#p(LykNW%`bP3(wm7Ru;lHF|YO^;R$io z+=oX19G0Yw<M3LRueFJ~59PHx1>*h97d@FjnUz4-=A<7?TPcwXq2ZuxxrL{|fIVP2 zvtP#wwcB5;l(3d|Y)i6iRzGbFZARPzxXwDAzN=(3ceo^XbHrS`e1@!-j<<yj%6AU# zvK1TJ3=&L2&_6mlvCg>;MJ8`WYq9|tw7+KQE%TV<hwD0uJ!-|Zes1pI3UOcWa!En9 z)5$5VkWq<&4N@z3AP#(b=r40apnUs`h2?Hlfsh$?8t|y)F(D8EqCr8WzdE}ARoK)- zb!Qj1K1<j<%5A0U!>J?u8Z&wMTf-=$(Uiv7>EU?%rP}mq)5I;zslmZS$VqMzpP-bc z{1l<ox(E3aDcAj&a}6nPjrkNW=Ijr|XT;e^emahyc@xxv6ah;3kNRdklz!WWX_9GK z`piQuKla!9%()KG`iw`t8am1J{wa1ih&LPJ2@w&0I<3Z_E(_v|EwSU;C?~KVP+P)a z-|VFcAdRJh`yw{Zz7d)Q%yrh~arb#ye9<^(b<dJ;#V=$MtY-=p=jY|#0JhMO&Bd<; zSGGOjsUFvr2r#nOnPYD~cHt4v3stXDas(J+8?RDR9W^DZPK&HFC#93uW(8g2qvEgg zks$uen)&X)9$=H*BBg&Qq3KxuJ81C#6J%j$W&N)l3j-bd|74=e2B!_i`?)4{<jE*n zOoH$i2-L+dYpBLvgM^S~{@PRvEG7#y86eAVFWxax9UFUis!_XGw2T2k`R!O_+H^#F z^nQGK*HE)sL?`k`b~xgsI8cV;K{`5<<3ztE`#pRmb`~+x;}!S-oy1<iGj!~au%X<9 zvDkbzGPu!j2g|=eC<yQj%>bfchaiN0a>obYkE`sxNP)Q=_k4+2DL4f$-S9-S7l|;) zX*X0~auZXEm10V6GDTwpYuMNX&c#}~8NZZvp>A?zi|#TRoX24Ll0uq_lS+V5%DFBy z?GO972udwj<VM}BJLED|UG)G4Jwg>#+%S?+MpAwyF1Z9GlP`jB)c&F2hX@Ay88*li z5K{0pCbGkIW<-bWWTUfv!Bsn_`32XLyr;IKe2Yhnpu?-Si3Uqt?a?c&MNf4={Mr%5 zxo(y8S6bCddGe}R!nUc<yaHT@Aq7}$bW!DMr!pyoyK!v{Z_!E^kZOX9ODROGOd*tD zS0agk(DerQ20`o80+2PGO~Ep-r6v(NtbB2&B@o?~5@vMQU!c?IzSO@ifusemc>)(Y zckD;Ca^Y7y9nVDv1;eiVK&Lh}q>9WRxn+>dFZdXVEN5K|qDyIaXe8Hm$43v?iboLW z<X;63Mrn)DC?xj+n0Oz4uccd_URR`1re+Jujn21QSf?Zb7LljG(tDUh8DK_@CY!B= z?Twzj--|x=C_Auw{rz$rJ8sGbfoe(}+wJ~-wipp%)6M?7G7qw1?qqhGEYonp_Af>d z#2l`?1d{|U?2CC|2@f^Zs)%?f9K;_1E+?~LeT+Y`GBXInimhdmPEuupPJ)x91tV@L z=2Nv`Q-6WW|KMVbX5L2QCTN#K6hAR-l%x|zu|Jd>V-Q)CobBgtL+I-0c41_5VZf&B zsf+Gk)=SEIgd@AWD>245mRt;hVeG#gfGzjmLO`(Cw|&BBVtaSC>112m1RoFVj^NRR z3^ZIWvkq)tO@BRa!|+OduhGD61CKgC9yO7z9-Py{@><o@Y;RGopRWh%y7{axrOdl5 z_rOkjjVsNa81?EgQ_<FLI|7rC2Z?nkf2~(kSde>pYhvK2{En3A1TK)!!Orf^+Fm&B z>F#`+9@_0V&v5D}%LqaX;l=y1fB9lx1RH7DnN)K%Twqu+lq#+1WdzkzxRJNOf3|A6 zncuxBIX77b#(oGnd`r=-uJLa6`JSzEL`7GECc_kmPv-lDI$n^!NFKTXC-~x~ai>vu z(Wt4D{~LRDq|i!JUTmzrVhc>YfNCU0EbTc6Pb#e>Fd&-51+st}D6#?4f%1<~_!z>R z>Cl^!19m|n&u*fVlsIP)AW@bSSq`<OSSs=?8@>v$Go+}n=Obi9q+|U?CL$>o<1=Ik zTkrw}HK=TMWeJ&72oDZQIb*!gT`2AwLLfx}Sgy>f+A!bkJ>y5!cr?iY;(ZW<qUh7K zQ*c;L$|rN?->;|DRlL^ew1?kOTLdOd+NIPde>#-~IVaczoxcJ#c}RDYk<zC0oyG{U z<S!DUghiTl^qDisPmzYPnTLh4`Xl*rW%OZtH^PAa9II7&j)k@RpuTaI%JMSbekvAx z(3cdu&hOnlTg~Z|P~BWXZBJr|9T{i!pR9Zu7fPZByrl}i1#-(2IYLJ0#d2UQlmw0@ zxRuaR6wJ8v=N6V~%%OSUg*UtG-Cfj)`fW#W<1O)$JYAVsF8=AMUJA7*jt)KlJrcJg zB1U9Dq(HO=peNnHJh{Y_QryNgS!70IKLsg}Ia29;8?<kz(}@JiThU-N;aDHo>CR3& z@2qGMI^?EKEkhbH=~387XdUE`R)0CpkYiWRMo7{qKN?5Mltc%L(ujp4CaA$yr4|QN z<2L$E7+1V$3e!1l;SExlF47)@yvT73=699Q8=Rb6l-qsZ{W~Fbssht4-pCCk*OUR} z)(s39!XFQmV;a>s>|MYtLUE~9T0nobW$}r@&K)Ed;ddkO<2gjngmmy%30J66{$XN? z>2T+amZ9d6QB1~4ek#Br!VfBq8!3N4WPjpOYY4XRKD)S8BOh_xfNHXRrtrN{BHlOn z5+U|2sL!j=TYtt+X<#r&b;5~VRPx?>T<b1)tnIqF<_%m--r|%;0dF>*J2bJsSuri4 ze6-zaTqI8aXpq=Vz%mohER0QdZyVlvfH`;T0buB&L$cW@LsfCpR3g-x=~Mtp9^x1{ zoZp=38{8Ho{A6KpldnfB+~7sybL$fvSv!oCL>Es+SVTZ}(KdfT?91xB0(ebep|j)T zw-D4G!Rf$h*qsV-zU36bkQG$K6$jW+E^$Nhy{PGcTjY#Rrfwxu6Mz+)4e-NxfLr7= z=skLlF3uEc_9~gqwUFh*b=6l5FxhqEMd+ZBk$grA33!M&YjngV)@lbU<`;j1N9{+J zZ3l{Rk87UH?oOA}1=19J^c+QIWhC($8TO}#PO^-C4+(WvKQ=uR@t6HGa)>0MPyTcU z_Wrwz7xB|-!XL8&-T(e!kM?%-l!spfw-8F$odGuoVHLncz>341WpbFGkY;3^oMV!l zr<QJD`ac&Zf1pdkS#sz?3iJgtciBDmN8pMBNNmH~CeWXrC{DOatd2X4quXWDr&gXK zZcCM}Vut|^Y87ecXjQ-e%y4jQ5}-7G$Mpylx@^VRMGp43@ea*a{)yg-ef%A4lrEeI ztl^{iTwk2EWJPmN<oX@@F!i1#*0ZrVnDvY`cl60f^vSC>LZ1H*2Ne2$q$e;i{o6hM zOLZ%opO^JtSGojxd<1}u1FZ7MZ$O0>@x_|K*2$b`RtTnHd#+7I)NvW;!r$-F`CGqN z?GZg_SIDx7&s;sP*f(*4qU!vj3brI`T3r4X62wt~Fm^%>^oc?0v(X6qqi?m{_7Nj$ z=5(@x2AD)bxze|Jv892k<Z#S+qGU~)@T0%q5<@O7Z22v}H;C$yvWQhHNDx!7P8oN> z<<#22PH&;-&L$08F*q38W)NgB#+D4{K1;%t7#j##k(3iKu9?wkzy~r`uoGhUkyi5b zp=WGof#J~?=P{&7+@JJve!98d-K}8#jaiXlX>}nVlYmGPYb9R4>iE>{X?YW{cer_b znQ0(qnLkhX?2CE(ESE<_NbZ4+fbVM5s8*{7>W)ZFT*VSRWi}-NYO^hv3Gb^Fa$`t= zm)nD+T+ot`->pWYO>boPW&Ld-$x`xw0?JEqp`tnYW56=OUE?e~i~{(LzH{y08@FFf z!wzX6ol1+^B<;f?`--G}a{DaqSx|IKoQ4>93LIhJkaw8obFVHrhVO$qIl$J0a`n2~ zhH6bihGs{9P1&AC?p&TGrm3^51cPSzfFT#hfkMMRsl`FsZ?PMTEH;C^Egt~JXRppF zPO2|8Xr|>wcXj}@91Py92xt1q`@%{=`t`^Lq3(qu>Mo^9rAGwh84tvP5z^<zLyHc! z3<spx>^pkG(r5U9&`X>(t2B;c%Fxctw28{}YnwFP{~B4kNz1QzCnmJGG*{dfD$_p0 zbS%rCVq9&k3LzoZm|U53l!30miXxS<6mHPCmZn5Gx;5k77#uGZlsgeWMTJ2>fbegL zmb3gI2f00qijc+~mtTFzku$ePGs|oYWcK6Z3_-y<Q08a_7w2e#UA8N4g%%Eos+l=l ziP=^(?Yt##6tzJ{3#y;l^4n5r_IE>g@3P?OK$&f7NP3a*nrxc+>PjcC;;DNvWVd8- z|H!*tYP-O!vD9Vx3EtpB7GhIkLbI6C5}y*Nm-y^F{OqtIDZG<uQ<)uI6%#Y8F~s@2 z==GBiCN7g3WG6+L=D3;OUwhU5aqTc*X$|W>JZVpX=)dB3TIZdS1!i(vDnUh&M4Cs? z*aG}pVa31K*y5|Z>gqv?fda{Xp*~iZp(4+8*;A{43g__iMyJh!{ncK#Hd|g20d<J; zO>Vq{z%!Iyjc%_oC)iuY5(sU52Lsi`Lcc5;?%|*tTh~BA*QSb+@taj%{r0<U0Sn&L zT7%}u^rr_<xv?(MD{G~sA#cja$VIUu=xwst@2A)^NNWY6KXPVMOTYr-7u7yQSMw@t z#s*GIctk-m;~mr#_Kdb7{ub=4dA$8y(i5=#w4H6<&uotiuWS%*`UB2S%#J*DIc+t) z`PB#*A8r)vvlyU~B-T(tD+?trISr+;QRb4fRGnh{+q?l)vO(h9Q*#vLXUL`A*?_ZE z`Q=@;X^c%Ke6RGVTtmFmoF#ES*JY1PD&5#7+Pu)s1|d6lOU^7uxIsPfj$Rmr`1*4_ z;N6ErbIK*;^0<RWuzCQ`_JYx;7m&6OnI>~m#`~yZ%C*6}=<<b(x$yKl`V!!l^|dA8 z(_O&`?EnphlLeWIB?KW~*02Y<e`hU*F=0$MTQzQ|)~yAdtPUg43F#ZC(M5*gpH@p2 z#(!YVurdGJ<=T&&#U?`x`KQ~;w}uwGce;Ur+p=D~rrfk<rCp|gSyd{HNDQXXn{nB* z?U1@_{AVP!5e@-*B6HnkDlNvY)a6+IdUNRfaHxVxpG%OiDyXINQ9vScNeA67KdnW} zW4W7H3KR+#(<i}Odq^C?^en;S{e*Ip_~}Z}9*gdbOgO$Oe#iJVge-_)41GpvTt9es zKcZzk!UhdGTOp?DEs`Ku(&o|D&P%Y1x$}LXKuBoVquhkYRRJQu(Dyy+`F8Ib>dZ4Y zkg9V?a$lZpFU~mdNt-Z}4v8AQXyMx^%QG+0<OGuSi>xn2w>01Ms)A}W1r-7@sNU|h zA&Y(n%q7m0)EC*<D4*+Ny;z;(g?I60(gb@chE5>LqNdsv534q50RI713t=o!`Bqa) z1=X*$b)APe4NJMLiv{u$JPG29*=fK^rPxKizL_XBZG+_38vhToZ{><jqAMs?Xk1^c z0GMF$E+klKJO^7rX(dQ$91l%F1}<;`JG?Y3l-}J~XwnTZDmQk()SXM3H`7>z34<gr z+!0Aex^bt=6%uWt!m7D^j;rCTYgDyK+wQaUdfUNu(fbJyDUcn7BwSPdR~Ka<g7fV1 zcE!PRekgG9$MrZL74J9BCKM`Yx+&U|9zl||ppqcO8)2>AvWz`tUSArl6s3p)Au%$x ztwT3x=3A6|Ck*r>t>~PPkPtws^=fahpJR2OgO}XLJ8?(FmFR(mOd=$hn`zK|b^w5B zp&H{U$0Unc@<yas0>K5r<={AieEf_xZ+r902DbG7qU;@DZ0nkJ;kIqtwvFAkZQHhO z_ip#@?%lR++qP}r{_Z^|=iL9ix%vK#nUR^1wPrF_=BgT1_0;p2L4Ni^G$u{Q6Ynf{ z1FEqqC%yqxK$PK|xtnx043@|UY-AVo#4y2u{Oa;e-flCAbBzuOSk}r;vV(qaLR4By z^AF8JTYs*q-cQQ+RbvYX^x;-FpZYlTsk6hvX0|b^Ex%qKrP2xV+}I#|#01t)h8^{Z z_4oj}FM7ZyfJtBEK=MsUUYAKRb$cRRQD19ksbBuf24>3Ux+J$xRLgFnsMGg*=%mU` zHJQM5|LC!QUhlglLd}K55*8THv2-rftG>32BMMaAyIH)>1<MS0y77^ReyIgdwI^`i zlc(P@`r@t|D7I+`UINq*<9=L_FE)YHf?`(wR%|qpP<tem=Fyk{RxxLxXL3cM544`P zM^$99g5}zy&s@CdK;Et9`Z~pzKH*6nKj@3Lm~%N&FoFpc2{zzL<2IeRV$eRRjBq%M z?(i~}Mcl*tAz3wclW(Z1O^SPn3wPwNmO#g9n}NomXdT%*95ozR?(P-e6M+x|E4&xz zrRH=X9#cG!P8t<aK1`hccH<W?rhO{yKI9Dh9}BI*(inYTtpj+t&v$1Re(B$f;@$i( zcgk^3jH*!CMn5{)qw)Z&AehMfr6d>O2sqeR@Dh!*bq42LHN}pyJJhzlF!^&fcs9sG z`sky?7Z^Q*XJ7B$jjR*)LMg!9_i`r-&}M&?Nl*+0ZeQpIk%20cd~*r}1D8>%hmUD` zvF-WV#}s(n*A)kRd<Tg}AhwX67RD;On{JJ~liL7Slw%c}34MaCS$FR*YK_vBRthip zgk$T6r-CIe6#Ac>fV>V$>V}OD90>ERDdEEgj!Doc^DuhndWZWsB9fH}fA>cfIwg+b z{q9G%X>Ad_N;NS`YUe6FhT+EN>$?h9JIHD2KwNg1?n*~eLKioNXw^*`;SI`}n;fc? zs2KPod%3{)v|^;*WVD<uX`s1!H@U=pxOsi8YP5-n7m&Zzmb#^=h~u2xU<+qaUx;sY zn<kTGp)RnV(6(8?JYvybVBO^^I4MUMywUR(KTQP6lT2c0ibn{-4`Z#p!>ynUm-Q|P zW&h_$0ghp2!;pDJZ)$C!WW5C*DI8*zXKCs-NTVCZ>KJRSiYuxq*J6mnkeAu??kN;F znxUl)^l}7S%0E=LLAw93UD$$=6XD$gkSI7u?4&hts!um?#)(uMW0LUUc$Fy!%f~1d z>CH@OUwyWjnS?j+LAm)U01PsD(&$n9mq@)u#TN_PbUt-D;2<h-NxI&>_xx{t--^iQ z?WWs58@v_46ls$ZW(aT34va!Pm?YJSvyjKBv>`OB7?UDa>q^~8%D{{!nzEdXw6E!g zvUy&gEME~}X|qNBQUTrg@=fF1_;~wGm`lOMHi?&<sYYU{z-^(~1WOh!cgOSIx<N7i zSsopsz0279%pR~eZo;4=Of@0nWSH>mz04`GuDt<sP5Zm>f};J*UOk*sZISgfcIu^C zcgH2q*YHoxr)bxOqyfZ$YxOfo*}?hVm<_?9zf&HeUjQ_ZDRIThs~beirSs@3_24Q- z!LEZqiIhuCFMm-4g}j01FfxvXN4!X7Gq#qpn~9y;RF~;Iwc%Qu*-FCQpvqCgXhFGG zXq2`2$-RJw9_7-r>=J$*tpBc{ENFap+0{uT72UW~lybiK%)+_+yl&@)9CM}pz^ClF za{fn${NHKd{{w5x!pZi3I#~W4QQM?(+n?%N=rd19+ApXaBO~m3o2-ar9n`kWXsSLA zWD+`L{p2FKZ6g@tUqY5`eK_A=pRd~fIFRw}J6dSgO|^uf#hSw;USyCAg{%^ay)5Lb z0T&ePL>p$$BtxC*mOLDx%_b)O;v}J8=21>IS%mmwO%8KAY|y&Ev62MdwJf2Sgc1ti z?Y!~8SDVPr(y$)bDXa-prjkP~RU^VT%>Izb>GHOxe9X>uK$V<98JbLV8WYAC4gh(b zh1BtC7;g(rDSD`_mw2I9PmkGZpVdlemZDnSj}TCO;#4wGO{ZZJ_+$^H*BjXET67YT z5JKD_wu-3~eB{T71W!~xpkn~J3>Kcg`=n}i4hvC}X;raGLyaGOlTxRix6@hgcXAk* zmVWTmrb7A|a~hhfrkk|8=*p3Dzw9$u^-s;_TuqcxVm7N=MnSyH5VtDSCBRGt*Ipgt zWTnt;n)d4E3psYf#fb<rREO|Cww6jdvfe!1p*f>J{rNv<45%qJ*@m~oa{4jcxWA2b zpi}z6a{vyojgIFJm^BWP=10*;Qzce{;1^!KG}_Cj8sYVS#q~qC7wBPA9@gFQ1G7%I zn-cY=I#?(rQj*?|vv9>qwA9C3-Wd#eL4nT1c`R%eZu7_5R+Q3zknZVeH$xKr(;LL` zPxOJT98CXi6V#=~y6rj#g3q%W#7Pv$0*!<MyMC=eCWjyt`>KmJ4VsMs1)C9ce6ezx zOub%re-_bdDt5bI4ZM#yO;Udbvr}k)espDVNM%&-`{~YRE4C(Kr1y5?A2(Hhg_Czx z1cd`+tF{`xbr{5H%sGOFdG83-vs)gCR?o~E?lAo<be=4y<MW50!3_it0|>MOPoy?O zcZN*3E?9_Y!zdQlK7^2Djr+%)do^oX{i~pm1niKdpk!^W38#c%ZFkwqtlnJUidrKP z-dhU3X!2e-Iq#c+dz55;oUx0R@a2xZ5aDngN#kFKvcY&S_*dW<L}zti`cj~RE6)}F z3c-Mfc(?>I@*oT;P^U3+T3ZOq!i27ZY2X9$hq4k)z*0Pc7|?O7lIx=a9RRNj=UA1h znJ@Gh^92<PX?0ZDgtr$YT3sr{_Z;Jnyk6yL+CEruvuvhufs@1tc1eQ}MM>XI*0T_= zfIgT_+URr43)Zu|*0^TQ>{>R3uv(<K$E$mXBU~6aY#MoipjXogqCf{%+d0z&<Dj?z z;Dr$9LJ4=)@EXIIn=-2FXIx)76{3ul%bBU(KKNEuV?6UJ>1N}WjbSZ*xberLR}9wA z$nG`B>mY$pLIuQ-EL`3V{4s1QIO^Y@3<5dTd)&J!I>wusc6{tF`6#^^%p`<;()ESx zGL?nd8)b4|m9amJ4Zrsdxn-qj6Z@~I@sM7i&QXwc7Lb_oDToG;Rm0Y3`sE>mo^GWW zh9+O7vhLIV-m{zIcGJdrTZ`@>qKM4I2zrI5Q|{X(TIVc5w;pVA64FX=*awwzcKInG z;pzZFsT+fgStb~x0<13$08tDNKzwas14aYUCsOy!LbUoqFy5G$5vch_ABTh+e9>Hq zNQMN!n4(y^b<3Z*ENSM3<s7fup=oCuWkCKGpEN9UawZxCNh%>P9JTiLVRQ=TedEZ~ zj;@mZ-dZSu6NNW=5o=3A@D{9>7(f?sV#1U8<0CH4pSUxakS$ABlJ=v`!pHEy+Rv0J zT}AFAzOf85u1B6!K3*QhM{~hi=;#6q6Z4kmUJZG8clOZ+AO4;BksY(;cV<HFE_4@E zS8NqKzOxX4GIGzAr6!Tn=|1~5oG%ZZH0Voy%t$}<>Nqi&Pm*@?5URFb1va;c73t1V zo|&a<wmF+&(7*>xSu@M#SqojUHz=}mBEm@#yjR1!f2i$d`0QUl7IpUrAK$%_I}miX zQ_$+<MbaJNg3mq>**-tbdR|lL$TH#;s!iUdqkidD7O3UO{m4Bm=9ns9){r@4`j1+v zogLnIWOc3$vE%NWPdw~u@L>-sM}2I0GXx=~-AdL(&g9<MhOaFyRHf^n8S@W%pt)8V zW;3f?(d9XtOMn>usdk$dq##6Cgx$fcBa$!|?XOpoMao7LQ|)Yr3l7R8ws4mRDewW^ z?%kjJGD_w<tCaF-@|`m;ox64}m1!&8)Z4_g$|@C4+SDv);t}-Nu;+(LIoo~QFU3o{ z`F6}OlK|PGVM~(SWvd*OTU7*Cj7!*vx>b?aQ-XN5%)sh3QqHD!!8d~)!Z;yxI)h4B zrAWr5fm%1a$PiDvvuNThFXa;n*mj|<ny75Tyc*FMWeoKwQNnby(?TpgA)Q2FIZA># z8R-bAsC2;8q&~(a*OsDCq|1zseRF0{4eu;y)fD$a<*sk!Mrj=!lZjLdUuw1YDxI-O z`kWX8zy2Go;xB`g2{lQ$suoGv4ZC8bQ~U`Yl0{3o2A}3@n2U%m+CZ35W*rMD=qg)h z7fp*&DCTvj)aoG6T$!p-Jd{hQ(Ij!FG>o?RL`6{81u_)ibM0iYTV-^q92HB={JdQ> zD2&KKDZJa8_@XkTxOs3v6&hoFDORs?*ajt$;2Z<QH|1$I4wWR5M$$vNxXikQyA@?; zV2xZx(=K2Qn8BmY<Uks`DW;5ddR8<ZnT5ZB^lj|+93lg{dP|eh6&G<~Xbn?UZj?|# zc}iL*@Rm|efR<y>KDHjODmrjgbYInHcjav#cID$addWPuiWl*E9TU~gd<6m1n%8WD z(@cL{wQr))9U7tcf4J7~J{>5}(kAO=g1-Uh)rx2T$^WqYcmMPMst|MjHz6CApKtw} zO}dksT2Z*Ih(An+vp-CS_+@m8kQ04ZSmXg9(U)N)Lo}O~7Dk4qf%G-6&##iqX4ZBW zoR^OogACbas#3+(=elQfjDIMlNr!j_m9uLiR<kLRLSX{?k{un1WXXc^C__0Ya%zOK z6DjN9Buh$3(DM?RN%4Wbq=M=qfZkJ;$qIH*=pyd(_I`L`3nCotMJA9nT*YaS!5yS4 zkd-D@f|B-ejXVrh#7G_X&V542ruIYiZP*;4<jfDKg9T0Sl|GVhMfj?V>?b9K#8-q- zk^{^3LW7x>_OA4+B?L0|fmsOgjKD1Qhiv;0kZ(9syrl&t95gujX%7QY8Au}HM59Tm zcYw;Iju_E?p2obv8jfM4Zm^ml1n3xp2b7eELkVDk@fHOmN&Mt5&Vn+GWTFTjTnl1p zjsRZ@Qfwcnm|S<ApN9eF&sec@;3c3+H7kl!6Lzv9Oui_9p6xHGGtdJx6}ia(Mpb)` z<WG=Qi(M+s2XC6sMgyL>P!J372MmQTl(*&?LrH${lFC1lX9$YoW*>xFA{H+jxs+$< zE}0|tUynAbi6QB)LZKEJ#<-HiG-4u6hkEiyNP?@}%b$l;)MtDm2g-A{NrJQ*pP?r+ z6Vu#CU=nLKEF~Ye&%r6V$O<Z;)Uscn<T*_Aq21BMu?4Ti4r5H+*v!_ON-8!0UzxLh zfr;)Nn+e<GfTQ@BsgcF-Oc+3i$J55i`F!TL;qvzL@OXUMyLs4rbJhNSJUs0FDXMCB zZmpdk12PhHaD2Spr1i&5@3*vY@K`)vKH$jmkXvVQPC)*W>osKtNaGOeYq%}}hyT+* ze|l3=Zl*TByZaEPM!($Fu*|>O?W?Jol-WkpAPPx4gZ8HA2)ij1;#1|9-SvJ2<fjLp ztZ@V~&H-d{s6p89TR>(>QwD9{(kiVKn>kRPN~%uxoHKyzH{>rr=mq0g`$;?a(o>wv zP7zW73ZBm_;4?PO_+-a$X2HYYZ%9Bgv7w)=rMQLY0fh%NHIW-EZPj3^p~f2#b=?f6 zsHQm@$Plq&gvBqS^_T{F7{bgY&5>l!a%iTNHWT5sL(S<hWr~Rpypj>=sy92hV})nR z^XO#Pa<AZHOp6DSIh+=?gPYjoS<B1yB~{y)M!S*hf#c;*#8ZW5uLQ8lB5Woqq{~zU z6>2H%wn18Xy=G_I&F#I8+0W*%d6#Pw=(*c$L_wq3RuJtH4&uuk5zX^JoXp+FgtazH zb6t<%Ig+$^=HCj>0_iVk6k|QB<H^4{{D$LmAtmZNz%}<SSVx+}9@NtW4C)KMN_MtD zi=>^zOX`uIXFS913^Ga3(iZhw(foNE8XCO>u<opHp0$c*O{q><6klY324d;{66rQ( zBUH;DxeAvS9Day5j^M~M4FkoA8HEAis5-3OvX2sN4uG)fH+c+ZOKCJJ?`%wgC&PRJ z|AggCBGk4`@BUx0s$-bGaYx|^?E5bMcT$2jmX28FSFnyE!(|o{;$1$ZB(n`PHs@OT zUI19*6XwE@qoeC4#Y|c}zi&9{C{>ih7BcRa%Jb8pZi-S#i)piwDUrI)`A%p~{?6DJ za*4)44;X~qEf>odSE^_(xzw&ndunLaEJ|7{PK7HYN_P^9U5FR~q5tX%3*Y@V_K4#~ zWs$^z*)$VI4e0=BUo5sW_`z|CQ}+Mfh}n_#y#X>yhfcl*^@A!QS_tF7lbw!oJ2LQO z!u|S+^DAJ_fz|n&PepC6LBHMU`M6h~<b;vL>XqC3P8Ov`$*`i6#A((O&P^`tQ<m*O zmkg)pcpJJp?eFS9rY<M2*b>J|NyXlB%eNHGH|0)#t`0ONxHimn#BonKgJXh{KKm}U zPI-!vaLsvb>{EYII2u<)w+-jydjPJ_IsRBDcAz%Fu7)TRhabG9E!t8$m_^MmKk>@J zoIhLS5dAj5yL<EUsN%D>qdLF)BQG<*tMPt#`LJgs=hN}AK?lbVB+>5uJ_Mfw=I%Da zu6C`v{B-mdZXNwuX+xieU*($-3Qz3_5mTSf5hr_bdxs@Wrd$EsFUF+s4y5*Be;2dE z^nf8QE8UgCCd7RBJ6qvXV1t|t`AqiLPur$L%5$wOW%OVDpH2NbS|7&h8@J}xDF2S* z2Hj%~n4z3H^97wUD4`jcw(p~CGG8)FJXfX1y!;_#AUcs<vOaO0mu2+wBRNgpN%wXQ zekHt5`(0YLf)jONEK{KS^)q|mh+Y`sBC4?t_*4*QFURf3)%<!MqKF}iWaCHO9>xMp zk%Iz31fLv3ADo{S8`T^BnYXra<dDDpcw}zN_bm$O!%OgG`7q`9v%OK+`YaIEM>&r; zy_x8J1D*Q#>DuC)elobDU89kyj7}Szt8&;hoBan0qhnLx4}WL2e_drt3l%PIuxB{4 z%)GO>lWn(^$KF224EEhden@uB&EJvp$aHVb&!xF*t{q#v54=(*_>gSGfxhII`qcwm zA{XcSXq=*tHv&|1_pq<{bp$)B@8cf8BF2H>Lh>Owl01kP5huh2<3<phaXU8spXnI; z-qYa-nM&yKq{J7A0FmX}I!Bp*vrPBX+h@*h9nCsHS*b#XhFucI;Sa6E2Gn*xr)Kc` zy-1D$Avh_2&Jwra)7BW-0+s`9<<Oi*jE9Yu4T{ypGr(LNalRkXuh}y_;2G_KD-nq- zx`?b0(&mnMvX3KEUMI*UVJ?2j+CVg5D6w(_@hinKZK%x%Cc-hg0OUqmko-Q6%_S8p zXiNp|Q#^U1>c43*GYv7*%<)Ors_ti4fs(t$pit6{Y~>k!nUZL0SHj5=Vzj4X-WT8$ zOkvtrAgvaKw2IJL(Q9|V2(6BnSgU%lAMgbJc01v1L-m^ZGre+~bs?K5Uph3RAni62 zNIU&FyI^kCWN&zi&jpm<VOpe);Siot$yXp6MYL4*ccECM)^#+SinN_7ZZED=?1hN1 z#eQPR;};T8y_mH~mx_=llGjaRiXTBlDQ&@%nr5Z_dXZ0-0g)pb+nggWBmT&35(k;; zdG;JF=q43zSwC_0GZ9D_WV|6-(Vs?#Mo>OIuNH6(s&*q}QI^J4evnMk8OZHb$t9c1 zhMs-Pb<g#9_tY)`C+=f(hGv36DT0iGgVj2G*&&UCU=2mMwI)TyK#3*1eA|UvBy3{4 zHI04*E)d%N!$iLT^x5-wwXkqXC$i69@`<Slu=_7yL){S~$qh_fI|trq+pqZD`apL7 za0Fyx{O?D=|7@6N{`b|0FEcm)RfF%@{#1il`N=`RkSZpBtdKP&6v(g*_cIiU5{x&{ zNT+K1ER6egb0;S9r#Zvp*2vN`y6|k_#tq}2jx0#hSjvE39|e^|LRZE|2kS3+n}8+< z3#s>x5cf46NuAHS3SW8WbT?x>Fw*JgA<4~2a|zQ!TxJp3vN2T`a?v^}<3=9`(F3Ei zlpVT~^~VR}HSbOC+%h+&&OC1cMHSAhQBKAT`uy^q%KNPWAEXDi5G)aKY=q3emKOvq z2%R>=W+|(k>mJN0oTg~`-H@D1@#qM%3VnIryuUgh_I^4)`LbE9MEfq{gVlqtCX@f@ z!+HyMFI<^F9C0Ijc_^H~A&ka^?buuTxp?cXWr{l1(kY~%faR1P`Sa^$$bc^uVqu8Y zfl!}(Of)O*x~h^$WMYezlf^Mk4`4#=3IW7gk*{t4QdLPFk)%fRc&a#zsAx3T5@Pe_ zp0sLR&^eWSUa-nYl|8@gOKzZGWlqw|90`YFrqL82=~B3k{@WLj-Aae~Ds)UU8X1B` zo36vF*0`bH?m{Dr(>;6ScFv+})yXl|xFv)|Z0S2wFLnM1y^5yO#E;|Y9{;#)ygfuB zd^@o`G_UxVH72uyE&nY2RiiFg0?pgCku7KP%ItuGv`cnW_i*2x4R>4T8%{W%Bn6UQ zK0`TBMq#mSF&WaDbF;D#VAleLAo8x*_F|4^{!F2%zc^C<xpl4+dVi-zgyAvU@TXnJ ztIcKxYrx&$7nNbKFc~onW|qx}WHjOVS7E$Dk<d^m9Hv%VdTk?vYZ{Z(W2qvR3ytYV zbQI3B=bSSy^l(twnJc=6(&*f6nasmqe8wXX1_sU}K%)=hrW>^t$C`9nJ@e_b>tXcn z<MFs@^jqTl5d7OgzZm+KEw82;JCpHJGpXs+9NO>m_9*ud+Ge+;cV0~qKbzBTv`6#P z**jWuNL|74&Cib~&yKLD?f&BK=8q_QL|*N$_U(v1wVk{5_0`SG&0arekMGLT5-C5I z)6+m_2TI6~1oPWIi4|Qc6y3EnQRI4JR?#UvI~`wom#ON0tteLk?R_A!u}dNyOY}eC z&kK&B8|bdUQD}UNC-;^_a53%rG|ugA4jF3zEgBA9l#hk#80Nqa(QL*_v;<tPKwh{h zp5fz_h%mRxzAND^J-W;wb<=dghzMscg36P7f;L}Li1z6nFMNP6l~Yhw1r+QGur71} zjKT3z`R>7yottTLVT49>yV<z(N5d3@dpABKJad};IJxlpQ|SOxJE8m+J><5_v-lVl zEWdG&4IsDk%olK3Z}j`4shDkJtOp4_r2<M5U+2;-yz=WZ*TSJ_!ykyRh#uF_M5HtZ zLt)q3<gtfe=u8?@9C$mNZRUp2e&VQ^nF0K(xne|f_gbgm0;c%Q#`CGjP)wGl;*CD( zsmWm(4NJNLmQC>_lA-?2IVrjr=uplcv!Ve6@^nMCqFa3QteCB>lAZFi)V!0RP^yyX zCKzx*l;yVvkloR?QzuMkebFWvSd(5tB%hCLD=QV3Up>bT(Rr0ePvq`O&j8Nar*JOP zXDe&zPb+#ZX1iM^4H8<|gJUBy0e^{D9KNC}y4?@d6kTryy};Pm?W5ZlLX}~f<tH^; zatSR_iV;g*M;8`zI5)!6e1&(wdusjepaY-4;R4+Ow@460vS0Yb2p|nCJ*k{Demxe~ zAO4Z&^plNWZ<>%3{(vUD_hI-aOUv|6^?Nqve_JbNQe!>#U(_VeY9|U{bu`ySc-YoR zEGq?<o>6GxfdZ)(TK=@0i8yZGUBU@<q*AU+uAUz1G@^6;yV<Qci5%)69PaF%pDb^? zwDSSK5|U}$Gr^&VX-)EenwcSUOnbxPiHU~YluzxG&}VuKQ00a}!l>_8jq6#aX69nL zWz>cm@g_H>7(zyoP7FB`c}O&)`FT6>J3X*`FcIYez>T}}{zZaCay}a-$C2K<@(w_Z zcB-#7tqrctK*AC9M3o-xi*3*i`9p#w^IpB0h_#X!ObfaD^l+Yj$3VB&SSHO#MnYpX ziIot91;r4|SDp7O`L;8V77@gN5@?XJFYgc&lOZb)V!@f{Y*Tz~4VDmvaZoT7Ah>jW zib{_sow0v+nGrQ#<8e|NL@@i@N+r(*pYUHqSZX1br}=tWb<yZYRU7FfpW%!$+WaRc z*fuf>dMbhjWz;B_#6yrT$sMpvScGLKHt`10L^n2r7%!!+PgKqGqfQzbkC+uzT3#6C zPiwWnM5D{+JYI)<O~sUO=@}X4wAA75M13sxJ1VVmpdqUQH|=qhBHRL*=v$z%J_ayI zvcNvKbngN|5LGKS0>~jNuP?rW*1stFRPh0D-j(-dfWZ)VxvHjme13!V+c&eG^eXt_ zoU=whi_zFyNCUUwR~$9re}#W?!(I+@p9w<~^;9$qMsZ?<Z-db)iHpJ*TaW}-M?>T@ z+v_%;F=St=Jlosu^`U8~4UE}(%Z4dbW%k4-k<goV)@+S`v3Kkn0zY;Fi%?KjJ;VmV zkS&rj>5gy|fsC@O)l&ozfCt4eRE^`q-!Bvh5+V=(aUVfX<=@O=qMVaS;nrkgOvy5o z;p*BK(gfB@3JhvmCQ&3HB%YZy`HksuXzIdJKT9IPd>Tv=j&;-5Nx(%SCZPP+G&ZEQ zKR0#*gM+w+n>4RCAjl)CrBZZ)6aQnIcHa0jvk7cb8)=Q%3h`KTiKh76#Tf|e9Siv_ zq2-33Mn;v8AeRfuZ`(QTuPdA5$1u(B<ty7&%g4FLBo3z-t~ny8MV9(*P3tJGA$?;= zAf3~47xzzV8<3~gds!VVgCk3`4xQCvm(JP{Xa<?zT{D~>ZGQJJCu<%}p00%!r=HSa z!P%NZeDzk4xL+)8#Pc1RZLROPr@gqRL$<0HFc<M;w_}RHlj~Tuoxdy&$*$)X|CXa$ z^K1cd+V8jW0`y2$hqB?nSENkE&B<BxWb>&UW?XM*a8AmZTCA=)UwZ#8<#AMRXLzA` z&>8;*#fgCEz62mZK?n}tRF9yTQwJC7cM!iW{B$O4bDZrJTF_naR8~-xA-%aW$v<sV zYwo*<1Dxq~z{SoE<8SMlpxL8x5d&UUYTjRLasWKG(fR0vS0SgKJVZMwgeOuSuoKn` zM0|Y)#1~QISZh#vfPARdbjJ92D!7FB^b7JU1AJQv0-3TS!c+x0`aw`&1_l~WaFYai zB-VxiRr9Oi#@^~%x4m1cUcXK32}qI@ecGwGT#UEMfy?T0N06`gsVQg8p7&pE!bOh1 zzWc9{;$;fzZTif`Wg-8mX2o4vm0wq7l!yu-{h*<r^Ije5D!*NF&s>+Be;Tk{ov@1n zn%bpj2)!<NV}*c0qnzHym-&Gm*zR%~SV|(A$@j8w%--f-aZ&r#>u<fXa+2Wu<-Qu6 zc3A23gJoDA!UyLdN1w5MDQcgpLue_lAYQ}}mb^z#k~36dAFvzNBImXHq=WMmR{)3q zo%y|`q()yP9xs&%JdTPIArY}+!<x9*T(Nx|nJl=ec(zA9N3DWElYxs$=hlc!dg%!J zE)N+>L~BQ7sTw--_EZ4oE*c!Js$!&0wB_qtiY)v2C1Cvdl^2_XfAaMj&~^;I*um#b z%#R$M?7y*3<Zm#*$XyW~uJ^vB%sBEqTE$sh;^8V7;jL7jB{&2?`NRECNXiIzRnX9v zmm7L-ld3-JyS7UQHe|Sb>;tYDOY*v5_}7e`Hn&~j*s_>AKrn8Sf7J5a&R4%rICHh| z=82yF!*xPb9pm29kzaM?Gdz@ExGXA3kL>DP?s>lD$nWM;EOYWqq=6b<t<!8;5h`+w z)Q)#jI7LJmFoT;T(kC#!&VV3;a?i)L60%^r_qnxkS8p0RiYz-Vj`ah3>q@TvAN|!o zl((7wlS%8}DR0N|+5s`bgg$>j#f=J_d2@C(S_&GLXTmbd(}{|2<g14H`^9m3>TtQ# znRNf;CJewKpdYmt=6M)uY{G$(<wndiARPB;IVor>8jP6E>w*c|5hUP-Z@v9WO^=w* z)ApYh7JXM>-i`d?{w^1EB`1*tzKb$xJs~#z)~rO-T%{EZhwb-}c12LCp#(dHzp2_n z`Rd?Y<ex|eeZ}7+kzO*3blXiYkfD@pBpFb!QFwpr#I$_Bd1t_Tba7+_d^~JpW)5rP zb1wN7c?XlImifo<iTxj(ItL5Kzl{MnRM)awW5Dn^R(nA#GO#{2d}jm+GYtVD1#__~ zDb=Ds2d-TByXgCsO=bd$WFHYA=~V|hb$tK(+R>WW9vT6oY32+fB1!JvVC8IFmA;08 z07Nq!k-!c>G`_V83&-3DeT3S63+}qQiW{T(+u3)d+KS8z(7<2ts!i1vAfPIUV6W(9 z=~*Q4)d3~A-(qi+A+}B)iZv=}0y~BY5!SIBz-a{a4;@*2-rc$${4+X4g4WBsR4X$O z2G7y@QIhcr(6Nq?2DVWLh)jlu9o)H~L~+_kXVC19$x%#S0HtX-B12@>hAe##nmu6& z+PIMnLeK)?*j;%Bv~i&$s%P_92%J{MDH?RD;-9FpF*egO$j}Xk$P^PAsGh5@PyBF= zlPK$*$vzh7DRJ6YwKUwoHF`HW+>3^0A_8kMfTdZ02}Nyh<<9r<q&Khgrj5BxRriQr zauiW7Z+Er(c}>4|PN&}OY(d_C)pWi+BG!OGNZ01Y8ITcW$nbnCk6ehj13zkE`J!XD z?RbCLcjE%h$qo|S4hiYy+2V0yG}0e0YlehJl$R@_a<GN<QzXJhTgy%L6LBI@lRHpJ z^(udAdhSi|-xe77{N>~Syja0H?86owc`IDuhb>>wETeAJ0k)jXlR2%^6zlhF<SV+L zCqQ5&M>Q#HJ!d<Bsm4+Maw#*tnjgBNAKUf6GD{-CllDm{$_);5Ph3>&Vddz-!nrYl zi<K43&$PJz5~jX(hi37BH;6<CTb)t0wiQW=>8$@CKMhfk;U{XcA)qePyi7)<ysm&! zz@V&@XR5_R7J?l*m|Q6_?A54|-^`j|>S4j4IBc(DYHbtEoFP@)BvNxZy+07>6(9vf zK{^z10-_md?UWXf`B=^GgdbL7rymu@mzEC6Wu^631ERWSHmyAYF+z&#AW3E&G$%v< z{iyw6T1U<fH!>^Eu#kvtCdh^8t3FV0W)O$PLCt9|n!siP@J<iGVfs*F;n(?I1AM8i zJ(Wn48T(Gesfg|!R@jDq9TOu2(9BEQ>Ep;golBRqd0CCdwu&qGcpqT_Q-LP@=`^?N zzVZ;?U`F;5b{}9xu!Fx7a2*dH!?;kN_ZuF6xP}XA^$oglsQ2uj%-H{>`}_Z@adB|` zw=PKbe;Zaisi_l%GmPr9{iEh}D<!j8{a1?srYR&*0H|*+2$^ug)9oNVT!*-_=k=Mh z+0@cBWh5z<Wt}Gc(Dm_Bsl;w`8qdX1g4D%PMj2L!UZRNPQZtD~N>L`!@x)oOZGP8y za9>p_bX}2}^c=65L?s2fLj5nFDhn$n7jNT|(O_cz&>vb(RqiBmD$=V~QbSC3D<ayJ zG$|?L#!!$>GH<{#^1H3Q)x;KM$Ot56cph1r6|h8-CM=4g2yAdD4Z~q>fj(|DXq1jT z2Jp#He(g^n9&BkrBU%#djoUR%6f4<y>l^5@u(BRq>0zv!iDAuQ{Csz|qEK4u3X&L1 z(@0)TSTN8rxV<@`X>jVkP2E6Br@25i|00QqJz6Pom3_!4Vk|2Mb+#q0qOE>acU6|9 z8zw4(;CUN~S_~_~U2Oq~V=JB~2#ahOm_N6F<9RIZYw(TO<Jbdv2|fDp7}_Jil{n%s zLoV|TRrYy7;O2QQfaGdq9W+-u&|rB2%H`d`q+}Qt1uSj~H+AF|JM`gC%bIR!q_uqr zsEgOY>l`gva#SQ@Shs}xpEd0jq$bDQ3;w7MV*=(ivfc1B>QX(;<aCJJ_s()Px=R%v zFv<3Ev`X&uo^SpQE7~0hu)eXv|1x9ssNUDupx|v$r*K-K!jTA-8^XWrB}hKMnTm|j zEVbu&oRV`G35So3K~z&V_a`JNy^#eZRCIp!9zfFm+8a%ZnjH80Y?H~dv$eIoremY$ z`*3Ej`o0^V<fmub-s)=K>he-S_&$6*lFQ<^>+%xa-!r`bd^)4+B(mi!l~33p5_JCq zp)yB9BmYju>ygMtKX(+@Om8=TWbxL&zMkv%;P>GUxlPg3dDW@f+0o%CT(`+aSX{}{ z{q&~t_I3{a@$Q(&V1~vaTe3m4BjR+sGl4nlnn@BJS5cytcDUATN0cq7w582C@z>KM z_h9}3igUE~@!8_OfBOrrc{~>RMyR#l!;Y`R=l#tsMGJFGJRNhYLpj57;GW3j#qh}F zuOu#sa|V;5L6r%iQHuecO<A3zDb5OJN--o3ih=^Gla4!C5y4~!g6H>)*x0nK-BoBD zuW(gjs5oXEZ_>!6%#&KU)g|AxgZbF5E{Zn&JM{vi_H2hxD*CEIZ)n!>wQaSo_3n$s z{l{s2gGcM<C0*wiM{17VS4ZcHH@NP4R{OJpxF-)j;r-WBe|!1myN&~<mEWfBx8v*O zrJaRHhRb*~(V^rjci-{rA-BKC>tF6q#M0~9@6shfE0l9Wk;*M-zK|~TQt5y{JxcME zCn(lX+y~3Y5@^hYy$_fw5Ak!ElE2v8jVWPKISb+N9kDcXwFjnC=ckOMP?SL8ajZ2e z2~1Xq>rG6iK^q;`>LQ7u`IwY4iPpzz=djK|iFOh)=JflpaQC;8|A=Fz;APM*l8CLd z+mxx))$=oHQO(id%aoPAZoMRAAQj5R1{h}|^^2;W#!Vy#3gPw7HIN=vS5(DKq@JwR z|BCBsCS`BHkE7KvEFDEly534o=W;xCT{7hg{TiHn5F2~Pt6&w{oc+%Cw%(9rb2g63 zE0>Cmu)}nwrA>NcGQZC;0?-AE5gw_e6JFA-r)>&z9L4xT7cv4MDTB^8GCi3Z&ntGG zNQM5{3PTia1B(GsG~(xdN*e3a_v~1+`T7}WmRst#?N$a~xktAh=+QUv*A?|N!KwXw z6?6*j2-$ct?U{^@ct6S}#5<FTXiWSNbjqx45{)uigRLZVC1GG{D~-s}R4a9^&r!#5 zY3_CAC32O8-c_bchL!IcRPHC+C33*hiB!qK3tL;3iHU3v6S;l{a?J#!`Vk0?6HqFr z)_8WM$<z{4f(y~P$WlZFvIcpbtnu#=uK&Hz6k(0LN>(RhoHfFhU_-Pn@~?$f*#oYG zbCIh5&y5!6HG5E|QN>`o6bFZ*GUrxIYYg8f>Vuj)nk3=xdY_F1f^k?uH-Z3@d>2j( z$>O|e4*T#Cnnx5!K7L5&Qr@nRYY7Z4<@u%`6$VDwB!)li!R+~Rt|C>vVr|*_y<Y$% zl7sqIVo2tR(#E7nH3A>@rBfQO7`TxIq8om>B5BNt1fprtfiV%)2nE1Jnhm<B%;@Ws zCFbxwLL_R=FW_hl5e$`+Kt3+n!z6;Swf%AlH}^>hVN$7{`h>hkk~&c#1IrCBuuaCI z&7x$h+C#_CTrPNr*<GXJ%4m9|G|#cE__)Gxda({T-hsf&;5z~sj%~7V(dB#8PWo|W z266#L!4yqwA!Dr`SvXi#P?duQ(lv=Q{U!nQL}~^8!|>YTI-ej>UkD^nar6}6NH=k0 z9dwY&aX8;v#))~R7_+j;)mwP}AkQ=jrDTw&r6g^15sb%;#NgSotXgTpE)5D|&DJ@y zFV(_=2tdlN-3uI#2~AR)pNd8sOQZ%IFv&B-kT_sx4`U>I&E32K=JxAl)}I6*rDoh% zy$GZmYDal=vo~^Zv+8ZRdpqzwfH5W?+qJ-u!4Z*F(m<cS0|x=Y(HEU`KVph>#kk_) zVozjR8Np8#pLmc#dZ~>P@dta);ydn|dKn<?g@Y-;kRoPi#VHcXlMAtgV=@Q@E+$B& zD>0AaMBWF+^iHx!=`;fnu*%+OIKW_T_Ti!Rzt3t?rsV=X1wR{zqh1c9Ol;6lVMU99 zp)Fabe(t%tWN<Yw2z5@^Xi803`Reqec}w`xEpkb|V6RRN5dPsX!u%5%{7=1TMy7u| z2iTcu<CH0hGQ9mx`BXf$F{6X$riUc@1D7HiwIRP`5Q#9L3q(y~+y0^}#dL9BQQ4J| zmY@E1!+W~W00Myq=q+_Rcjbd6g{cuxRsp(Vp2_o9K{XdaQ3l!IbiW{q_UhiC7eG@1 z97Xyx^j&QLA9}usiQRSebwlWc1AJrfuk{zjoJjpWtcNgh>ZJ#OLK4`U`;jC?K%JO( z@I=IL>3!ZKOi>FVDGIcq^yt!mJ8{c<E4^&*?6&6)-(~{WQC7}v3l|+OAOgBUpdb)$ z-Hk@)1>vd}adRg()fJ*k@A@!R3XEqb0_&C_?TWvmsK6X{bVE3ZC(ukYT?1acS8v=Z zz2|8`p(2sQbc!_Xu)nw7!+y<4hh9DP_UO}0MvUcDNVKI;SBgHM9q2RcJlSQN^0w-K z)YH<5-*{TY$d;X8@a(63Qaqt4(OSAMolOQR*U56Zd(c<vc)E(L$@wdb@KeprdLFM4 zb)h|?c>eG<C?ES;TutJj+KXNMG&IYtjk?E{Hx7z^zsy!?nY=GW<k9DyhRE4BnktLa zHpt>{+%-**kDT1+Ar+Koa%g~%(WDBZsLQ2xTp<<KBkH^?k2>3DD3PPtgUqI(9rGzw zdWf&`blxaB;{wP&7fMTHU_OUtIH(kKE7P#qW)ti<_W68uaTR!j86{06ltC)U1xZQn zWd3@?(U#2k4DNIn{&waSO4;GO)C<c!@Gp~?8!9QoS8<1cyHjce!~$}47-b+(kz^pG z4G3|GK613mOP#fn#p0)qsi~H)#M<WwDk-SgN2#+P!DR*(+O{bzXMFThHF_>xk3YZ7 z4B=%wB|R7}sBvyk!3Hb5J4<HdIyLsH=Xc114RIFI`50lwrT@_H-jk)5jGlYC{*lqP zn3q!RWrNLP&~+a-#!Ei3x_TB_@qt$Q<Bd3i+F|s!Ij7V)$$Xz4C{C6PDP^(>M8QH9 zJH#vNy&fyd(&v|%L^kU1o(ujB$rGG+6g#cBJGEab=vnuLn0!g;V%mb(Mkj;sRC40I zHJ&FUyra~YRRd@Kc1LyK!(EmdP11Vm0j(&JsSE6K`!8_Vs_Z0Y>AS=9h2xenPgO^3 z{^%eVn*~hmG9*vPk5?6Cz9-x&>Aa*Mhur|~k1P$Cg5-I1k8jF=VuLuOwk^F6jz5l< z7q#gb)K)^Xp;t6ESDz``+Ezdjk5Put--s#I;RA1XG;9;6{sR@lFF5h(#KLrr0#$B1 zCr@a(=xG|q&LIX2>stZ4_W=f>G)&`=(+tiRSBN*W<uHPjb>k7$za#XREo!#W40we$ z<~Zwf@d-kmnQ=jHeQDsUSnmqz#jiY>iu3%m&(-}g+|pr;+IUf<?}Y_jq{a6cIRnce zr0!QeFit+n3JB4*jwwCO1!qBM?s)2I{CtH_MPyRy#ZZk!(NIMHR0m4Z9(A-TE#!O9 zgL{shY&UnqCt7=a`RL80N~8OF2TLM;gS)Z;P5gt!`j?jd|FBs9l1ToyA%K}WNtr)Q z4%e@!t;rdZNjC;9&WkRa8COk%tEUsL^aaK`e<09imcHJ=KGfGxA#CM;{{Hqk9oG_l zqX4}y0u0JkLu12MzX1wXQ;UOcnNI{_)X`2>)awy2+IMPM+s@&;%H;O7^iM>XA$QYE zVZ&EWx5xA=K9mu@(SaJe0SU2s!P2KvhRGqcw_Ks~{;Y$1j7?<&_b;%{&%C<fbBv*b z9_8N<Qb1eSi?J5dwB4D1%v?Y5m4jK&QkY_r*0Ew|<;B#5=5=ze7gL2+rl6OPSX<EJ zGhM;jv#clj;Zp6?#&8#z?AyG9g>O^&NhJcSlUHDiQtj=k;5IE8q26-rQi!iai-vG? zu}jda$*98yK~NRe>REUi+~5lFXxaKB(ZhgIqh`^fk=QA?Zm#GmPX^S0#1cyJg<Q>< z=`6>n<Dg3_2T7qjmj_y9iE6B8lafA-8rH{|Q76Y`LpxkdYGlv6?gbjJGi!vx6vIF& z7ZPMe%;_yWYiBZGdSW7l_E7lBb2AiL;z-C>$gIgJ4f+=0Ul<<MHXG|~!<V2NA8QHm z5lAity(Rwv!Tmk<=${=`p77X{yi=iM#><gaNqR2mBSi}-{k|$QN6;8tsck$R+GyIy zJLQcBw#XpA(IA=r-s5Kzi~WnZarTKVCz_F5@4HtpJv#6>nFS}cLhOp_$V@d2t1rO~ zRoddlbo@7;6mfM2<@u|DL}Oz#d6~;%fX(bwH`rF}G}EaZ!WJc>p6p9d-Lr*I7?Kb% zgq0g_%q5BUq{ThNHTt)Eusvbt_cuP^54}b@z<4ND-J~!BJBz)KYb;HRUX4H?NNLj- z9P|d?_#gbXhonvY_;~078el9H{yrwEmij=E#_6!b{px3-Apchx;FS=753~G}81QPk zhY&;tt||YyHeEWA05~EO9!|(`fyFHv!5E^>)eW8kGITXC{Dd;G)SbjUC}l^<BYH<7 z|DgM22^xokDZMwuPx@+M2_uL>jZyTwU{AqOxZ#2wZ$goza4b@Pb<QGek;<~8M$7cd zaMUbs&eB(pvZ1Ge!y-`+@V)j!Z^xX6DvMyHc?il3<J=11Ni4#AeD>%z8miSglnr?% z<NO2UcCl7I-8#O_9BtYTD7%o|3bF>L4*pY946p9S$(@jK^D$$qW^O!B;r<JAkYx{k zqvyKt;@w!2gROA}>B+q?80V1}`@`}2a#Mk%hVJvpXWw*NoDbdU1-3mRknecMzHSv< zuf~6{0Zc#1kpHp)|Bn>P|D}k|#P*-LVkr7w7S_%tjs*0-tPPw^L`;nAj7^~U_@JDe z9Zd{upxoCwwZ>y{no&2W)$B8@S32Mm)BN>&n({~lfFM%QBtU3UJP<G#O<{Nej<22Q z+U*)qNK}&Y+F+~(a_I1K_V&BnSz2P0=XP|FBHV?Mn=^};eP=!*6BjZ=&E+(YnQ0Nz zUUi;r&uFEJD!r^oEJLoqum#%lsIf`wOt<!es}5)-q>t?w$#T0ZBN}U(HTS3{wQ!@` z;!IQhPhqS{@a7nYC?q7^IskvjjqL1^5_V}N@-BHp$t(tML%TO$*HZ`D;@EC1i(kB8 zq$KyWhs4KzUx)6fsB~8QbNtbFk3!Z}>mZe=bhfjYbNFid!=(Y)wm1q!qm**roccHC zJyuz(*Xu=jxyoINP;&98d7vz1HI0N72|tL1Rgbp8($c9aSkrP*O|Y~i^t;2P%%uZH zlbCe^V`wMQ(_$-#(gkZPh||RYKZw+&ax0DX(Q*n!?_sK5Ols5nF~ke##(OFeaq{>V z6Ak)Me4_MGv(V_-hbo6g`4pzsL>nj6$r^##j#l2uMF9T7C+&1Km)8!evKjo(o6is` zr<BWFm2P;CUqHZlRIzJ7#gZn4DwE?>g({PQT(Xi^oVr@>F%Q1H*KKpKDUcFwH7JjY zjlSM{T+5W1(usW(P^w}UhcB|34Fd;h8srnsB{z~?6-nI3Vpg;lT~iH{i4oJtrQUC@ zEyJkUZ_Z)&MUxs~&+xGtI$J}3T#o^ZJpevLNLrCxje~|$QZsG#DWIA;ZOG!B{xhB4 z2YAeY-)`2Mxs@z`e;o4t?(%VW|8REme0;UbJv!$9dbo*epLdJH_wD$;`P0Lb++4Dq z`(^+31v?4vR)T-E?I&r+0J}<VZa=iJFQ0M|2F9G@Rpx%N{&1ne)hSuB&D-TGU2=TN z-re#3?n8##Ewk<I6!!g0JWHci;T?aH+B%oS$s=c{--0p1Uo@ZleW#Y4Zk?`5oeU1M z)_<Jq=liaQKa~DuZ^hc)_;$979tWRG7J|N~6pYK&-r2JnfEp>sv3+)Qa#!|J!p9GI z^l;a||E~7zzUu7x`XS2I+4cRX<oW*i(K(>C`MYb_{24x%?`?_g`g;E1_VzyP`5AwD z-RJ8{?)hh{SM9@k^VzFhJ=kox;FRk<*`40cfCL;-`*$DO*>M<tYrZ9{GT+4pvlwZi zDdzGl99T%OF~4Gd5orDI5hs8bzyss~atCpMI6@pRM)0$MZrpsE1|}L*NH{xVzF^*9 z{$Q@o0+jJj132S<3=N=v7{D6;Ii^SKo*7XY`dbYT+nY94WD3?{UK-b!DDaJI^pl+W zlY1*o2W1H`Y9fsQ>9Zr$#8FmrMX*zO;nc;GbHq5aMbXt)yK2nIS~YkxLt-xyY~o9a zt?CQK<4vE$V_3Cvb@`C9Im3GsD&uRk;webk<Fo=n6zGV+>jf&(9=VVgHQBg4sVomC zYW_k;4cQ7Wsh_~A*O<tGprO@h8#=Q@5v>w$hJgCY$-tTB`y9|e{aG6kUY{kgoMeWE zK!f<?iYrtX9|bC}#Q4p-Ih(T?Lj}Y!@I_6d*$N2#5*?UlXdsA7*n&496kU(1r9Kj` z{g$a@=M0R7N(gE=9|AguRKCxERx^Jw2tT<e3qr%gs5B|Fob7qeP9R9CWCIOJr=bB) z7H~o2C3++Tlp%057e_V=F%*D?gv)uz5iNYno2u?vb=W})Q3knxy|w%#vW#6rkb!yE z7l>%J=*a*bI8I?hLt_pz@a@VH6)HY$CD~iB{P@y+eKFjY7PG@>o(&u&`y<#j@NGr+ z`vQ!nbXR{R1(cYm*%bvEL`_<kJ!iLD72eVm)r$Ay+Q<(sjY>6srNZ!0huR{%XpNN@ zZD2bnClT*@yujnpULp>()u8<NLEYU(&VD^t^k5h|%FtIm&eUNvE-2)9nC-+I?fAo; zFyM0TEmQay_cI+_Q8(01+d-&?c4wt?t04nFt&KQBaMfLR&=~as>H>}$L^06ZZcz1N zM9>WB&&VvLmy8^u>EjTym>Fi6eSD-plF{;274&;uqxK~v<r@V%K>*C=P)fgQU>9{* z=!n6K4IWyrd8YISAUQ~TQyqrQG%TRgB@P`c(BP5vRBw6KQrxcp$y~KEwMvDkFcH+S ztU3&b<0W-eZG8xa@8w_2RnAnP1pajz#R|@9>=lZ}z(Vt=m^C_uWL#nH(_?p}UTA3s zxKIl^4h;1$ZRbJV^)BY!DXm>DsCjJ|%ypGS-hBv=$0}9%$9F;bUPgtC<!1)$FnM`5 z=uSElEYxlIr(mYZSTf1l?@wDT3**3PMOWlO-`?=;aYm8>U=8lH$Q_a$4hJD^S)rE> zw4-Zrz**>w<q#Bw%6A%LzQ{pJh{j6_q%?U+F4qCpWF%s_>sYAbKoF#9rs@fLnwxip zcR`vOa<dPlMk*6&$mkOEa%<XDqAe%AKDkyXh|y3^Ob~|7K2xIA(sFdXj$`Q_i#CoO zMTUD}1G&<)(Xaa+2y?C4a~^_CM9bm$aF6iJO%J>#DOayI*%wKd6wKJ*T@iij<&&EB znMEo5&3S#|{)A%l(v5n!ttzY~pOW4X8JMgHZL_JMa|8^^+)7>UMW16qgc;GpIr2VK z<@J<tUMIaDaSP}aGp3g$9phg6!^%@el0VRTmL>B6>>iSr&eQ&I?bFmwX>(=V&Q1|) zuBQ)R9^{0v*^T*9Q_U(|xX!?EX=A5-2IY>P$Vh2@r$UD1_MXs4$8D!V2IaP%&`^Y5 z?e;5FS#V!&m$_D1xkaDvLQ}^;T~*(LQ_tU$PY)F+?~-*TgJ0yMIXR6cdXi7tQ=X|x zi}Bk3bs;z{{<o`9z&2n5s1?)^`T%W&HeQRM`Ckjbt>BLE2Y4gA@m>UB9123&6oj(L z2;`FC$fN@iNP8lX4h6ygzm`Ke6oj)&31t@$$SuQ>SqCDp_Cz|vk=>GJ3Dt)zwN0GE zS45kyA;GTw4C+cx_J)k5M9sXmn)^4}rhEy6GJqg@SDu2Ufc8Em2#j4OE#g<Yh*y|h z;gKLP#&@VACb<K(;vpb);sq-HG~!AVkvRVp<azv{k@EA}?ftEsdHb-yH*<v{P69=o ze#hcT6FoTne1Odt8Hq3#8VNh)R7*VqVOodc<R-Ddm)mf53N+&A^~(~p>PoIJ#LICL zQ8($*7(9u>x8GI`N$YUtld{FS3SE<;#X437j!c2JT*oa~uRNuR3)#jG3BssFr}M>? z&`}Ku9kC4^@bid9`DERshnK!32oxJ9>|3b{I_i>WLq@$v<)s@(Q{6hHr;6kY)bxZx z>K{(2EI-;H|8+|J4<s`O$A6^O{tdjsWag^k`oAL8Pn5Q3Gc1)v_R~b6#88WXy#`?6 zR)$(6p8v(#TR_#-C2hjEI~TW$y9N*LuEE{i9fCUqcXxLW?h@SH3GSYtL*DLhzMkoK z&Gh{1r_Q=;in>+%z$!Sq>Zz*xc<y2{@2Am87SLJi_yD_IQK8>=@59i?1271nU<7;0 zQ@@s*sd7J3?~tD0+r$z&Snl5humW{qE^t$cZ@b)(tapX1wRVv!);1y=7G+oT8$E~Y zz$2eww)a62g`}*f<-fIiK?u#bBB3;5Lr$qoK`ci@W?6P%{~F=|uM&!LQD6u$7hFJg z-+VGcE9srv9c@%3J<5P!^GPD=_%$9Fdq|*5_k8y<)~i1rX~~c(D26{h0AV<AKx!%( zUvzaX%vQEyeY5jbbBO?aoh@7(54-gi>613|$cg@)eaDK$8#*!Vr@A@!Wbu3Uyn10p zSvt*P(zoQ8MgPmt<8VF)faRhcQN=4p*PK4!uE0=})JyG}Av+#Ad(2DPrRVp|*3HcJ z&FXRQSoRHHO_}Qn3vl6D{pg3EXX2L>&@?2zV4T=<bC<QoEHPWd>rPm`fS1Q-=*a4# zi8bbt>NH#4kYAVfPuPXjF)d^*-gTv{s+eXTpCck&6lA~w8=&QEI3{}~nZ7&6weCDf zOALk+?zSg;n+Qj$X+koKtrg~mnk1A1!-9s-z^tDQ2RD|Us}?E4bQ~G^W@rGm`76k) zM`wJ5@@KY0*Xn(q;WAG?x<Xim&g2ZmM@JoSeAVK;Usg=V#l(y?6l`}M9WLHJUyWqN zgEl#7^65Iu;)-b1TShYzhuXT%T!kHQ!`V0$TPQprAD&=fhGNm+v_pWVlSsL|-AN%S zfrCn-I8<>_Eo%DJ-uSG|pI0MYP4di+bCpZ8$?YojAPhT6n)QN1dX#gwxVv27W;Ic4 zVf(>Noaa|7X>kcG=nH~kB7r#64JlN@<+78f#U{apZ8R0cf_V%ZKX8@_>=<Y8Ic~O+ zlPs0mJ>Xr@hBfqxQmPGm7Klg_S59e~-C}GYE21jftyz%}z*?#9n-Xv6<VT%-HCQsR z%9{a#E1#)b@+?KS@GP_}_5~(NE9-`7s}xK$Z37A}AxnyQaskph9)3Rzk7<yZR)z)D zxCAtrtGsL>oi!gDt!);}HlBr|p{Z96ZSn>yq#4Mvty1h@SE3OKhB3vDB2a0!k>ouX zk|XjoP<a#K!;jBi=qgk{&*iNEoOX}lzxe+`{!NQf{dXSB{I6h||MNNXUpp56=R<)y z)Ab?=IM4>S4wa9XJ!X>1rQUlWcCjy^*!2zh&xU^W)-g&iGocR|Np!ttE4ked25Il_ zNHL8cZQ2sNYSJ`0Th4zM!P4FnVqmfIC)lrqbXYIPjF(=&{K0VOBkxdzLBGw-M$d{R z98I;bZD{QnsuV<aY=f~|uVaFxEUk%#1z+YP%dmKE=~`!_7Fn>IWaT1~);N#vpxlUw z4+?A3SlXDs6<09pftQ_Iw`lGjG))ARFC$0<1~$HK1sIO^iaOy8)h*z<1F?j$g@Rm- zMIqn|_Ys#PQKPRz7s|;alOrReC#MY0NUl%#7A;c7S@vof1otG_T|uQ%6{)2p5yYPV zJ@J}}DzAn19(N_LqOnO`8%fq`;Dn`3SbD-lZWR|YrAV(R4D>`TT$_Q*JY1(bY6dEt zR&ZDtsF(lnefvOYb<Z7F&A44tM>50F2{K8s?^lYHW+3Sh-*H1;q*bXVmVaO*q)o07 zt#nPCcG9Yqap=xDTSSGZXVi%$y;L~?W&mFi2*(K{>X$W7HS<%~L}0A?vlJ6RLtN!c zd5A7JQATvRgdkbSIwWlbAW@K&FRke~2m~=ciCHviHP;-L7`HiYxPPz~(OW21sA|iP zDyj}yUno_KraWU>b3KHJ6vJrMR=|q+5wBh@lpbt)Cl!ZR0A(spC<aBQRD!C2ZNPyn zSr@S?F7e|9HAFAcJWA>kokzd03i_HVPI%sy$~>yTH8#=a;TSPCoUSwGnROU_lh@1D z&GUBH&dlxU;q7hb_~P#Ac1r&Bw%e!meQV?RcmLk-?cSPSim<!e)8X;+oSU7|yS>}f z^~=tWPEldLfQ0W)xkr735=hHkfIjc7HnXYq<EGEAdpi?>pF8dKULW4N&9-KjE;8&c zuAIPONc65104r()o|rKp1GItOQpa!*8z>~EQ@CtRzxgs3oX%=krnGCA8etK*Ji?v* zsbCB0Qw33Q=ykA_uIR4}VP0(1b85>y#*wmw`IcUmP*M+DO3Z&ULn4O=5PouF7Ov*o zIk!M5@|1Ew1(yy6V&Vv18gccqM5aI{Cqb|?SPAX=^^6G}LK#IvbgaV9EwrKvckqhX z{;I%34}^hCFd`6rkZeH;X8v3YI(p`!@gs@(W6Tp{ouh1SZ1LQlpM(t)Z?S+v-%Bn$ zB&AI30t&I`Q1h8z*o;xPV{ib4h$s!@j%#?tmxdbVs$vQCxiv_V1o^7!ke<~dtzUs) z?f9JO3jo263m)VMs%59^-R+>j>*aj{K!7(=bJo&R0EL47513jYG^B3s6+;De?P=8x z8rBufFTU#Ho_zlw9(iGd$_ax2``heWlj1&)XN6HVxNHG`71Cm9ZKj9MY)vWv^~s`q z6>MbLw4QFS`z|^r636qZq!Wk;Y+xoM0I)5wYY12Vqhg8;&JyRDL02}8bQAenNU?U! z%7YEks5nGgyY#bdQB|=YZ?Pr=pmvyCFDla23+{fn?KcM;+lZtwhUg+j2O&}#YSFk+ zD1M-f-!lCTD0BS?b0I9CU7U|<h>&Y5+wgV-x__BeUVoXlUho_54Hg39`Wi)^;BRra zr$=9(fFHMPW@>d6!^UopIliy=SsO1mJ8xwbUGwxRz3DR*on)^A>-;;5a}~p($Td^? z&LwJ$x@~hAx0mu48!0iba7=C`m$~j;zE6d}JFAQ3ACGr#_d;(==nt2=pLbraQy!;? zeB3&Pl>#ROyVXPt7anIS9%E2u#&3LlFX!aVyGu$iD$GhAg_?!xgqnob-~p8=RRXH| zw5cp<|C2IU{*CHW|D7CJ_Kin>BqmT(D$5mT%5bIq#aKyfpf*#UEY6hW%5Y@gw;uh& zz*1(&xM{~TDaO9UL5MU7HZ-(0^T@<#J6`9fdT5*$WR`(XS`${+Jo3XX2{u(Yvmh?` zSQIN*TjYToredap)s+MzMJQ@g&BLO2{gEpEkW$wip&GKtqXuaGgHtSUW|0^8M_lMH zaRW`N#x>=CN@Xa;{tCgEpA~8=u;rzm|7AH;FQdPlAoLmBC&iu3K!cL$j5;ricz4ba zOd8q-A{`-rv;ybBczQB+!Jgp~dPon`2%93nysvUvM4@-_s~L8&zbO++GOPtA@*deV z0ICvgK8DC8!~o75uHQi*{}Teb06qoN^6#)HgVeXQUj1QG?mo`Peh09CtmtKIxOKjy zg$?}@QuYvli;nh$ekdtBRG&}v%x>LsjF>fqe{Gc}0ir8YK51eEy^4lN&vIj;J#!Dj zR??iQpTBd|hr2Ad!W8&{nvO<NM+c&cp`MtVUO~Wp#;#K?1+S*BE?!0!!-jBW3p{29 z??V#9hQw!bU8|rzGY(Sh0YleAjCA&j*fSoGi?j4U&0PRI|9}bXIVgtG;E|6>Ko#>p zM{F}<3(oq+6jA!_tHVP$+#5z9l>YYY;_?L_n)I7t88jc&nSPKWf)3LmEWnkij|z&< z9jf1f&d?0|^A0t@m9CE}L^qXEB-mpo(C{dvMB&W#S1$I`4i4ZTG|KQS?1K^g!SFP! zMyGO>|Elm!=Nchm1A_=)q{riL_&5l4&5?PH0P`8c0AOUd{&BZ;Fa_A{dpLh-9(r>J z8}y;;!yZEN01G6DWRhmT8#$LBCV{Kr#=Q1*NE&ndn}-p$PwfAGoZ$EvsqmjBz6R6& zJMk5imQEoc<k))N7XA6dt;`ly;3K}f(A2wFw7fk-y_CA{(?Wbl9l-ubd!=PMQNZwk zK!~m4$$NPlG4}vV=D{|>IAK_%{QG4kn6D1>i(|I*kT1V^U1Ba{1_m)-FP%Y;J3Oi5 zd9KPMMwY;A??HSMG+hOTHLmc2IbE;O3rz1K@R*U3>Z8M>t)V^AZd>NCel#@G4ampN z2Upn+&A{uYcpB=Fcr390wZ;@qSdGph!?Ps&62)8_m;F^e6LAbPfa@m(D7dxIw_mn> zgANcB+%Io5TC29Q8KJMcd@-y{c&SKpbx{xCuG5Cqb6grYKh^qCkyXc9bDV<)-if37 zT&U(z6Bq(XXQ*VN9~r}u;3EpCbW;j|n<#@?Vmr#a;xVnerGf@*3Z)w?GHDEZB}U7v zt}tqd$=B_SjX<Uc(iBD9@^15BDmD{cy072i0_<H<+OKdSRM7*%;Seh$m_6e3SGfiK zp$g6^E*63SxoXHtAmo_K@o?@?>~Vy;t9Tl2C`EXUG%%{5`TAD2T9MbQD7MC1j<+7( zT44YwMW1a;oEz=m=3)6`$V##w2{Hp;u08V61xpNQQ4F=m6F`biM@El>imBRakid^g zIg`piYYoIilO+m}PS0GrcJ6pMs)_1Z6q<%pu7P(oeM34;7bq%m6sLG_l`;dBqH&L} zSEG1jjK0ieGmlqK=i;Xj35#s{<PdXwI_`MlF;X%;h#-mXe&oCopv6_-04fD)@g_v3 zV=ezOI7m84zX1Hf1t9>0;XeLCIhrVezIe!&V~|r?!?9(h0&wf`SW59Eq}qZ)>MhXb z1BC{pTDCduBuFF+p<H7#N|wd%H1PNzyT#y?1)=b!%_VDBlJv_23$1|E9|TEQ1eF3D zEr1n4B6Tjm>vA_yL>~p6W@->2O;fWHSmtD^tU)L_{7`6U;E8iO5QDm--*{+ge?DEV zjeRqF)<+ny?7PP)1HQngh(t*JjVrN#R1^Q($()P*|0Rbk?UccU;&=H1M_^E_NS+qT zIh*?3c7u$KEP;LQ8YSa<w&5O_#i_3zX!I!s6vPM_)*fix^SN+4n12sGkSTVvb#|?R z5E78ywh4a0%Y;(chJ=tHKmhIrWou%Mwx96~S}GE%eqM*yFxP+E<(;4#YpwP~ZQx1> z+JP=WT_^%MSLFPR=#SI>0190GMExr(N*he&RFFOa3q<^hF3+3F5k_hlg;z<Immk-s zjpbYqZpPR*iPLA7A=xL>eavMjQq~*|F;gFmndP<}QyP-=cW=<vmhlmn6YExA3^dwz zUSg=Ex?(%%p9(VLU7VUA4prC^4*`SY(qB<g#BhRIq3fhxT8UcWC?t@!Y|yqM^1nou z+{JcyMAx$c)z^z!XmR5!ET|3&ae{A!_5$rE^Cb73`R1IPVP3k3<Vp7-tZodmf)vLc z^T_>%>`q4Hy)(@Om^cg5T=QB#XE4q=!-CtLUK=+^zYEPRJ@;$q-V|oYY2MbF^R%lU zkzIdFOsH$K?aX|4wQhTYEAS#+G~z{_d6^|fPss_P4YnQ=F|f*Kl*YcqJ+y*9D#~Z6 zwK(Y|I+mAA^3Jok%AEdi*C)9Cm&`=jl=y?0p&HH8k<a3Ggy(qGPK^h|1HK$J(|URX zlMxRx+EWNo%kD%5_{qHfdc3H6)|q`k&O~LoVIIXv8X=!zCK&?7FH;rVKqyPh$a0KS z`$Wea<EfO4rqpd#$Q_NT#>cTaQs75v5Y@CSL|qxio&%k!rNfSCnX=LT>|mm0tqkg6 z5x2UwRXhXO5g<jV;WKm+BXhb)1S>RkHGi>r?Cy7awzEBV<8yf|U4_>!@=0jN(nZ{I z(}u!Ja^1RD9Ta;q(-LeGf^@tfuLW0-LQkKtUaD*Hs1`(mo~ygv0`X!wN<Pmn_T&C_ zg%BpHE(SWNN;2o@T9&1Gw&-P+B`9HimpsJ1-X*U={WCAp@Ut9bT@<&DgyuP~rp=3U zjLYjVXqc2Sd&q9A)vuN-d*R+TIqeD3r*{SCa+_<aIay92dgn9{cR#&Jp7cB@ypC3l z#yYX(D`(6Na~^}ooVBga*psA?B|DqN`n&8GwJm8^#apos&H4oio1_#q%XTc<WKG|^ z+hC7*A$}O!eRfQeK~tsPmBO&3wkh9b)i%pmCZEVJBff9ct_<)^*-PgpiV5XQo<@+6 z%#tT3>|UEDW_D(K6%ktaQffi-Stv_#d>r=|Ex)0QW3jP_TNy^ii!Z-S)N4Z;EoEw2 z^AmCs@f&0_yxQOYi~UzL-2d^s&%*ZK*nAfDf0oz$2YKZT*%<s5)R4<tT6Y-+d{vAJ z39tarwSagKSfB(qneNf{NMuh~oz)2K2RgsZ(5(&wS{?4HmQiU!y!&g2j_eJ&6&`vh zK$8J2C>@eK5e##F8ckywjEn|%0RZw8iUFoDifQ22;VlK~{>%zZ70!t3;3u`PnE+Ci zD@qO|t1E>Xu%1}LjEy*M0>mch%m8zZ+w%>2l+Gf=K=GC_=%FD;R>k%N6rM29!gBQ# z!S=^77X-A=QkpPJ{oY9As1+s*Q6VfJs3{R}n&qjD#|QKA?@F2?#qe3cm%Y&HQ&~#T z8e7Um*{J9>=L2+2M&W);C*8ALe5ri5-{dRmsoW@2L|U~dv;l#x?$n9xsnWDk2mn#H zQV7()@RYSvVN;S3Jfp=GL_wtQ0~W1fNC@ICW26RdB3XfR0ZL!tV1uV&6fWHltQ8T1 zD_%*g(;>}069Yz9N+9wY->3~r{T?F2ga*&&(C)+{n+3V%EA?#ic{Qpc?|BD7+5@dy zGR}}3o4@>c_<Tm;#7yI*;mL1?QPr7qp0oI@(T;=$VoACxA6xrqQq9YM9%?GBa^V)o zrj~GbG4JF5#nZRm)XGx7r}7w%I-~jx1f*1~H@#Lszpb)L@Sw1&t{KYH>1<;)$KNNd z87k?VrH-=T-WJOSG4HY6+$zkPGrubDAtrbg*HI0{2C?OtVih;J9CjkVY6ptCiQh~| zO{;*uAfmaMyp7jRKuhkpAF`2LWoGeX<d+~3O)h;^M6;Nd?r{}}tXo%yyF+W&^VHPi z&ePMg?}lFW79Sta20zcM;iHVRvAa`iSL^%!_1rM><7;O}=VQw=k<ZIp#;{($&Me1w z2a%*o97CH+#`1eb(Yps4qxZKZWaJnc&z30Gk6iBTnc#iyxu7heAM_EZM=Y;CvUY2m zqs#uu=tNQmEr*(I^}2RztE1EY!3Sfl+B$Ibza<9(cLnczl6wD!W|ID$ekA=N3uPbQ z-zODQvo&TT`%e#Z{5emj-EY6HF30XOhGY2Gea|G5H}&4XzK-3meLiBOW8~)v{@jD# zq(jh07QtR)LEv&_7|xw~)Y65-s2g;;X8$_3*FJ3Tjq`TZK;apb`GyVHZbk^3QSvbZ zehYHM1V8@h;jOJ1m5YNQ6L)VwT{e(>g%dH4sQ`$OC9*Gxl~Sb1k&V-8jGH9>K1g?O z4fE6d(|RtDfG+10_Pd3t(0q|dEJS)F``eQFTqy&MVZK=oatCkl<n`*XiGqES`c7-t zNTXkXqFEWZ(DWuB9+*`kpX?>ziC={?gJeJTw*-8a7zs?4Ox~RLeA7(s^a^(~otg4c zVjKz*+>UxJuXr4mLM%hxY#f$G30l_URPnTA;6xo4WMUY7j!Yf}Wjww-4O>Ln$D!1D z5rpq1pm1n(>Hv~47pP;Xz(?g6Z5cgP><56y2mg*cQmXs=rv-$|YOPC)vVKBXS>`%c z=`GaiMW`}B=PoM?liPZTOk7i+K{4vt2~h6`MwLE@4=9x;I7pxtC_&^BlQXABTWBD5 zUOd9=p@tLZeD+Cw_j8pw?UCdK$&v*{v)M9L$YlsSZJ6_H<rVF>1<fSh833!)N3nVt z8CO~W>5)VzYz}mOa`crE#nQ5I8WGvIj@TeZhPxk`;v>woMc%>m5Rjq2L5tWR`8>Ez z!kD*AcjK3;`I8)_U6c^;DRR6P#IR)q+|V*kP2sz!YecK4u27xEPf+Hj5ow@nBo9?F zrU&exZ5;IAJjthx>^}N><?(;0Lyjo>BdhgO@Q*CjKV;Kx&#Bk{%M$%f?uR9ehOmFi zJbhRS{1;26x&nW_z2P6Gfd68uCU=>>UigotuniLAh%`}C4UiAnzqa*HQy!3mrg6~y z^CUI;A7PeS<4=(<-3W~RI%_m(n?a{r@7GzH9qOV&3v8W9k33(Wj!PUiUrw%fJ|Zb6 z@a6Scc6xewovX+t_Z3S^L`3`@ooYk&-mf<*-@Dr1?~hwb7Q5-wV-w$N%!Sb2HuGUC za#oP08geSk_|>L-s<U4Q_@2YPAJCuAC?8hj&l+-;&D2c)hA`FsofxXMwOhYCI_&R` z4kmSi1^@qXi9Wz3KDKOh;09xKd9iJ9?m}jS7c}-!7vqU@Yz)us!0=U6jaU<2!Lvu7 zAQDiQ-ipw^(Q+FX>mn8d_CJ`Gx&m=pGKk0#$CHZtkbqR9b8_3ygVu-Uup&~5l_Jx` z#h=AFigE#E8W?3sJk-I}c9N9AzbE6i!QjLQ2#~^#Cuh)Lymj-I49)>_Sq0<($&?pY zxV=AX3_$Bq{Fa=7Ys82AG#K0>TQ@$+TvP!$%F|avzIdlDhsGcw%BY~6`$6YDb4W;) zZ)^k>%v+qAahU_$862EcANL^r6yVs%&xZ||iz3xv@>v@~y^6!Sjr!27&c$vSX!w^7 z;A##LLd43@$4+QwXqur1KGeZNDhznaoZd!}w(j3(g^mX;b415~#Eg)PyBx?|K!c79 zV;ls=AEJ_(e$H2TW*M~Ee3=D<L17a%5s-0<QWaqRHe8i@fl~!Uv1yP0B-8TEHe8^s znm)LlOYZfh=-5wGPd^%-E>|Hz`}y~n9P_8)mai=MLYgy_q(msnP96EQ<M@X@FZGJ! z6W3^PY{S#hjj0)X<bVe=>epW;C8=q90r0?ie5{=h2aNu3K&}r5<m#diX3*15HJZ&U zA5BT!W5EQxLvphiTmRiLi|b$KJ^oiKCl==axRP-}Q_C%10>$T1?TYHKl6ONJ*Zs_% zc|5n4wJj|nZO<X`hx?+m>cn_kw+|juwPcv%G0I~wkoDeMPesiQ0~F2;4A53pQF`AS z=OPFVHB^t{jl~M%{0(v<7DP;l6~lJTcB|fQpk_u~FwQ0Sgxia?(;tDWb-lh|QICG0 zS_qT?;fQ;hTr`zVvqdkD$>fm_4rL^S;YCWE0YWs%zkKBEE5r2SCB3_h6gP#5KrYTW zs~8Ahefqb(rq(trljY47eo;xA;V~N^O)YPB7@GBa8vbrocjjeC{!sO#*<Ank2|McR zZ`V(@^1NrwL2J>4$2JfPuYTXqK0C)k#NH7-z>c4~^F%F~5hs3y`2tpeXNPPwe*Nms zvUY(R>x!`EtNxW1i0K4b)Zi;JFqs~r!&^z2Bv=8(p8xiEnc==xs}7ZsRoyK>RfFdH z&MhstCoL#)HhIBki~U%u|7DOK-BOc0^z^i7-%0%tPLng#rHhXtb>QnD=A^+z?Y>j$ zr{F#=>#HcIYclpp*o&btcY4><N7IDB*FDI+b71}o$)@#i<TDhowvSk>mFl9{o)v|s zsGnkIgmCq>R5xiasL*Wb)15m0BUCChsp;^x0p%4hTHDNFKy#vUGu1I9ArZ$+54+Cp zwLZp79Dk$m@a;SHjMY+^g{=h767IdkuW*7RO4}hC#Zw?ScKp*v)=s+FQ`&7?d^Ly{ zCq9ZPoFH1J`||sSpajX%Wz71BshJNa3E{2h%{Daj4=|{Zp(ox&WnvxhdOF?*N4;FI z$Aaw{s`01J{!}^kZAq&|!E^+KMRZpbu#j?7(&xn$R&kF}2Wk!0(YZlxH3ElN6A;L~ zPP)t}GK0ItwtAez3V2YQANWBQXQ9`ux~~3ylJB$z&tWsA660_ZW4av1;lFAzQP;+s z8y4#AA+PYklj|p4k2fu!m|}i7w?%W9>FEJmDKu5}O&&3?AHF(W;gXaiX$VwAaGBF< z8(s@@>sb&NAtkrVl<(fDDLF;8IH+_4T+=FVFDO0K-}tVLdxeW1+%Eh)=Y2x^F4ONn z&z*0vvR}-g`FlU)v*Aa*9+TtsKGf2T`^Yef@;#Z-R0~ukA}|>PlO`^QeEqgNfQ&S^ ztP+9=C=l|5R;X~C*=^C#rXC;=_<X)af-1?yUzHg{lQZGXlNNQjJ<P>(zM%9vq8X7g zYlmQeq(pZ7TyEvOk2acVp6<i=9ZolX`Pqb9?lE+Q!h_T~Iihe$A8mEAX|2;|foMX> zKz8r>Qyute`TJX4U0|>5CceccLEzMjJ9dftwlWWxCE6+s;yr8B@Dg4&Z)2x45b!kr zBcl#coQg{u5q}tIYlFJ@QgO|QdG`PlM|Iy2HNhiT3o47kk%lk%loM+kdC36Y+Z|OT z|FqaWGa_=>)avJhwJ*xGQDC{};H~T~Ir_tE*{|QX7#!pIzM$1GVf(+b-C$+b@mlzQ zVqulB#Kmr<YX(BNF!+g?qtj~e-8|x~v*H}02?<lT7{^sO!DREKKT>CxgX+-S5^wIQ z`D07qsz!Igefi>d&9{8~?lHXPPE(B5Megag(%K}|HTvx3M(K)TJv?@Z@D909*dYIR ze-QuE((nHbx6H-ypT>Cq;FbwmQ2&8jcGqC!1L^f6Qa}TOLTE*j1z<+-!hFNV6-Ms) z{hZnVIWx^#Q}<2*g|)+}9a+91Ql+H46t$`-UaT>DATuzo(G|f{Qa2G?(xBJBSQ8pL z*^?Q`K9miKMAD*9Q8u64mdVnu(Sx_Aa{^B+UXw<wfXrgDER^gx$_ZIk6Ye^M9D{Q6 zs&JL_HLOrKjKgx)eh|OF-zLMI*P`1ek`h~_x`>QcmMg+oGm~_1#6brV{L@aUgrmjn zTJpNoVJW5Cq$21^FITy~WIBq5y|~*Zar#%*P2yysk=%$9g~JXs_0RP+O3DKw$;tV; z-RH2Udd$$~`l9YN$zR4^RLOTVCo9z5Gj7X^PHgc#%GFeH%XBp?Wba3%v_8IARYu=& zI+Bn*Y*AJE)ZzY(tf{A8zpzY&Qn_JXlN1YE1g~%9>dmXwM@u;+{2SKRxu>0c>LN3= zu3OA+dR+m#zQZ1?vyC5sm<4f4WxfEI*4Wsm4)CkRLxQh)ESJC^r!BuqTzc`pdKhiu z)#fQ3uz`}&%>JMN2)FC%V?TB9<M*dtIk2hjLRU830gL=vlV^T6f_e=S@hSA^iykJZ zjZ?5=6&tdLx3XX~{75nzv{uIrP#LFKDyry3WX|b!v>U+yZ77?#@3rkmh^Ft~AotYi z4q0iO*dOdd>+Dj)Za7M<L3);~eaS>Dre(66gwpCS&cKA;Ly2Um*;oBJ)*Fl0$=2y{ zy?b!;)ZM*VJhpVXwdLK``f~MK?*ppb{r2+4&yiwx@lhE5yd&%HMP<k6+x4=4bB>or zWXrI%_4bRpvyR3?M(YwMGO_Z0y^hd;R|`w~(Z%zcM8`)Wg@2>7OFHFpmdMBZ@p6rh z{w=lZ=>*DG-dK^&?N=By=B`G$jp>e!arL#~j`z=<`!G>&C`?ow%twKIF<Wle1g0OX zqtKWPI9;Y3k+Y67lvc#_q&(K9pxwz{9<1<q$<kICQFHlbA#2c>82o$F46C1NnWmsp z?tA)pNm<WKiOHpTRv~{1y53LFHHs5njYS4Wr#Cfj&|Nhg7w7;lema<AzT!xzk0}yP z2z8nal<Clc`QXN>Ln=bdtZPEj9?3M}qe9cQWljm9u$A-1#xmDyY>D)Rnw4_FxImy9 z0F$g^59}pZ?nc-nvqt)?itmzZt(o9!zM@Vu|0<hxtAi0irlB8T@c({w5JoX=<UeI% zZKU{#NJpGuq$XC1IM&btAt&;TM6nJarUPFP)OT&`;e0X!w^5X#j!i&jMvuhkKaTLM zQr6Df;zRZ@8h$-b>~4lxoK_FD7Qkh#NYz~cqVysHx2wE(7Y|P%J{yq|fROjI)MbgK zM~hi4(16L#(Ve#V^lEFFy*s1d?HJL~8vN$*_~y~~1wEX0lP(9r0kn1Yd8+&6##QI# z=Hj&^{Are|_+#8fbIPc^D`am`iW<>{&&v)b{@nh88{^#m{kdJv?Ap8UnHtc^={IIr z%O$_Jv7lefBX7>d-o_y^|K^RGx3=$N%UX_)&*Q{~odtu$w~>gK@_u?}Pk*&bJ`gg* zr!kLL?YWp#UsWs#D@?2lXm7-!SAkL7%E%glrTV_to+aR7ZgsCvaxfjd239?TvCc?a ztPAm}&|+}qKNwmg&9OGbYeLPz)*n41>*<aEFuaMMg&u;>;8(Ef8IAQuy8dEB2jjzY zVLH<NR3E8}H6k7s`om~t_}LbFDpdWyE!Ko=;all{Hpl+23&x*avCl#m@U8z`sQqj? zbVono#i3^-qgH4|DH_?jcEpPZbQH<*$%gz4KwPBaudM<O<&7Xz(hSI3-(0}ODeE`d zTckm%+Dr#);}uHzqzdJ<Vrrsl*TSY-nzkz70YG?MJ`Hp_jO-2oG*R_XHI;<>iUr#h zC@l4ZA*yYRn8~pXH~d`sLaEuXH4>xQR)-8D^grgn)Xt7ZxFOjaqP0c}88zF&JkhoI zgRvu6!Chhhu02p&O=IuPmy@<{mVhF0&=JdUxzZjMLz|Q&V4*VPrZe*=tUpqJ&y)mf z&jT6~S5IQ(mQaZb!u|ZZrnDUgFGLIh@q(_=!$<6f^032(ta0~A4@Or&K8YGMLzD@L z$|bh%us%veB!t`VWXzh{LirbLB|`ks>@x#eZG@j?IA5{LG>y6ztUKetxenbnNoj9@ z2?CX%i7U$p98Q6qk-vm4P!W7hnfT^AdthNK^9gad0|RWe2vFSE4*e~n7-w4vdCa>c zp30plY-`6IIW{^1X4D)_QNR`t{ufN}JhDwC9+}Go7&TYBm<t}fI|XMj0IiaRVlV@> zG;%t9XPKieHjhbYTvI=z?}DRU+~Hj3Sdox%Uj!2g5xl~=mYVKvVZ>Sx`m6d@QTt9M z{4DRo6jXa=lxQ&XvzZHCI0&q<IGu}&Yhs+If+^?7fI-er4Rv5Vt5;vZz53cvK+>dA z!spBoKgi5Sm}X4suWsZ*O2-{W4`|+mfElZ*AJ?q|?0W;x91lp)XvDFp-2E=b=k0Jl zEZ8ioXJ#}5i1ozHzgH#`+oD9wWUI-Ahlrsv{4zmsI$*6gy~$!h0>IIt`=ENUr!xsM z^>N#xAo8)K#X@>E2NP<;HOO#oMR?0qN5ZRc1t}(<(ujrahLlyOJvu4+FJG_bds{z# z-Uyyx2TaJl0`gb$sl*)3{RldD<5W<ggSYzj+P7yb->8<Um#Y+=u_8C~NH4U?dBQ`g zh^Mv3!K0@JGJgb=9m!0lrQe7UJ<ubg)a8SliqoB~f32*XwEf2QoSLOm8TauUJS)Ih z26a+CLk%X~pHwj(7k#V}-RH_((PMX~H3jj`wrS*XbqIUTW_MD~PBDfp2>^GTb1kg< zIX+7P!CrW7?T`Y6HkrW0xADv1@Z<~H^wOj*#V6%O05PNc9g4?CPDvs_95E<kp_*(p zY{e{ec6pyhKULf3Cx6tv?Xt<fhfebf@|0g@8z40+$>iE9Sb*3=e7$95jX09CrHy-( z$C`_Fva;H>`?5iNYcK#WV8go%$CBij2YuEw$9tI_lc`T}^{j#RbVETc3);-0vEGi} za21pyMdJVx7Ghz=k|>mHveI4n9(jS)i-~y;>L;X?Mkw^J$wGnam;wBDlJ(+;%O>B} z8K2@D`=@hFGp}f+1P@|)d*4=GH;PCX^-AK@(8kby!--hh$AYi5zdzLq0QcWb-Szzi zR@c}u{S%D{-!4aBdcj&*g6+<&H3&tR&!+^y_$P8=1r%uOGJ-II?kUMo<ObXlsK!C| z;vinWr=OFfj>LJ$8OOo6E6i<>9np-UquFCHh?5O{ie(BdzY#}!3wFNJkeD`lq$E@K zAj*(*uetrUOtMoTbaGD7n}Eo(+9m;Hv=wIyFe3&Pq`VFan)4-!t-V1YBddPrHH=dz zSzM9sgF+*k6GsacO_;#99IKAOuWb7IlRP^(@K)j+9m)SroWsd)GLw8@P!RfnOTtHH zk}{8!1zCtMmWpTNsa@g)d61ZR{coOqIoSRt=gPtL&(X^N5gJ;@F5@3{yInGc3k?$~ z-p78#UjW$b8s+5?ZAGUPRauL&YfqPE5_m3Fm?qJ}-(gW94tKoezRkdbae(;Gr%@fc z>?#Qm!-HX!A_GNYp+I49{6V2CVHw0yJ@%ws;CRpk&RU-aY~54`3^xhwgB-iK)i1?C zYM^rgO1u7#Et7-fVA9@a0N@b|oR4cx2W0l8P&eM?r`Sn6Xx>ngsXXie;yGbx?0m}d z{e{%rnHc%4p=F}pm>TYQjK0?iQt2%2?cJat=bvpc!)kh<a!i5WetAj*#jM$k$Ia3P zf*A7aCF-3~Wg9GeMRl&)zOIR04Qn)-#ReRjcrK35NCQlXf-eFByaZRMF&v!*6TV4j zc=9OoIwYG$9Cp^#W~pEKITC}94mPQLAEL9+m2>ZkofD&0B+^l)FH}ICYLF!Um^%@D zQ4X#oR8Er-`Et}&I3ij&o1P<XqO8t(kb$dwm_&u7Kh6<V8W)ffRbOOjh7_=ff4-sL zyGKPcRW7;Eo{vb@BvGuveXcWUnz+6hKbk4><+_m52bgbpkYPDM7p+ee?c~*ji@jt? zPRiibtG~uPnpV0dH8D88Ina%)pfft4JBW*CsYf9jzuf*9RGcSbQf(KuI#aA}-c83G z<4p75BbZl~!zukydFMc=kx%*L30cqQ%Zqf)j35LD_Uay!w#AX2zW5*&lJ5Ak%}2$R z;?8m~o5@m>!=p^i!3Op*u%15k0|@$9SwaV;U$pC>bkNF+W{Ml?12P(s#>;pBZ0giV z#_=jMnMEIJrnBtbbA2+82Q{9R{ngCGW1KBXQdC5<k<hm~<@$NpmD-}k5HA3W`pYvw z^BVM5+-y3Y^@-SMIaY}8Px~;!VM1WD7rvM-(%fEcEF4!GaEuozCiSFlYj1h7&(*LO zd^8w=3QLO@$tgMTj&q!ipmf+Eduohu*fUY~+?zir@kQS0{Wu2-l+0keN!EMnG56BT z6CRw`Ff>_rOJ_^ZyIVK9eavG?_qqSX`^Dref2Jlh;~G}1;IzFP)ffCwHAU%fe2w!X z#P)Ca2F{P!ZvW{qaw1(PCWG^@8u<@ji?YH)IG9BdF6Bubl;bW~p|SitcPzD5-CXr_ zeYqqsJK3nX%5A$%A*Meb_`2)#G6b^@3NZ@&)LTGe?AOa0Ev&B_03nDu43vcZ#>~XA z?WwvT?ZD-0Nf=0F9Lr*Ach0z-=vo495bzFWJw@Wz&Dw))Oa{iN3%w+d`n_(65FDaE z(Lcs}VhNZ}T&QRs^A5`W>yyA^-iUW8pqH#kb{IRKcVVJ|ORxdiw>!g#JFw>MND?Zj z#qD!)GeXaO0GTyr+{XP5s=mK+Dw?G<81p7u>(2}+^nvEq^2qY_gNpJMOJY&m`iN6i zfac@t)wb#G0DAV2a`Ov~+UaVTD~U)ξHZ7J_*y9pkMA{dc;b!*o^KScqGR=sPp{ zi-yjaP77h&hxMbDb+#(rn7KxM8dkjvtC@N|sH;xSbK}X8rfCbxJ?eU<QH;??fanTg z{AGS<uA!NuOskon%0NZD8B8VKI73q7rO5)YP+*9KVL@wDDnwCitus;CyAbN?g3zPo zAbWa(ch;c7j^MV=Hd#p6GFpG)Y~HS12DlxMCRXDHf?f<C_J({jLxiyZGGcI>5A|3% z)r%}XrNJ^IdByFFVtF5h%{jzVA<cOCeTnKxxoR4%MLE2|UM7F~a+=u6FFXEh*xb@x zZNRW`zNN3GONjZedIcpp|H8J)lPLb!0i4476hE?RG#gF4tD)f|v-z!{Ya7@wS)No` z$z6b8<}9hYW(*^GRcF!IxPPABp#98Zhl>1HL=>m#A0SFjWuuYz<mpIo*+_6)@T1H{ z&hflFJZ8yf^)$5o`vdB=jLCP-n0AJeIxf#i<oH=di8OnT6>3&SFZAu14w`wvzY)cf z8*Dv+q>XjI=eCi)(HL!nb?nxM)*Z@vP1oqhlGQ<X2M7hlhlT{lLnB0fa_fuPkfQ`f zX#2mkW${m;id_p+nx!3{<X<N%5>gTmOIq8my~Z%30*>h;KZh4)NU}@e>P9qd<Euo< z+hy*eGx2!tl{je2`WHM7d6$8Ij=c9{=3|dl%ScC4L%U>WBd<36ku)!~%8c8#FO44B zj5<BQ@a}7Z-s>YSyk3Mp(@B7c8eB*3S$Xp?alU4DX=iuvTETO<`Fv~N@#039zfv;g zb_*%iu*R{4_J*ulS|Rs0uFTH$|EUDw&lH8fKK}2Jgux7*KO?b1E)Ug?SXyTklcZG8 zQiC_x<iKE4n;7HSy6iiI)$7OU9<bTp`Bb=dHoP5YZ2BbNq11>bJ?@=b_)d~6ai!s@ zS*xi9CNTvB7%=rmWa&oo^c(!ZK4~fhG`<laAyz=50h!I`nLt=O=B6}3#>;`^8Sd|b zh|@u5UI3K%;|esxW++_fSO2D5L?g+ENYx}tExam7zzjQCkstj`mKciTi4EBxq$K8k z?7eU#mGP*xB5bRDLzr+gqZJwPk_@Iwr^*ElJqnq!KLDm-GZX{@gZcpniUe|&3VPR? zPQX8?ijB(OvSHCrSn^>6f(%e=Mxk&{?V5xMx1x+LlLvsZ0Vf7{k>MIpVR#izbz&6E zO3N+W)k27|^8V~;O(m4lFW0GAg=e9$$t+5hk`v5nGslal;IMs6W~QoQKBZmK!)f4y zA+BY=6P2W14B_LhYpITdDAT8VqPg2}OTx4)f8dqMBLUb10*^@9F#8nBaN+kAa4OmI z6@n|-Xaw^r+1h2MRlX38T#P^{v_<#?_k5}RA@neLUcB-Y>nveZt)KD=i!q(;-Wk`2 zt9w~^_ogA+VU8uUL<Bg`E7NH2TYbMbYG*tj0)f%UFgzV^ML(s5%8ec`Bz7}B#{_ZJ z!?m<hD2lYOO3nRvfiZTQVkcCPk$I*DlB3TdA*zpX`#*f`In4@h4p|5ZJz~=*MMt-x zr(|YM^8Z#A86H)=KG@hK<Nb|_+F0(jb$L0NPwFmMpgR6Sx8r+z$Lmzh<Ic@_fB)Xx z#{NW#FW>z~7XRhyvVF`gCda4k{f^=IXY8il+t=S?`_FFEj28?asr|2TmyUTOt3-;x zbX(JC(L>Nm6c_xX$1cQ=O#WDg{qMQGwPAaYk4*k)sPD!wf-k~Hy?e=fHfjKw<r=MU zoO+?0X%D{3uNnj{@q-lvYSE0-OyZ_ef;T_VoE*>~Qgb(Fm{M}p_#Y^cq`OD~#LYZ- zU=>~a1R~YUJJw+$an`|3FuA33OWI-S`Sh8S(@OKLry#_asJbC;ZBJUX{6S+Md0L}w z%nG>{w&TwW9v3@fjNKiNjNP7J-B0psoQp=;y&iHph1zHLFFZ|7IZpI-s;#S*68o#a ze1z5J_J%ngBZwGk^t#|uS{}Q3gCASue>OR8>U1qFUJzyTtr^a0)#JUt{Mw%zex6!_ zEcbnAdCu{9yV}^Z%j2ijStzIiPXa!K-`t1F(-_ij+`PVh=eK(1HDamEW}+9o_TxoC zUSw>s(l47u`#@_5KKSua5!OQgKVdK$XwB3nt21@D+8tf@&qi00{xB&1h8WcLAE!P6 z*}!Llm2SJ03N}KD;b-FYWxtTjs3HF_3z!~q39Cd9;Wk_Pfe@SD8jJzv0tuN4pC?9B zJW3lBeN7cbA$)|U;c<#q8LkueLnoj?q#1vcn6++fpDLpe6eX6_Vvjb+)K!2JD}Npn zwV6**GYZjy1wz@n$_7P95i9ryO5*N9D;)}X7Uwrql-x3SJMVnpDG6Vzyn^sT5+X@n z@v{j_5Cg`Egc=Omy{?C24p6B9a&1*mbYpR5jS3t)S9EMh70No@;;<D(BLyzLN?L(N zkzmOfMu)~eqrATO`F#2*T7No;WTrXxu<yj%fF<ZPMk{3m$LL2wJH&}puZ7l#6ARvG z0<m+^$Qqe{lA)!zP5?C1kq~IT3oM-_KCMhh51Q5r6!ZaFngvUc=Dv4Z3<%}%8wkvF zaQ=34v@ph6K^j6Hyr|q7H&Q0s7QZH!F-TA~;Q8wodr0){D=La4-l0v{>W~6z8hjot z<RzWH@~0sun6Fl&S+$q4S)X@MQPe0qSTebHxcv+q`e+Br&<R0y<d%siv#wym24QPZ zO61%j26ltg!jvg_zzqK(VmpQWf0g;8#yyzRsV@;qfbK(~T-FuJUkWMZ++q4Z6o!2I zP}rAs1?O-O6e^&dRr@KE+W^-d=IkGD69!^Zb_iv1eeCe!!}^CX#O_H@%TpLSB~Q@D zR<-;G!qExA>Nt0*gmwpD(W6Ua{W6^2=V9k!(ZVaxH>JqrGXJt@M~?Q#<i|ZclB0$G z=0l{3W1{R}jN^3fV=Wd5aKpSBfZak<4-Qh%;L{2oc-Mkdtbu;zP(iuZM7mn|^9i@M zCZM*wYoB#pempWK6^oyl(Z_Jo2XpF;_MyT3e_pO8{~!mGf1?kq(?U`Ot(sbOwYJV5 z@RJE6R-NI9)%1S>pLDfI{?|*Xv$@dIM)H0&{-lX~!AiP(DfvqceVMM-e}AKGKKW&H z5P6Dg(=LK2_eK7`Uon8S^a&L2qJroE?Cv#tgTi?0k}K0wT!jy1OO+3hj$rW2n`%c( z#3B<?`<e~Wl7w6~5nTI980)G0TY*;o4^zpOhA5R1d8%tG;kx<8z_I&mjkjzAlkZ~! zF2R>ye(m51hT#(i>71ok#OG21*6rfa>|G%O#<jh*g62<OiuuFI*s<ARrdy@-8APhN z)okoYIo8toZWc%<pCfH#?G~`oY^>U3LPna|I=#@0wdOc+gg%A84bvg{bE`;Zz~?E8 z&^3NOu;o_6$VTYJzOBZEf;1WxCv_h1?|w30PHKAKkLBVX#{<h-5!vWOl%<fWa>5Zv zfMr;N30|C6Px*nOZ3`zQIC{;ziUOlUjpDkGl`iwq2qcd*0*N)l+(pefcLjpuH*VNF zSmqrq;om$RadQ04uqaOE{}&+lpP&ME@JBPSKS700P~Tcv^<k1CaZ>42R75vsT@n`M zo~N7No<S|<T%{EczsuPPLG<!u-Wuv632uV{V?Wn9>Y9B3xy6Fq1-wCs0}@eC#IVt@ zN-;RozN4mPmkVzjf$40Wy5g&1nT%q+LWR;ER_wW+qS|wSE5K1d^gc@;{sj1|w49>= zk3<14xIP}RFFk?1Oq*uYoObxmL~vW75hw@+w&uG+&eBcX8HTLCe;+^3BT`)LRrni6 zU7hcS6ipJ?JNgN8!(L51+!Ocs<MqNoZ=eZdiJlTGvoqpOQI3fuYs4|`1+a}Jk~?G! zE&zK2J4;PsNyc_>^uCSoKoRs()u)>^aiPeo#gHgBRN>Dvgh~`D45Fq~)fbMY@(NMN z+(EYc1{x=Kf(RO0AoVRJ<r`X11T(2sJ&_IOQynIML?w<PDhyz02?dmD}0HCNx&% ziPkPZd8R|O4I#|66MSQqO&?kwtOxJcJ(n;QZ8Gj)(4gPCn2TkT_z^T7vkJ+w55Iyl z$W}CZLFIl~en;NEk!?0@TxmQ<!U#ZLRL`fZ`|ibY6b;!8jOpm~N`%MxRA+5krPRT0 zqFfrOd>c|x9m%j8-_pdoNE6(qizpDmQEs*Qy*A)ev3x(I{1@GZJ(1@9D5DI2cJSSv zV6s9#XZcH8z_Q8Nf}utIqo&d@2BV%5eG{UYPK8BhSXc~UqiPmcI8XUF+g5w5GyP@d zh*_~no;;h`=Ln{yvl#-BW5&EzK*aufqWBYMhtvdb!^v}hg{#5Eia8e7s*w|ZTr;6c zLhTTo7;7}~VaEj{e(&MhMeIDc0zF>faZ0oBtN6O<N^|pQy>vK0=WyD?m=2OuB4z(t zfu9AL<sfE8K~FDcSlHVV?`NFCRz2es>Iu4<T2h@t&Z;Og&Pj~&w-qC%`K1&?viTOe z&>e*weH%$jBg9t*l&Ib^g46UHguJdU3b(vB(@Pt>^FS1(7yipLyLSNrAX4~Ncf}(( z5tRQHJ@K&^e(cR{#jTwg|K!J<Qr6A;!>^rh**<BW<~PqzhMwE`KYlN4h53RY=SL3w zjR$hE{td>5;{*8fpB_IZ(q?QwJW%Y?15S@(_GIP51D$(_zYNIrRvwqbxkxX{YJRTD zXuCf*lb9v{sPGBfT_=M9<9nMVGGYQ#1Mwfgu{gY6Hu39?Rl+(#1`5O~!Ue<%MEL9a z-3rneF%#(?8Ev;BJbg=3&H(2`IN6Avo>YU*=!Dr0g=d1ox$b$kI(z~159V@3Kyem^ z@?q`nfcl8)Z8=Rmm?>~lBCUpytSJx&2%0m<GK=7q5AMh2_HLBe37;Wv533>mfZKVn zoQS7H;^Zd*#Z#!~>#_vH-$4l(;MjsN1XMHN+;Uh5@_rGOik>UPE$S$Z5MuY<;_`1Y zv|sx){$>i(Zl?c?lP}3#@qL7RYQcgLxT6e=H={{Qb~2tDV}NU}F$)x`gfEwN?ap=u z>aNM`vP!Z|c^bjKheNulG!xXuf;;}ybW1e09B3#{P1KBBZ!6XY2#NDZiz_9z#xLry z31|X5lP5(@b<~JiP>;zD&EjZGLWf?OMO@f<qT8f~>}aKOCW5~Dk6IAOXuwoUZM5g! zV=LPk_Ibt_RColWPHdthUvG{%w!FqI{Ne?yjBnkSF1*M-tKM>)yCw76%yi+zww>_V zp!#Ni^R)13d8`0Uor=g(CX^%R3t`pwOCPqvf9jn1a)7zAPE%195gc6pOBSt6W`BWm z;$f0dw}a1BV6?3A<hKfib+Qz>aYvq@>V~zyeuZtbz(`)HLsi9(1&f81RNTgUCFN~h zs_d}<d=bp*4Z4F*Dv2IuMxL}`4wEJM5u!s=l{6j~HbODF6dkSwrySoknjS%u?%|Dy z@g5-LXmUo2%@irgYu?8!)Z*3gP&7<6h8s{9hoVQ7iP@IQ;)iC{@4;@>sZ8}Xx*-}) zihHRjXqIAn@2E<NnR0lVD~fwL{Q|1&`gjd_(#5H(7R?PTS<y{3`@}cMQJYcgDUKH< zmuV92s??{p+;T=9t8$(}jeq*8PH{;82E_Y$YDxdjMlSnpnHs-8ar1EV?8t2WbX|RM z_iFk1jm3Fp`|x$)3Z|g<=0LtrPZj9q^f!*i$^0MJCNTd?F9H_k{}?+mk^axxgy+9% z6XNd$F+ciU(Nn>Gq@=0>(FLJJbs@yQ=?H6rPIgaebt-Q(q!3bSxI)0FKa@W2&z+HI zsL-7j6vbB}OC_aqaI%rxNsuVpna7)M9!a{inibmaBEGCc;i@Xpp9rZcSBY_$v!ysg z269G9W0%kz;JSA`9FQCpB58c_EH{lDm8fDLW|FRg{USzP7Wc?0B`d4hE?D8OI^bI{ zpNT@>;or1N-ywv0lT1-=q<9?u0mUXomA*|TkKdtbB0E{QtYDkb7bf~nw!YV`xVt-E z5HkS3RZ8#hsEC8Izthh$-I{nnS4C0A$56mVB<c$m1N;2_+mNJ42Xa`%(|3fI&~HV^ zFk!#HBOugaBG73jH|{XweTk2EC;F05AG6v6Jpk>9kzeSIgSA^|gm5Pq@2N2q%zEGU z4gP+9jfEk|ZglK>EIH3fr-P(U=;ILEy<#Va?c2FdFtq`KPB7PwEQWV2+1(LMrNxy! z=7oj1jwWf;q+GDp&{6fFQc+vBo5srhOF`qs7o;D9_Ym0F>~}jg!6~;}ch{ftA*qeb zhWr+k+JyUeX>^yp6kFsCFU1UUgWGSn8(J6I05V<4a@9q(Gc2BhYH*~%>7S@88&z)z zF-$cxxRdf*Mh8C+xeVrd4ij{$s9b)3cDA1rZJ__uKgjKAC8~o^*wlM6gSQFGzTaTq zvu?RJSji;SB&nf0?VDt>%*36l9a)6rEEp5W_jUBzKGQ_V$_4*xuT<76GqwkL>DEVW zf|KWMjh^k?@o9Veb7;ogW6t|qt@iuxl6K$C%#X^1Uwh}nEs&AI9&S&2$MPk1TZ{X< z2X`Cip`mxp&B?D>mHQWg!kHV(OuK2H_nK?wBC(F|yt!X@-X^@cJ7v0`_h0#KuXDQP z^}JmIeW!+VN#W;4r^RiRVg!LZm8msZ7`}C1N=<vY=S4qtjrO8oBZstBqs+5Zx<VWB z@CU7qVEhlxz5z(GeM!G<+pM;2+t##g+jdXe=Cp0w)3$BSw5F%^?|b*{f8X1CWB0{Y zR>aB5s*|Ux;+zw|%rEmx_BP?<+|jyVVs2A?UQl63Q#C%UAUb#2PMQ!+vv0w~nI`=| zJB8y9ml4b;**I*rXhi7Nst92NLs?!jagmr=pSDu0AVLg=2mIQFEhc~2LJp7%HU;)> zz@g)0Wa7gqaSqn56H%LAj*JT5Qno+Zh7AM`ei4Hdi7=>MH>0dH;qxLYJKk==p3q@Y z5x@w7lS#308wZz3!Lv!b{b0go?<`hwF36c7HU$B5&x6AS>xxu*Hh_An89A2gW1BL1 z(2Rhv-#4237E~fV+7FlG%Up$IYfx^)g(WO)=eohg$kcFU`<YbUl})#0Y3k2V+{h?U zrV#AQI_;=dt2U}W_o5XI<sk0DHp9oaMkj<L4r#W^Do}&A{`?yXwYF(N_DscP{TM-f zpb?Wbpnjn+KayK``$4s#P;b081%+0;sfVPURT~C|-@2dO59)t}QBr$P8}=<%Yj?c7 z-p$<XA8S0hBSxRn4Df>!KK`iJ=&^P!yh|~!%(T=&?>(PHH<7Ou*!KVRj`8d4{`XO( zi<k4ug^1Uai>O}k-SIu0S7*2PuR|@!yOXzJfi3^{Uwe-W#(qZ6R}8J6w1V$hFZv72 z>Os|;Dx9ExLntrZejmsrx#T=My>L$y_q~U+c-B${eC%H$Ke+@q7btP?;3LDtizJLi zNt3DmM!1syDrCuj6}IHRiZ|tx;&s8MNPD=GzpCF;msSBiskgMf9PF9kuj<h%7#c9{ zv=$~t(%%G-EJT~%oDvAF$<n%;X5pa3+H^-!DOIbGwjSAKGl2>;V_jIFLmL@7YX;$< z&R40<A%M;E9tX0ikWzLRenQMa@!RrX2qW2fqwo-cP4_eh+X^S|Ev!QT+xMpB%xZXm zfTeAYnxTT&=RGBUQz4?(!Q8SD&NM=`9~G`^j=6OYrliA62qvym>#Nlz#@c?*54H`; zXjrnnG4OclBq)(JC<_BpV29v*(K*$Gnt^rPksY`bc3tVt0}iY%w3R{c-)h|w9fE_n zL_6BgpIi|3y(zYa3Hh+ilA^UFUT1;!^@|{*Q*HU`GY<R5S>z4lZF<|JSntRf>;d7; z0<8f1RS7Zdwkh5w$yf@OiV$wkvH;fIUkdg|KY4v|=z2>WgJnT?Q3@4OE(Y}me@}6! z6%Q5&&u~faO=N+uzrV0yUn17LZ4`ZE!FF7zCW^=gdk-KimRR!wWIEy23*gU&k_-F; z3%V9ggLDrY?nKffv<(MZAs|B1gAcwJ2YM!eQ{ppSvLxvNF~o(UM_eO5z!HV}xhst0 z=blQK4zVFC3%8XCw{Q{8fG%O3uOa4w*`#~u`&Iy6(0#nm#L6Fj&42#G@t^K4GG717 zpV$Bk)~CA(hfjB^#Qm6%x*DX0bk5WOdTRVy@d55~!2!~}Ns!1bNlkNfNmkD<MD>`^ z7gZpU%(?24mtvnE5DvPO3LLTnRJqCrhDZ#gfunRL+@gJco!4SPBL<XZEpQaf>-VKU z_t!zg*83Xbsvao1R|<~eolw`p1&)&T{`sy4%;)d(QzrS-J4)nZljwdc3N1Q{FRy;+ zkiRy#Vcf}!LIqLGrGHJ(sbdBI{*cd5<Z}e-9Wuo+>Gb~SZ`JJKIL>H7M-2PVXMxSX zin%Eb84eo`9S$0NY?!D>(OeNzA@T%UvNfedO2m?4O@WR`dzcga5zd5?w$cCLd9t4P z;f@~S2dsu9tuKf^1Q+qq1|!@XLJjqXQbEKX;Sbt+!ti$^mAJV6d2RHMMguMm=6^c~ zS<2M?oEiOzcRtW~Sc0<1D8F{8(yl9&D%FUVjyD9IrqbfpxoL9PT=Wu>tyLe5$sI7J zx*21m$?<u4PJ3HO{{eWW&SiYnqcwsCsAiA$y~BY8B{~zK1>%8vgVs=Jj-TPapePOy zf2;p6T*%H))nBF{u`LoHx!geR%Y%qVkrwV(xGB8gfZF`!%m5rzpSYX%?Sw~A3r>q= z+de-^Ps{={>Qa~rEcB;{Gu&M2`SDe9{`gMsJJ+xci2w69VoPNHO<T<gQ?MFy(J^R^ zth+0+J~)~(s5=P|CXB0iOQ!@iJH2$V7MJk~C$-0JH`5;-R@c2Z6vR}A#4rZ}GqBz$ z5y8r<#Z5iL`u^s4IEXMkaU_t!#0N@b2*pu?qeZ{EpfM;Fj`}F};t`$V6Hbv4C+cgO zCS#ULq@2=<?}UOMTobi4u*@fiRAF_Osh1AAG<UHa%0d|8dccrlhz;|ib`T>9<rtb4 zqD9EZTV|@RX3I@jXu(tye=}fFkF4i<ZcEOB+%3qDX{D+L%k{nTYQtkhor#ro(BB%{ z_Umtu-P!9_+#OmStWyLcBMx}@W9eY{S~iz6=cSS+9J9=pA99JRBsGnkbx*WzG>nNH z-6#o0(>{q_fBzi!9o;O|ZO{!Nou7Y51BWJHkPo9Q)B$1D82w!joMrAK55Y$xoIAnR zNP>8jx^uBz#CYt0uW(zGpWc2f$<e_eP#6i^h1*G%_;fek9Npq$mG-GvfwKl_D9RV# zFwcMqo_^JBjNxD?94z{vKSG=g2|q{BMF*sQ4thu!22B7v91?>PY_1Fpr3h6rMl9b8 z^Bd!H$^zy(-l{#4pXbZ{8w7Ouq4(s``TP29vWio#>XvK6)Ng<w3JN)>q+mf}1&vUn zyxmEm1gzH=y7kq~0?+H+m|h@bSJSMrCcE;l*Ev`Sp^Cud<Y92`AN|RZbQ6X}jg&0@ zcahZ}SLS9)A(_ZtaI)<P$GH-^y`Esp9Ug3DNa1<IIm)r!hh;?%@y?FOBkjqT+!|+1 zQqxZO-&<l)_K`P^gMKoa%0`5@PUVRN^S3Uhv9nY*<I_^K0MRe0&s1vzJae&kws~MF z70HgCXe>JxmmKQb7zV9!G}e#aOl1T~B;%_@DX%LGQXhFW*NhBRH6Of_er}`f3t`-C zH+>M%P<cNY#>GG^cS<chbwH!e-tq67CS7GQY=(oCKHw{f6B{oQ5}#x(js1Lly9#gh z-`bYN%_p?}9e4F~|700M{^8e^HO-j0*>jWcHS__5D=%sNH<1$;>;DNtW&BTSmH!<= z?au1A|E#(nx%o}wVZ-2qH|-Dx76T*&*9!inFTz*S`qwVEFfwaAh&IIhN6$_bf%}uL z8v_aO29DGV|9dJA;DmIgS{<IM=?fiFBP5%N8seATWuzuF7;{9*G7LngI(5E2igez1 zL8-U9YOum@?h$B-o=O32r%t-?st!zr7-J2g%gQjSY@VWlI77%s@l=>`oQFCU5-7~U zz@IRwNxMjKK3#NFsEw^sKYr79f;|l79}&t1toz8|;-^Xow8IY(plQ?uQU;_eMJR2l zA?%WK$gWEDM558s@QEd!i=X5s$Jro<*<30}==P*1MC#q}K#?3FlEPB^)NTF3%d_I@ z_e^vvT9hQyiPn_E+2A>vF|XTLGlfyDVRj5tU2MF#C5P2}z*ZO<hR_qo)H*?_CKkcy zaS9mduvW*k@ya(wuT{if(tkA3((w(kr6;yR5V8DNzKv76+u6sk`jS2@O!nghI4~2F z+C@Gkw4zvXQaE(Frb96W&q{6^(t~#iS0Y3oaJLKt=H!$TB$M8a_(~l8e0OUy8`{2W zJW{iNrn00hlBpy;p0yAYzq%n}r95#id|pmH{sKHMJBFAhJV6@hIw#yhZvC#AFFDSG zMf?+8qb;4-kZ+Vv)LPPM1)Pg`QWsNKM$&m@cnjsHPy4cjxa+amd9ca23$MXXRSD}; zwT|PC0yaQrv|3Y`jXM(ng?LLB4qIZaBAS?u%KIC!sP&k~O?%XG{0Y6fFOkzDy;fK| zTD$kd`Ss6t|K6SO$*0dgYz6l;_nr5*CZCTdeZqHd_vgJIlMGM#`~X>mvxB4Bv|e4m zSHVdR_q4og0fA6N!LLiaPn<B`gD90Jy2p}<j$2QAOO+0unDqXhJ|9^0wS#$nANP4L zWv?f<Tkh_^?wpWHTGFL7BId1z1bG7Dfsv@|pSzZcWedr&;E1Vy$21Bjqm{IbBNf-5 zrlOKre@{ITmYhr&W{*fF9T_o!szxqy4n<<|$;n0~!Sij`CWev7d1EaTd)UusIm96Q zp#x<{7G+CCTrMg*4vAz6^hxotp*qYaM$4LnJ!FKkO%x?g!-_r7drU`GCoWbs;!Mn} z4kMP+AY6=-;ld224zo=jsYCXSor{ba1EztF%*nETd7LWnCxzEstFS{P<rfMOK-7q~ zv`HZ)GZz^Ytl0PlxBQaPv@J6j2Fxd}CO^TXlnWP_Lb60h5n<irmW;{`L{i|m6-Fuj z2Ib6-2|^Q^YKv`8)i6!`S(l7u@FuMr20;VEn+`4F>CDS2F1Y(X2Tv0WB`%)xUGUT= zeHNXBA_guKwm>Z{VUAc)e+n0yCPdlgqFXq>i|X@RCc}#avqLR%=&YMWRHEwr0h|Fv zT!-)swWAUMJG%af(X{~o0ow_G!ghb+cYi3rNL&Aj)-6H1M>v0iYoB=8pTJqr-lr0# zLct4E$n&`ZU4)Jc@NgT*+1rGUGic-fhvgs2N?Q2o9{`-|04Y&!j)OU;`v56c&3{_{ zy8=qofqIQ}@&`n?^j}B+2Wa>ombPx*&-dIv(LNuMTW%i<xvqq~fuj@uci0wajwU=a zaRCqSUymF1gfGMP1cbR5a~%9|-w&US?Hl|@yL`fB80>p_{rub!2OK<Ke#^CW^?n>s z`E+%kwHmZ{zCsPZgqPO(&3}2j^Rw3{?Dc*2>3x;W^M8zc(f511A3Pv5Jc|uF;>N`S zH=9)XxGH5pg04>F)9<}M)oAL)+u&Yyvhs$PMr?vy4u05ogO@%Bejs`Z@SaVP(V*9D zcR8B>RF-S1bhSDg+)S?~)>E2ktp7Bubu_q|UQ8^fRMTi{wA9$>{$V&;PqEgh(QSA8 zSH(`Z-SucWMO))j;iK{QS%WX>$ysnuo^EwspS-c6+u*X?@X&j7Mrc(Q7gQ9c>bSbW zj=E>JR@aW3_Z2YrPriQP3de;aCGrt47rEWaR;3_iRQK6(^YP_?4Baz<8i<;4xziKb z4{jKoPk+KuZp?bZv7$~QUetK?`Lx%M!v&!WtYod={IZxL1QCL9c6#{&N|p(`m&K*( zW}gAr@y~hXEbhy>oSs8J9x`L8%Szh91>Zjo`Mfe@)hx5fLKxLb#v8#jVm&$ZnU#z2 zr_#hhiFOlF?Hj?0Qq!jcT5QwOX!X7%k0Vi%MO|-Kk5SUa91EKyqjY)SP;xNP*)WHg zRq1W`MC$dOr%;Ie5|^fKtwlqc2_>pJ5XS{;#vq#s>!YRX)Bqj#nQ4{#)N@STGvh+> z+<pR)AO?KCbYmDo#`swzl7S4DUS#`3jZ+d6u5!$55JlhF+E+E=)AaC`2z4RUVX?S1 zl8G*>lT0C!FQ6!AhZGYjV?rNN*rL$+l}*IbFkEa23d%UIu$9Fo8RMuf7aN$EF7-`_ zTRNIH$r;4I=p!x=9VGa$tqcb^VSY-eqp*dOSCWIkA<Q-%-*YlDXno(oA;y3*o#5%@ zl#=e$VS)fS!MeDGN5cGW-iTRrf7R{eG?bHCK^|J^yPT9g!d)o&NeHfBxwd>8a4|a< z#U{}8PAl^K!IQ1HVBIq-F$cw2D)|#wG^Uc5b0WRZA}aGSKv%kxOR98mD*=7~18DaY z`mgH`CPqfKzhQ1;V*KQD`}6U?uP?4Lg`A7n(E@JX(Ye=InlYf`cPWF3)(!F#9rnks zEn4K*uVmeMw%pdQduwB^s&Wh{epvN|=k5mx66WO=KVk7YAo9k?nR(rl-;pBqry~)b z#szpWl7P)(i3A1ofO8lteS7u#sn-i0NZ8L9by;!+jW$|2NLnM|9}~}a4t(zrOc{iX z&^MDO&T+%%U_H|fPH=w!^}5jV3KldQZn(R#(+kY@+wt&9c#obkD8IEtdQF%zN!66x zX|T4L@<Kc-**e!kg(Gyo!c?3o#u4fpl*r-2Lvt%3`6}+m+eIEKTI?Q!K$AlK$cIy} zCqhPC-xS({h3w$eGh1%=(luQX=B{Lcs3l@)C2se4JR(%g+4+1N5Gmq5(Kfg53HbK6 zl-7kP%^QymvktquQj4fETl}?Ns1d_9yL5ZJs>pHvdKu{Z^pNZ{9p<T(A|ugKFgQm^ ze95{G(Ky=V%t>&X=^4>9D2A})5cxvli1D6?ptSa$UppeY=&~@~ycDQkAL3baR6vDr zkSJ70^IdjA=9e}p6Vl9?_~_HuVag8|hF@6moS0*6CZ<6A=vfCRk?+jLdf;VH^wO)S zV2V)G9W=CgJ+Cl6;KeP~zcn7^1Iouj%|fXvXjE8AWXWMVFW@JV8BAU2NtYTp2`If_ zB$cvEGTIs)sfW-z59PLChYQMWFj+NZ#--k9*lS_!*0(s&VH2FVDC3UremlfGf-&3I zgkNqHH&nn^rj$z;k<qA)ATG+XiXu3Xz<_R;F;FB{3Q=wziIjRvV$OI8wz$D%dqh}z z)DRFj<*SREHw)T6pAH1uPmW3ue0i=h6{VQeq(dJK9!QnvbWq|BZFy*MAyEk04}9OF zQs2Wegps@yLJOZBCUOy!RUaQpRlqD{XEBV1(rZ{FW*PDi#J=y!SoPP@5r9Vsd2ya? z&Uswx#c;MW9=tY8q^ZekAbO(x<(W!P!<SH2f?}!;ztwAKX_QzfP47)CBq6zuZG~E` z94+fotnE8|kxFp{Ylw;9Z8V+i28ovU*@4^6$*CD!N86@a=)@kmzXIV{WG3=x%b7Gh zzq~k3rr$lyu<E3U7k;r84JvZnNH;*uGNYDCpt<ijL-f!d(1f+dF7)b`JjR19rtj`d z^n~||F}z90DCIPk1D`L+2E~*MAd!{4Zp&GI{7`ir3WiUSz}t!RJRHB*5v;7LaUxh~ zJKt6YGv#y*1DO*uc;RwvRV@%37-!77axMJW$(ef6r&JkIuE#j*2&YwUb6jy4?O-mp z^I#|;Y5VmfbB4QRCmkt*3fhhT1WH(P?6_Ol@9Ft^GQ9WNj)HDRf#z53#m?Cc>JIM5 z%Yz@Y*!HjMJA!huS43NB{OZ5Ey)b=3Jb$hBX8Q;3^Y3(4{0YH+W<UOfVE5M{;B-(J z7m-631yjo^3+=``q^wJuRa$%A;H1_?rRQTgIW>qF-v#pSaI-)`T7d#rPccWdOgj2P z2};N*dq5zC(v){Sz?9*lu-nd&LONE4fiy#eZ8CoL|7KPYVXv{ns$%rR*3^>#>UG)e zm?gvb<z%j-OUjt^1OX(p;M||rafDxIgSzhOFCb{AgJXdoWfS~K42iCG8s|a3|IRu# zA2GVX|8!T*5F$`M{o53cX->h~;Zi7WH9s7B$m99f<u@6{Ps(Fs%nkfsS0a4z!%zfv zX(Gt=z%^b&jy&{Q+xkcoHOrj<dt@@L@4?{8OEX#_a)JdXV`GzZpSg;9{r%t2S{7?C z)y;*oZsQel_HzcLl6;q(v(9v$K?UX;(W#S2v;pP0SY70z-rT~y6C(a)gdq|M+}@cl zjE{2ZV+x5u`gOLH#k$Fy@CijZK@ve?`(Ok8Mf*BUhw;ARazRyYlIj@e7F8pxTDufW zaLaLtVzx?`jZ&!<cUI03N-;^7Xp9luaGg{mvxr5sQi~abc2;x5gm*43Fhs&ziQYh> z1kEA!GXz1;h7ZhJJ@A&tYU_C9D5U}Y&g%9e_eF>84QIkx+-x)9>)26D<=dqvI_QxL z0RYaE!E!=`iLTY=5j<dsUP$phX=kGExw6eugQDlrmj@$v3~xxdBIj)ZUQk9ec59;L z47~#k6HN0rC+INCH^=BON=NvuRMHRgYq`0pLc#=h0}ApnVi_8n-&%Z4i7AGRtjv*R zuXPVKsBTKD(6rWJko;iF3_OWjKWOK!_p-@oDUJ3Nf~sVrZNU`}g+`sw&;+TP4nZ1~ zfOIkNIbidrgm>BCg;L-I;8aTrxkgRK=DXExvCF<^F!YA1%3<H|IdjsyKquM9)0#xN z@VydjDaA&1_6%=Vzu!}4_0U<fC+0wmrjGEGR8~CME#T|(s1VuX6Xl&N*TN`6Qfyfr zbL1lIvo4nKqpc@T{%|b$L2wpHU#f;q=DVJTQxaam*TZf1(rd?~cpdhBaP#|ILm+gh zK)qSN!3K7{g)A<9g1~y#!%x7!?U^sn)jEG>iTPI-C!)Wb+~V_#&&HMEV#bbrzVwj4 z;f?3g-(9PWjQ>2n@PA^MV`5_bCx$t;f16=$O8ZX~xBI4cm#N)BQ{My`32qf58B7wW zf0;NkKbV98gfwh<7IOFXg}1@I(%i@5P(%(4$*jV>^I0!xxPpXmsneUf-2Em})Zjj` zZP`#UaXY+!JS3dBTpc&;+p;fK8ww5t0fXzdDyovDyK0mc3H>k15=9b@9CC{Do;T{q z$aPjWChNR!WEiEE%R}PKQxJL`e8-X6cb1Ps-S>gwWKv25y(ncWSr$W5#j;RMq||pz z^MGY?Fs(#&a<C-;y=x{sgMRBMFICUCwWNkI!GlEA^R6_i@@WLh?^2br2((h#IX+rR zUU_{s<5Ay7+Q^Hz1KY_CdbTdclUu#LnJZamZ$p;&^`W+Gr<1S)s#eyp!fI0aaZ%+` zJe`na)NER!S1QgMbuF>Pa~a~c%WQEm&dNJx92XMTJ^BrmtxOu3Tx<_)H&vBYGQU#k z^xLq9^;<5P8-G!`vo&b$*RZkvo`kuBb1|M_<0U0U&y6d>Q?oG!x<E5EBAdvOqiahS zcwmEB)qUq-Jka*g&>i1TgDb}xeA6*aUp_dfjc?()DQ+68j<4$BoWX_E@GOg;*TOZ0 z*I&^%%(Yo<D;L}Q$gHJCNY9|1^(#bXh8;JT<kw*z{<JuC<J1q02KEiS>bas1co#31 zJ_wz2*Os+gSe3PPQP}Uyp0QMY4W5>RIW}2Y-2Cl!e%xM38^>iu7i$~}u0+ynI<7Gp zydC>k275hQaSC%&D|mTES&i@<i5;FBF}OYLxWbT99G%{em)Aef^8|KE|DXjB@agFE z`S@dk*#n`!&qrM6BnKj)U)#rR2hq=Dj<g;9cZcUkwyEgPO7Eu|{*o1=Od4`n_Ze0a zrRudlU=^+dc!!;pv$aN-XMSD3r`vO4-Q3ch*Vo6Jr}i`Z1r7bJy&X)z9Kc<6p91AF zk!cb$DLz$u%{!>sl&;ddP*J^2H=bzX(3K9_ijL)q4;Z9<VLz9M&hv1Z$dGKMr-LHu zn5i`wj4Dh5L2@;XLWvJ|;1V_b7@O*4r{tEmTYP+W_7kZ5dD8pJwv>x+f9TK@oBsHI zry$Vn+3`F)_@dA_hdHJ_k3@fB%;2Fz3~Hw#dB+X1dZ31_feVz`-t~HWd;Q`)tB{s9 zqhCB(`J&HX!qLk26NUGNeh1|0{jD^PCGGq1NS43Puh+e;x6x5JR{z(9H$;J+x8uDu zR`1CUQ!pI>vv9GnK$p)8@DvfI(#CZj{yQ>UONRyH#zY~7%)opdZ556>?Bw9N0!B(5 zNbr9b(BQv_2*}?EsK{Sr5adr`kKxcavnmuGi=_rtQ_1DxEgBHcQEx=kN5u~UN#U)? zr9jYOK2L4Nvs&Pl9+yBsKf^UWHbRixDKicNZE!DH!b4J(sQx_!Jg)7-1X-CnN`0LW z%r<FK$wkDf(n%7ydF7YPegO@DQk#?yWKuyqIfh1Sx>FbDO`yyc!*~iV^o!2{t(erY zag``Lb~-|`O5CstR}?;LRN2k7Z5A>3k$N>j+?1cHb%iufsqcs+@yUKh3>Mj_&jqI5 z6Ok=}KPOKV_<8q_VqEs_NgdGiqq!jin+TU}Xe0C}w%>3*(e&$l7zUs<HeT`dhdrNl zq=Vr$45=wZ6clQ2p_Y*xPEd>x09D*H1E5Sr&v>AN;ykqEf_&-KgF_6cHZhX0xO8eb zWAJJuSQdL<F$7s=<Q}Ku!?J6>U?vHMul8WhBQdo9{(^x1L%D7f8YLo4lZKw0X`k$B zBgMIUuq%BiB25Fg)pclc@aqPPWQ>QFdv6t~Udyl_m%45gnL<34_qP_0u=Q1zBj2>? zk=*iGBNR8W{K7UaTJzt~U`Tb^8>OYh29+B|C}NFk{Cr>00;5(E6;+o=UhWt5;)h<0 zP|7OGFBeo27IV&xP=qyKZ#+d(kjh+`BIl9H9@h#Mk;*LSpoMa0w-`!f$aQ%|z%7F; z^9q8b3-9{j9-Kg+7nKiUMB)|2s`iHgWkl+_RCziLEj_7Vq;lzcXTIG=wtAmGv;qq@ zmT2ymN53NsbTJII6KOB^oDoWh^tBbM=Ixa=SNxNXZC=5mcd8ew$Qc-lF{aidwzM&> zmM0UmNfa*r`b0f~FHB_p*GpdtCiX;cZ5a^jSzK%!Yel{<ka_)k0?7qA{$wKdCrj_W zt`=U2@wKiN>n<A~a^WqCv~*~bI8mnX!wq3ZS|aGx1yRe2V%BAaY^rlOSZs`644V2Z z0_Q-Az{O!>FtF(UG~D+6RZauvK#L&75n~9j_!zwm?)yFsd5k02Lln^i`*i?X_{o6^ z!{$2Ps=f#nP_$AAN_lw2Y@Ga26;SijrB|Ba-;4`)Tv5#xJCe&Tns?cPg@w2KH0Z@f z>`z5spHw9CZ*fYMf<%ipBR)@=lkHb=&XvJT3HjZCj!BypBWf51{why-B16h9(MMyr zuz^avWnQOP9|7UPnw^7}x?`^35QOe+`+IL5Zf|!OXf(YCt2=+nUrsKM(+_yy`f7G) zKHRk4_jus`ct8l?y@uo0(OhMRj<L7m{R}PXU=O?%{nqgMIV*|jIPWQ6xY=Gwn-{O} z;PqE)MPCb$mxlrI)Z%;2bo)GKMkogxN8%%`^43yt*uC2oznlPHa|VDjglpwN8sbDe zC0Oo5obh91`!yth!=rZMitAM*8Lis=D)(1NEichfG*?^J?NxpF5=W+qnB;$E=|!$= zBUQREeV!M4zG2GfLls5XUK2_|xo5{jfrOF9rHYh5_Ag-g9~phIL-j0@9^*@o&ug$C z=(Pp6`h;ejp<vv77MNeN&S&j0llr97d2Rr0Rb-6n{l<-y#m<ZD)%dn{xdl5K!UZii zcCl)8_z>kpKNw)Dg$4d@6~)ZV{MU$wiJAQ$fbajFP#MnDb}p2}3cGnj*RfifxDPxa z6BbD)=>y@eZ%|1_l`>L8F*hdfyt`=?%9*bcbkEA&1Q4v3?%Z4~jB3Lt^MF(K8z{r^ zKd&m&F0sQ^p|wUqt4=baEr?eDrx=y%Abw8J&?u@MHWwRAt<c7Jv%CWbseAVjjOyP3 zl@tJnc?GYdT@uc8y5nqnhe;-TyKV$gwb7mskeiecTd1$FPVezk{Mnxe>OcvTgJLR( zeyQf!h(}WClC+8#oY-THCam3@P!mI}OuX1amsX3ruH5}mgxsn2?9-Z*1rB=T6(ehH zanX6xN=<nXU($O2g<I?R`((^vaeSqqwMx9)0b*1)6oZr=XWCi#i2mVGNfIXDMOTZm z@lYmXXs)YyaO&yYtl8uA3OSROm;sX%EUdP23hG?sp{H46g;?t>LF+Ve-r3Ah@3%&o z1aLzvc))>$0&zW&Q|V7LCBC#B^=P^FcKxj$)yb*fqjz#@HN6@$q)=heX-f;b&ux0@ zzJuT)zdiAZecSvzv^Ld_MA!yc8y_f^2A{X&EbOnnesq<;E~%iaD!fE^i3H{p-TJ$6 z&r_!LAcOTH=h(9(b6|TxZt4DVPvyVEOOs$SnsAXb#fb6>^?E_a<KJ3lvBOtoI8n+P z_NYUa7Y@%A%e^2^I|K09hqlzS?CXd04}0=RL-I=Zj3LP@+oMbZE7XQKS3kv{yqRbV zI%jsu(?e!|msF246g|)L|4FP4x5RGgDJ8=x2`jyc<_&+qkRPZ^<1jmse?+$4ifxaJ zrxs*vG0)K=r!Tm)>@Jm^5W!M>#bsRwo=VofBM@x!?pX67`>jWT8JcvTTuGjUo1lB1 zX}5IYErI$br^xoSrplw>MrIE0w@cDEpdcES>o6kLSl66lp)mNvnwzi+2CnniX9Y?$ z@<R0C_7MW?8C2RwYEu)2-IZ4$lElzWBX{AJI>!9XB2bxV>i5bwB=)D!e%<o1h=U~+ zpL3bHEm|M!UEUjfK3ZWp@NzmXH->@aRCKLNlWsAL(p@@kw?aT$wjOYX10`xKz@&>n zHnrG7;<WVxJ*2?uyeYdO5ay}|p_>s3mSX?LnGj(_)`e1XCH+*A8eb+KQi<8IkhwP< zLrj9r{b%|zckJ1;Jnq8R+{HZr`GN{tt7!#>$`rh}m7Uy@&4s30>QJ`lAzT%arx4;; z?EJfLqg1r%K8Dco_pL({X826mJA49zx(ZOADlZ(&?inD>o2V-5HH^FDp<drytnYWC zoOPD+cwbl@ekxR(gAHY)39)A-ks#c-E3dD%MNjP)Lq(c7Dc2E;=S~tga#GnEY{I_- zQ4AZnDsP7^_IyzQ8#yeFh=FKK3X=2V3{N5vG<Q{&eJ>w6E{3u&b5#zRm6eYgR^T6$ zsuw-s?Mxy;LP|;^8TeXakdcFy<^Qdbo2n(i2I4>vYVz|?0iM}tfwC-IR5(a;S10YX zb~oRVNFk@%Ni)A*vo1*FcZkd8#8%<is&|sU+S*@csr9Cn2))xjcxz>=5-`X>O`V%I z_cOubO{m5K`mnoc;eQmZ=~l9Hn-z+buP3N-9~a$x<aK0~E{ysPIkVXN%grh#SXw}G z{AAT-i`nW~&>7I|Qk_&PI??t$*gJV_ZmnV9dwsdHV+}LV<in>bf%yP!FfgR}yBjFe zXM6B}rHuZ^FqE0;zrs)s=6^e7-K{NGi{JX0*wZgC?aZKwL?Z(h5Af-;4a8tXVOYn} zD;^g?X1#^QgOvR6ohk5nUKfMZiUA*DGUwGei4j$PolVX*m*PTy)m1@ulu~AMmP-15 zrYs{@A(Q%ju_TxKT@lA}0w+`fH@shr+H@UsIH>;Oz7tEdx-DXKT@~}khhAqiU5eqF zSbVxO{IUw&k`7+^atlOO`NVy{w0yG~*%zwa9iKX7m8%6v8jngX-@2fciRyOFM4;*6 z)Z*Vf%U=>BdKJsL%Fj_`=9hg#z9c<f-h>gmMl6(Px;&nf98c<#CAn5I>s+P}_dwv5 zH+SXclxO^E?6cW=)uJk&x||70HbpKp46XXLk2YuGT9emo((z59j@MQ$&!uY71*&gD zlL4`UJu5C?<=m6gm9Bi{e8x)dvkW*>`kXsE*6Li{SI4&esU^30arBmKF;|>^T1Wz? zq}tpZ$CZ=O4vucRHH9_vcN>=ZDy67(;t1u1mYi`#(h&F5W)478!6GmkAE(rskuvX* zY?_tsWrh*FvDP%OWvV`PSSPfxa(sTC?WShdRj%ttY@1PShMnuy3BI<<g~DTrr+9q( zajdmAe}(#JuW;{ctLP}R*}ifxV|eU#U^J$~h!6Pd7?t}bmGPA0O;b_*$dE;fv<$Yw z08;iK5WUNHOru={JD!g~WCPgPNwqTHYVf?OMoxN()Gqa4*&&I5%`>D49Mli$3TxS2 zX>A(eg~XoJkVasb_b#5KwU@zYOvKiekM}dCEq?!}>$AbZt1SKZAN{o-uY;Zbe49NU zULS7<FC5tXl)c?=KORdr((I%3c{h9fUav*GNaYZNxiVZ{>7>5LLfCzK1LEU-^8BQv z+v<^O72xgmlWwh@zw!J1m=`yS)vJ)_`xx*+4^TQ(^k^hfI_lfMA)6cFErWJPu|?Qj zHADF}8d3-u8T&$>C1t_S-DMna@vOM@y#NRoSIMEwZE^l7aW=scPDt3Ce|Jz`^1Fgy z;adL|m!u|-c>NThcor*H%7P2Y#D+Y9=j&dEXkhKRDFZb2tr`xV$$;9~uMa%4_V{46 z7)UjXq>*^AZD4Pnu^8iJH(_CZVCcX~BT8?I0<U`=jwDJ4H7MvH(a_3sXNE}beAv~q z8^C!;trZ0Z_XBEt-%e0Ir{q11eo2<p7-xC_7_=yAQSuZ3NiOE&3p^OAZA>>F(lowo z>NOzV0pG}$1^N<=dIlp(6RW4fjyy02r2c^g8Vt4Z`yac=imnQQ%!N$#qzzR`w3>s8 znSp6EuL;&GvHG^m@b8xSHG2A`Y%>;c#Jsw8ygk_aOH6pfb)hgX8k4wsK2636^mGfn z{XE-(Bz!2D#Y#wep3zg+Bi_@~kd#G#|LK?Fx%37zxT)9e|NA;i;#Q$mL%&<LbtSIX zPtyLwU0N^jbnr?hpRecTws8fU8gjSt<Mn>><%VEos>|;E=*J6T&)fdl%HhJ284vZm zaPe#e1|xE9k8hmeD`bb?uF5+LWmN-sd3D9GZUwQFB#tudxbQjg*Z5=I#J>2y$ZX$V z<u5VDABKN~(Eqai?=i-I1Rcm&q>SPQF@0EpOd!T!BTzAa7|aa5_oW9iff_@Mz{Ox= zvHW4+5uf5JMp1^B5}uF$B8j1lXc>ZrMaC#?klaTZs0303CJr5gf@Nyh)jcvdV1Y=j zrE%8*6LXfI;cnts>YB1vbN47zNJ4HxcPB4QJ=oX{u=#v3d?OE{waK~l#19@x5A`My z&uHTKttBHw-bC^)18km?uhLRShJ^4wQ9YrhUVB!{NQOKDdQ^%N!rl!ZI-QpJF&7S4 zWZ0~4H5>eC0Gc}^g1hEq_kkbV9RVKM%gz-Ql18z2pk|18^^$sVVHXXTS*q+TQv48B ziZV#(a;l0;{qlY3bKWYOmNT9jM}lC3diO}gDOOE|I+#gSuzKc1ZiDoX5<<NvR<oE{ zq)S-6C((emaImHLw|@0{>Ig|{xW<O?(Bv-?Yoa8^<Vf5NzbowWhG}Y@%(7SL!S@}8 zeCTLeWU$P|>Gk_1&KTr57h$<vT13T_0XE-3(kD5FWZ|K;x!9&@q|$*FyTEkS&$p4D zyug1ivR|a=Nhgp|H2cYBl4qw7+i85Cq3y&g@l+Ale$iYKW&|D`C-D$qnX;BT?T`Ob zZ||N-P97xnmA#;MRWxXKj7Kx_gj)5xq{Q(_$}d}Q3KA>=lv$9Zd`}}n<BqSz`0v8( zNrFV>bu&c$ZhaZP%br(GssIP5TExRM9r){l%(G@!#PIzJ#UvNm0545TUOV74Cf5~S zgCeu@kyJ1lJoJ9hBy*-qKu0v_GKl3jqHj}v>?NLEU&mnHXW0`RX3uRCnAXq)1E%~E z_B*m|be&9D#Y%zHkN|$XNs4<NUv;Sgeq)2|2}r9aR#RB41?*O(9@gLB*VvH3w~>1c znMa1V!O`m@BgZ1X+1Qa3Xu@|`i9R?iq(}PQ8*LLNE<eT#CPJp%LK`^fQ~N-$1z#03 zif1HSyF22lhQiHk`C^tH7>y`R<FutE#v?RmS4x2U>TEzs62VVY-;gN90lRA<tD0j; znJy%Y2U+-6Tz)~I1${tjUkQ;{#MF#2fnh#h6$M$?E{DZN?zIMKM$6D(px6l0!QM7{ zN%pR_GvID3@xNSJBZq+zm`bvMD%UOz58%G_z-LFqw?%~>f*nE4w83-|i+^HOhp#Wn zA*gM0BgaxGnb(ZbnzKD>*Rs1R9q}X!kHQpxyr7f8q2Pr;T)_ApjSAyL1}+MFJ_?0M zP*!bpi^<E(dB(t=5Ws{pgP(fc)1T=z>XQ5AI0cN`I)#_J-0!>$!E754a?y>p+Eik= zjeRJsU!MkgmE`uEF!=o*J&UrBV2|R)_W%a79|HN&p09ZVR(l1;J?549Aq*ar%iQ?Q zZFzAjIARL0x@=hRC=Ws<PGighU5vG!$3+wtUy#LB*9>@+1qqxwQwpMyg2HQZlNwQB zb5I4LQ;RpWw#>!v>PQ9)`hv}d&9XhxNCtX9BP)iiHF=z2kf;VQ3#u;J<~S>HVdw%3 zzH@m(Ap)ly?st>%T+m6qfKB#$I4z$X1q6}oZ;J@;6+X)Wd&}HvNR>9A9ZZp3xS~dm zyQnDNakKlNJL?_d!3&utwMT==CJ=5gmfi0^4>i=ahg@vBB^am=iz5_D-%tmjb#oL= zEYRIcqtI@>lzWM%yjDfl^Yy9->rnZo8DTJdWgAL)WsmIsy7v5lT{Cm;Vw4vErf|UK zO&+-FbT5Zjhl4$ifGZm;X6&Z(jIC#QZ0ao;@xwdq!527g0GfpkcY8~TF3Ze_<i#92 zr+zCt9T_XyKafL{YF*68_hujtFL`Um#!p^pD=W|8bj49K{j#|3MDhVoQQ|Rs6|<EO zut{^Dn=Ii%u4ed?1yoHZS3R!waMmzy05s!y48q~s>{4jJ^83P<y%JR5jondvPg|n< zz4fkkmZmohgb&~~S>>R=TN$%3|4lzD6BEn7%~}6Ro%LBt{@GFfM&p4E3M-=wAk&>k zA*)mb$R+ARS{k~@q-He_MgePoyixkQ)LW|nY-`#hL9;x4wg)xPJW0TEfkB>4mKC;5 zguqC!oCyNnIgm)O91#Z61!ILiK9Ni)k_E&!Z9(Ypbcl0A4tq>BYK=ii)HQ|oY=Z}W zkYBh&Q3j%vzaAD2_dr47&Kp~S`iWxucCr%kfJ}i+aJO&rvtD_H7{n6N3XQ-9H4C`H zENZFICkshGYwKK7(4V<8FsHZ~E;1-rwtVKE8s036>}W0~@8tEf6o6t4WjWi1u|{HS zJ(DlR?ZwIvpMs%=Vyt?aQgSX)l`tBm=^@6l;2;AAIaQ~rA2?wQ@AK?$ki|NcPKPNG zv_6w!cCDZYvTeh}p{%iprme27E#JenQN+_QmM3fMqf%(6HV@M}*2a~|->Q&wX&P%9 zvj%q??5DIH^A;&e<14A)Y8gW-jy_jkUP@<Pt{jn=>g)_ZJxSlqd9pet%~C^&oxNy= zbxGx?)ME_M(sdj>Oj<}Ji%w^gO|LyGxV2p8=h(g#JUxA_()+=DWV2D2RH%2qV!;~q zcxVXx1$M2taRSk!K9kMZ<XpVxNyM&0)TKe{weF(Crm?|KV<Jg|H4wN&qrLFpU|VOx z$tSVg(cMq~3r|&W3gku@VWU{;*B$<JK3+Oz(4|;|C8<X0A3zMu&9)ZZr}Pbe*Wo(k zu4|a?%GE|V@8iB0?pKoy>Q5j`ya(WpFG1(uQCoio*@|W^nVyB~Rz+EH#UkL(Ui}ij z2~nF&LA*VlxCg%On1FRvwKfskx>OIbp_yC0@yVxAT7KR#3iTPNSK#~sL`c4nL}i(P z*-hEKAi)>MP=H!{-v|1Zm`$;~#guU@qwhV9%3}kb?VP({N6-sW2q6Ig;}u65<#z8B zCl96MK$$jSWQxJ+3F@|jgF(C~``tp%z?6<6XIuMvIu&2TSVi^y^3?ac1jQKeQTXUL zR;lw&GnY<>Sh;(fW^`;4CV>I;F1+r3o`&#AmvVVnk~DQl@H?*eYZ*CVq%iynCK#dV zgmI|n?To6WE@+|G0DnP{fnGAAR5II*@C<abWPe5@`%K4oM}!({5?AsYlk(%i=zCSb z;9lpCKz3+59XzJ*>Y4_%YqZ*q#M&k_m$xJ1Ai6UbG0fBIIxx)R>e+1vYcNHRa>kj} z*~S+DTr(Q^(;vkH<M2r~!(#R{V%$w_<Cz0Gw-9qvTy@j&KTb!)u033grJ5t{Xl?7F z?XcWuZE?1Az$juJa_GY5zDC>KeSW0P)5ST%Z9j#;!(oKHgR6%)93e|F`ZVmd4%Fkc zZlNyLuIBi7i6FJ#k08~t)!9KAzk%+V95Y1=>|UBjQ6t?D3@x@6?e&+y$v0$059VOr z2UQXka?~tylqW<<CrM#>$Z)Enc%}+H;*-uh=lA>Pv&qrkT!K<up<Y?&j^~ayzBgl> z{4D<-eg%7`4$t2{L~2s6nEjJM`G0o@V`lzm^1uH%w*M!HnUnF~ZWQj;)~(cSMfUCO z6^^@#jxElZgG?7hIcS*;l6sw8{?+eFPsX~5duja{+OOc`6lL{XLUhnUadD4!e6fxb zzbpT24@XfR`?VM^=3`Q@cwU5K0!P?vkm$Q8Qhi>8jN>;`UW_J=&A*?W>8mL`a_)|2 zq)WBrKb%)F)sE5dl?(G@IqEkOja!zpH_&D_kMMY?sEm988V&#V0!a?SR7G0%LQ`P> zEN8al<>7FTiUeQXSN+7_9qr)bzSCDi0G=EYAys^k^g?{mL<bAs8pa^?a?wF!%S!sN z`JmXt=oA7t|GhzE+RmY<Vgu7CxB*tWt#Gn*xeP<ls#q?K;0NZDFLj2&7Rn-WDrWP- zbSh>+e8^eO5@kgF1>~2ijtH3|w#PvO#!J_Ts;a_+jlUE{CXa)ZVXIyI*{cgIbDg#O zK%DIms~_9xRrAgDF+uD_eCfYEEc((vmOEo|CeMoL`g|*}zJmuU*K;PuVejV1an?TV zo^tgLkUi-jjj8IfD;Z(SgB^#Ld%tZCF+4}qCyQBs4J3M*O9It^HI9&(XX9n_k7@U{ zq(AYdbLOV1_)x}4Yi1ffoPFg*(=X7_AN?`nunkDN+ce~tf>7FLugW&Pb_BI+X&;AY zajurnEgZMy^rki^aL%Jr!Nbj)fe)DOKq}u;Bt4mBLiOf60mTHd87kQi`js7rej7KP zSD`q<OR57e(U+IQ4KTH%M3*<YJ_U+e-Be~yu9zOZlE{*XM2Szh+lt0?PviJ_f9BWe z@$>Nb4`7*4;r(q!fdBR4`sdWaDB-n0j~t`W+1629nt*PPZ`Rx7)=}pRqQYKv3kKaB zf>v?!9DkvaKI@+Mbo!I4#}5*n9>g>O-X2f5w6r~Uf!>c3-{kj~+a(S6UpF5V#F<4# z&Lt_5^^sDlWl*9hY%6>KmwU+~0DGZOCv7Pd6<B$^<V}_&5N$#Tdwjp$VftAA7qmuQ zJXRc=zzDJa{_y9o>SN<ZRGuq#hn)H0$^f%6h$>&ax<e8a6?;g)NF=~3N_8|wH(+l? z>04$hTKG6Q0y-jGFcdBdq^eL>V9dba<LV?i0z3|I?T)og-Ds4;7)Y{JRrmFtLA&S( z3FB-10I~L5#29dKS@i}O@E+!f0Jyq}E(&NWp&m@wd7roiw+g8jt0)8%bm6R#ic~!= zn;2(~9Ns1)^x)u_WTb>~-_c;fu#G2bBrq&IJS7`RaX@4rIVIOpy3@ws-f;&~@In8E zlWs(gF^y>w(Jlc}Kk1i9D2~l=#$`NE`Zr19pBZSo04y)kT#E=z9Vz6~dkpKTEY4Ye zmcD8X>u<sq_haa#7)rYYD5<+`SobQ(IL@g3-{O<|(8kSBX64(i%u!N}%d@zWku&(| z5txm(#f10pA%s}up_G9_Cvo7)3|U4vxpR+XyG6myo_WS7No6i!4qmIE++XxiI7ua0 zF~C>9tJ^Sub5=zyUXB2(Z;Efr^y`+<!oU~wHt$I9nR-lifNH$c>%9MN?S<6bM7UWg z|H*lWnCJidY|HlXbJ944{sVd;hUFOT>x>?{A8NZ_a63q?*GuZJ>SqpGXV14EKL($k zcK<=e#_`n48|wZ+m$*XY<^GIe@r0<5*Ok8y_k5a1AmIP%a3eq>@<90E^f4HB)9d+4 z*474hMyPUv5IhG7_T%@P1nt2CdXE1t$p;urBfp4MBd;@VGuyd!)3MZ-qAqdMuO?qz zzS?}n2&0A5!fIf2F+3fZ4K08b!3?8^)5Yre(@+;`2s?-oMhB;j)xv0FxH|BMp@=@F zgYkTz?7u1N0~WAFbTKWA|Ee&=^f3M&IE5|x7iDAs3)Yx6rk?Si6%IHl%dbCiQrHsN z=Ghw9Dy$cm%WCHa#$ZVqV!9ZA{(oi2!#%eCJ2WsLhSb>W_m3DG1z{F5|Ex<_3={7< z5~z}*G~5(JGX%N#fCssnJL+(low?Ckus}FGb2A3Wum;*hJucNDjtE*r&ap^5v|Y}^ zlt>DiDM=pLwOUC@P8Zb3N+Rj#pEO(%Oik+|z{d%~i0D7GgM@<Dj6`AOgYp|}6GaTo zLhEp(c6P@FHFaTmuw_AB^rWyFdSdf;$)QEo!&l9c05$9b@s9P*4s6I_A(g4R)cr$I zU&)6QAOsK@@YhaRj6DrdA<-FTuu<scE?2PGf${ROom9mH(!d({jMq0vKq*5Q>(LUe zW|K*c%k=|98`5{5F(YGc%I!&jXGiLCOPC&|3SuL&HA~LJN0eupRvi$bgfzdNU6%HL z&UbN-zZIl&gDw<x%hw_?+8%|mBai&@A+hgH4IOEdK?5+V+8szR3z@Qlc@y9+a3g`v z76nK|?TS&uwkgUKlT{!orpe(^7tc@|N;y8>(9pCHr5JRKlB0P13{zD=7A~=*qsfY6 z#3@=MM~E=PL1A~}hm<19w1g^Id%l#gtznVUDZ*ywU)${#XSwtqaKl$DGp7dY<Q#m- zO*wL24U0-n^;O`Zjmnl1-ldle@>TGWht=!)Q7+|{5MXJ>ko{GGa~ec@ZZ+8CKxMS% zYPY?r@keA=Ms>;Nh>cIIE_YyZZGBe%w7KQBc4212k8%l#qMUYIY(tr+5p(l!@I81~ zXd9oFB81y=fI%j%FNSs=oWmY{X3W}eUO0!1_CVbXzlGfftd)ABk?GQw`bd$z42$h& z)n3f7*U1zWgvrrT<=IuW?wfHKoEINHxufq_k~A;vqm2l?m?v@)()pQQ2X}2}9^{c> z6g8JV%onEX;JCy9@D*20_+Kc1hPtU=vLIoVCG{DiK_`o^vLq~sjdFl^kA|wL_ewWv zfRRjxGdu1)`>;)}ejPAP69W9TPMEtvbjuWg5}31EEa-_GAuI0yHomW=*k}e|&@o~- ze@7;15v3Z53%Oe3<{@RAO`y~8G@d2WdYag+P@Q$?Kr<b)FLYGRIoMOQ)S-qDVP3g2 z-<4|5(<Qk*C>U?zs`om4z=3#+yik1IeD9^n#G3>L;(KPgJWmW22o{2wg#1Ww8It2= z3nft}g1{vf%<ED|ioiuwr;3{;N#u6GS1<va=Vu?0w{-FB<Pv$IgTk47i@h2#cAQJb zj)_(rAKR+C(Z9HIQ$yqQ0f*9rcCH%=XbB&>f>3LQ(|Gp@{;byvwX#bL(MN7jL|%5o zQ*3k8`wfr&Y{A2wpQ_NKnzpu4w^~Q1$7ORo_0`Ii1v<p_Ap<0cd$J=kNZ%109L&`x zZP;FmWT2|6dd>t9x_p17cWpg>0tFt0NHo*NwpbU234pL%U%Auu==ErTpEW!=c;|VZ zg1u_NVqXjBaSNUj{9+gLE$n)aQK%nyZgKZ$=X)j)KeGHo(PVEaOb~nEQ>t`ctu$lT zioqBd;!ZMWipYVQi=IveD|A2pdD(7ATg6pkut(<LMT(D7sNT>Gmer!uA^(vq*Y_25 zi#!9AWow$tn&hJW*$jYPZZxLd+i=2J+nBA(79iq6o5rTbg#D$)zPheGG1e-zG_kFx zIjAg(-LSi*Fn&z3Q+5CMdX)4xInCN?O1JVQ(v;adeeF433$#zKU%GgDBZqu!#gM18 zwEyr>7;aU5(%U?645L5T)&04RDtpC1`2Z%G6L0>zr8X<`-&9^RF|+>LbqL*=x=C68 zkt}H2%qfoy5$r3m36ZN11A{hi-H0i@vU6T2UXV3ke|?c&mA|4Bk4W)4P<TB(Jw@jp z2-r0S3Ysz^!?c%92G>eAjsbbLjt^oS<dnRl9Ab=D=s%EC!@Pfg4EDhtqJ&MNRS~%A zjR2Y_WGK^ltq(X?LF%&)poMLuMDTlV@^}RbqIlTa01Ba;3F`e#Dgf>nGyo7kf3OeK z?9vW!R+?)s`y6~$Gm90rTU<fZDZPtzxza^nIpwE@Tu(9FQF7F>Zqs{_f)DV0_E=oD z!{|R?mTt@f@c8*#DD%-8q6wqn?#1*z4W_D&;hQJgoGw8a5F8_`^I{!KIqi1a*gann zZBgP_C$kS%JkH^+yF68npg#A@PMgQ$){`5NV|@*Nj&131z*-XUR}n_rWmH%iQW=I{ zQWbIZ$y5~x!orIKF_$o8`>}hLezX@5&D9W6?v->hy5AR0>Yl9SHeTq1Gv}m~Nn<f$ zaT>0sk=pbCr0+~lsd8YL92>~jO=MlNsado#YaENIrsXxKlXCuj*-Ln`nvhxLfU=Tj zf`@B>klWOVQ~j>U_9vU6m&aH9|3}$d$3(tv>z@r2?yikDP2=wF?(XjH?(XhR<L>V6 z(73z1JN(#t?wxbb+?|;-d6REeJxTFLrSfLg;(0#H@1bvO?0JoLrv1UsQbg8n@U6P+ zwR9tOCbnZt(mX4D24<jww8KYT3`%n+liGuIGln)hkR}SZHkn*tH>q_)DKZSzQc_L7 zHa)NsayPy00(U$h|Ch~?yz3rNCAfXquNuzQVx~mmGgJqLP`D1W==MLc;4eYfsJiYo z=f81AEd8PFIEVrsA{!NCN*4Ca6lbkSHH}SE?$agYTcco(+2D4Qk6ZT}3Zj#~&${z9 zphN{cK{H>QuPfA~RPGo4fH&tdAyG0agd102_x7PO&nYXQJ>NADvN?4x%v4CX5dTQ1 zO@@c9_<V$tAW`137-QoNg~ElSV9)Zr6UQ*5_cg)5@Exz{CH-P**zRXEJDC%O)$D4K z=NVRMbAcoJ>82HrB={p7jLbVlXl)VfLmc)AFd`lR&FX5ksj?!vq@@2wv@(6!(f9UR z+r0K`J$mjkX%IX-?<`*mux~3c3%s~E>CpOt={R2KXuAXAZF015N^iF(&2ZzR#7<o| zRnmZo1%0R+X-6cjv6tq)X*1I>SJ7rDesR>96T!i<z;2673*Y%;1)+rb)q*<-4E&Mw z_#WSJo^*Z3H5u$y_kdL4=O^s^0-DyH+1zkxmd@Urt=l3ZClMJkTOHY2tG>lfT<o&x zfu*3isKJ1_q2$Q--T46a3rJ6&fuyECK6q=UM)sve)<s>F$F0<yOJi3j_P6HUi%_-a zW<z3uSTaKMetb$sHO~|e3`BP1L<099oJKI)Y7IhVKn{}?^Sepniz=dX1{qk~l$u<| z{Mo%k**5ZGVm&a*g}<lCb^K3$@j7s^-UvBa*#9h+G^?I}&r-0fQqo?IQ%k7tNNUJi z6I}?a+oLl#-NmRoOK=^S`%GxY2KQ9#&Al9$EQVE^c`$f?*VVVpI90;r3{1j&uNA!I z_OW-%cgAU$Zn+v2bX1HdwU>`~^)MYS_V?Fh<Ah(IOa5*4u(bBaxwQ)+ST=08?iG5M zxc>=*ka;RQyX)=l@OIX+>hN$CV$FlIoyx0AaO>c*3eP$jVU5GPQ>GN<1H^mTc;}xk zOM1HhG=@+6KRpL5H2*Ql{L6DtX7IKA?k~?lt*m&#ON<W9lfNi1BuovuXpkz)15rwf zs}Tp-;pU-&X=_%U2zv~!Z)(x%h5J;CTuG@^Vk@(nn%eP`c>#Rb48?Dpe8nK|4Iy(u zlYwINd0Zm0Mxh8H)!(!?uLj<-VwYvyPcrYzIN3Y46tAgu4yu$v&3&X<^VdBIE-K*T zY1h?Kfo!rc!URa61n5}ygECN%jKZf-A4n)|sI{0)+eT`h{1h<$#QuySV3}OdkC^;2 z`@B67ziGtRf-Y;vzmbqzc(P$_H@3{s@U|PZA9Q=%<66_Q6-Mn+(sa==WzvR;L<hrC z<>7Smhozifn#IoVw)BND83|+8nKZqxD>9H&!deNY?zTkiBZeRDfHa`h_2nP!xnS7O z7+&*H47fqZm4n`Pb(s$Y4M^NjkXUj%qs}5WiIN*(HEnlTR&L=d7(s(zrBp66vOpw@ zt_D;a#5cj}y4Li+wkZ`-*)pUWN<qP?WVAFUnv$1QJW+9}sJvjvsp?my_ddC#BbGZI zGZA%DuNnbL&8_I=y7FZ)3fSb5RjBSi#oezf0(JXACVmZTY1+fJDpMa=Tba{&_wM-I zgkD-w=WNHr<ww$Htqp1Mfmj`O1bs|Ya#oXkoHr`l0wXqJRGoy(J+MjP%WXm*2MM7Z z^;N{VQ1AD55fiaIVaH;zR$d~fS#l$PCNF4NXR}$1xg4By%Br^~Pd(ev-_dgUM)uRA zBh--f*l(MrM7SK>NOC!H&pNxBzi$tO2ahR#zHHZMaCyEy9KZMNk7a*+a8-Ujt*?4> zX>hr_J)ZBjEy8jYceK2H+ysvuR=I0%XnedqO}yTuMUulnRcU$px|kWtfE0*T?3!mM zp;M3UkJ&x1&nipr-v~ZWz-xc*)<AtWdfbeFe7t_LiWHsL!?+iJCy#vB@U+*-G@Hf7 z+4I6#`pvY&^dMwuQ^$n}Z4S#`SvJK_+)t(fCy^_4#;zh@*~yYOKQ3iEO-4iWG+}mi z5&_vQG;~qQCPg`zH+uCugbdY6981|s3KEZ+tB+T$D%_2?zdYic%5#o2Q@+fmhgsz4 zT@>H6IE#fiH0V?+SX4*cA*DAFV3)pf1_Pd@!THcfpe%q&47`*DQ2^*_F!@ecqjZlT zzH%yHzyl?>9*z8#G~t>8s4~mC))4Ks{dKB~)VD?PLJv9U7~e-MvPHQ-A4-7QGKz^b z3_(t$oqNy;=_LoY1}bOJ3`;D+EVA@nw0J?pV4SR_u2Gc}Sujez?Vg{QYaC$Lc@nqJ zhOD{W?}$U_i+M$XdyFmzK4q@tC>b~hNpLqUL34xluvXnC>Ixx9H;~0gSRUO+;w!>- zjE)9G&&b6H3&@65{X;f~Xaq!sqq=TpgL#Vp8UP9B7!-gShoCz<>mmUrSMizHi@x7b zCLR22-}1I!<?Y|g?*$gS?~91FdoI1{{dw?mo-A#>IV7*$3!@v=ZtX7W1sd2?m1F6$ z2)0xDoH&4rYwvo0ahy(#*VCn;<#}DJ(dqW~?CE-&Eq?<gfJc=La(;dOipMWM0P;5P z{k7tIojLlIe;M!N_<HrS^W*IJ5NY;@I2kW5Z~emY%<cT*<rM}q{EjET#B+2`bwiu{ z>YsPEI2_X`3gIc|@>7#~oO>MED4{4Med0lph*%6FS|L4~e>fs~|NEHe{qLiq_rK40 ze@ZAVvOdY6L_{hEJ*|=6UqTI%{*OVih(ru>S|z>mewDujO<Md$`#F07RxH*X9MLES z;iUZ3{QjfR8RYz*Leddg7@V|jdUyT9nq!=_q<<e1{q~mV+aCcrR$9A!X9Gq*nl-5_ zG1_ZJDX-}+(Sbx-oKzxt<<0GZwh6(AH4ZlB?wyHeu<aagknpwE;^U)2SfKtqiZQ@R z0^kjJ_I`|<q{j-BCMUtTp~W7dga!f}34HjvZeV^0R&(>~2xYmX1e~f?*?QyWRvI5C ziI%@of%iz4@^(+Ez}|$>-JP|o?lcnxbG2Ic=cU9PH;CHEJ)s09Bs6^e{XL*BPucI^ zp@F@Z5OPqzN`#6;Tw0Lnfqs?jY4MdNFQLlG4gQLUkcl~pfsSdQ+K4gy)eg2Z>V24V z9)+_;t^<rxQt^}gw+d*0c3>k3d%v!Z_atGARVStBxAPJ9Jukc>mM?>XJ%Dq$FxjJ; zF@_KVt)Rg+1fWkFBMqgugml@h8;<`6x^Z~UF{nRy>4${Nbz+S;fbJqGZq94!Jaj8k z5g|?X_C})jJ9?v0U^a^YFkD!Mz$5T8Rd;MW{uJ@xFQn<)t0Y;ZV1L2`vy<P=gy&oh zI3k!j!CHmRl)^$HcRYDLiC>Q59{L^7DJ6EN!g#u>hOHYVLyhCCG9c>XNK1oySUCzm zHaqg5MHMFa*zQS&Vw#}Spd|udK^}xYwi5%c{vLCVrIa&K5(d;BIsjQX=;Hevhl`Nn zQan~crfejT*!QSWI9r~NEmSDdN;15YUD@MnvN>3&-7J))#SR_|CG=JX6x_aF+pQJ+ z#MPLnnEO|3@mBD;JHKOgQg8@$Z9v)bo7P9%1#RT>g{`sG9%&%oG{dt+b%x5B;NyLe zvR}q|J4h#kS-MeU{P{w#2QUerETaw{DvTm;I4Axv1`1iL=h-%0MUkhi+La|f%ZeZ< z2Ej-oL7evu>LO{u`V5PFJuyxxATO;R=d(p!7`K$rud|4`_L`_VNz)kEyY2^X&Vot1 zapv<u?M@DgvQ+ZRPAJzM%kZyh4}9@$?plQQClmx8_;K)E-XQRKJ*BuG06j!nBz`Xm z=|Bn>>bPO_%G22kq@(;)?`(HPPMrKZW=P+)<h*r}AhJX#&ZZ@rZyxA_H%1yL{o1lc z`?LWw{Pc*H{4qSZhZ9(4Vco}#Kz42^AV{p-b}2Z6d`4g2kp{H&y(odoRBI@ao|e^7 z^BG;F3FCllQ66up)FP3)lMeVx%RX@@mHh0Ny9K6^WmlVZkaNe(pd-u2Iux$E#wrxA ziY8BKC=Q{$#6>vxK5uuu=d$m(9f!2|OI^L>uE9gE8E1k7sWaQWDBJ?TrL$!VL71xM zfd~(`A3<GZ*@QEW&hi{iZD#^l`)ITrZZ`yQ=7EY>e;}2;yhzE%k;0xDZ`w{xdsLH? zFO!Az`Sr@WiPOw=IT?}hftE{<cl_RRv_LRz^tjO+!}>zH3$$`?#pv#uz^MX(EzE*N z@iQAnrif7>=PTlQ@B#tq_i%1;JYlRy43Nb0uq_gCI@DKH{KV}AGtH!TMP*eTsyan| z=1$BkOTt@QH+AoR{$tW7#-hWut?eexKW1QB#!ZosLpy}4;ECS?(4^S}^A-=dQ|Y9y z5If%XHsoS@?<bBN7kB-J^<mTbwtqfaca(kx36(3hVRoKn8LzvxfeT?3%$!~$OZfqe zmk8h%{p<OVgaMV{rl2hY9E^xsWOtjlt{mAN!tZuz%vnl_Uc-`4@cxC*g+8-JVR&HA zmuDF4PHSu$p2}?+DsX%8*U$voNkRMgF(KK+Yhk&!U!yj3bfu6CrUzZMOD|X5_XXNQ z_qeOwI(t15fYxgI?$yG_s>FjA{**lZOj%p8ZtRYr2<jzAkLjj`4@s~$$N`M%>_0Wz zj5PmbW1y%1FE020cS2%aP4){pf#CJ{6(dbGbwGk3z=a$ZK!-sYky^VGnq_KfzpI>0 zpR9kpB!_tzz^x9X%vj@G*56xy@6@btLgzhP_LX95Ns4!tk7h#&2ylsdI|3lc@MYjT z0P#k7IN(xggiv!2Kf*ad@+{4IYrK!&2COf_lSoK?WZ}QFJ4_3GEAVMudfxrZ#^8W^ zU-t+H&=Se?Rwn0WU3&ECihC>~BH@<a63<^t779cF<f2I;_?VZ)ne+sPg?o(3CsG82 z?Whl2{1^kJwo^oP=B|h^FMqjNOH(dD1`ot{2>qfML3nl{qUSg{>ic^&YwZCm)6Z4Z zEhz8H77{AWcP-LwNX8x_Ab{O>ahVyWAuwyyJ&^ZTYl3Q*6LuGwbR3kbRtxr^LIL~y z+Gtc$5?p}3-5!NK0@C4yul_Z~K<8K?Dp{tt0co+Xi>z}2q|*s@U=1Q(&;CQ(riB9% z*YoyDp_dMGgf>&<#y#m*akfDw3qOyi0Z@?^h(Fp-Q>97cXVw_ljk60#-dR#X<APb{ z!dcE#sXHu(R&I*SO4iK&04bt^jYokZZep4CK8F{QnPd1|<jaCvb|d62u=EesWn!l# z1^`ov<fQ?6ToY#c#)w7Sq7MC&>@v*wGBJq-u1slS3E@;yY5dqXmnGn2T!_B!RLg$* zav1`~+8JvCJL-KgcR=}B#z2^0ENftm$LLso!jLIgy2zBmzkI;}VkE!SSVapsC6j|| z5(}aE>XETo%Lr8?`ZQ&2Vaej|&wLMOcVdt@BHGNd@P5@y>GXK(I@ZoE3#%|W{ZKRh zrn|hC+#}CkM=gzQ$?HHPtKZrN?s!F-B)o`;9WqYQw<f4@QeI+!y05nqK4q^7{p8V+ zX0<ENC#33xR8O^7<34h0M@1>LtoB<h#h^w(-jew;tFxt>zn_mU_x{APv;Mp2D45Xm zMbWNVtb#ca0f6)lb~@=+qFSn21UxwMg6aq&Dq_E+ofWWf84ZW>hZ(%G!cjrhK-Q4P zvK~YlhTL3QNzJzBw%*uX#zcP@6IjCO>ke+yr*5{vYp!RVR-G`#V-h&mfp+pBOySyh z46P5Tz2-Ye1d8g|)&|90?#A{Wv;MM^r?!D=E>8qf7`38^-_r8eS01aU7zepDNBtBw zM$@!xDzT4FnpBXCGOAr@i5_{eOh~MS2RCpadA8t^AzAB-O)AV|seJw8n)C}%I2igW zzyI`wS-LVg$?zw~ervUos%_Dz2n6H#n3I*x&(-rz5~h=bXxmz`WJTI6Wu-r`nMg3m znTcdtgTa)zR1Z|GhPO8&EuI|Mcb_1Xs59l`4(VFi(vaF$du#EnX81XME%iY^mdkMn z42*8w!*S>TD9E7}go({Cy?r@+Jl*8T?{;ktf2+Y_jAMQDcrA6S!w$Y|A8*~nWFF-? z;JCPVG_kh1Q-8RSR^LqG!#L5s7zr5!#p0g#x=A+>m1GrW@NJH|fFe5=fnuU>)EDb% z{@lEh)3nzdtlbz>pBtUtUj32N2u_Pdj0-xkRiEQ;mmTLZSWoU?Rgt1&$8oGgi7u{7 z7hZIb+Ll<HN33M4)Zg?_VaXTwlOow;bh#VMz^1*tfyAQc-fJ4(C^p8pOeWNn5djyP zf?Uq(sNANx4(k|NX}(D+xP|O21KL@$@ZP`m8QUh&$+If?8#8`$;rCaJC$5ETpO~b( zyW`v0<joIPw|0%5&-Xup=-TO*BihNh?N67dxBIAm=+fCu67wV<@G;PQHUD%AGtm9V zF$-Fjf5j~R+WGb$l7S}FH^aZI7+#xyTQMpb@>65G0dW{jfoKuC!Ht9Pm30ZzTd)sU ze{lyRF6J8(vQXS8pnA&e^Yfn>(l*oNp`)|JN}t%}3<rx7<3t#R7zZvfWRWUqcYd$v z&Bein$Nuj5A@q?Y2XozZvc-<)R4!>RO0h`1@U<LQXuLvYMMN(IueHAx)kY}WUOi9D zzLJ<Q)t(XY5tm<_SRqsGyqg-RCQ4vIpGsFbf3P*c5*4ytCC)tB68Yx=+u=ih#YC<S zi^m~wXSD>&oE(U82G+y6ffX){85{FdLRzE>kc6c_FmV&H;Gu@7+~I+0&uWWnBk@;O z&^?Zv5m(gWq9T#l^P*y&I3HXd`v+*1e#kCCXuKKauSZtpII&Fo`6=tkhTjW^YgrC+ ztj@&bl9^a82J^sdNeq>=%A~3Cj|4xF!xz7eQbcua+mzeKAUI;C+EY5dh3ZOYvN*xW z9+mULMjTs0B`nM(9>mBsjnMDUy@vGp0ix)Bh!J==ilO{=nl>m^!}5~gIx`(MD2-xp zKq)f%5y|xf>S-`Vg7Gu=F2zDBltf)Wn!?`gTXsZ4%;PV{18Y@inVx#9Tg^9h@yOfL zC6Nls4aZ64uqL&kQAP$}{ppH7PeKJ|GNx2R4auz9{4IK(!s0(-n3ciuMhww$_0Wpg ztLa$fJz!b^GoiE_gz0JL83kPX&N`r2@;>j{mGXYUK_pYp2WUh~l-2O4XOQE%q5?zf zb;i!gi{78dT$-I9SKHgy7dPvNT^xhAm)=iTO@9abyShG~3cJ50HYIOrc{x8nNJa*? zeWl(XqmN;m(%x}$K9{?p(IzXYWfsOO^f&&mTtAhj*X`BIU%7tm_q&U#N7dJ=zjOUv zpWgv+l<+iw0~%xlP>C^+8$em2ZmE+m24-Hm&c%(5ISdVm64(R#V`&?Y4=GKGku5Yc zM#Q(EO3Xn6<RGQmR^Nprath#aS+o!a^|67kHzt9@{1BgDS}Wak*lJO^)`;4(%YX#7 zaDKQQz9{;Acea7}LAKkZiJya0eIt<+&H_OSZb4FapqozfG}CuVUmnm)*DH4bbUGSv zsEHu<@GZ2)Qz!w*KWjat*UD(86+9pzi4%>e3H9pe>M3>mU1ym7?8OMdNcAk6#{opx z$zNt9AjaO8X5=a~owu8>$C(mFZ29-QF^tk={nAz|a^So`Gx%l(r^Jt6snHsX=si4~ zL~w4vJ>SjRumut=w%aQ4MQWMWVe;@jY&RW2WHDm{&w&VNMAvuao7O^}0ZO$*8AX1F zM4OHz5KIA-!?>kpO7Q023f=v7as>}1hh*KEqSp%yalnYGZ94I*b6Ul@PrKb9iqeDa zyJhSR7DLG0RtvCbBznNGR1sE)-ZLYvntP*o=8!>mu#Sn+fkTQ!@Kg~!mPrtB72GGj z0eJ~m63d7`jKfH+vsvl|Y#+tuKc4-<cb*hUjFmPvxc{W|J3Nj=|AhkGC6>(naXck* zQBz!ap$c*{^JTwyyFRyk2oHvjt~r4gf-w|v+-*R|HNd{TFX3Y|JvuLWiXT8u`XVSi zU468<cmEeb;q)~dZ+6vte^~rmN1F$<*&`k<x8TB&y7xZ&=iSxw?(3`c;vKEmTi^R5 zcl+zX_94nz9FTMr2SyT^bF`&)=WB@Jn?>;iy5Da0H(fLnoR#vaH6h1HlSr4ytc{qz z9S$ev3|9G#CiQ~(lvtKCCgDQr3@dpvXpw(O{AjSM3<fhX|Bu39W?GOR9afX!--<po zSak-AnQFm*FJAIy&?7rd?gaCxu{>vv!iBUM{+4P?A_Vm*u=Hmz!Ut6t2J>tcbDIvA zqQV&F+S!76#=<#lNY=?6hLMHW^*hP@*aWGJ_DorEFmLiM8u&Sq8X-aapmL$|7wO#- zp%!MRuu@s$>Li^q!uH@U$m8U1C~~kgTCpF3`Y_w1`fk6Ah3S)Osag;JX+!tdlws0M z;VUt~+)Gv<%YpnJn0^QP^z9SfaUUDcY+}3?vfls@w`1}0JL^v-ZGAGL-&NR3JWq(5 zq&+nrf_0s8qqT?6K26Pp2Tv4klO!`2{+hs3OCn-j=?gJ}mYn`71;RvTfcBgQCXjbl zS!73q&ZJrvah|K(9J9E9e>|yIhn+s)tTD0!sYlap`=|OyAEy0Y&$EY6^_tx52!s&a z%;*weXB1+g-0RdyUw|LY#$okZ5Mx^^k4qE)B9Yseh&UJf?Ihj|A9*a(Su_CLHl(t{ z?l?K%iRkLP!5y?<7(J~^L)dO7-l-cTY=0~nlAfl>FfKxX3S2Nxz!Q=%@UnoJRLqQ$ za}DoyHhz4k=R+eD$o0j{55qi5i|S^-Tl!yUi?CiG%0oUaTzUfR^zFEqXpk^GDv=af z!$ho?-+f!STEjU|0TRDo5}OH=2DIr+ii|mf4qGAlZ%+YJ^(^#pZgF7#Ktjcf38wH6 z0#M7?P$qjPN@m@*?jRu19xAe2$iU_H^*{Eu4FxhJWTS3$FWdTalZtC$Ga%fPkt9$e zN%2ld8jAgnK(EglJXBz@#I!gqYC|DmK+jMyy=N^D+q!*K!^r}0*CEm~AoL*o8nF~1 z1`zA@ybhVh5F(j<o0IBMab&uXx{~T)bzXE$JV`>}2=>qnAs%#$x;bFN=>XS-yEYH< z*s?*zG%H@GK+%Z`1X-SowgLEV1bp_qEQjapm4#X%812!BBz17xnM$_r^6GO0;||CW zRxNJs-!zI)Gr$-c`1Csva_dhSbaI4`WkV2nWzH9Ihq*zmPNzLjpP^0?Axvvg6t)`8 z)&sT&g9&p9!{HU%J51q2Oseb?d9qYvZut07uD$MVaNMXkZ`H6S>mK*koxYP1UT_u& zG4?Ak(*m2$<BLmjmYK}R&F2!><m7qA3-p8Ll>Oj)cLh3nhuSgRlSBX*jk0HO4&h(Q zXRSkpFhs{+%1ie;B5L3_NBsE$sX(t=AB%JD_-8`&?z&-sF|X$HaJLshj-D{)_Py$` zH?>H%H%#+m6`fBc9i#vj+|VJKLU1{Gum&`P=2W4s<=H3#mr@IB4`o@Q<j*LBA*|X= zQ3}JXfM*CBfPQkUBQ&kT%-C$|4hK4a7d~H3Z^z8?z<;zaC^q|;0cNQUM;`7TVaKtB zs>BxQF4=O(sa}1eArSZ><idNklTv&x2MhIA@krIYT&a-Hwr~;)!d-{A%&y>|G}L^2 zmRzLzooL<PS8}VG7rFj@EJ*~=p&&RNBWd9iEO%*8R;P={C6BO)n0LB6+3013)Au1O zENsHfu!FIut%Xz98Vaiwa%;`ArU`4^Q!z8O*FekK{>g<5AWFYN0(g){<q?1frQVHV z;4v*`t`%&WBn{#t&lKQomf;T-J0`2GVXdwSy*fiR4K_Aktby*Fuyt@O1XC;?@6%EW zBiWj9GZ3PO?B|fCL1kbJp^H}5yW?{t8tm}<D#kt+T(n+WuRDG)Zhi7PuXBIX@3|lQ zr^c6w=AVd{^z{F6U)zzk`PcYiX!Bk93S(+6jMytw7!#l*=7ZeZkiJ3F(x2>9n4C_s zXnxsM)$KGWg#*BNLDE<MIBFZaAhZNTf`eeq7*PF8&J~3L<`|-deO|U9z>m^z#s!0; z+v~8k?}_)RD8$=O)J+8}1r%p5XzQ3L<4LDvyfN~g$eZM#e<SeG8Ebx}Yk7u<biZFu z1oAyb+|72|L+`7V)KM>N{g@s8iAQoJgTjTf&%5OYb&mh-u@ty<&-J)SbU43u_>g;E zt`RE>*GW%+f!4}s=?8jc)2kPI@C!XZ2L3FkBsnJPb?bQXCw;tO_s+>;G65YdxJ%_t zid<j_bV%gm#uKcX4KoyOgk8dr*5G&}NK`~R!6Gmd@d+@{lv5+oace#={T>iJJ64@Q z?41J&D}I<sXYd~i>U<6uz*s8I7H&JQ@ouiUjmWMF$j|Cv@x2omJAaGZj0%IX6xb>? zsI)x-<i64@`?O?+tM@y$bmP9#jXF?hbPlx$B8{HiyJXt{@uV?BEb$jD-xBD(XVAf$ zc1_=!CL$usx12`MgGf~h=mSw<4|4CCa+PC#i2LTTu=Wc{tGSGQu8E<TjD5lh{*HWG z_!+)wM@L5L-YW$IH;5DxGsIL8<W#Dw5PO_d35UiKeha0f0n`3>S6ijgT(n=pQLxZ` zb&}?-rmwFBRh!N3^`Hu@6m!NR(K^sBON3z)7ineS)q9KO%<ZC%34rPEybSR3yFw9! zslj#xLe~ywMGZx>d`wr`gwOatL*|*+cIS$0QRCJ8%P+tRbiJ+Oj~Fn8FX;Ge*@89< z1MYR&+IAwqbg_oqtnYMhQKgeQW+Xp`13Cc@vgJzm9X*n6p!vLs36TY_23l;Mx3yH- zYU&vmQb-!-?xl8IU>sBNSqgtdzVnx9Y?D!=YYaKD|9U{@kXMf@BTP<nv!l~l!xgXH z{bjrQD^s_y{N2S4G2~kf_>wa#VCm|<v+UK=JkedfEk&ew`ciRSinmGdrvhbqRX8dR z(aD3&9PG!-d^ZVjWvgQpIMB@*lf2$~!rpJrB?}*A)0IKR%bW@@hi)P&QxC9p3qj$0 zv!Q%5X5pO03BHD%z1x7yHC8u_l;Q6=s{ExhLy1zqMTO&|%z`$mOJNI=Bq=VGZn1w_ zh6Q8{j3>vggufoUzk@~uA5%A9)SM8;zEIXKE@meFG~IIEYZ}3AnN+#y63$s?19opK zAI4M+pQG1ILc2{VA&dcQoh%H-n)U7(({=<b6$dK6BN>wR{w|U|poQqm<w4_^ngGXV zOZok*llG>|keWm<0U$*<7j+{y<w_y(#*mC+N>lSw5M-HZ^yuLq@uQQ5-mbe9*yjkH zEGKqXR2?_Olyx-{jMGRZnU#~lb*{Hm4?Ne`d`vHar0)E*ZF22w@5<acd2tOpgT875 zi%z>egm`;bo#&>U>8l9!=JrlglcD}ohkZG!rQ-Q}dziD0)w3az45V?dGtAF0oa`bs z5_x0YDytFa<Ee%2(7gV6VK(U9zJBn#6X<08Q<CyaN9v_nx%#_5bVW`{miawmndZI2 zkdoz8*7T!icYGNsB-mnFXiuWifSF6`fSXOGBDTFvuAe7{e<~<{TGa-uYQ|jKxwqyR z6Sylw!z-nlcV0=|O6f>BlkH-v&~*vrb=k;6RZ-ONGL;N_4IKF1L(x5skLC~?ONH@r zx2;o!pUG{rYwLSsOZLK`cWKrIcjIEu;>q^yWpwZ{Oi%d4Zme9v6*n*V59fcrhyUkd zl>hfE2<yKF5X}Gi0OHGY5pMY9xp=Iarduvn#4C-{p;>|>_67KzuWtqFGxq=rCtP4g zx~59xn%L6UTx=^QA`T)qI1iIb#flW%=F0E?Krv?KBZ$Jd$Madl@lz7d+ATplX0i5z z8zt~l@5$ST{FHdWne26OfGI&89D=9)-P_B_z2CcHPbIp|wWvXPHqLq$D6DN?afM@E ziB6zpFWghNu%;>?G&%4IY4r7b81a-9JsJh?nU6w{WFNW)&63S-Dg4hcx*j=M{ehe8 z{Qa6N4>M~w;3Q!xu*JcoGhJrpm{qxXtHQog1W0d1qTb>9zCp_k3zMIGop|D>R_p4^ z3TgFl8hbe7NXtrC>^+Y>*&uxhIr?ma71_Xx8uPqf;{q(Tj($bD+E;!c?POq8!(P~T zW^qkb!;K3)$^JXhG#e`O=+Ex0i?I{UuxP{kN<#)U?NdV;=@2W!t6}FpG57)xW)9E0 z1`5w4U31kfa{U-ktf$D5P$LZ^?9iaaG>K3nwL%lFaktbH^GekAm9$gCR+8#S;6+t? zeKmFH<Wn9p-$ULc&do3G)XI%774<=+Eywu6%|Ukl{^~(f;lU{wR1&8yr(b9?Jb)8P za?O`pl+(6veOPU0kUfrC7}9@QM2WL}sNzR34dd)hqOY~?$jvh%=2gwT=9ZoI291$G z&Au~H`;zg?WPiM?-A(qBc8@kISmm_FEzw!vEHH9&o@b;lxhLfdpz=xW-bPSB#}1B! z&VHTJL*?2C{&Itp!|V1kJ8N`zv-5Rmwr@9i3XhA^^XblBiq0UX3KzG_?dAD7IeL@3 z0^ZT{X|V|J3-Azr=$-foi{~Q|S>Q)MPuu0$J<GL2TjTR~6F9}~;WB8y*|o>u@eub% zOSo0oGuk5BBYLBgU0ZnWA><+C(L{fGFej21+n)){5@rRXoz_MFYH%yE2iu<+%o=9n zZ((>aCXxV~pDD-!W*MWF)<FL+As3sUImilT9ix@jLH}rQ`fovK6T?&gE^>zX-;1Te z>PTJeKBgc`m{p8MS_}QZgl+6T<{)dBO^i-j5B;aXtG|W8B@BK2h)7zde=o)(X_*Jt zFzogJ@1lL+(qkYb;f5`bQw?L2%j03$+c0e$03WUWdGjd!eA)H(w4MF+io^SD`&i#7 z{^5K#8~3lZ^6sPF0$?v6@~+bSr~OFoc=JC5BIiT#?Xl<C^fwOo*V}HM99`dbZ<(j| zui^Kdxe3Y?v%9EuY~Udq&93m!E6}h6zC}R{b}AK&VIr*=p*H{8<Bbd$mOxzv7O_?2 zGJqtVF}vb1sSHc#+t7{Knj@PV_ywm1iEC}IAmr7LtH8hSf{pt6On^j{7-ORov0`+x z3&jj6s;r*=nci>09CxJl-OB`@K9)L{rj%eXclX4GOQ5$sF1SAshUdq29bcFaGJ($P zFMb!pVW=lPSi~_fBnXw$I>NwAIsu<vgdN5QX<R_E&yTsX6#}@87&Kjo3q>MPn95@L z?h@r~eO%wWkPJ&=gpjRoQX<QP5UIAqL^@A<KCp-zm|-p?kQQ1Yi{$*%kwG#Bq(?uC zeW6Omf+!$?!YOgKSKw`r{8$8z!^>IK1Hj}SV5FdMxFz!J9Yty-d$+Q7=k#101Hk%e zICT42g}<r*^4|LdVS%8a1O6W}HP*F6a`;^YD~OfKxIN54LIJ>~gbLb<c`9cL{8f2! zrPJ2IA_4OR)u<!9I}FfS2m?`*O4uWqNHva_3~hwEh-SV^Z4x^orgKbBD4|NGgRy7{ z{Kc4H=onxGboVjh)r4HKDZf5&=_kLj>-F_Oep)Gu@?Av3qLPBo1y%Lrim4Rv<M^Qd zj6@+oV&#+5BjXo_z}xvItaG-$l7r1R*TYIAH;h>Mjsk9>C=&OrJg>&Qn_O0yP*gFb zf}R)xHG0UDc6VU+DpGC@QVwkH0u;PMUPd;It;dSjmJQDIdmdb(isf0bNH_WSfgsWV z|3?RL;TnRg1X_4opHkRh9!L(EVEP26S}@XFKuc-gWdq0^3LQv-#r=<>yj%QS+gDvE zQlH&!(|8`xa<6^(_YJ5eBL+R0XLYo0f)`NG>LUWER7}Wg9|J}qGB&=Ln~1%EV3C~C zYfQ$X1IX?;7g<+R%LVw@Z=~QXat7+}^ezGnQ^itTdx+E}aRldS9R;IXU={8?JyvK- zVd%o=n6RBFOR%<N1P|{Bp~Vzn8s8d<O#8to5ZXw?rmTWlcqk)|s+hjQ&#|4~g9uu= zO4`x`1o$C9t66?PMlqp7>2#L&T5H0#yVh6KK%ExDl_6!;ZZ8Tu_E|^6o~YG<ydYuA z+QMWSvx<mgHn8Sg+=@4~$Mg5=I#n@7;X$G07$GA%ZdUUL4SN!@4bXT&Sg?Q@z9O@~ z6m)mS`<tVo*-|mufrmH#gqrgDRpku=7V|LU>0aRDC;XaQd^BOELE>sz?%?Ngbo<Gy zG}s&+K*(x}H$Y&q7%N~P0{p8i^AHoMLo_Qw&{-HUBa>~Xr?$=Blk`?S#-|?jmKh15 ziQ|a|GDLk)s#BC_?T_KWJ$6jU1KiCXHe~TCNpKQB%nWTa25^JvhKgVP!ddzFSb*nG zNQ>nY+h_<z(trdW`?B)NAlC1MzA%)-@H4U@*g{Bdd9qF@FYRo_>COkCS(;l%q|N*1 zm1n@h;yvxz1lK3XGjhZBA?Vp5NxhEo$4cTXbO+-}d>RolKK$~23Bgr3wSX{=;DnQ< z@je37++!@|1GkQ_X;Eh|;bwt)6aX7K;!59-8!+vTQtrb@NfJzjT`dFQ96n?8)VR_@ z<L)fA2xTOk25oO5AWPOET{r_rp;nLm?x3l26v!%~O8dqmivcqp`>9w@Saeo#J^~xd zhp*3}*~yi9O9^RM!dBc#AU+T=dueL-4h>5=IP*T#q_Q~b9C=0qksU3UdJKpcvnf+M znLl<+^*|R1At9o|KAuNV%%Di5{RsdtyuCg^9@ezSl}ee>PSxD>Ae53gTe1tF9zUys z3Eju21{nJfRIyn($AwVF3)c1Q%$z}na&lr*3>GC3m0kroz$#)p!=k3nYBwTutgu_H z56AxAX{=?Ls~oWFpW&%@Ee^|;L(VlTF-{jIP9k{mAzI~FJD#>nIgHKh52Y*By-pQ& zBCtF<K}o)lShX#nzC*e5>>~+VLq*r%w`wTUbGgY3@)0*kHqJwd`p|ajifI{aRtv|5 zpG%bW93)_h<3Gy@yHXfK3)j3?DO^h>Djzg_X2A^$Zx&k;ov0o9bDTopMpDR98>XiK zI%%@3=WC5a7tnjMx2zZHiE@G1^nDxMqG%znsToIJNuQ%KLI*n%S7U91WuRvV0HB65 zjJ_e<*EF}SkDjWkw3F<J2Rwuw)$~vo4r!)p?KUCL>|@Hq#~$Sta<*|4Q&(e!Q6x&@ za$5$YJ!(8pzzNLXp+E+H@2?y2KOsadFbprM%gC$NqgUf7rquGMXX9{7@x3RdU;>%S z{+Vef!lLswOuo89e;WRD58WePjHe!!s?I!M3lPluz1Fttr`^UT*~LsnNIN*SB{YW` z0u6g*;W*)B#=28#`w_Arqbx8pdn>2;7Sk7uv%+eefhzy7Dx;hLXUa`*nzw1>`GNJ7 z{@B3uD*vbEnwj>02Ce^V>mcp_pCN~urgI((M(3mQp4_DBEU|}nE$Vk8N~gdF2PtE? zVA&NrrCf4{#&zv3pt(e)ACPm{sE|{_T${{5zQR7;&5v!HZ5Sh9G&v=vbXRyjQ8~G$ zJj{@DG*{?bozgKR?^j*GfhGv#be`33tG2-pnzs4IuN__PDId|_Hh?g|7(###$~NBN z0cdv{%04+3SX<e(dr+jMF!M;(knJ1Uob}XUXW?{+bCOUMx*?6FK~1<MLN=_9!jmjH z%D$JN%1MW-b(>;}i5d61LW>q_Adet<*q-w1YgI?x-_oav$uJOrW2MMkR?|QqD$ZXD z?kyoBN=ORGXr-0Q7<{E+Eik_4uY!{w6+dxD)e3H_$;o!5!eK`^Y@i$OWrtrzF@>8; z0uOa`Ui-%~rm|eHR0r$7<^#95k+?@4*fv`z<&?caRa%o|dCt8R$xY#0Ha|)uR-2FI zdn6}Gwy~e1z$KbJ&#LmMlUA?m>YtuEdiDFAJ}-=4;yf>;vG9{j1R>C+pMafFC!Mau z+ZBiNjW`zDVKgN$!sj=9uRPaAl6{qpWA07Wu-PT;@_>pbR&#=vpl$=d-&IW5-#%%9 zOw-Xdkvzs&6D9V0*;j0iK-a}}l#E#yV<YQf7wSwx31g?e`&9H0(0uHU1}xa6PO6@S z)Dx4vke)WP36bED+@=hn7C}dwYFzu*Mw6#PyDd_yV%;&^F(H_<=3fApC$SJ2^C{<2 zp;*Q&31s4GR(jH>w_1F;6$1pm!#NVW(u4o8iq)hUI{IRRzxt$k2#0Xc0fvr#zdJXd z(KZc&yjCaCe8(*l=_Lbk>HFpij#~wFg<gTF%nRI10#Z5Y|EiImK|M<hzx$P1bWV&W z)BFSWeOfH~miZ(ov}aFu_(-AEz(OgqY^wSvJ|4R7JA<3`2b+9p3-^>GkE`9EWeNEF zR7b;X`=+h+kV?)P_qbvVvsNGmWL}F>_Yuj0WafDya5e;AjQH7M3Da3x3lE%h)^+6R ziP$T~U)fTm8zjoNDM{lb9gYHp1@WT9!o@xQLnJcX$1Nd`ewsz_X7-9S(#gkcDayV! zB%=YTsbK})sluml9FfF==hh=jbpb}u!M>kUee22d(qQ00IsSgd#bvVN3bH}Xc(3=Y z6Iu&1#A3L&MN<Z)7#Cc1lVoAmktl`D;ipdxM}J^2^M76F3+q*stq#nu?z<>>6fqFz z{ZQ8RLd#}^WEMr^O8Cqk_!y+tkD|(lJ6rg*{O-gz$s5dGym3b6;TR{#D%_PdpmQ+r ziAIoY<4E^RPB_aDe#;_xAwZ5~kL39}j+QR@-I&*VaNy5!J8u2;p1V_R3YSH4pb*&~ zOvPKT3tGBfDW$f};h#-R%576yGFH3OW8n^}yzd$LK<cg>{Vr0;9up-_hKWszs|a-$ zPmNeOXU1f`AX%Rd`zj5LY&$H*h*nr1$mrV+LT_h+3vBj7_E58w6*|p%j!LU~KoKTU z$F>DtwI)S3PLRtarYi#NplbsVV?6$aRM-P!{3^@@OcUqk;+wJ!h?3&D9dcL-u(g!* z#ZYq_yjVJtfkCayq4LbHrWT=h?&<S|S%b1g<F4xISg4X3FxQ=bxNK?Ju2!?6M#z<Q zHW6j*b*#gb@vXm}?mMt&>di=D4eF}MVIJzNC{cWynLCzU@EyRVCoxhbIMhB?n?m#W zGvWDB;A(unrC;rEv26dJWfrkK#z<T=xsoH}n$Zr$u3*!a=1xvAkP{LyGr5wl^^X0R zQt|(E4>NrwME+BlCBwgl9ITB0`84`}4mplQ?{npPbgDTekVJH<jbjZ`0_m;%LQ|P` zX<0tGicUI{Mh@6w%zLIQ7VWbqUFAG8$d2!s)Tk>Q-U|Pu+8G3b9g09P4-L1X^la{0 zKjF>eIJMi3r}k-m{d<mIVyBdKkI(XjAEp37c5<Zw;dFSLlsM~&Q%2N|1v(Y?)-Cr~ zG#qPKrW2NDO}I0%m}VVstCx>xng$*r3cUX6Dg)j6K$MkQRTpmr-8;s~yE}aP`dbqr zhn?1iVE-+MuCKuw-WDN~TMjLn@dn;>-uXv2>B=R&ifk)4O*oV*Tt_i3G-bunm4?Ex z;Lo4*xp`c1sWzAs#yO!V9&;JW_1{Pi6J>*3fWs4MFW|@NEcVhulW9498&J)MKvu%< z^}!1C9L94rBv`o9#b`UYa|SMmYuufFLdsXOi&`vOJYu$we-(Xu{vc=`qdh>-^!l*+ z!-jqaIl5V{KOrToAHjvLxsWipGu45kRW(?AgV7gbyBES%uYK-!;^SLoZMluAQ)-*g zY|t(X_2I(7pFbq3=U*wDHWx9#0Sov;*R$$K8PyE!tl1eZ%9lx(nJPY$l$-3=2I!NN z89ZlZEgZ<7s}=h%5^rbnf2@8Qoo2zz4iz`O`5-q7#9hKp5l9{M`HG}%u=V1RT96Dr zi5j6b>+bJywgj@;wQ+-JTnzn;gf;5q1`$AGJs27<AA(}ostwF<(lF1Wv%{h7*Jq>| z9QTv{yxJM)JD=$CcA;qcYc%n4XY=|}<n1xK=>2ig*M)1P&Efg>aJ{=4L^HRs{^9aE zdp_30`4`91&EvDA9km9lX1FBiG~DfL(NyUuNVKPxRy%1^)z~?_v~||#x#9CV{N~$j zP3uSJ*Ej&=<NXsy#SL|7@(OFUe-!l^NJ~ca_4A9I;EIi?Kzpma|FGEg&RLjFbGhv1 zs4^Fv-TC>kemh&0#pN-os!d>0-Gg#tSw*VVLm#CaQWNrX_gOJqIjM?f;{1N7=uw;7 z&%33=>$!AogX80^r2X~shbwFzd=s_r!_)R`H0F7{uE!l-w%5zk$Mq8tp7-0>Zqugc z?ZE8Rk7RL8@*ZuH1!Fd}oqJ|HT1gAIk?SCh8$90aVO-vG5!|W#PN90CE{>n(zs(sI zh8IjKW4WVEbf<fB0(qhR(ZDES)G+F4{t~tVd!YT%!Kh)hFxqKcbg%vv`2QQTV4yqP z8xu$X{kQPnn1z4iF8og-!oL^^|BJ%#mk`lHbI_Xttxxsu#Z}-obRT*UHH<b!Cyj^h zQ}35Bg@HJfE$sQX{opU~!ywi&)&!#(#@N*P#o=Wo<nXW~Y76{{fs+3$4~G(I3N87# zleE+khnY)V?A*Ag2-LLIfJ$iwF{nv6w5WqmA8U0gqa6Ur6}BZRu!>Gv30Q2`4b3Ju zO>b)w_&`h15FOg8fvCP4m`oT5X!~0%7%R@`w!klk*-anN39OfsR6rkt=LN~kZ?mNX z`tT*v({vRCF8gAT%nm+IG`V6>1ND2Y^ruwSr9cW|z5wA+MgG*;X)Idh3G?*USU~^< z%2Z<Q;KE8QI=&(K+&c++E<|$31KAR!%1@|sEHa)NdQwp*R<d3P|1f!@C2+FvU-Pl2 zip@^Rkren&32ufV;ub=v0<eN-gc}1uO0>CRGA#rKJ<__U$XJT(7V^@Z{nQ5AAloZp z&5A+BGKW|z;@DcuD+9e-nA7S=*oYPQ=mOzDN@}TxBxqL?Z)bW6`RKkbiut&)BZ=qZ zOeNaGdFp1+m=$a%0KY;AOM-=|hJi%lmk5i>nGe1K$v`Y+|GNmN45tbJ5)vUY&$1bl zYevjSv4HZo7DFQFz;47pXMzCe$V$>aCU(nuNeZvnD{0Z$h{kdR3HeE!fFrTl-)0c9 zf7~MDLWi%hGu#BVHU;vCNC1#oTKUMRzl9hadjc)cA&WKr<mrHu2|}HO*>>UN5cymd zz3OA}JaJaSbYNy+w};QXl6XU^U{EWBoC&e?T@idF@`{aIb4c<mDTuk;LyguW=%E18 zf<ngUU4(8`lE;4E25hOmCg#98JZFRr^t+C$BsC6mK^Q$E#JJ#agE1OCqX@IEMB!_` zg}<)+0vmypVptm`H(*L^9Rv_iD6tl3l$b%uD>sIO&}cx?6mHAEF~;I&BbpH`T4F)B z;!%OGZ<>YIAtVe^ni0<NaZSmIw9%#WO$bay$v}%{7<ThUBlFCG7LDdLL961+#S!X_ z7IUVd{gFx4wfy5aDH1`R>{kOQxpd1wH)Tg*@e{eNA-AF{*Hy!rQ92Rc{VmurIj!bl zl>WyH1g&GglL8H;BZ7VvrA_I0UzCwfg+*j|!X_r@rXw@8P)pQL7A=T12W1pQBjM0> zD~#`aj{9y@#Wx`Eg+=dS{NX_48gt;K<qCIqB{8Jmmzd4<fX^gDJdbVHD`_yI(%RZ7 zjnNu(Z8e?ON?XXAWG3fjm**uF@UbyP->SWNCj>R$jA(c1%C6CPTA0;@AIL@)eYnxZ zbI<<!vdZa`UDG6W2eSosnMew{0WWry?<OPpC^@cMuAf%q4!qR}&s2&6_9i&v^a5Iy zGyr9^$1e<~tA&)1DIcE>jykh#flmg+X(~Uu8Trmbwwv_kWogiF+g2e++Tbqhdj{Ge zJp^iHn~1<Hlo7%qH7uXF3}WCST*3sGD|WbvZL%+5hZI=P8-bS>3UWYd{jOJmte9u} zhoJzN?<lfBWi!8FNLKzOA&~Q2bIOmX5L8Rf5bq(cZh@g=-r+<FjGnxSW(Fh1N^S^0 z!L=GJ1hw(i1z>V+*-$u@;9gmS$tB3@u*S=h^ht8(emUJpuK+4uM<#!iA>D2&q#6{Q zB8T(l6%=t@Td}Vl&&vbAY*V{>JL9(qyujfodBdd>rp%Doi3C?@&;m5sMUBUcLKNgs z>LKLisWQYYJxoEDI|!@aVoSu9HRlRlB?861`x&E$J`G0|@JPb^f(>;Pke)xfjkKhw z2H3hfZLIgzaVQR3?bH9<cPeP+?KN>tZyE#@KMzSFl}?m_&%{O18sW>U!Ez4E{g~x0 zS4`Idy7%__*7H7U5cZ9+52u$&7<V2MIEAU*%5zZ-->FZWE-_zYYUz6u?LfZo)~X86 z0?e-(5=!r;lh~<onapub_M36wz#8)RUP8FIp``)BJV%^p-w6~Kvpbj_7Z@e;(l!-| z-;yDkD1)2=RYQ^Ct|8j2r)e~rs<FO+y@)+XE<Z)4sGW3B*O1n5&<Hz12eCSf=A!(d zGJKbjV@u=%@?GX$P(RcmNUlArj6HP|o8Jspo#6ulwEalhAH_nkGVY21+J|OKI_Daj zY7;dKUv?`t^NeINe?{SGtW~Ey6Jt84Xr`!y759wU2^J()eOp_QB4{Tb{EPlNUl8=| z2*TQM!0&Me@^L#2cFbakom0Nzd5K3>GL;-UgFKTAqX(L1D0`Es&Tzr{4O9v@jG}}6 zFtkCe$PD{P`~9dplPWU;fYnjP>poPoNWk=$NDJ-H$+L-XB3oO{!HMIj9*IN89=)%V zzARAd=79;f{GqX}vD^hI>D!IzTt=Tem`Dncsy!kara}|J(zA7~{|?z8e`M7zG~lu# z)S3`D0HjF})QmjlM(U=DVi_>YgrvP96qd&_dA!3y8bEz$4Ta2UNu)XA7dx-I!=_R{ z%~8kB8qqN1{ClvnVOaf9j*U*m<C0i0YtZ+*Lz3kxqW?;`^%jAJxfA-Kts6^jomBG9 z=msQLZNKtE&hsvLtZa#0#$4*hXh*fS${TohstxKtHUEFb!~fO%|Mw7vhW0-O)eoet zJEzfL3|>By+x<Emr+_3TPA;CSX>dYbP;__VkWxKNH8F0B{&<A;a&QVGMm&qe3+Xx> z33t8q!MA}%Fj0?Oa`QZ}>CV*|2f9|?A{fR5$-<A(MTqW^q&%zlGk>*zLu-Z$POyKT z-v<Y{E*p`DRN$c{sUvnvf14!uNrh3cFkuWBy!irk@(SBrxwjZYX`Jw!u-)9F2rPg@ zTc#7P76SaTVoZVvR+_P3;|EgD|E%;57Bfl2ZzW5bP^NNfEN89JWJUzTkCYXB#rg)$ zSM-`Jebd>lU0~ZxI{L)axaMes{NfWu+D;$y3cYbrY(tu|>zLeams=<VuKblQNW3k; z=i`n$j#C!2TF--yO@@(sxNGr|X1Kl{*T*XThAa^3yg%WldUM#DukxLTqE1<9-H@{e zT8G)tWDuZE0(gSkPPO$A;Mwq~v2<~C8#5x(I~u_mGCf8P0wrZ(y~zLE3q)PiVO~iu z6125G0b1V@YSSUJ%bp!)tt})_72xqSTJ<_1!QVA{uBS<gAI$Blh)HAov_e!hq-0s; zNX?F7;zwzjsf>egl2$3A-+r5+<1OPi$9*SJc3_a6eJ)plmu2L%mFqB>zNzXpS#N!W zI+=i|q`PFU1zg9G<Yk?iO?UyReg-;V|72}-5pH@$YK<Bbi$fKWUf>R;TAr~~=*ZYV zV$$YIPGoX#Ffja9d2sac2@@h<?<zF77m9&)ia;w`hkqB}V?Cvb5Q3<E{^!mROsi5w z7suiKsh0g}Y6_gUNYMq3-$~yI3=O<T_RM+rW=8qLb%|||k(wuYn|%xu^Yxga*+Prm z^-4J3z)cgv2~LRseT^Ozo%KTbn-w?J!6K@yJE{W9F4|(x`~&u?3R4<!N0}d|X#8t% zE^9h@b*g&ftxe-u$1?kTnT&$`_Qx?+@-Mb3hD%FjKjCGFPGfk{V^0I+o@}YZe5ld- zGGh34H}AP}jo<%=yLSw-HCobj%dS<nZQHhO8>?*FHdfhQW!tuG+dkE|yJPR}-f^PO z-y7qL8Doy$^UFE%%{QOiz)RnvCp`Qzhq%fNfJ+jr;yc4qJ&!fr*yD6tbC$o3&2BP# z{3;z?Y75AA^|xwgJg+2wG8z1KNS&FE5TuxaOsphN0?MKvjaaL8uFIF_*b!_+Q!E@- znu>7O*9EvzIc(7bY~hf*j-c{yq>8uqEZzX>{)B3gv<eWwNm>FC>K=5qYiJ#_0&;G! z%IhFadr_U9Xmk3Ukk;v3GdDIpJ4;{wIglCPW;#zfZJDUl;y9d;F2iUsgE|7;@d1rl zT!Lh>K?#=EB3s$AihRGq$iqDlK8}f>yrhCbjBV9wu4zGLd~JA>VoN81=1>}Xnwv?z zQ2T80*vv3%R{n7BXgp`kCapJ<E$Z)f)TY(^SD}RMzsynnzndlg37pBw@xN}W`!}-$ zNi)j7n<Y*po~00Bz<lW?@cnzA2uJCmhyNiX9P2JBab-H-F9OACeYRy!QJnhx@sv`L zqDuJb)+j4u93DZ`h*Xf`7LD?l+pi&7{jj1bi^eU;02`)WyzwnS-@DU%1OD1wPmUNY zNeVl|eiEj342T!^cqBl{Rf{%|Ss=cF)H~-nB9YaOfhM-+p`966c<l{MQMZ&Q-te=e zFUVeL8?Yn3V)5(E2p#IsPE2wKR7waWw$XH(>PZlefo2Y0JTkYI$N+P;k??>sje4YH zNxK!-BnwI^WTuPDP$mV>E95kTm-UE4mRKVLpDh#$DF`Q_a>OYlDd4QR997?osl_Cv z@#|fy1aqFS;Vpop(6F_ya<D7{`zvYr*usyrH2GXrMq>Bt*BW9qT-TaXJ!?0s;yH=U z$Ob0+k9jZVJ%*r2mSiSMX}D`ZUNIHbytqtDU4lt!6Rkg#=5gz&gC|<?sDmh)lEIeB zVx|L{9)r=gUICNy8tA59^9FS0gym>3$ta9n^M0Lj7=;&MGC5369f)h`R(<jcLKWCs zvwWa$!1Q51gZ_0NbEedJYF|rNVA-ClO9ieAr$yx$$9YH9%29Sgwckn-tEDccmAaq} zZ_)~k*Pm>V8<?pl*)SVWJE4^sxW%sctOa;GzaI?jOVWF*-IE?qb*F18(UC4Ko#Ltj z?E^(?m;sE|3SEot1w>ZGC@S5Z)=?egowM8H@kce-=Ho41FZr3n=<U_w{dmvEJ9O>) z_4WCqA>{n{C9ZD!*8|{{|3gE#Z)WjvZ}EP8xg35_O{$|Saxiu4S{bS39!hW7t&^Lt zP&<86Y5UwgJuh*3C;Yq`w*7id>pgrvO_amE*#;#Jy7MD2+^)+EKN;yKidu>S-I@## z{Xzl9ZB^#jr>8y0&1ir3Y2^M3H}{tZ_ZXrZZEG+;RoZ4lgwY7rxIx<HONH@|F&ea0 zE0GG!7;bwUrb7#|$@w~JKs~{UArBO`p44bWF5^xA5bZBmS-&)69#3*1upl}7tOsh3 zqg+Lw$=%3@C1=0Lc)Iz^8sB%%fD%_Z$f6^E`iHM$JRdjL?zhMJ_gIEYt3u)@2s}N{ zONlL|rw>>_DG2-Pm#P<A8lQgVW;VR+uFo?Bwm2KxF1IWjJ-)9yhR*kE7I)xcxaR2} z(c)`g4q+`sZs+-HetsIS%li*r)9bDtZuk3F=5)4?M6E6-GZJbsk)_jiG~2dU5A#>B z<}sS#q%Tl#S=663WYOo@me|rt1)YLN*uDRNDq33on@aKTqQrkwDgHy0_%|5jKdBV| zfI<F~O7RaE<Ui>W4Z*XhqFU&`4gTv!58d0~A$S%|^uKJPf*DYU)X|L${&{nSPOElR z(Doy=bcoi8BJFRoDEuXaRu(_V-n=Nor-(c^78a=e=79Rj!8SG?MC@0n!*XC5hg$Au zU)LZnb|HWi{0bBylr(M@TP6z;2aOfg<(86k%2O?GG!gbxW(3JPVMLJx%=U9jQAoR7 zgFitCvQi#f72<7huGZyI7`;?x)omvrQBx0&&hF&jJ$l7U#*<bt#)91NaE;fGyVrH# zC&7<h@hii;u8Zhry@gxLr&(`^vvEd)J_%6hj0U=lGM7vah!&6{%D-GgsO;c(OhYAi z1%y^sU%_|Ox?G>g?-yX!coaVbO)*V!8I_lvvDmQw(M=-It8weDsPPZW=50_%Fpg&T z^z-EBw1-(y6FLcsajQ*II*7`kD52KU1UZ9Z2yGIc)!;k00)kbOI>?|I#va=VCbJfo zY{b=qqU!&y>IDQFqTy?!L07C+UYQEect)Pc0;PjUnEce-K0uu(4E<YzIe&iqAxVOZ z{krz+7g7{;l+S>Tjz{<+dVZimI*&&iS-}>f!EKR)yTvdvDm-p@He<TiW1}$-w?M@B zX64OE*Tnb$?;00AkcbN;Z-K6e%qvWvriddu#MA2nA*E$a=^)h1*-jf0JzB#%lf?Ly zY1#MSyZ3eJLYE_3oT#BtD7sS-wN{BM0)6tIQOBEp1^CD}rihAlH}^Km5YzQtkCAqM zQ^@a&HvDEwP3~;kCT~KGT;OWy?Pz=EOIsZLh6zhN$c43hf5T{l^Mug~r~HMlbfD}w zsU}a?rdk_te?z6VgAPfc>OgU*AT1~4a%YI7_E|Ats6$<6)q~Tn4+3dO61O31vn#Vb zuNLL5vBm=!(n2U~6_pC%-!r4#f-lVc33j0Y?T6WeY(1Q#32(rbiD2^b0rYwqF~5v~ z)4D8)ZKOTquSWYg;lElE=mppkC_8e|gwc}%TCes=G3ddDC*DadXfWpN2&~TprOaYH zV}iDh%&;*gI4j}ti*Z=d=;7&+ynQXR7)z$s7Fsags<JF?&%H~pWgSQ_x;EThTB$`1 zTmBLjfvN7@;xA8kyD;=uUaTdG$Tc|w_v^`b1BP50TW1~6mLUBNYdB>Te5?|8gKEXY zG6fyUU$&+GT#XVnkCSYLy&x|xJ#ZCG{V|*PW)UyZmm^*-V43AYPAh{;Yu=V~PPrxX zYu(Ae0KU!P?O=bd=teaj50_}A_?@Cq7f+sj<I}q5C)FanK@5Wo<4hbO#H~jbg<f?Y z>eKZT5g1VRHboF^j}{g~>_y~%ekb6$Ra|jSIscl+-D;$Up~RxjAe+IRH4HisMk#K{ z40Z>?nWmQaOPUW=P^*UrE+_QYjDvSoyBKeMuvK%|As@y0vzW-K+>Do_P?+F&>PrH> zV(4lR=ywWUI<VJ}b^PS=27jW6xG49g4|y~1C9$$+Z{c=*nqDWRfo(#;O7ea?>Zx%S z4DnN#wfEK-+sqk?R!L>FWIpSN9;}qY$iUlqu1jjqc}UP9Hq{uD|4=!nl&YnS<7o>Y z=%g0eiE(()P4PJH%yO14PdOhKG!3g{54kcSDEM_!GWIUQ?gk$IFy#*^X?3wjFQpVh z!OZvMo>VMNf_1$P6QH9=czqzsiw6OJ3m|w(9dGFkh`5=!)RLI%Ryw^d-m)Nluo#OL z1fO9i?+ei<;%d(>=|o<3Ax3mf!pSoB*kF54Nc|V~E2hWLfFxCE)|&;|78zbh2Sp<q zD4-(7<*d-lyTDHzE|>`mbil{S3oX1rZl^>Og74ZJDB!}fB>!CzRV>FZf^4em4Mf?B z_3$?qBNix1#1QD@ELrKu*+j{y&<}BH0c^dn?G2={S(=%(E{yGW?qk8O4>OeIytaiJ z5XT$Ht!!lb=`7ietL7L7bZeK~4!BqOza51A95lglP&)aRn6Pe`1>@Q_{>h$SKs!+# z(4wj0tH(z}Z-^eWMt;$v;fdH^B@b)Xlx_SjqTWHAarsJ0AS@XU+!ySgb@7FSx>c3Z zA>OM(T_4Kp;bF#5Gz-fFliJz#sSr`i+2f;&mbd*^*Io|#fA$FfX9msmzt5mMHMjrG z#^C*ficpxsNCy#zh;1MouN<V+_mwt_8P+`WKy56TxOmyNg|`zy0Lt^8Ro(Aod*!`) zCIJX)1pujVJapxSLnefm7*<F4P!j+~>{Xv}(&&@F(F-c6h6#Jw{3a}AOvx>u`GJEs zWp%y6`_3|aPR0Hz%mD_(1%QYTtAwgIIX>lr*FAC71Hq@@MEKf_)rO)}ByJdn2CcbQ z1ILa`h!r{IpL2qW&I4goskiuBYdh5TDwU+brY@ojuhBmFwmYw@L}<z+r_!n_=5{uU zc`6t*4+x3neJVhHDoi`<Z5^SN_k7NE@+d+cX!F<06MXW^5W~8_!tp|??OGVtsbqK0 z1QRrQMHBZ2V<3?lKa*%8L15VjPn&Ioh~QuS;EIwjdKZSVQ+sfpXVHRW=H+PejysSX z=W)7sG=tnqp&8HGM?s_8RH1{6o*4~cAukN-<SL<9b*X|p5h#NK?7uiG7pJ(v)P;)P zVQ%#G!U5YXQ>zcS^g^RDK{3Plx#VyP5y_Pp^VjWuBxI#Vn?$~RNY&T|qLMXagjCQ? zWCMLG=YpU-&JiX=Mb<<&i@Os3XmM1?MJEXDY^x<}1B3SXV(8<P`$+s)8dQoiRcktJ zLG<Jh%8-&od%A*(N&%g+!k{g2cO(N{X#Vk>FaTPAx%zT_dFU?%E_d&FrkYU&jr~#d zsb;aG&Z-(>vP{-#8&NaGN*U)mM${VOQIt9IL{rixR<#iqDw($SZ0I@1F|txpFColZ zuS*kxC%iM7?W{+AQI-P<yJ0*#%$^OoMS@TT2W3ap8oyQ7uBZr$O}81fQ#7adYZ=B< z#08Na9AARl0v_CC`0RCiqWXZy*{a7QEI@iMZJu`G@_Rq-%kh9i`+&wVgM%nqt8U_z zH%8b4V<~A8WIyQ?!|>He>)#d%TY8fyiizfmlIs9zg>Y$*N?^z{@{(M)^x82p0yc|W z3&^!gbMu+CM|Os5=@LI=lUg0x<qAvL+!SHf%wGR`yRv!(+jF~&HSLCiS<`gJ5a*Ne z<yP-6Cz|bIrg)pPuW-G9lOKCqaiq!-3fkd-ivxR43yMm{XE1&8F-GA`!}%P#K}&Wm zc20v38@$TGCP?(DJP)Vlhh&KN%%5=)YonNH;8F<nAE41dXsWytNp9}N$^(|X04Ef7 zbRS~AOG?Zs39y4%E>D<$kaOCIXgbHIHt(`r%>h);q-xJTbl{dGdIy++yg9nl7d?Jf z2*D#@kX7*R!aIr%Aw)L&#-8g&2Iy|nf-`BTAs2_`p=$CuoK$MJDX1D?VExa8=fQ*~ z+k3dio+p{*8!_5V)L&%9^EFN$@|^96cGGO-&smc@*HL+!W{Pl`{i)}CT^mftE%K<h zt!&#vA~)<|q*iqXt#^jqFtS-s7vs;Q#$Bzmm<o@#ICLt9und*TDaVQd!^I%dOn=pC zORm3-IyeTznt3)tJ=C(_k`t-mrcTv8MXE2@OL(qwD9aFrqdG~SdL>3|@cszH$w0yr z_3pP%<xW-UMoEP`tgB8zWo`#L1n_+LQZ67v9>%S~KaS8*#tx85npz@RWXm^)6;IbH z1vS*@bW#_?3}b<kWxw|$CjhiBEe^`IU4<tP(IbqRdBG5H!fRF`AU0ua9fzRs00c3I zUlm$%e<kun29an)rt6+Us0fM|T_X;i%8o;wT*a;pMYf=IOegEyx%%SR2KihcE!diu zX=F)$z;z*}VExOm%fb9FgiFT%he1P{zkk9m^4C?(PQjmgMo2mWuR=r`CRFvXrut0| zjwQ~`?8PRf&DG29ZNHs2pbQ9)Cn*K#oMYbSqoXYlzq>+!qV2Z)DmfltDs@MAM&vi0 zTK^CPMQgETc;%A<hwUfe*p0I76SG0)zorHg-z@I};Iba=BIf5}(0A?p{#F1{ER~sK z##?RQU`b+M>t>+lA%V%=_3@5_4KS08uwU-Q#8rA)`t#)8^W@;>P5pTY3;YI)&#ou| zPj0*_d5cS5FC_KGCVlTpHc}h56wf%DL%&P+y?P>qPWi<gog#mbf$B?8OuxL3Jc)CC zrpXxE?Gx$Juj*>+KAs4Cl*e+k-+4S-fSs<i<BUkJWSH@zqFP{+2NIWGKOPU+iT;9U zXEUX=bGnWja{FdNjtQ&(dHCx)Jt)~NdT_H~8G~`jq^HT8M~%Lv{mSfLn&9&EL60G~ ztpW{kV~9U&b&|Rx;@R<%;4oi`7)!ECf0ZD)H(XmD_%wYSEFXkJV9IxL-+K6(w~S7Q z{8NT&>*6xEtYQ=?6a~(y>yn})YS8a=CSrBihnC%&RLM>FDMyi5HrBl)4bZ|G9sP0> z2D(0(t5u5f!*>$gOv?uLI{4*vt({WSW3`$MP8#i)02=zC>|DX~bJwb#;{r>?e<~SY z%&O;~KYn$pJ!p>2ThIN)$v7QYBbdF7XFGp1`<ZHeD&8G!HXXZvIEuZPIH(t;jAi^H z)|*%9C(gq0K&*0W_Gac0(%L$`J7rpfgkZ*!8!88|+mU!IC47HHY<}A@Z(^oGn26R^ zd3laOg?P|^f|VJaq2%ZYJ`1zpp*4fQA#s%K3Sv7ydhh1afHRWGxa!lx3R-T7(Il_H z1F6$Ov?8$GN!bR-vd)Nn007Gg^e2?Xq)Tia>IvC}RV*)h!_XanRhi|^uwN;P#{Gyk z2C7kVGi)MyK_@SgE&(M@m4#R@u=Ccz3(Tk}BQX&s^;C97;t86r|L%tDflPc&f)O^N z1LXDBVG#SWxxxh)vcw~KQ$w3D{pUfE_#=5qFSHqW%2T9rY5<((b?XAk83^T>rh#b) z(E^Y%APQJCB5G(eH4K=Z6)8;Xej}~8l`cFi#rZAf6}Y!(2X9$x{x!Z>zrY;5@dcUl z@5xU7PprO*519eO1bEH)iSHR3Bers@409|G<EgOc9GAt}%xWuuenFyJbXbjxx4=$R zWES7H*6Vd@#pH$aFZHEQG4=VdtHg}x1k`vrb#_8~+a9LQ4}x9~_uqT+&bECl_)2Nl zf4km-GL>8*6dpS)t}dGBeauhLiiAuXi4IS4`5!`F60Ch`aOb|tjhD6TOy671>GLYF zz<9c+=klel+LmqX8YJ06u~q_SE-1CY_#W}M)h%Ow?>umD49Gss@c8n6bI}X%LRm)% zW&}SPN}I9hpWAzeJ}+g2H_HL^U7_iI5|jMC78(qK9S`D=XUd)RqtEoUZ*raP)NMn1 z_T|E))6!4$R@WAk8U&=BvLUwgdT3&2JL;6j_UNY#Pt*jO{4VLC=Ty<Nr}6Y2taB$E z?dVYKkO*Ynl+|hUNgQfm4!XlWlhZ4{_6ocyHGSePyc`=otAEbG9r?JwEp)-(9_qB# z7^C?>1J5<m`Bzbroq_S6qU8Twll_Oci;14;{{<TSj|R3AiE_$hD6l}jG~zhF+D>ss zx7`&PdWQM`fCg`_v+N8y_tZ3|FL@S}INEF~dP^*>pH(%?ty^lk8S0}y@a|Wf7NEOO zW@$=aXmcVB%1fq}F$^&CknKc@VE3!EO}_33Q5B@WHWwr_#Gr`M1;(HZkqgD3fF(0b zLu!Y}hUX>KS`XTxS~44!2FoTGp#VvUVX2-FOH{>SBbB0MfP;UeE!6@Q$7dn6*zvK) zA@fSiQF|p2i%V$6?gsRP;Y3&dozfqw`iq0qf@Xod;EsIC<d+`d=Lypaff|#Ci~y_O z0U9OfRVji!99j`(;mX{^=o#r;l*~cCl&ni?!5tUHSTxusXfovplv;+_LufMOIb?_G z2m051wi=MSg1qt2-0+7g>~Bg%IUKYac?QTJHk)`*nD1hjroAMAXlt8AOkfg5&(5En zi-(QRF%fGP7?ooA0W+t*v}d*!$r6)e;CznRqdr^;?i|O+OD4`RtBy90UuP76s&yQs zGNFtk<NfF}q5gHf<JNW<D}_1T@L^v#EJUNH?=Yjqt7H`1_<?m^`*9~T&kjMoEy<&* z1zq8Mw$}pPedaa6u;T*xV3M}_s6OnsvdjU#?ZmajuoJTt7`VI5!0v`=2M)S!^0F9b zg!CSQArC(6yoiT6G1=&qW;=uWCh0bUZUlOEjJ^HnG}X&CaEx6kgg8g929(i%s6U0o zS$fOUa{K4)=4`S5vi@%9ax|dqHGkvlE7n)=+tOU<d=Y=3neY3ie;E$X8@XPOuhUyk zx0AAYS)NL<W8-DjYI{3^<}`=?@#(d_#J1bZOK&S_{WzzSwz&q^*Imycx#sJApXh5p z)0dBTgLg0@)^__Fc_84&Mix1olkMa4LmrkpRvJk4_58Scx8-$zE9$VXCnrT&D$%D} zHqisV&2&{KrPku}xw&0$mQ#P8w4lpcGoZ~8`$IH38|t1>kWA!>8=X>+T@YU|fF929 z5031=16u#<Cp*LcT*M6jbNxFa_P;S>X9oV~`v0)8|D7Y-kN7`UHp4~`Pproe=$2dz ze5i(6=wc&uJ(chK+}rEx{Mq*V-tPV2bkjBV+VHu##@4s%^YH036Blp8&<omVev@4P zy`plB;AB?p@`~iRTnX&R8++({+~Ixx2fz$EbPdPX2W2q#QLtY1UbmxxVCbz+P%pbF z8c@-PLC!FOuXv6_C=Z8z1{2sC3My|P=M;5@ux?(_Mr`i4L94KHYZW>w)S<BJfw1@# z!2_;Xb(YpHT$`H+0rGqCFd%M?JIT?1rfo0R^#FkRCAF-+&I}ni0;+}{4O!(SAgG!v zL0(8Z55lLF@q(dAoaJSpOdDZEr}i(JK0!fUsOdEIQK@lTG^kqOW!8q}0qqJMeR~)r zmFubqPzD8r?$OK{?V2+Zt~X+miME8{BO3l}k)bWGBYOR>>~{7rEU=4EQ8%g;JUcAd z_=O<A-QNN7r2s%2wF;SJ5Aac3U#r>*ztNz%+wgBho`3_RHw<>Y@wpKlMK+swvNc-1 zLvE!}&&C*=Yw=giDfhnCMf@kjPo$43`#K^)0wCOG39q_&s<2gc5P=FPQn3m<0U%$l zPgPPALHbS0FGvBOd3ZYcB;*5ki*<-IRD&(x-IO1-z3k%roBAA{b*Pcw0lxxvJG6;$ zSOYtA7qyj+ZBU^J$jBhQg2Nm$Ri%R^a{Hhz`NLLI*Dro4%BvJ@Qj-cw)j09g%b%40 zR)QX&-(!&vacIL6s_Y;6g<%nIL$n)GF5=!KYT)q%Wd*8OU1613n^wz*@y=v9CM+-6 z0beMRif|nn=XZDqKqY}sg;={uty!VFD2^%~Dcl^)HX?*Vn?+b@&j+^5YesNCVW(CI zKF_RQ3lSbi#xHC67musQ=1HnC*K<t<wp~Iz$hs%qKN(9_aam=3&`^UoFi3c0g=rp= z@2pZ=!x;-2MCFW3sA}y&7^3brpOG=I$Pp>h&1GN>q^RML%pmzgA1ZyOPO5R|J)$q^ z;{--y1WI8A0Qx|1$pQ`9t#av;TJC0<2V*9_3dw<>pi2g|f4;{+dB0^Ux59=y<GlQm za985>FC*%lkQ+Unp*x0a+WFbqAkZoYVHIN>bZyQ{PqzzSv<PisyEx3tFaKI}@!%D? z;CF*Qu)XXhS|grTM=vG<D3`!hqOSN~3J^}tGpwi(=DDCF!7ISBJPwP!Gb&f@;ysG6 zeD*=_%FUV7D6f_$<kP?N2AQDUXq^+C>uzq)T1Qw>>)-szwMCx~km-O1;N1vOyO~kF zH*$i|str@KiQz%dGuFj>#3OUq`eon3>H7mv<o+xlKA}HT-}fny198#qzMS&9Zw!OB z8;>krow!nGz&pU6qLMNAsLCYf`y7xlbTrlaLBL<3KK6-d+aLs?F#QstJr|3<mM~nn zLQxsmq*s7otYS@MkBu7-7`&kC0V1I5)hC8V|E19o4w{%FI$7F=wL+iSK1$wR<4ywI zx(~K{`fFn>O5YLr=|(WN?Y)iLzl92#o2kP!{pO(Ry^{h~=_=W^pf)mia_s|lpcWm? z%@M>4Ir;e<{ydu+Vko@BD}-$p!6pIkKr=S~*>H^%dPH9%9<oX~%#a^h_kKuKLyaJ1 z1v(5Udt+K!33)Gj(52ST9`i<z(SwAp!nwue@r~)uxowT`xj|#k8Hr-9GGTzHgfsZY zurg+RjIjCLGPrh`spySI<oQq@@jHVyYovn+vWALDxcAJ*X|EGsAcWj)_j*kfDB*@P zWq5mX8Zf3D(@M;N-PN5jNEu$pK;7z*tEP^S$S~xyL5EnMHFQ~d*gn(GfE8T052UJv z8!yu}iWS4gi5m9d=okP90o&CnzPL(<n)_AAa;z#;%h{RUY#&Vz^V*Q%kUWzb-L|mw zYN5c|Q1zG<(OY%E-G>k9Y-iBsZXZ8xj+1Wsl(Z8d^0Zm{0T>#^7|0t9y89dX9Z3tg zIuP{Cz8I))UEQrH#}BGP02V8m+9oURVY{?*J2QB=op~Zl^zTi(cTjhI>~E}O1Q`^; zo>MdBmEto^#)audR|!MHI6t`CGtviSYWPo&wEbo|+N$OaB^Ct!m9Vqo?Jd*WaoR1O zUAB0a_@4C}vgbY0b_BHpVN?9W5UUGAz*f2YB}A?%xz7N={H)#P2J1^xKyXq+JoNz{ z{GXTQRsVjCQqZ>d%2;%yN?}9$K4AdImZ}Zy@%$0^s6G=9@y&!jCc&zk`eBPj0USC@ zUbLH+lUd!I&$2qJ8HMIApV-F!qq4g&>fR=~ksE71mPV;-iJPo3l{&eFvd3`a?T^Fc z#U37qMuPylo0p?{@>yzxusW)kykmoVshWIT$=ILsg~QKP#4X|?^c`xmgI6f!ovcLH zpDdPX`k>+caB|!zFORM#pCLi%wI~1mvSE@~bwghI*HT>S<9GWB&ZYd8pKG&A>H7KA zv)t4aq?hHFgs)k}!t9^h3e~cL$o=O=Nq5(k)jzZK;RR+$V$-BC)`fLH&)04<li1G% zpuie=RFrc3|6dOmR#{iqbzT-5U74O_gi!mojn12X_ZRq4&&<ElyBX;J)zBukA71kR znz@;#<Css69CH1N(mIgNA|r^HAcg$5L8aY~>#_+aROQS?H1E6(@ADZ;zJ0DXAlYZb zFQngdi|iPl7d{ODgj17hAx2vW0FdMu48qnwJa-2>E#YUjGdq|XXK$%JQZ|4j`@n)c z*-^jlv<qz=a0b#3lBseCp(hqdkY9iteX^kf3uNeQ1(JUz4(MZ)$jpxsxK7&^3h1&v zgjFV9MhQ_siP9p5K(pOaD~6Bz3ViqP=5?#CnVU_cTo(OHl9r}Nx}0k9M+{hX#sG2~ zv)XWK>q2ojLsHbGDvnE4q%}F$>&PJ3j(mpYUJ^&;24r1!vX$^GCB$zK`;o6<=2Sq? z0a8{OaT(nPBu!m8j609Kec#%tCu1u^ND>XHyI5&-H@&RDlk$b>$Ex2>?j>WGH|T`{ zD4$MQ9ud#>x4){jle-?;fV&zQAesMa0B4TmM_MOCll`LEXrECjTkkbK{;WUNRQ#+g zA|au9tM#Jms4Q{$AVTVr_zZA7t~y=Ic7Ae6-SPzNYVoKnWCItllH05!!!KgDhSgSs zeFocHVwwgAD>rIWX7+W6wEqY^Dg#=Cw!Af-5>?=C-VgDA*mf;w;gRtjG6`^K$KR$* zBVC4wmmt&akWaZxfIUlYED%w?LMCb`G5s5M6iq7fW+h(o+!%o?HtMEn1@~~hU${WH z)o%z-X2jJs`6b$29O=w-k-2X_N<xW*IxcN__+;JK^;Tku^ykPnc0J`tfitrR@<TTx zNmc!rEdgve8>>rqNoFB3&t(0}X5!r`qmkD1ZF4U#k5ht9Zpt3?K;>?;rO|X-xZ4ZO zNmu*}>ZCC4v-Pvd7I$JoH}UypulDPskAQ(=^2$F+VFX>pbL17O5sB=UTXSGv^y)?{ z5dYKQbzQdp{Q0_HSb&g67HTPZ(03A+r2b!}*c=@H%<B5Trq~QD|7f3LW&3|<pBj(B z`C-INtJ$SnyJ-x1Ai%?{peBKc1N6=jhUW$o!T}M549x)Beess8@X&b9kL8O9WbAgP zraHH&$0~_LtmUd|5_}X3W*vt?XHF>4c@JPq%*r|z4nE0Mz1(ozF}^iPPHpkw2AdDy zghWlhHL)8ZFk}gJ<gMRrK)><=>cw~i`NVh!plt2dqM6onMD@)T>*EGDJ|}?@zjy%w z8^`<x>Y6B!GscNse1cTuyhdtp`bZa|(qTo|lv-vuqL+M@f%H!L6-Ob1>C_+tPbs(# z)hFT-Hy3$<FA{O`gq#nG*aWF+3{IhId_g5V+a!lB;wod=&ud+-N=eCjOo_Jmo2mhA zQ-Jcxdb!YY7N<~?VU5hK*1Loy;!>-s0G+>>*=pq+Hc+7!r_jDuClUU-owPRQIwMGW zn<bp?y;?&0UMCTC&^w1dBGg^-UKQV<dPg~c6=90R4QaP?pjsjou}y9U(G;moE8P5k zbwla`pJ&YcJxD=6>V7r9*YtfsR=$^1+PD`~j>nbU!+!vhr!eY<g8dGwYBHFJuaLJ^ z<m<p&b}Yd=SzGm;IXOP(Duu%VXPcSV!L)}RLTbf^_mww0sLjU6E7DjphgLvz-F1Fk z+wo`tM`XfT5qbk6Vi28*-Xil_=zPL$0^5ib8k=+YWt5U(xTk03k|RWWNOyvP_mFuR zTgb+i_gJZoZGM2hUmUH~^X}m4>8`tbBXzy`2MXiW(cby;P!oIqsORhPoYTJU3U}?> z;rmTlAm{1*et${Ve62U@W$*gF`*k^d2eo3E(d1eNSVNWvWra{i8>O+GLMAtMDbo6R zx_c<p%0uJ(ayZ$2O;!6{>vcbg^Q9Z+uQ^HIY_y|VFi#1yS>CHSS-`lF+MpKftmziK zo|S9vK>}3{OMq3I=b_of-)2TzDl^Tm?ga|ZZP{~+Cm>!yJTAaog>jB65T|nG%>V%# z@&yOa+2W!L7GMw`hF7k@Llj01f)A{rY}|*0Jlh2XH2{fshXG0$%&Hp=6mK}RBZeG? zvXX2<jvfPehoH(Np*SR4D1Z@0U>{)U1q;7qB^7c9(bw9R6ErEXEGBbWKxl}ophRrB zqH$q!hoUT?so_%)k*=m%X2>?lTPlm$m08R@0Iy-3KB5f($og9s)IYKl7=*tSI4Mh{ z655f1o#Vr==d=+j4PC58oRq()5u8R?U?*QkKT*R55R@EP-uc8doff+dVE#g!BtjG5 z5P=YdUjaq02ugCWL}SK}CV-nT$7FXQemB`#fzSx#w`AF*6>zJ;ljJGGfl8`BzcfI> zFmDe}y~Cg=^Mw@nG{7>uz^>XG1tBt2;v}hpd@bp0m<3J~6iB&F3yJhxnQ0~egYpay zGU4J7qfCP?M_moQenMP~^i=873K(UaNrs<ezzV~Q&YEy!L^)m>HuZ-xk{T)eUrFSo zjopf!3`jyQuqbXs?vz$BaH&%gU#TZ=OLN0B@xOKA2vMa;_CSL+DE_1%{(t;J6j0~X zgY%=c=`)Q~=J+`jcG$M~=pbqqMRKNP$%X1s61nDJE`Yk$*UD&LB<G!GxWyk~5M}`V zAH<sAyX8}KVe?IFhZ1B)KxXT@4_|l;QJ}`Tvt?8Y<?S#X2B7o}7ly_u1;worlJN~q zmhgJ$MeA&dSHe`tfnsv&9fNbzWBe`2&*yQeq#kB1%L6K10u}tUCQzw5lD(5DP4oRy ze`=`Z_!kn5tIVc;cTD3+RIfJrz2tzw{J_}w?A9cYLLD%`K%g&CCP2Z2g2femydr9+ z1_eu<?3VIlgv6#42jtPlGlcK~*rrAkO_W5+5yluh^|j?CgQ0pWvKPRBm`PI#_<@>7 zy^!Xl%JZ#lgM`Rsk=)T^PqdUVWzhJmm>nfWw?*X2mbvIG#<D*_Y*7tX8Shs%ig%@; z!D<EoRG};dP&sS>q;yKw5)+KerO!iB1U<>-k<WodLa){|&VeMn2B1V!69@Dz;fRjA zuF;fp7>yFBT;1=u>Pa)aiomZ7K$#gqWV>NQo_<m}WZAI%0EaBEyg>DAenMx;J8{mi zJjJG8TSaEC8=sQM`Y7TUU@oD){08;SW|jKBwNRk!GMHqD?5u#e`C;nuW^E&7b<!vr z&I$^Jc9Bu)VX5wfg2_(Q3&LWrz>%e^hQXvBvHAGEPFuubR03|W>>(K{2llxmLJ;Od zo!Qy_+K~By>N4;dpq!~O9w3cz8K!i<QCh<<XsrO-`<mRgu*<M<a&OwI^4(YGr_O=a z1RB}h2YslC!fiBq#^x&Qb=LtpgHnG@D)KXRy6b@w%857%$-9k=RFG*D845wvtTRR& zu5zs@`vD09ff`)N1&SJD^b0yUiBiVuvS6r+ZPbA*R#4A_h!+=Jtk$9R*r^g@Eh^5b z3}DsfLpzYyr5|3B4nX1Vps|)y(m<nX4IoP3U?Wh;C>v=ENNV<STEWRj&LQ-p#6#Ny z*9tCSr?`wS<t1fXP(AnGdoi*E%*>`F8^w|{nl!vb_3aj4jmsO0#=3)`lqF1@te^!4 z{%Jc+7HbNngeN6<t*4yRnfC0^0~En+H;&!mpVhAz=O^9=eV;~(b4NmqVyp2!f(#3% z<>cU%cdGckb`%2?G%Xhk(G3N)=g#YryF;Bc%}spbfgHq~ah%8%X3ZZuL<qm88B#1r ziV_Pa7(Y3{u)c|pO=dq|U6hH>v}z94F5Ds<vW+$AWs00?h+elDJdR3thDTn+8Bw>o zhhv6MOA`pA9by)`TqhX2y7C8StA50r1}wvQXG=Rd1|Kx$w&>{Wnt+?8=1$ORc#JP; zef#@%I)EO@l%(hM{_Lt<j_>>9&HkxA)D`czeEO)<`lj@?(Tv;H;yRL>$gfwHyUX%* z?3jw$(evwT_cGFRhpzcpE+=_?{9TVPWw~2z)bWQ%?G0z~e9h~Vrsi}E^m>Aa%iHPe z+1**Tp6T2EeOtn|&GVsI+=g73davq0+7Puiz1=a)=)Re1{@$nj3eLYm`$5`p*>=58 z9y7ZldY^y29~OgvSKt$MfPTtQXLK<9b50QW3&Uw7R|pJ;@gz<l6o%7y=HHKYguw6^ zU*dX0VYZAry3RrZCuMFs8dvVox#WUH?bT~2YHranS1p$I9UQaEh=y%-Ugps~NFWwW zHHvYYGliO5UQ(~v^q_$_tcQLjmAG$mQwf8_UT||&%>}s_JJY79p^6o=R{h>;9kS9a zf`m}J(HW<TOjk|t>OZHcp^mBdIGBqZ+;OqvDWGvuNU-%Ar9H-Y$5G4KmTW?^zzwq_ z1pukPplhoC8ZE+?hdml3n}m*Z?_cYT>8xM=olg4JQIaOZGTDD%P5hgOWmW~9nG2XP zQzPZOXsBLqw?4C|4nlbDN<L?jdfXE?szt(xwce?cF}wrSygu?^)OB92emIR~jbgD) z5uxk0{W6XodZ3Ag=B_8kDB1RaW|AROJP+&sc&a}9pyU^4wKTRn>S2B8z$;&?Xu`~@ z5LCoBc>gzmyY<$;0@5<j|IFn5?`=X1_zcVptp9nVWyEKtXJP!$Z$G0d|8tA~lN<i8 zt4YzW;L3^XbF6bgxr!p33jRU};wPQYlsH8p@c2o@#PNs`_?;5hDrJ<Nf#UI$_~Hmf zfyfk;l5{|N^3$Eq8{c~8@2X3ZTj}nmPZL|y^~+dOnXb_<D3|dr^en_c<8Y_|5`f7+ zMAcq=d<bG{03b*}c8=&>b+wgkAAk}Hm}q|@1jTQEdC`7+^$t1EfI(pAc!=C3U^RSo zbO_W$phziyetrUY@jF|5L>f?Kf481X|280g8e*UjKs!nzg)Q@z0wmP#sqI*P8*(^! zY6=RUV>M3sS=f*eAp(e8T99)P$Nn0K;1;0hIC*xM^Uqks4MtgYYDr1?nfZAofV~g| z{(PK6w<`diU3Ict0vKQ+&z=i^G$P<fe4D>~1&{#j{zI~M6W4wSbAacN0{wn&p;XvV zLi#rpaPUv`%<$cuGvZ3%rLh47K7r0Yz*hj@*1zDX0lw5)`Bu?_cf#~W;mMItLjv$S zb|J)afj3aV7S!eudOQrS0SF-8q45V$0tb$Txbf}O!f<eJDx4wYWo7{&dgWfscwvxX z#S9pL&|A(2qXN)OZq_R!{;G+#wf4fR!|deqp|E3u4PLi5@8tA53*hr0@cL@~vJ2|$ zA4GqGlMf(;Xn6-tD;~px*#doOo<;}(jR+tf2qqEsr+3AlfIcI3tM#j8gL<NZ=(5{4 zySW!2P~ZpuK&R(x0fzYozUk%X*5{{w1Du#X<^%q20MMtO!TmJ|bg3U>2ePxhcx#i^ zZ;R#oW!{1|0~Az(hYr#9@^L;2HBIkH+_(6?eWNEvZSEv@S)D+!ofH3!qO2(B0qFe_ z9PIZYn2(Q-PD}`hJk0m<SwE!%@gaxz9bXY{#}7moq4N;AUE1yW^dbaw#Rs(u_*I{V zizugq9{0X2-3$^Qko!V+^PPU(t@!23++BLt&G^~PrRceH_C_`JiFNZmKwx91cFhOD z?Tn{?%Qz#lH|Y0bTZ(bf?BZ<jbOUbljk7o)c;g^1%)Uo435SXR5dQJh&tPdsm-eZ{ zj(YZx$=dzXLmuE5Or-A`kNz@<5;zUy|3wv|hOq$Z8?Aq{@qrVdf0NMv#W@0v6@s?N z_bxBOAOD1QhJ=U$EI4Bx#s=W~;wFWB0z5RnfP3^9xydg82!a?X2e@bU1k8y)>lYb_ ziUb73sk>qF^1BDz=bfKlU^$YM7W-Qr_6;C<sQEsU^hNcn$rln2>^?vMFcC?-)akFI zv)#Bs5n(;q_gEavsOnl?EBv>-KMO{amh*xsLoYd(mE?QtnlYOC<XWqY+~_C0*;Rkc zv;(YXRr3fhU;A1HQM=B@!0T7ht#A%-iWX8*G>F`UV$w=s#Ox-Bt42ZT+UVgWPJ1*v zh4**))koUNsEArVX*J4R{_>ixMnaL$G@-@YVIo1(X!W$4h*Ror&4!#!t$@^Q3PPC& zMstISW-I_?Hi|NI=chN*f=(rlg1;titZJ8IkYSlh(Yv~`Fs)kJ6nEznQ}c=uQ{d3B zY?i9QeAoLRx7?UP<5tuB-Ba<R%vGU_J=r>OsQC@r1_Bj}Wr!>VY*uPFrUhRX(va-J z3{|R|AH$_|s8vTc)%(C%J_>67B@fFM$B$Rs-=(~G&`ys2$C3lGT0eJ4=i~gR#*iCZ z5Hj<-Tsluz^{`-iZ}r9z!egy}H-o2s8i&z_)R-XtXu*(LjhP5z16yB~hT3ZpI9t`m zLFVt3<Mm;m=Q}TZe0>R5Rh6W+(iMtA7<z{JhTvqBt!QuJKF!~qOignSl?KMC`QP^2 z&3#t0k|oQq8YgNYR`y7rZ8!dJ_RNY<BiZ-X1vHH8Ap*G^d#bAsifS*oS`-F<cm%?A zw<7m9`QMs(Mo@ta{KO>mA8tvnoD%7QOTqaU_r$ZeJ86G&t{ssty*FeA$lKgay~4E~ zDSracAh3zd?3Cr%eF`Jd>Ey^!Z7aPUnP5ts4Z^<!CL3%Pns|dslJWVhSzHaP;mu+^ zfL4(Wh&GecUa%gD-bSe~#QJv5DH39dlj6T#I4&Jk|0QCYmrc1~afwvLdU9-cES!A2 zmZUBQy&vX@1*2WI&D=En9usfT&dGZ90Ichb>8J^rjXj2xrQF%5LtC@Ci(2y3U@azS zF4=2-&a&p@>U!6`YfPzWRM9_vKNN@|Sr%XKajBBg(3~ddYO0cD7<7Si=j6Ty{VhP# z!apUkT`>tc&<TeF*kB<WB??O**D8+tHk&*3BF2VITInB`2#LkdR$l=z<>YM!YtT|Z zGh~SbtW;XMOEU0UJV2J&3yMh$?vDFhY(^Q3$&)<{0XIC<cCc9+(<C+W5`$$<7$^@D z6t+ShPy2f&VP@jb0}M`J^NVP4=`gK=4?{%->X{fpy|Qebt}uL~$LJ%M*Gwr#lYTR! z>gKiG6#Yfy1KI&sp1N-FHh^iN!epBy_5OqzqWofeYx*iCn+%*O(B--961ez!B=;m6 zZQ&o}<hFXJ3jtTGa-4B4CW6UOtS+Bb?zR9h*F{jbf*yVAt$M9rds{|iO+YcT+%}kV z#d}ckp`D(-@N`&RyEDpk_nR8;$NLPwQbm_PIb<_+*nUx!JB^ZjRp)jjW6{EA`G-m~ ziCGNwyY}*416ib>z`G;FZXcJ*yslt$V_Mte!+t)n)J%{GnmHv>b#&s)*k;qTF6cGb zdEHdm=*sfOxmdO?v0oeE-DT#P4XxxO<44gTEj56`Z;-~C>l&Gy>gPW5zOK1V(y`OQ zv~!w#F_*rkxb-w~vAXr{uGD0iIunPNFe(SEjMz<ZufBstOQRO6j&Nvfx0x`MrbpC& zN>)m^IF1CwZn#D1>skylnXnyvK$(ZtFI+=fzJ+|6;gNYDw2Ehpj4x$Vifp6kgS9^` zw}r9d+r4`dEkQ&5cD^$%rLr@yNIBy#x*`=(T^WVcy1v>%$&c4ES(|xO!2-}%yE@Ly z85%)Y1=2-b8)5?<-U0<oY*uI}#6BezqK?b=JM*(v0M2{wQ-oQCo$zLSUJ&!@2|boq zk{OaDWU#?%xT@-hunzO)=byQ7?3|P*pd!bvYoV)iq-`I3L(Te{>-TKy8_j4I67sAY zTXuNf?}U(B<0Rdj^xEa>aMp>(&G!MCh9-%$Q9jy23~X3X)C=6yn!br7Li8j(D8T`F zGd0qb;Co<vyL-shuT^jV<_9rf7oi~NIG%XS{A1Sl=QU)4EZUPHnP)&3m$}CL6DVcz zg@e)7WNmiypt`@c6dirdpvcOjriu%V*~O$?p8A~ODl#cLJ_5VwdTM#%4;R&)=^AHD z2nKgeIq5O&8#NESx`o|h5RW>BN%NDcz}sJ?bbiF9sUp)}98kA6rUUY;QgNR!0x%i) zSC*=xRnunf1IEYFK;HD#4X(bTgpCAnvE0?b7j(4VActzG*-k23QK^`-Eni}|%DtTB zRx^+9)=e~od+bPonLq(E4~|9q)HA=c%%jaqPW!6IP&to%8AYmRrc}Q+gX-ZSOlt42 zS*Gg=+B6Bd=~p@FFv44DRbocrH1Cn+2pn~T<gSjfC@ZKxi&V#wrjm-jwm_<-&?xXp z#7S2;vmFf#l_64l<d(4XujHjN;s<ZN0u$rj1hL5*Sn`*rYLDVVLVrV2@7>mDS4nF3 zjyoxB3zyqHj_+*CbYB-mYv#hJJI~$V*$y%trI&Fn7MbdB;_qso8QS>;@2F4gnF4=V zr~opT;bAkoo6%sSn?O2SoCFWMv1|EoQ<X?M`ReM{Ov}ufj{1I^G81V{6|0i*2Zn<F z{)?wJY>D5N^F5Q+D?2PFZzH}Cd<5O^U+I6W^vPuJF`Kj7oL-c`x8ZJSC{*L9#@kih z{2h|*@LC>!_2v1p^j@LlFuGjo83Na*R$ci4fAqQIwO+}jWg=uq6Jg{z;mUPv8mM{T z^{sEbk1_w2B%9wbDdg8F5RpPE=ItnX+{t?t3-e$Ta%I&3{;G)z1Nrp}Nm)3-RZ%x= z(W}h>n0E^A{u$)Qw&OKq=oBi9i%o?mELzKy$G*jLeL41NE^(|lPyb|s%Qc%Kfj!ww zXLWEHMYn-0>V7J>7j;U!U#yY|0X_ME^ID=v%9&3=#j>PO0ke#cS!mrnLTwLPQd0&Z zHoOv`k|iVIRo9EawbP5gUv8|FHLsvx%k*1MyXRy|@yvC*%;Vw^$c*Iu5ngH4VWaRy zx&1aM#do}1#Mx?d)ze^IDYk<N83@PNL1cO1!u_bL$862>W2Nz-;c=|al0f_E9q+a` z7{mYogNT8;WvbC?>8VI($dXvVhROek^b?{2R_^KZA<G^MJ^74<=weY2sq`eZc`Oo2 zAvSI^U%6A4lhSq_d7khbFWcoDrM8QS82C)sd(z?LRue^WSJs_5Y@{MPV<aPFdVm`b z*Bv#wb&X>c5$WMn9e_tnRbrs2!16XKr}Uv=cYLd{F*kvKqarC;-H8M8aHx-5EN{*c z3P-Saq-9z$TJpiOC%hF-8}Mv`qd;f}+z_8C>Nh^V0oy8D0Y`j$gf6jbSDNQ%yW%4S zU!&Ccc=4ZX<kY^w&BW9->q8rbdMHO$&<NiuAM@^Q?j>0vm(YHA(JR(!Ljh&fdECG| zycgXso`8S_FH(hD<vtk%w$^8k$dxV?xwj>UHa_4}aX|?x%PteXM-QTcI*-{#KjBW- z*5ugsBkv;rwbbr#g+{6=yr}23HQHuQDM&^5E&LWeBrH20Q^kQ%PwFA-SNjrO3ugv< zO5I{#qeB~J@Q9IC>fBDV&3YuPK5)A9z*IDI9=vIb7mi<ECW<ROH#qe!H5}_41J@Ki zcPy$x?)!JD-w0Z5`1~gJpf7bf8{ogrHQN$ol_~EF16rMpUKXAk{p2Vc7$+X#AK3Z+ zw5R!;<uPhtZZ|hmM^h(0V@=Cr^H<|3#~F@k{#rbSw8Uhv0pY%9JAw+5kgUBAp}LV) z`vqT;IzFj%=u`$U`Z&!h^g;Kj{oyQ%%<D_z?d{C3(=`4TJU<MJn;J1e%HA5Zss51% zH1sx<m-^Pq??sMrNE-MhU_SI&YCDA@W$84;L~~uewd-dM%77uOhHHeKV0jPCtJwz1 zuhTO^*|ivIY!Fy+KLChRj%DDYrQn)0zUj)@Dk%4ZnPItS@*J8Eo2{WPIoIR!aQr$Q zfDdVS6j!$vUEk&(^~J!Ys~K@{tKoLaYB*aJPQ)1HrF8Nd4t}thk<T&2<wAKbOuk~= z2e*`Tplth0XFu<$i+_F_RjID;zwR*6aFMFC&o7_#k7AFh7XzNDam)ooD-c({pc=dm zk{vXM5gDnl(?YCj4mYD!ppgkYE0^8Zwz^vm6!d#-fIggP8eNrwN>E^%k4u5#42R!W zrV^qaM3dCk8q|~SzyT+n%ljxNlBOaEA4wf@$uV6QPNl+J^XWpAv`qHA6<HtGX{oo{ zjfQPXYovDMxyrf@TLqu8lmE)SD7Wko6md-GNr`&|YAcqfOwCjgszz>Nb#}FDGSzO| z+cCNhCF}LEG1WN#;5&0dLkYD**NV#0)0TZWuplc|@Sh?@m?soZ%cw6z-9nWv%gKFv z6DdD$F6AJTa@J~>dWUBX4~PQ$b=7*wYlUR62K5}ZcH3E1gkzGRMK{H>mXG=TXSx*9 z@L=8{)(i|;V;ECa1XPk<u}ZabVh&UAkf5ggP-oq;BF~9=+ziAO8qUSGZ{)6o?WJ~S z7!NcZ#B=}BSTGUEOjbu0M9u3+Vp%L9E?vmIp|{r7Gc2VGS+dkoQ7kt^bIbaP`Q$4O zQ;JvgPuGzjCa5)I<d#=<+&qkA%m;H3yaQ9wmaj&z*F{s%LvpBGlhw2<{Xk{w5>|3u z%-D9$&@$N67+%$HpB|l*nA%!NYk~LuZ$L|8RbdE2Uqz>@%5VxkBsEvBjU<<c5RHgC zaS7D~qwBlaEg7&F=`FC@m(G1&GUmgrNqh$v^|FVxo<=`~dK-U4&u`#IrZ~&BJ$Md* z-akNYtzGm((7G5FZ$HBGhrZEZWFccY<bv5SP^VP(mg+rHiUt!pforp^*&PQE9(3b* z>~oR#(^FKYFs?#y({Wb}&5~yui)<tR+F4!ej7j&-V%}*X<vNx!wyt@yelQp&S;M=| z@2}$5lLM>b8ET`~%Zgxwfm1WAP1J+rGQVfY8Ss)V8PX7cT4-VW7q*19FNh;FTi|uU zKyR&y>zL#8uCpWE;mK(0mRGk9kBzd>!%3Wvc)%h;d5IcKW69jV@k4D<)3;`(wqbuA zP|=nXOOvsG7cuE_{Q1<JbP5+&;7e`iM!p})i%9f50%0j+tg@F1izJT5Ly^eqJk-N5 zXl|hLQhM?~i|O@Hq{MhGj)-!Kb~I7*?Z5pfJQ|CK4~coS`1}YrtTHO~*wf-E*b+C7 zoq3r)f-}eTpIIfjeIARgN>08*Em)#FH8z{ICu*Wtchac7GT9JRt^a-ML4Ra@*+?u8 zdye+Hr-00UxC0*SEWP%`(ssVk<oX#swQAC6HhriPtJ;{(#MEl};zD>gn}RKPfQ^cm z586p8-&X~anRAuSP2mhjShi2{^Y;y$gF~*EM3N!?@ZdtU@1~GOMJ=YL0{yI`6LE<Q z59Y-cI2Up|8}=s%g5Y|02I_5R)Pt`n)oSe=@BdKtPEndfjh1cNwr$&)U)rj)jY`|L zZQHhOo0X`vZFimSak}pv{Xg6rZ~HZ#BKBN!troeMAltrp1Fh&;De(&F7SCt%lj!*> zVGAl0Ctev|Q}<(#RH1o4!6NmJ{a3%}g1MIMVZb5=?yLbVr&Fxz*~zf%XJm=yTHG z)i*b`1uJwtO&FUk7`kLf%F>%Nr~B318h+)Z)DE}Y4~D}szp|U>s8El42g^-eV<G21 z7RX*BsYYqr;xcx=R}+m^)Md1`n90C*W8U&A9aYtog*KXit{$2?&yO%-qer5*)zQMK ztBtK~Fz}*oV|{v<+y`BF86z_#o<3fwA_9tg8WuiaP-<;8@QgC>-9&v~1*$K$w%YI7 zv`*55;C$ktbYnSXH@^kmNFtFyJyFH9mA1x$E7#iU8Z2c*Xksb8XPT?{U>N}J=NV2# z^!6`DHQOcfekBGGF2bzl%N1Fpr?W6b2Nack@!x3bzu6^%r*`hOL&zID3!ACJZ3SO1 zl5w5eKB^3RDJ{BO(eu_9scQ{f2Fb)L1uMSxdWVd0Yu>H-9<FcH%9j%x4yoTeg5MhT zRzhaB$$lxT128tKU8iy>m2&P&)S}O2YJ+Ls;aT_^iZvcvOS?%gOi{P*27?bxtv^0d znSC0W%u6cBq2G|+{?5_TkTDuV?Q7Bz+;~=z$+habveGto<QQOrb1U3E9Tu!M>*mv4 z1d9;$#uH4_`U2Nj8!yxE35bE$s@jF9>z@H)_)*Bn;fbvkgkY}6j3m;jx~US~o?ju( zJVq|s*g|a(;7wey`w6hV{7Z=rWZ0J&Zp4(YW|+sQapI~1FLkFC_i3+pLW@{>tfTbM z8oNF<3HF8oD`97!G&k%%LqbbqZnU9q9)E)YTe6hL9WpK~N~zO$MY*~>B8U?(YQI_? z0#>5GRBC*ip#T|-9Q!7Fi#Ct36Mbbm@uIeF&C42SLlU*89=g1Q_O~$ON*H-!xpg$H z)903<2uZ}~+`P+IZHA332nsJhv@=D4Pog{hxPQBm?itDqn9mF$#WETF$W_83x!l`U z)6;ogaA*7CGBcSjvNccAsa3qY>t%Cp{#}pNDmkxsoBRp2CdFo4Gstgvg@yhJGjwQM z636u1)Jf8psn@SFue<hLIW2ZsR9sFNyHEbZeY|BGlBTzc`H$Q{@?=64o<VeQSgWq~ zj*O>sc%dXe2TCL%<kmklj#V;4*p%I;Im@r%{Q?XViv_*InCmUCr=k3+5Rm0NJ2@}* zdQ508YyW#&AfM#VSMHknZ&f)tq2?YvP-6d@=^z^9-3Yr&7zPbSdz*<<D}tS4sSVx~ z`-_1j|7K(_<?mC*``CfVgZOCoBCrIsjSEkfU4CX(z`r(rodnJKmjU2*6~+op*j)~X zN>@3VKXcH=Msss>OxK2^B{lMK!}H3xe|REvl+0d8y0jJ#0%T(6V9%W|j|xc#p;{Qt z^;Ef#eeK?6Bo(Chr3Ak8V}~!q9!x0io%p5>LS3^-DV4`hL;aiCJ0u&bWORGJ`793K zq5U!EJZJdDc42mKG#*`~823V%9idpJEqZ>dmi^X|G`ZNm7&inyyC$~dEf9}h<L+uz zXSl;Xc9=rHN5D^tOZ7fOMS*v-)cj-lyn=@0GjC{R&-r7pj~sUuXI=pT(ere%1z;o$ zCyQhuThqXVoB;<EF6Gn-hBhTeR6cA@_OYuh(RXytW7|Lb&O4mlK~!!VTIM1NIg8KJ zY=V|HGt&Q#{Hfe-kuoj-y|s0wtW&kDJ2_Q(jbiTBxBe>KI0iAGy4HB|^ocWDN?qT} zL6ti|h^<d=BEFfPsJDwqV^dPREnRU^E?164529Ur{6uY;)vPF8Q+Wr!z-#*;nXs*t zOhFR;g&J&skEB-`#6)L$?n$2e{It`!AjO|*?qQ=a<VA<h0lbOQi1M=ky+{{WNYzKX zFgQgbcu72&8H8P*wBe;=Tw;s_v$@Y-z4o2?8BixAgh0^`2=Nxc=yENc)|i!)%DykA z>~G1ltTG>7%v*@R;R%zVWDzT2@|k3I&b^%Gz5PvU2R}&Qd(;$30Maws#on$TJ4Nfp z1DDCy40T9zehgy;(8vEdV^Abm@f+Xd_^4&N6kk)^Gpn;otVp}fb$EWD{mABV<)TpH zCEe1ffm5Qn?pdG>_Pd2|FT2qN-hQF{wU&}WWSXI4x937AUNywWaPjtP?I?ezEy{Rw zTXuKEu>eJcu2CwJoorb7i?9QvR$q5#JkkEbK~V6}1+yqr6+N^Xzc{|pDtw(Znk-`_ z*q}_~rTeu4*jUCM+1b<MEIJuH75V5DT1ZOxW46_qm17?Q6q~5syHV^+`>W~pdM-zx z!1eklyWxvnLX;i|prbPB(%KE9MV2u^lDF;Pn6(Ld5=ZyWWhpy6g;x`NUpo>agUu_A z+{|L1?YQ066;{!%gYD#7Q?fpVQUPb^JF?J7##3P|FDng_oRB&MYuOa%;^&?rD^S`3 zJrmWmpXY&eH8V#qkepyyaXJ#<VT<=&jL=_fEU<^~p%i+lk*_Fe@oGYljNx^GdMFVE zN1iv*iT7GPbM*^5-rbW3^2tF4bF$~P_N&A#EcIh74{ViJO#s}xNjxFp@B4-)D7Jw_ zaqSP3VQyVWdwZNt)2VxH`EkmiO~h&K-INpu!>!}T;44sq>**78h?VCM=SK9wHkH)G z+c)GURhHg=NV5HdeE+vn`w#N5a&!JS%VQy8=VtwnkdK4wpO5=L9~ee)3u|XnM<PaX zYeQ#KQBz|(6H^!g0T?G|M^i%^828N>XK<C|n`Z{<a1at*mf?A35w{@cvO^{~reQc{ zws4~DKok%XNjGW9Fg7TXn&5wxSdtHf2iXrlIbLg>ZZlfD-d;E6H*Pm>fH_E$<%N@k zCb7-_<OC=*#B@wD1jYGf6?9;KL6B}DBmgkdZy*Woq3=#;e{m)^L@pHK?>-=yYbGd| zE9Kz)c`i9Jko@B_I3QS{{=t0%WCtXuengOnFW7KrOh_u>?!T=-a(ezaD8LUyKr}?U zKHGcG2vm>EKc3+ABHTa*%*@EwyJtY$nCZNDFhW3V#8i;!u<xQ&!`S(8!GnfWyMD<A zY0iQLIwNnd-90@X#0&)8l5SoW2)6#5ct=3<K_2~EJqE4*`k<iAL=5$Sq&pNKU<d^J zIDoHDG5#d(J_2Yy{;WL}++M)!t?2sT7Vzm1@Ovc=kc~RlKBC3}qCf8Ki!G3W-fiF1 z*UYynRP1XGT!3%_LoHG;Bc35*eGu;u(B>pgHx(foCs1Jh7kDt27tz8S5+l?Wwowqo z=QSRPV(JpO;5_Iz{v7Bzf}5Dft!ICZU(EPR72JDj3Q{YKBqk;n$dS-(6+o<=7cR2b zRlgUI<swYfgZ%9W&&xHqdcB6!np^7~3e}!PDXV(N2zEvC8aGD}3IY`%Dh4L{2F%0> zG!1#)|5DW*P)B>|hV(fVlS?$ei+%=EFM<dR8~kTr-Vf}X0ErO`=;#_6_VH&oz)uUz zfT<q?K@8a1;MpE*z^}4so2d)H;rVuLPw0;gHN(#Y^!P8H$qCEWW1RqHzWdYfcat_J zsXidMn|?7j{1ZDdMd}0e&1V3F*oOoK1QF#AOmdpm@29p9(EsBK{H{<*Gl&2U6!h&J z)m!T4a`}`7bm=!T0Q_psOiz~C!UXi;Cuxg-0wT14c>BY-;#c;$i}hVK`4e^cvmM`9 z*7R`0^l|h0gB;r4pX2ibGGF{8S^%COAvy(gx2tHpPPkw>XuX%q@Pn@^CNwV`FS1@V zF%61w2oC*yH^iU3C%~kQ&joXS8^+@I8QNET3@6d=98Ykozl-6F0rjZQ+}xWle|i%J znVIG%jD*;{uGqKsIu%-Q^f)JwjHFn6#khS33k^zieT}3K@_4?GiquaSjZscNeZtuU z?A;AT29pCKIEM#SFVcznsnwK^<d2vW^5`l^lJiZ6girZ8hOMaJ=H`srR}o<QSO3|r zV8}p#iE7{y4TT2zTmyB}QHxySVy20MCZa3N)pBr-HPbvI?p!sqUQ2#)ZZcb$@mKB@ zFs(LEtJOqTPVYO5&tad|l;R1k``}Ri=S=PZg~RzVm=nv!4<-H*nggkLtV84{=$-J3 z9vuFAx)*+%sr8lDQ@}8=HTyQ}#7?z|*d&RiA-$H(zqgfvgXU}`&P(fAPLbss#9m-b z(|U=X7F?!pJX569qQ_Dp)0%@!=Api$eU5vnPjpsr6Ai8Q0HgWG99klQO6qZm8fIS= zhyD;n*9`ODA4&I(-9x;JUdWJjAZZ7c1AWn&J1!+vq2s(MzwP!zjOZHb*j3_`Y{y)I z%j4j1ZN_Tn(9K%!ni?TEV>v$S7MzkH<gTSuInsKX&yxY=jbaJ7sQTHKvNRZzPC?Ql zK*E0{PJbuY?3VQ~&YUibpqfkr*S7FxXnL0zS#RBVo87S4$5!p0tMre+o72j$rmu75 z*K?5-sJ3)Qr=WZ#)tgLNoY<G(8RY?t$b7wFu4IRf+)TzX--5Q9gNdBCkr7Y3rYAg{ zTQ=h5j>-exAFW`dZH6u_I(3%IlAiMhoHB3gmkeU7tcR^TO3k+o*1@%3aWz>RIk_I= zzQ$vI8NVy<pS2x)OtOB=8l1z%4rPDowQ5|Y<r!CWTF(XOdZaeEjYeJ+txw+68Fuxs z5cTm_+=+Z+GgZSdqWBtI%J#0&415VFh%`!!!3Z)_i{X9cvv?m~qD#UNAkS-m)+~tz z3rR34WM3I0o*{G`8mX%!sz~!DG|m7oIA$1d_=c+G^__!5pc$Bm|BEEfeby3{SXhUg z3&W|iYXa?&_~X+N7FCT!(pka%+s>e6R`Ap6JFQzk-Gl7+PLg>A&-D7ZMx^gjtJxaD zc<zqp6ft_eSWm;_81<DUNQ;Xdruh&<(eyjt?;$TU9O={}d?@7YIc$<X9=q?$M@{!q z>gIjyAg0L<POJID15J&?Ed1)+_BEO<a&PeF>ns@2UqBMu{x@<#Otp=3s#`l%z7?{$ zz{-i0wvY+8Tt&rFp$z|aJ8t)jwdZ>IT;k34w8LjJc)6+=*K(uo_~qb=9+<PpSvpVx z3vr};^-X`)kbz~=C!4n-sG`&$9LvZPmU|xF0b9$8eo+UFkW5;@{vl7($M5;Do=Lzx zjgdU@T7X;Lh-w4&DXPk5fnax_2D`N5C6s%ut%K!VZ#p8aEfnG?GhxC&C(#4~u3b`+ z!Sa4aZbKyZ>Jpg*p9OkxB&H|y0s<r5cG5DO8*j;x!daW+fFX*q=R*IOX)v?Uh|KcN zEZJo|Sk;p4ZeNE$fTaU@>1nXhrE3T27ZWYU<(#*v^+2*!5?t(Tu%)hemEIk&M{i%D z_HcVVMWxN80X~n%pT%qojzsT(nqTgby5>AA^8@Sh)dPRTi<{w^CRN>6ZV>pDOf!u! z99<C1i7hp+q768DFH6JMdwFuNYsT64$x0@g4?T+a4HDd4(JMA=ct^F4Y{I-dwSLN1 zCn>*bTy4L`mck^94o!)?wU+1J(KAf+-DS8czEMnfdjVYsSaqGb7MF3)GLB|*w>ONL zoxK8#l47SZzL}l`8%4lg7fsvW7Nj3I0Jf7{W>6d2KDD)+5OK^%T>qa*Wo6%&8bfu{ zuUP4>!7dGe6Xiw(3~f}fHP{f@YZj;`!YNfnrzBK8`uH~0I6Xki*n5z@@}Xg06KX(H z)`k5hXR0qE3V`@gZ%4WHGf{yY_FAOml6`l-#i3@%>b`7#g5?k@3FzlI^E$v1BT)uV z$z#;^&3P{JK+Lk#SDfO_tu)mHBOgC_(9!1iPb-y?BS+^-WSG8qWt9bwRd#I2BfYZz z$$9cz?W#0jWU*!;(vciUPbKB#U?&5-elj_lXmM@R-lkUz#_J0xWkOZ8{Wf|XuYq&F zeXTO_=$H%7f6B*e^kN(9X#5J<iC(Qaqmw?jd)lT^*Fnn>%nkfk)8R%bu8Ddr$~?k7 zn%&A3ZlrQtc7No8LnAiEbc@38Dt^)W!M@_1fEHNa$%lUzkXEeG)B%qABStRMo$2f8 zP?#!meQ!#>=k;f!H%+60@{0my>z6lOF*F?9hrCLS+t_e&h`5)3v!fNh46#1RW{@aM z7Gx>~Zl!L-s)<vo45=cgTRX)8>_L$<VH+W`PYW8E_n2G;$0XWhcBnzM-B$v@<ZtO_ zY5$-my)>EQk?$navgnc^u`Ie-GUXqva*s2R#I4fZMTqjD)peM?qX1?vHp@p4o=xh_ zx<l~zL(QAEXqzqD_TX@D0pm9urD;#esRVk<2cwN{o9IOI<`uFVTUGVE(OJXlr7RxS zxt=j6l2*9{Vj)7c=#4TN!OLwllnP+y>SUePp<H{R1^Y5Nnfa@!uv1BR3_iSEv}8~p z;s_K)pJZFf$geXMvy;6*`V!1%JTJ(cnPRWuq|67NDXzue4NKx0;l~IPWDieD!f#)- zD-%QXwMv+AE_aDfigfcbA|le4tG!G-JEg^^{vO;@W?*7irAUR(8;Wrf<uE1-k3J*; zh`*Il%w_rQNUGh!RPjNDcuZE9+*MWiF#9%zv4wY6h+6&}4Cb>}>Bmy;{EnvG;HM^# zql@KJ0NF)}$z7E7@&Pta`XQdDiS|rGeOU0U*jtQH9#z^EuSBMeAaNuA!G*T@?y{n^ zMOfJSfFt~XpuDzS_Rywg`>SL{9<ETGB@hd;3Bt5~s1UAj9WqyAniy!62Xlk3njHy$ zq3V-7vGsO%bnFpECs=FPIZ@Z4V5Qp-DI1=>npl0hZz9@44R*12k%sG34@~oU-C0t$ zN}aM~VXUHgv&XqWy#Mw%R`cLHxV|8KHMeFQbtfS$z$Qsx$c=2KaDn`C6Lr%o^9}LK zDcKSVcP8@}kpp&F%M6y<!a$z)1&EK9!Q+GU%Y{%l7+w?Db^rE(FJj6DOCOa5(PRU6 zqEe)$$3F3wCtJru@hNjMgP9BN<8SlOw;Vao=?<$F-j*K0@&nMCWk~A*lf)|&Y6wjy zTK<V<1^v6|EVTUEz|v%F<DpHaV<;0_#G}kR)^5bZ{e_Mp`#WPN31dB3kFNo*OLX3% zxjVqaCfF__9t?<V;3jGnmn8ttesAO9FWih0{EV8Dcn2M1BPBKp`Hm$n>y?Mu?|-Gn za{Vg_b<ctu92u5y>uR{V(tvJahLxWgJt<Z*^rFoNan6Yqs`SAW)nVCbn_N-MiubSc z#vLkfN};4(ki{f>h*Og>1FAk9Uq^IB8_ub=!tB3#j-fx<8gt_p_Zdfb$g{p9Hq%La z{<%iEC$+2sh;DVy^)e9$jkkd&>$e<6mw&#@sIsjh6G`P?+S>K&7GhUfI5E1d6TPbP zb#il!&hKfa?`LDJ=@=~rqQ_L6_H)^4@Qc8=r<-vmE+XP!UI_G5J(Sq(d>2c?^KMlo ze^)R)r<c4+uj{r9;;5olTMEh)^4*Ktw83*Yi+<9_rj$X98a;YWLrZEpb(sekagI!7 zyamg>5*^6P)|^^6!WB#!W$BDZOOE13(Y!j7MF35s`OTXDc6XsqoJ-rBHOe!Pc}H8C zah%~fV|wi_g$*+KV%D}%BWit0=x3KdIo>1tc&BN1w#?mgSS#Hv&MnG*sW1l@O~x)^ z*EmXT3geYm!Acx+M0}WvDl?gTY+(ibPCBuj5TLb-tMHTPI+qc?LEKTjrpF(ZIrE)F zwyCHl_#{(|d3g+?`^wKJyxYfXzj{*_1ID1Ew7fQ$_XYMa7w@4lkw&8|OXhj6PK>?Q zY_FO%*M0E}VQ|;<{E1Eq$@(;gSp6(BNkCVx%gy3E#lp&hY-EQ;?%C~xJk3%bf1Z-| zm%47?^r5)vFL|(^ocRdl>#ssJhU3pkAbx<xSJ3@c>8Iycw^fbb<VAkAB2|>hc7dXt z>^(kUL*sKgb#`ie4jB|6Bpf+l#Sj@vO^=Y2buMHehfwzN!TO5FL-{I5AYh&dw9H{^ zyvg4D6v#s5vGKPyMP#f{g#B13d&$sJ)N5*x^}P)l6y|AV*8hMU3NLIW0)DwOO)am} ziPNxda*7S*jBJ#Li_~68MvZtFV7y3q?#qqRY(d-&e5_J9EIr_hYPgT)`Lf}icSUbS zfOt^nGFQ#%FimN+zN2r4aMj9EOSR^MqtI4`kz$wKm<4~KNo8`<UtS|?z8IqovKc+4 z^wjA<u6fP|HRYr6WI}ZYtuqL{g6uaQ8+7sNEFYpwk2Gjf!^vrpq8mqob86!o?jW0{ z>ECx%*FiOzKdxCc=F<stNZnIQw2<}Af^Nc|T6M5i#e3P@8h+qvrIa)TMGo`3X)AyI zT}s3Fx;i)hpG8U#h+^2Pu{}%QaZ~gpJS+KY3>m#Zn^8SQ(1?ka2YMsUn>$iLgG8Z( zZ3V5>47{d)C8{rN;HJdor>E&Y4Ne52byRiN|4E2Env=4)38Xpgaiw%}d~H=1qm}?{ zA@~=gKm8b}mG47ju+3mPvIpT5#G-3zE@1GS>7~wMNA1vIg&;nf&<+9i126qsDCfFV zKW*jKcE{2WFhbwkC6`C${h-&~agH6f@Jek}{05RoXg6$mnX{q(d&ab9s;pb^uTsJR zT63jx4wGF=N-n;FW=m9(I0}Dr^>M%M0%Zr|<}S-?ct^YZY(SBxOk(MvcO*-w=k_PO z)uK*hulmCTd%POIsvE6m2z>oFMLEt*q_`qoY{`={UI$F?KG68`T0oGGy~uvQEJ+Df zO@-yBW1`7WnzqH+U+c4^1+kkj-<Eu;!i2mY3HOt#O+Hv1d$kkoa!7j>kSW=jQ<rrc ztxCK|sq69nry!h(5~rpHRSf<2-pdZ7S}cTTG95zB`1iP#zcaa2A$MnLDjv&LD&met zLa<Bx0xDE_X7-M6%U{GdZccz%C<D+(5}j5q=TW#gC%^T2*tjRL$!XylaeSvaXu4zV z7y)j{yTj0WeXS?W)M1uz?T@%|w5{<rT)n??2Mxz;#yeWtTml*0z5KMLiw9=oe(s}9 z5y0{x7<?8D+v?t4lyO>yH6k}E<1#+FXLz=cA$Q#l2h|m|T7y^M4vU~hpDrr<B^-*w z>x^$yE^BuVE^E03Jr&wAr<>Q}!ri`<y3*VGy?0O<#oJ}@?XFX|wa&c}p53Da0Oh)7 z4RRS3jGot%FUN>Fp|(Zf)d+boY2n~W)tq!^mHXIPY%<`;fu)l~@?002bEjsnWnNjO zwDiJ4oo<k1^_xt3b4m9$aKLAA^K7x6U+v$tM|VEUBMiBJ#CoG!5VI991yo`9a1d4K z{JKf0Cv==}+ta(yR;|Rw5YaXUXX!iZbYOcq7Aq6ujQ%ghR2MI1n9;Q_>E6&=+-;=q zG=FNx<9@7zn03GZpyzxA|MJrS=(OQ~X1LWA&&(I(4{|h@YXkZqL*RU*%1}$OXjY;4 zh(R;acO~wgeg4Wv(KQgymQQ9VBcPmmBx}BGbh1s2FP339I%ZHXQW#CzCe67sq|iZA zE<1F7hHatP#l*ewpl4r#nyo&ejiWS0?X@4Uxwo{~+8J5rek)|7akb`?t&DIIG*t7T zIs7+OafgUfab1eZj`RXN!EV$GmJP6XdY+v_=u61wdOX~Ni1i*HEwL{(T@-T!b6U%B zW=c&t^79Ky;P%TpyiS>%dMzj=)xF~ctvj8#_63#mu~Ym6(bN2ec{6g5*l7aDjo5-= zfAff|Z?4t)djS{6trI@ckzWbPl0yh<{;+g88NV?Ca5`s)^!UAlm@nZzHjN-hGclgM z8ud<TV(*J^5z9ebJwZbx<I^h-im<1ra=}9vyDYF)Mavs$HEu@@iXQKc1Slpg<Uymf z^n$OS{nLFEZb5d-eo|901>8jGq}&|(Bpk$HR-hB{$Sj-f?<+ccCT^t|@AzWVunILI zpxT70^5=>zm6}I1xivmT#Ko3YilgGv#abW$wo4@;BR^kTB>qnkWNwfZ5k76Nc~i(A z7AM)<3ArvqJM9ND6XOe@l%hPd)utll!gTB4jh1~o5Sti{J<8@OHbMD(Md}S)+ntt} z{PaTNBC_IbDXe65lDdbXm(f#R=XloMbZK>iAMtpng^R4WKiRpmDw#tF=7SbnRcYYO zzf1;u^zU6t@ULQ@Bw_sKv7CL^*4MA-vq>vSa~{WDh>T80Xq;vH4Q_N88RSa6rx3Tc zK%YWyl>klRtM67Jf9<msho1Sbq;`FaBqdYLwF~B?LAWuapXlCMtCK(kL~9LrFU z9-wk$_Eq1*-aFj7*Xs*mOwF&{`n~u0K}J(_TGO;&chm)#7~f|nCCNIXjgUq=M!dam zmCbiswn8PyH)uH4PwdNUuQFxX$Q<*sxQ9M(4M%R_G{T9DY=j~+!hRQ#6lVqbJsTok zn~@f9gH*ph&dec8Re1n1C4UEvNed50rLEz~Y94^Epr9ODQ5H`CgRGJB6m-WboUi%? ze)Z{B_JYJ`4|lOFk)w)~?D0Hoa+Tsxlcm<O*GG0YYUADupt>~nZUq)$O=oA*^OSzJ z$*46h(!S?K=f2ji&tXZX5#%*yXQq^GaY{X_gV`01znCu5cGm)}h<vYgEX|<C>a#4> zaZZq?Lx2T*!~FTyka+GP=TVWnrH=T3;Lem)OVsG5(F&ckV4XmQG)~~>Phi9l)H=h_ z@t&1?={rZbO73dOh?hfMzBF|wjEmF2vGaP-xlTK!(NZ*Z2Bf0<On+yey)O)>7-DoN zp2)aROhf;piWj6H?v|O9F}%j@O)PB(y(Xsd&?&V!af55Am=ybNu`B_EIeFb!?k60} zTweUWLE{~1vVvVJtLq5d$;~!54S0VXj0cJ+Y;B$MIWA%pWKcbj{rzHv7O)W6X1+K+ zOt}62yj&+do9?2LDpfBGA!S7<-ConRhG_iFih|k-%IDqtq(n<9iGXk{KC-*l7Kfa> z78oBDdY$-P{P#>cY}e<Jtx-hZ$*BbY{_9b;IjuHrf_hs|$e1PI@4+;<@`A?wMKGlC ztjTnSc89wW+QhvA8@{$&Aa7tR7{%mC<-0;Fvh?zd&?>|q0x`2EJ1L3dM!@{u+HX|` zU+EC;+FKf5+|C<KN%t^)ZBA!2;T)e!s1=1KQ-(@jkxb1?7ME)~NQxCmH^313F2bLK ztrDWD7jR_THb`HEKRZ1xy4Al2VrH%1I+HCc$a<^Jj0zcr*TMn}$F+ncI-iS~K)oc| zcMPAJr>-rGmNjW(s%7kID5t9{v#4P3hOLw=`Y@=wemoDf6Ow8tgE1<8O~qb&c+m|T z%!{Kr$u%|T(9fsru$SNLblEU4bb3p_mVR4y^&WIoud8&vnR_*oCcLS%j6d+7QBS5V zHf!v~K{19BMMhY7v93HN-8K5Ma$(yheG;0@RvIgBQYw#p#`yBM+-pB%!>x8c7es&b zr3-t@H!A7mTwsoAIImx`X_#&>FQ7)tf3B<l?qt`K2ZocWP3WxdA}ETTy@~AFM(<2! zDRVt2)z<)2V6mU7p<<S;>@A@YA(g4-NJ~1c%}m^y-divqoeU;1hSo`z5p<rknePo7 zEF-kav9-y<Y5T@}<f_T3)D%IF_4g{Y&73Xr)}P;!{@UOFY=0Fsi}^WGo{WuTd^^N+ z-RHu3gb~b-!E3L%96*>Xlt|`SehxZwg-*~JV;$1oNZ~xJXOuQ0M}_cFWcgNblC+!f zl~-Q0uWD&hvcq0w`xA$91Y}A9r%$bZyO`KoRNmP0wPyI2xJamo;Gu`_fB{$Ry7+Nq z1TqPnWkTsDxyi`RmcS?er(;qBHJ+_Vy+vnqX<^;uD?>hf#pS0Zq{H=%6y;0JZl-A# zG1ztOs_F8oD$q~^bV3vjZrYibc`4p5+hh_YhP|ndJCFWQ<1+g57Rje<b>!GCpyLxz zm!?DipE=wAvoYd-HHQC}Ovl3de>fWl3k&yupZ;Gm9SalZ|7XtT4ymGivB&`eLeeA6 zPSiu80({o<!ayDj6c7&tjbE&uuv10U10|Udt5m{y2BVbB00kAEum9+N-E;E&qqW=C zxH{`=o}1xzoO7}<v3W`78TxtuEXi9AgA#BI2@OOJ9Jv{KOhg0(g@yqH5(2fc5o7S1 z>(P#vxC?q26kLRa><6^q6d1gSnS-1O2XtAS1PCYB9!L@k2qg(DLIxxNh?q!m-;QWe z1SKErIdB8C85{^l5)4gjyf)nV;mMzyr-1q6(+Bo%pgpJ{3d+8B-w^P9?Z19GuxOy) zK@0MV>eI1EOn3(2!TtHacm0b0dj1U-?~;On@$~Y7_1FCcB8e!0Z7bl<33mm?<X@Oi zpr`27UzZBZW1xPTw+aTe0W2=hw5*RHQVhC@dkG9~0B4T{7Aa^b%!mA}hzMln=3mf> zA-Dz~`3hV8gz1lXdtwhn1U%oj_!aS;0u}m-4;LyJUu$a+%m}v!W$!;w0Hljf58RBH zi3lXV{sR*DZ+V!4;1WD^V89it|7LLj2;IX62y1CC?^_WGF&!6&+&^%@?}_S_7XCOr z1^GErQeB-2B!=WuH4kMP6lNg1tL|^!UMErf4%APdIs(%_nXZoGlK)@BH8PW%LV4#R zA>63wt6df;8axuXba+HWAdsRP&@$vc*{c;OsXpha-H9D*X_%lNXEAO+@Dc<Y(lOA8 zH}ZQ?zn&t{<`62*=}%s)UoDgnkv~6NAjG;5z9H10pZQpN0fJu*^TUh(8xUOp)_VX@ zzkZ(Iwx%JLS)6FU&ky_$zmbrx9IFqi@(zIhXR0FK{}K500agm=m3-JA2nmV|0tpin z9PFDljsWYqEcPc{Rf3BM7{xCoio2{&=J|aHxE27i2l2_8hJZ4pL*;+5E9wV@1}@Bm zIscP!-6!(xNB8sZOOO2BPrY~_I_&4!=?nbT@6$jXYwHCOWJpJWO&okvG8zNv2cA9T zn_SnXoPT=hsjuh!H<LL0J(L7o(VGwnh+snBB~voYG^Ax6q=-oNx6zEg>w&&!&=8U$ zKN-yP1$0mZ2*}S=7&7)S_yd}dVfou1@R8rAc^@>SM3Nu+M*ro|`SbJj_XekH8mkoo z`5}p?JS*nynm|Co5XJwNg#ubKCh7-16MD6(9|RI&f>~mPI||GQTKYHT#|uRTfz%A@ z^*KdE27)9yz!dg0_8dn;luJN>CG}kjTRPmg*7t-M@-9dm9OWb#uG0PxbsHPS;{jp! z9cS!bWu?m;as0JV_&fHk>|0*zb)$0W8m9G`-A$b35rc-L>=*>gT|htjgU>q$w=uC+ z&3{zsdRLKapAqlf^?nn1(mJl#EgNYre1ixeyJ$|*(lXp~D9fDF6^V3%yyN*@@!AR7 zVoKZqX%C*9o6u0qnx8j*;&x>S;4nAT7D3DckVTc<)=xjODRJhukNUzz0n|^!i$0FK z46*arKfk}SwgSH4_6|s9cC;EYC8c?20Pv}w35P;F=fyfPX;gFw;0vrHk<FrNohWOP zvFLc(cPTflVxU)2L4&z+u{@E)Z7zf{99|qmVkgB9UTU$}HXKgTz0fGT7E-Ye`&Cm0 z$_8~UV?4OCeAVcon2-C5OrW<oovD77b3{{<b2BaVX_*JNgdxz{ewp1)h96|S&}1el z6!3k3*S(Cubb{;+o8bZHvvVOF|HRxJB?Wwmun~_Lr$d6g{x$QjdYYy#>hPtjR8IUM z{$CQ3t#h)=OT-aoIU8O+T~drIVskr*S+`VC1sCim3ELc7&~MPJLJ;6@?VeY<l}Z?n zD6mP@&=iBkA>xM*;#%4o89Z&%<fMl|=Hrr7x&rD<{Q8v`xIQ%an<P1|0Ib*F9`~oA ziQm2;nqQ+fU%7UiHK<p7v0x!k)$FjHblKKZ&Rp#CBoXz;J;PNt;16f<q<0-DAR&aK zLLA9QaReA#d~XClE*H&b_5HHF#G4=lNt^um&4v%w$rVdRM7hilD~G;zl;)eMaav19 z*w@G<+x3-)L{{$5-Id%z&2o2NKrYb@M?e}?2hAb<Mdr%|Z;!ah<M%q!Cal9Vo?TKW z^H*LaU4bb6fyqw9!ou!F;=Ji1gM?{Rn`Dv^uNOWrMz<!)<@0#LKvNS18TP0QRUM+r z&E^x&?c}N5drB);r`2h9{HFgBuKA<+gok)#WGYABZjAhUZiHYn&LcaolcZf20Kn#- zMiv)yMVJ-akthyKO?uu4Yhp$gg>-y+mL+9@#ZHXPdSuHU-6gF66`2Q0u!VQorC;z@ zj;?O*i{Q<q5sb48axT{_*e0}P1Ze~&EfmuRdA=u-+vCBzs&7&cOp;M}fBK;xvo*<g zuVpM|M2YOsvNi4oVHC9*w}!-!W>1fpqTmi((%X}&dfe>Wh;Q*2rl9sTBh0>ZjPXqr zza}ad*&UNE>8t5<nv~pr^W=(sxo$;eVD7eEd$SY$7zX7sr%av`d?j+9QjfXRq0F#q ziE}&sd9|qZ>mOaKdk-+!i=#QR&u*?w`VeSefqNZUIyGTee!I`jbg6(yB~MD3ARLag z8B#H%7!Qp$t!w@KGTF!tUG7q<=y+Nry)k(mgyfj4>?CMZ^RbejD$QZxYCkj0Pj6KW z%&Mw86qS@<AvGUL14yza%50tq3q1_a0{4>F`4*VR=x)Rx^`y&bTGj~^AD;|@b7LYr zyycGL@uD@_aamWF?fm^)$F0X4S{O(4&S$3g=a)NC`^^)N;b3F^(+7xC6h@bA!IoaC zmWBz;NDw;ztb2?(>6DP3RFgNTbxgJVsOe^78NAoO)U7R_)84)w*+cW<lqZqO-%uKh zNSy}x#`32Gd#&h&vCt0$n*<<F{jbIHdNtkaTk(C%{MYF+3)jSO?Y&CTk+ca2-#ID; zc|6z8B8r-cl<b`xfpxn3xk)W`N!*Pb*lut3`t&#y$G<9kce<K&P1xQ74?43jgWiA= z0wKohS#0r_vrx0gl<=rpwyS|SnhtJbLB}^<u3azw;`;;iO$CN^yC!$ZVdyOfx-^a3 z=Q&3GSVrqPKGD`Nt+}S2!|)GxM{6-(!ravQH<Xo0WP)!kCI_GGOx~=KQ)7Lm^j9#i zn)io&lOY^A$ueTA0+m76&6G0sR71Fe?o)@<^gy;Z#{^6x?y28F`4qGTzJ)>TM(5pu zi_%DT(EzG>fTyK_WUT>3&I_|KNA%&S3pg0xbtsnB&hP9urVD+kYGvd|m($_cceM_u zWW;{U9Q`HgQt0hZ4V%VhZUL-S_}cMSp6%3}Bho<uu2vDuL1mVl@!>?@b8)Yy_2fP5 z%V-WsG8~X<hergB$L(3W9(fZkyC)>x8+UruMT3OiZT|YRmVUZD;X@e$g{9)u%L@vz zIySaGU`dBkUZ5j+X#(tEZPmWHh6iQUWK&Z_c>i9;JF|^i1wvFW7A2$nwwdQM)2hR{ z*|sf_oV&>vj8>UT?kX>UE9-3=2Wk)UAd1N;WW8SmVzkz!S-7^lgv=oi$}cMiv0e3I zF-O1sm9u@+@o}joutZDbE*=gEnVLhJtmCewq+{>v>AKhJx9*22B&Xfx?}q2Zz--*$ zWRA@uhqcyENBCDk7}Rbnh}osBi1&#mm}bK_Mdpg0%MVXhOC9N2ric3QUMEcaC5nGD zG&Hb?t>_@Qi*7nNsa|*L@CfaxW|Y+-80!=M>-XwwAGLc|8V(1=ythDWOo!81Uogl# zUvW0e?0X@-9?8Je&@y^%)CeAg<QSMtFC{dbLi@YD8pBen1nXIt)!fE~8zPLNe|0K^ znn*F9&~V+lodxU~DkH&BQm#?`Mj6N3EJ4sGmneE8Wscz2D-SlU*)zTxajLZR;4u+b zoDG;t?zQiz>bc{;YbVd=G^troEK1?2j?R0RveXDYBu^+`YYRLU?6j)ZNci&E#m^uf z{GkA6ZS48?0oqP<Jt2FhQxTtkwN%)JoQJa5J3}zuW|mjia(=u2o8jDaDIib%6^>}B z(-lrF%otjBM~$YHpm?sh8FF;hh~^UZCJaAJFRz#jWbDJT;e|B`VWRblyr{8aMFM+K znje10yU_`lC!E(MG5%TFSfl!olC(>TxcFNZ&Cc`E_)B8Mu(LR+cql~OW`mRL)3()* zEmBPf8s$<1U@3Dx7u~HHYO>Eg9v_Z-o1U)frxWg6%Pug_SM=z>V2#>762|E|U<Fy3 z<#iWQuFelxTkKM97eI>VxKlkACz$Js=jJGo&UT|S5_EqP1jZ=24>K&X@187nW4bQk zLoGg9_MuI!Hd+7G|EuHZWSj+i<^gUal-+5G`<cFP_9Z^3A+Z7H@a`+vSI*97>_uVA z(L-=GnXCZBsbRt6fZyv$REvT+PJZ{ZyVIV$G%#o^qGr9~8C*lg2K5iEb?!x9Ff+u0 zU1tx^MVvXo=$Hh#anw6ZdI<SnCiyu2lkfY8hVk-SpsL4df?`d@LnT#qoQqF^^2%_3 zVBp818Wo?}X4f_TW79!`_CXcDux&=~<Ji%tRq!UG_d){0=1#`?x{C~;>*=0!->GD; z5m`g&m*m}0imr~8%3GBbzZ(6CN1n&|oCZRPa8g^$B!vSm$>6(Xmdh+D->c0;?91`g zLu~B@BgcLMFX3(4glS-T*VKK}`!ZWd@$LOwokRuK%bKOb4S43I%K<$Oi{nS_W-ja$ zbFKZ}kXLUGhc3g_a?+G;PFe>|EAJFh<C|OeF)e5{UmHzNvIx)kms+v%up`)&NQY%p zK?JpT{%*TMiajp`<<W+&Yfs{U6ZIwFMZiHL^N+cws0-+$=UwZs4HW&!^aD^%K<O<K z%N<YW1mwfYT~8{4eJu(KxjG&U`rI3jOtN>n-k;=#en||ndeU;G*?y*F9uPWd3Eacl zmJuV^dKOQSi0sp|PN~PhJYmigo$XkFl_)Xp(fRq>l8Emn-qoZ6By?KMh4PIvEmKyu zfYHBlZwAXEDd$uQZ)<Yc^3B<YmtIXP5gHnAy~6tqhte(~G6iBQFIIE?-tI`Fnx(Ii z;RUF(?G<%eWfHm9hUs4;5lMMMb5D5J-94&4gPi8;`b4gs3l2$l6%q~^ri&kIdaZ=v zJelWxfCBz2gnMpv(+|ylB)vvnVkC`q9$zoECsXdLt_X&dhH4c_T_0Da^2eOaH3Yh5 z&g=VVXEm6=(6$~2Pa{}cb_a>tI^Nk=5^xr0$rmeoif%LGem}CK(MK^>IFD2HTU^<p z!;h2~%@Kv0&tf}YZ4Av#Qk?%B%ENPalpy6hH<?M^4{&KngoXv47;>Kl`vOc8dWQRR zwO?D!o0!EyGofO6zL{l=B$=lod4Kmz$)_EYA2h~T;VB&SgbwQ^*KTwiy76G#>v?wc zvmJIu_{97aCGMQu8WK6tg_TgZKJ#xA7|SjM&V^F%<imq;qvSAMGknJu*W_lEa`0A0 zhgz~SSjg7Dj*RQFYjCKMC<o10a6)_=qog4R7I`p{IeD&-hGi8#w=J%wJ4`e%Zyu}x z*El#%)Gz40g0*9M2LB53@`lT89+4=iJnGu?G|(YYU0BGJZZ-f<>hh%o3}-%<_>Gcn zsbUQM;x>(~N1}1F{0~lsP7a1mC>vEJqx^wf&1ib7i7mAInWa<saoOIOv%FLGU9f9) zKAD9-)U*(5wl&#W^H+!BOB2fCMQAS!DHR{>900SUiKH%MujF^TJ3ovL%h3;~S1JDV ztJyJF2mYP<;D|W+dA92#fsern5vMC#3~OglhiKn^CfpN8I!PjJ;zQ}N901Fn{ic>z zd~2(o^PX3nRncmy&qQBhKy`G9NFKL3(s+Q@lLf!ax>EUmP41JscX_wx?}%J2$K@3h z@4}zxtHi4iHuSHs`8S;nT`z7!D9(%&dvYJ1iEFw8It<=8*L)mfMxRxAsovzmucnsi zED-|R9A_6Inv)9<bVtv|>)(=Kk<dA=`I8>KwXaM)GcmYrp&xKJ616ki*7qdW@0zu% zQ`w27e>OL5g5}`%hOa^O@Mc<uP9m!aLtN@JTj&(wcf>t&zopp9V_PFSVS7Hux<5VG z(L+Y#SkF~^ar93cTCHLw#P8KyWV76aMyO2#RCO%O!I-=tLal4WsU<MIBi7J#j?X_M z9PIy`=mTUnW|i!G67$FuldQeJoo94nCJ>Srn|EqCPIve5Ier`12&BkK3`)Ev%awfE zbY?E@H$eAP|6%UEQ4yz2*@5YbboTl^_t#$-ZD(U&v!L=gFjskqG)H_2L+8mbYx~qd zERd8Gr!U1KOk2B+V7j<$R5xU+9(~}GhBoM!jf=N-ZKr7i0%vQG6n;b>##4hpwzrn_ za9<HjK*-ZF9QFh};fjO6tLDlz55j^W>;1%Xt{Q4;mXfbxUZC}z!a|x-Ozhf)lR1#? zp>(5jdB#4ZYog6)a+(Si>~VFu!~|9&I<g2Dq)or@_p`%nbPY#d7`co>#>jWOPY&JY z>pzA-s)0*?K&y*8(S&SN7QXZ}p4pDNJx6r&OCRdQy7!b(u8XJR?)K5Uz##k=EtnT$ zwIXAP2wn`uh`@u&Q_`X{nkG+%=OEqFVp5h%nb7%tj-i%kochW5!ixHc1bpK*j^S0{ z1WmQkD2R(-20h=U@{U{PJL{ex&+1-ACG}ZPJY#uIN)Quaap=mXH~CcgOG^5+S3v*R z+rVj00@1JgB9f%1gh+@T%lpK%752K?^kHM%=wAgJb0;(q-faR1FC~9*(TAxc^(s8M zYH<&q5+Y(7$wf_v9l(~!*<8j@_@uq+v^qNM0RZE)_IeD3KNklyX{_{}bk@e`f}f^^ zP<KZ}W0qT$`h;G~kMhCS!YDq?v=M?^O|O|n+7PL_%}E)OIgqn20?40#;kM5&fL0V4 z;=2=Jx@A1k?i6{c5Lw2^JAmZM)A*ypxAL3EQ4Ck3U84tUPInouE7nO$lB1^BE9Jqb z9RueyHXzwRt)JLI0cbrNT+b?z({d5S(0qGPz1Llg#P<B^tG%WYHzh!O@JiRmDdadP z^fAZ>E6e=M%CdcnWqERn}6I&-u!jD0gr%E@Q-?WV6DNwW;KUmChrk!aA~yy3&y} zJPi`lmfS;n-exo<6XYe=9tJwkMtbINy%>u-9@y*(B(fOfBFQds0pI`9CYeigGr3xU z>YCl(lIEy!L{kFSy?%Ww4%t>#xdv$4R{@MBZ&wd@%jD0Gdd_h(4WxI|OLM+kPvV`w za<5GqOsHSZjv}hYNp55xxi1o=s|nZYkGoxEe}&IP;oj&kf8hDilo-_H<!dL9eAZ-1 z?6um9q*E5+hg}_2z5`8M&w=3T@|`07X$y8^-O#Jq428ItQM`bCPVrv0^@li_V(2Eo z+svu8>Ku@5y=jgxM%T7<TlTr|Ec0obG*dqvSRT=M2V!K{5XfvOYn*i?X%onlFS?Zo zsnucba!vF+okU>nY_=GHWu$X_Cibby-yT)DX=sgrd16w0JmIQ~dY2$phQ<zi?2k+X zYMhAbJyte!R&iRHYZX439ADf4T5TLvD9b}Vfr5nyqpL7)Hp+piKbWB|$8E=qFWhHX zt^z1sH$d)HkpqVJtDdnDxx`iqy%D6B?+MF)C)!zy({JJN+S7DxTM~14P=ZXQ*qKgF z#P2Q#k_3R6>l`4QOm#jOp54#5?eGvj;Pl^0Phhpe>Mp4E%-G-PWldn28qh@@N7_#x zLRCGDRoKN|1IYZJ5GFx&lx(XP0ipOr4<OtOmE}R2BMCk6G3(l$yS<kiN^q#j9pvWk zZPlq&Q42JsR(iDiP@Zc?9ZGxZJ-8g+Q_ng-ybsBRs}>7VO0Y2sr7tyzx+Sv6H1xFG zoZR7r4WV{4W#iFe5Nt9V`-#t}9zN!M?OiHXCLTZ;LrpwzAx2}3m1bB=ya3IbLD-iV zeqpb-X=%^R3(5s|t=CP(9;QZfxe9Nyv92dA&P7XLy^Dtc<>?Q1k?G4263w<miY5ku z?F*_fJO&AFJK8X%r0N8MsqK6TF9)I&JKpKl;`>3pl{Sbq7pLx0E9|TgTX$sScU@mL zOU({EV20kZ#xA#1ry-WHIX4oIRCr97N<G&M^qG3j_}#Xn^SJm2h2-8dE1D%Av>s}w z43(}U+LwwS^QyZ|@_`$5m>x@|Af%tiBFJ7C*L`$*41~Pk)}ky&^j~&}OHi*@unuXw z{G4utMo-a(envBJJSUHze0YL0Bu#Xm`0KC1t!)PxPnQqNyjxA0pWlows9G1!Ck!Fu zaFbp*Qa(G@H^^Htt2dNfPipqrvRXIo9No5abA~x}!6)nZId4)etLBv-vjQr)eQ%y7 zoTD>ETVh$KC3v|yh{*>l%6rYS?l<;uo423JguKe*z%Q-&Sp$DZCiknPS9yiya)UD_ z=S>!1cX~&7R5C`GDfxj_eXKUtrV+JW7v33972?j}_Rzp*zs&tbc{~B$j68IW|C~pO zOOWJDUqqL37~`R~T8>$ZWVgFFj(iH?rNhO|W=UyVnr|fd@%)J}qX`So1F?b%j0|GM z$ImP@wMAQ>rPeaT&NcnAL{WF=uiiFjK`r@g;tJJcJoTy@3=9e?)MvMnmtkt9nHv-K zT-|Q&&7&ktF}SL_%HdMz<4L`kQL`Fk?SNk(F+6<QjM1AoK*}f)fU!)|l9=?eGeEs< zS1m|-6}}zcQ#s#rqhH-Y(Dk1~$9-k3iK&9~2I`xQXA-=JuR+O<REw#urr$JC!!2nr zwVt!<(+P1;rP2ZlJ!`8W-QW9Ydly$pA}`$4eIm_WH&SPCKYysX$mMhFcH*XG3SmVe zvz#$@T@!cF|MY$ctl;kH;kWDT9|>>lS(4qAZiiEmaURf#bJfJDmNA3wlqZrqEd7QK zBuX~&Yx!<ZBDD#CvMzxK(n1r6sU)0{%*yhttbH7KvUs#v96(h0lXqjSZH=#;FJ;pc zchI?)`w4C{!!cJ2dAH%)e$L2}s0(yd_dK9FSLtS5NIjlTTTf4-64+0{J%^f_g;Ok` z#gU;2nvyx{Xji#nM))!9ht!~OtK$Bym#91lfgzG}!gXrEnK=2cpNFUr4F<WJ(+TVB zR+{jXfH6tXVk*f8c`%XdLqMD{_V7}zP+YRfuqh0MJwDF%4i+IDLEkFbY>Z85oW$Iy zysAs9(0!@NRA{xtbLr+v0P$D;7_<AWYmu~-bQZp;UgvB5X<S$y-?eV3%fHBk2HN^v z$XpC34E-z818smVL}Y;5ErGYnw;A=~o>$HNvy2N|!h3VFwD^;yzoWe)Dm9J_3uU5F zT^BpctRCHp!gkK!3Qrb~{2Hf5xfivVI#ceg;fyno&00(7urylheFSa}6#urEaX{u` zmYloD8f{}p7d7#xT`mZ^B<Iv4;>!d;R=_glpn$#m+}MM3Q0hmZug7we8K5HZ<Yiri zvYU0HDX!OAiHrc4nlqMRfS^qMBR>K%XF!Bv@@l+4CD-vL)6kqmnwmQ3O9B@1u}nl2 zmUWYpvW5P6C0bEXKlTGOg!O#?p8@6nJ!$+uMZo`!B>$`Jlk-1{fSmt7w&VU=1l*>I zDGmZb8DwIUbZc|wf&+zP1|6E;mXwlAldSyb0B*yh6fTl)2L^-uFwb)T>~^@-c&$}G z&AbSFY<z5g_~e}!8!!Cx09%AKL{gCK(GbJa6!3`ZD(px={vM$IJvum`G%{xOFUZdK zGbG^<p<09w^^f{t4CF(B5iei{XM&ko672`Jyp{)w2Ld9aLqI`3IRL$VxQqCT3Kxt7 zMe8SE!u6+M6ody3>qKstAl2zkVB+;c^UU(=0pTLb28vHlA0PTB0&1F5p+Eo+0cRQ{ z^Dkrfkb+%;%}WRxC?>xEr0pfwixe651@p_wC>hr`VlV@mllHx#Zi5Rhfjt#DsTM&k zL0{RK1Ys}XzF4stk#YO`367s3{|95|(4-3!t=V$bDciPA*|u$*vTfV8ZQHhO<1O2E z^%r+=qX#|c`~x}3*pZoguV<}^uNU$RNKgX7aSRYDwBv9M;n{+Ug3M=uKB=+-ZPF>c z5j2hx3<~!Hnt=V?1%K&Y*+12ZFu&ZGFhK-4y8QQd8QSss(NDm@&1o#|3cD2$fc4vF z=!w@S-~whLz5EU2^sQL--A?uW6RYWfqVex;-E9#`r@@a$FCm;hSc&h{v7V@C25pXz zW@i;RCS%Uj{h%30Q3Ls0?e_ArT!Kk>_Iv#>S{d47uIq@bw{`sE_8HXO$}0!;ps|TR z5KJLOfrH<MgG0bYffdw&mSGGLzEpSnx4=KRp+3NiDDGZe1lxhE7lZ}A4O$hR2omaW z)<K~Kh;|BodVjg^=FpI!!0H186@aYD@nGei@-ECVEkDg-dc8@fVf07CR`H?wU;l># zZ0@#3w5PcJo%aLK&#UZe?1*H1{tpK@LDUV@%R@*66qo)V2zVgQFY+If`14C!1RDBn z6LibpQE9IYCU7O+c4qXUK8EiH-haP_o9*wnx+s*d3IlHcC4O|`E#!^(1p4&*_ZdL- z%O3Ju`S6SU{$E@5=;r8&d-|UH$1iwbmVx5753JdIN6{SAoOqti|37RH>SL@qQvoNv z>(NhKRZ+hg$#~z@obk~g%;O#GcaMRcEFEK63^Fuu{WoEn;Om~gigRF30WTQmYOM`C zXJqX4KM=5wF!nzX5JxMmPgtSZ=cl8N7&ox~{g~O8$N&g40?Z5LzTkM6o)qj3ya3Ju z^!cO47$_biR-ix`=nU%{xD|?Yq0S0z4-#lW6H1<<{O^VO89Ow{J+S|(et1z9%KFR? z`&XO}(TxP@rcd8UfbF^7B|t4qs3#w>kbVhjyoezzv;O3fS`$J(w~oX;YN|#aMaHu* zSm7#9_ifW^&x~5WeUi6<s*gFj^zmJF_^p`$bnWN8Jk3Mg^-ic#3Ljdy!A$igp2BbM zKsyXCc>_Ywj-5R5#X04RP%-WN1%(;6335VgiGN6x3!II56{b#WhfQY06=>G~;MSP7 z0=ArEV|x{^8WRP5)nqw8f>V<Re35o%N8tH>9Ze0E_D80cGxcWBYlW82$lmuqUZ{;i zcJHmkQ@zCA1B?tWB@SEqMnQ=H&&9A+D+mXoD|_DUU7hOB>se$r$vQ@Tj#a5ZbaeIo zj<ffyKeAXDk){T!DYDXM>!yZ|^5Yu=zgHjFlsti5H->d0Nn2(D1l6WKt$iO<bv9_@ zu?|!Edgrd^lS;?U<v|&0+(JHH{U0m2W?#U5PC<_x{ChX}A?BKJini8f+JZC=9@ZZ^ z*~EIqsIE>lA?U+W=8q<9R#M;2!N>Xa!MGQ|>df(ZuA;(rLf@&garY0E^1HbiD6_lP zER4VpZl1#!B~04`aOgqkMq}wpN#u#cvO?M&jV;u1<8!q1O<{#g&jI8^Yd`LG5Rvq7 z_MX<x>e(JlqQ)`xH(4*|qm}gDb{oQ&6zmf{Ya=M4z*o5V7i|2ik|J^UrI+Jsjc0?# zN-vC_9we3FD&nQG%j0Uq!U32P>@4Wv9WMZnS%fN1dLB>*m;}$1HHGrErFOWpxOdRO zHuIGzicC{d;YVds7C3CuIdAcn4Y$adeH4~H#sartn%M&eZx_k@ms>>{YR!juc<M|A zTV>02y#E|@P5t_GSdDXz9Ge4T2R%9L_TP9jhJaey&K+)BF6WWPvX0L?4A>|4#l&s` zHRlr1$*z0%8ClDTD#TFX(pEM#Xv=9??H+2V^SSHQtau*O?I;B*clS`GhvqEt2TM?Q z(>`z*f>I;`ng9V+5E%uNLyETgF0CqS_@IxI2BYy65$8@abM%2!7$S=^a}vRG4ejAd zi*8@DU%Li=F5^kg`jqR|$FXS9>BBpul?0+6VFK-iMETxjX4RvQjRPxW_j_^nxb1kw zdDue#M+S<TV2UYT90*9RurM=xr)<3hATa(fi>eW|ZEI%)U~<Y96xl$t@_xZ?AW}gD zzHti~c2e)kch4Ki&y2eGl*9l$2}#lSF9@P>P3_W)<*IAErkWSseMB_|D16`CQ9O#| zSoU312LrudO~*y=c235=N_f~tsL8M*$L&3Db(9rUEaVa1<=}U8R`q$1c!s{CTEJB5 z5^^60^Z-j;$<hdVVir;Knh2S}Q5{F*;bLBp389zgP?Nm@#^+o{sdFnI-`L{9MG)+; ziryKWW|0it#R_7-`P$)tL1XJFBoar%B?;KrXE#8gRouqxc1Xf0ak>0xoPw7Cs@DsL z)<^WD&K`DJAA$7GC3^~sjI=D3E|y0R^<q9ICGhhzvll|3s}9JAdSLUIi#mEFAhRzv zvR|4`qD~bF`6?G_`=}Ib_+3rbPtqyC0w@y1J%dT^VJ>Hq={bCbXhby(Ycmknqu56~ z4#0g#&f<I2NhY*c34i5__Zt3&NRgIJk`P8Mq#}T;tRVz~xtg<J;mH1aP$}9SieBa_ z4(wYQjNBK;jk!Rwnm)9fD^AZ&$G0abWUMfcX@lA)4v6}^0MS#F5HXrCAY1Z02q^(j z%WS%OM_qGDbDBF|doLUf6bKQ`?1*rkSEOh^3)!JTAoUOs-}!B~J8=9t6N9YX_hQA| zitIN_O%@)#iEUSiAsiCO*A#BVUZ7u?<&3)ShB5s?Hmf35FJ_i?fOh|f4MPkZ8e;3= zA*<wnfuRcO(2(*Y2oto?4B)5P_T{Qid-Vaua2d64Lf?M%G)pD)uIjRJPczxnkkPmg z7)E!RbS+~B=05f9)}q-6@1=+#jOsVvxzXKt821`wm+ojO;utb&*+;SnjoGrS(9<CZ z9p$HEzlP3YpHli<FRYRi$IO~4Ng&tiK-T5f6rdQwP*2&E|336IU4;kK^+{EHL<~Hr zj|HJlnpJ$AbE0U<<{fyFAWYqg1Mo~|vDP0NZ#<AKk!gkBObIb!?`Co`i_djH^E|#7 zLjTLq;ch&6QdSwbb0E7X80Xjf2`DORKXv5}%MrNv@hm;5Z?Nw;V1V%`oQyymK<~m0 z{>)BWfOGD@=Zom&l9G=W8EaPYQ)G4h#}<iMCK>YK&%C(yx&Njmdy><kt^I6xjwUM^ zt(jC(N6w}fTx^GLC^HI)HNB*e+I74izCrR|L`Ndrz^l5ie}%qr-iHQCt+IK;MtFYh z^=n6ZspebVDL6p?%*?w-UF^K1&f{M-kMWR#J@VoJ-gCwK>Z2RmQ@4ZnIIZjuw<GgQ zCm(@U1Aaty?X3Z3+~T!iUyGXWCI%Rq$Un~<{LUsV+Pz^u$}l;8cogD$_asOX4_JiL zxoD=_!dlBDR6Z7Xyiy%Gg-s)v?1ql63{~yYVJ7k>cY(OuTRrUSN(m>gV4{-gtxg6I z>*isQt|td8)!$tj$m*lzf*xDLD}=&{6aSZrKHMtYUMT_tDOR!jH=IUWXclvKjM;TG zzibw|_I}%pV)X1hd|~RktdVKlYF`)zF6?aLf-%(kgfrr*a1~1bg~I6?;>t){5TPyq zx`#rPu>Ul7cE@OD5D!6|4|fQ#?`D}TP{GBhaxAkp=3(2+Eh2*s!=URQx$l2;rIF8o z`RTCf?HdhkD}80O_ld;jGs!t2j_Ror$s>O;6Ud6<2dH&%jEoEbGdOiJaPmm?Xfs)^ zo!gCnzAGxyMw*`EZ&Mb*aib!*a1H||+)U=~@m{~_cxY<daV}X;w2Zc)=Nu(9QPeAF z9>pEO^*lo-E|4WUMxD3WhUZ%Ua4X?x0o=LCt-Bd~l>(Qt&~2ud|0$23XPsDH+d2h| zcMi0nl)`7`Yu@}hWx+~8{^@TtlIb+vH{&?_!XsGgoW?PprT5@AXu6UulQutq{9tFI zSaMrEMnp=CoN?2Ey@j4>m{7+tX?5{wcM&nYgT_~VjhRXb)~lBc;+^PY5FWS3v>%BC zzc`-ysEm%9knu6>Fyc!2u&=2d<{tR2=Ct^{e=Vf)APXt1OK8g^luP$j)Zz>7z+UQ_ zW`v*SY0+8AwNb*^l)vFUi|9OcB+3xS74PU=J-Z%yFk~V~5~+-GK-quWSpcHuHk@tp zyGtj|MW?s-|A^)8=(g{4k&-=p*a0ouf8pL^mf4m_dv#7Jwvo0NmZ4=uUno0Y>CdYd z8?#xP9kXEnvJy3V_qyHe)B!vzi>QuLriB_)wm~QCOO3PT-gqnd6diXX>Z>$iKP>V* z!7JV3Ct3TBJa>Xq$!5IEzj>qZCufIzxBDd#TbBJ$Z9zJv3oWV6x1|>q+-mkFNvuA% zA8s8tF>VMAC@u;wWj$GvTi9<1Sz82}Z42#Qy}2|@aZnHDzgD|P^U)j81@Ilj#_#}c zRgxB=q&KjERo32~LmY=fv@z`*CGoO?kk?Re@L~LXGpHnkRKO&QAh_E2?{l;)_IP{# zrUy-kj{3|L<4{#~_05d+$6d2$VFQNmI(LOqM%_7$UuH(fFcU+p=>|`E)i^w(<Y8pi z>o1yvA=HRN+$d^XwWDm5>!*klOr7aIsPjAUZWi_(goN8B*#&n(uFa0KSUUUh?aHOk zR8U_@`<>|oDP!lF4XBPpj3;K0>e8{7FjPob@K}>X3{%bm7qrt(on+o(SA9Rj8=AGF zih0;G96hp|ryQjCd~!Qvu0tC<qtcC)hhiNhtwcVhoVK$2S~<gF?MGrg!nKJf`m{Y) z2I|uH7NlBR=X6G2xTa2DczbBB8L>noNI>$kG(wg{i&8+YifhV6`}96?vpcu^UJSDk zW&Yj6SPq$`X6eQ83}~l@xNvl5884x+UUo$HRuCW&Rm8P!G2Z1MM!NiQKM7YV&3w*| zEaW*^^Cb~*mr-xF@S>PVzq!_)SsEE3aF2-G3`sW;Ji0Gw8BTy{;A(20uoE&=VW=VC zMKt_ych`FNO?0%26e(9$d;IWSJAka7MEFSmc*&VM2WOQu`S0CCu8t4>hFN4WP*m5# z{47{?YE;L{f4~6A+Q-n^NnE9fS4XwzIzfwUIR}}RC^mjw|LluS^R1}gU^Ce$@a=Je z)PG2QCrZaDr&{kBO_&qQ-1`i+3W?piae%MKBS$XO*4d1<CYEw~T(-{m9w&sC>lF>a zy4&I3(s|0+If`&TQd=PB?yu46X2PcGjo@3wM^`^7<GhPaskHxl*q@`vfm(zyJd~q< zU~fH=^683Yv*ACV_14?QU=0CVZkmj6lt)p)xjVdT<V3n$jiB=oQ|I>QJK7<PvHHqr zFEk!@xrr!M@#8-mIqhXsE1)Y=+-jhv;@SsEdRMBcYb$?ftvF1pUmkYsWn>hdh+FO@ zcj5^m^O*)NCv{nd6Dugy2N0W6pg~Q)xzxbMIIy2*l8q0*F=G7QzFkKn9}y;*@c$KZ z@mI3R5tmPu7B3AL>A5~P_{KlovtDb4j0I=u*t=dqtC~Zox_fF3juaQ;kBT?hSW9R@ zK3x`$Bn{?0z)rkj`GgL>tc)u2uAy2P;BPy+eKD<jpMGkw>CHgL;)ajTIX`&RSSe!n zTGSZB{d}}84P%b&lH9(1*r4GsvZs#B4;}cs>jjIWg1jepRF;?ZyIh<H^kRG&g`iY1 zwI-;!uqZ)x(jvhiUXbG#cru(ug)N+$DOLLjgQH%#VA*tiMmNQ{ST3(<Y&C<~PruvT zyc1E}gaDgZX`qTsUSgkr3_FyR;3*bTug<;woda2^n~;{Lo|Kf^I_hXnK-*|IHYJ8x z^#|KJ-MFWBY<3EB()i$W2Mud~UWt>A--%#iSFF#miu9`o!ce>=x<FHq`4dc{?A&7Z zF&4^cAGP!-DSx-Y_z#4z-0XlUdMzc~_56CfxC)_I;B_>#q=PO~DYNSgC<nS_<=?Aw z3U~7g3Fm)S)AGAbTO-rim@Is1n)`0P&JroD%aOlNa*KpvHo~fa#W|WC_l~pNQl9EC z3(FLIn}5Q(#!7eyjO$n{wMvx~k_>uDcrD%C8@}5*wK2w<Uy~>^PQG`@qRBAlCSK^) z!8H_r3yY+YHosKws1IxKZD9*eLhL0BrZ7&Z2%_(}3tE&@IdB*8XzW_fmi3c!ks$eL z4k`TYp4a3t)~p?zpknzGQq&Ny6CtZ9a{0!K9<(hb7LYr|JrD&J5%$W8<UGBqk#PlQ zo{x$BSbu1M<4J+sjdo}@{?L}X0ZD=@>{G4BIKlGvFtb=|K7o0j?TZb{3`KG!s$`FQ zcyRf>Kw-0Sk8D}}B$*)=X?Yxl4>#n5z-W&LSwCvi0k3@0+azm+gmCeevR=gU|K)Ay z6Sfa{{7>}`N1KMBSB^or5pG>5pAq|DIGCApOmH#C4KFB&#^>Cflat0MFLzA;Sj)|d zXX7$*HjZ8M&AMI!Eo}d7gb>&x^p`QqDyXKa{~k22VT}3B6|O~f*a(}}2ygj;yHIjd z1b2)VMVSOv*tHy$w2WTrCebk0r4qj9<q`|-lH3aO4V8TD+RXv={YM<Zbit|7c(FF= zV3Osmb#q&cgxzKqK1bqTxN@LH@5yjmVTKlx<^X(<agKFb<<-BL1@*Y+%_^m?`ygw# zqC2yWEG1-ZBSAgo&5!m>9&tc0tOo%5{>#{lpsd)GCD18j7yy*3n=n;r(7joP624)X z7@b4o$(}s7aR4gM0-KeDj$JWF5Jfp*$>QLdacq0y7KJc2(Cs2u$a5|(mmI7KM<+H~ z3tMr@Xx3(~en&*yWfRL2ZeJP`<Rl-mB<I*P<aY1<WusdZ(roB2sPBU{cK*D8aYz{n z>9QaXOSh$#3b`Z&bK`>aGBr6LAR6?f`OKc`p+<ng=GK68%@fj4-J*wn7L4s#mZ7AW zV7K2Xt4!XJbosYU{8JC_pZ9*gu@G5z*%n=@Tuh**&1}HACCzu?&}0Pv=Gs!|+{Y}7 zT6X2mhuY9%hwH0kqk2oh;2e`{bu<MX<Z$#h00>~~qFy)8ZT@KfCq-w^5L=Cgs;%~< zxw!dSH?3I23A}Rd=Zr3#<<{xnVa+BtnU1L=HB0SESoH@{U0#M}d`$6w|7|95v{42b zz<pQjwE`(-d9An^M9eE#&w)5KV3&PQXR?T&=%h{C-~HqQjPgU$I2U~qPZ8p_@!Zz! zRz!!U&+l=%>(i<XPWtNoWAkEvWE0v1^@u-ma@}rZV<uqQYYf^W5I#>o+MHovojix` zbFsS7(X0!H>9k=G&lnNOY5r1mTtD%8J)rX!_9l?UbtRUsO|quubXN&xP19Kwml=6W zQ#8ijWhMmplg4Sz*3)(gTTc*0oUEESBFY5+tmGm#nIo#AE7{g?k2tFhcGcEe&@hDv zQ6F#mf+4oo`F0OH-*M0PwyKR8^sKmD|M8)8$O`<5C_^jZy`JFKPl*Cj0WZ(|`|0VA z;<|qB{yWw+HjKV5Ke>VA2G1Fa2d-6o*RL!$)6jlC-F14HC@;M1pcRfD@Cm~7+(__c z*^u0U0efWF>iD#Zz#ozbZ7xqRQ9Ie=bb<S-<L1;U&glupg#uh1%LOktuT3VjHtIoX zi|kC&Jelm=6v($|V2Z>Gkmrp)3~X_gwq?~1nWc)jaa=i4{@WmFnaa#zB-)&n5`Cnt zAHh-{91PM%{&~O4Ae5H|s*Ft-F%elMLF*)#T)0eOsro~{@U8`_v^BQ`AZ87pJ4(8Z z+cHD;nDilO-+3G*2jzU(xb2>0hb#i@RVnn+8Rqu6)VWZIYn2%fVPQWL(YmFknVDB# zRfQ<a+HLhabeR9d=#xXRuCxr7W3R%;IZn8@MI#7qDL$SlZ0uK<Ac7>)G$98<5wY{u zR#jyM0UpI{U92}_g!*VPoKrRB8{zF!74A+`(au}LXHOU|7skAK-&X7NN$hwML{-X` zn`#c2A0jL5{UY>>_0jm5?v~jqGiAkP)4HwMk{REzr1Q>cPnKYmJo!HG^EfqWK8ysY z3r^Xiw?Lmn#Eu$YA8kt6DreScOQ4AkbY>zxD3rlWJT-8&*Tgxzv>QHAtM4g)N&c7; zqistIsN7TLx&=if|Fyd?AkbV~py}yNxnrt)b;Hv|`sgb?A(x)7;BZtp`U^!}`!|D& z-B<jz(0W`>MJHp@GOsR`%pKd|K-n7gBT0IGuqw%-?eiJJRQ&J$EC%pt5&C|b8PHLw zu<xP7M`+iW6%_>>$sDm5-ru$Cx=9#^n=gvswYgWjfA}*LZ_Y{OtD6{TQa6>YRV&EM zNHcy*pBX#3J+{%(Q#x}3K?%wO=;F1@yfu(q_f#Z<B<Tug7-NMx4OJ1GFEvb@FBniA z1@WER7<}mfLZTa0dG6&Feive@_id-7f797UYKzNwg0IfZachgn2l6xHmue5C;T98) zT-ur!VjtBXo_^yJHtx^Mn4UsBxm*D#ms2j?ptsM3xpy1%&*t(aHTXJyRO`3ApAaQ5 z|G0YZJsSZhlyBCcm(n->VO5<gQgWXmU~@|E)rZ`G_~-mUaX}vLo%NAAYqQ0O{URIc zp$gb|BbZ{)Juack5$1DMG*g5!36yr7$~VOjq=rx4NO191<qxA!8Zu?0&UGlPZOz!% zu~F|hUb~%jlid~DXI)J~`Y6C(I6XzoIQ$zfxP+a^C_M6#oVu*Rvx+?*4+RG?s|YW= zbjxIq6=v*aw{z<Q%EKmeK~-ut=dQ4`?eFbr>DIpi3E3C^2IV)s9#nD^Y1J!Bsi<kd zw;x`akqdY`J9U9%YLm#hGRnjf8AYpetwt83_>)h*GAIwa7w8YjS0Ei1(%_Z1Dr8ZH z3f}IFW7PoPSixq$PhzpANYW|<lMk7=rE#Lbj_-^wFN|v9pDJ<S(&wvv0%M&VFI$FE zDR!_d3E4&tDg1}O!r0X)oL`Sbf;Md<P~a9;?SR+GZ4Yv~J<`jdt{I&7YHB=yjHQwC zm9c!A?qY3_hl~nOGDDiA*zx;U#ag5`*@h2~aco6>2r;)Tp}>ovEZ{LWz>RTIhU*t} z*sFl`|JnFsW%z$-{@57*x7Ei)$jHXP@V_4G{~JwYWaD6A`~Qppt!_0@$=O*XgC5u+ zI~(2kgSfq;6WHWnhO!;h_1}VYb8}nUt7X6C-1&ayXuHkp1;m*}o2jm3vR0Yau%d%U z6ha5ZN8}(WY|o+(_YaOw!^OANGdj8^HZ`S~C_rR#g8pFl4Ja#wbAZ4JqPw;hh7uC8 z3xJw~AcA9qYG?w}0{Z;I%7DVxH@Y~r(ldg9mMtf-S)84peofvf!1Rw^_<8-@xHQu@ zKq!BIzQDA$HnxCl1pSD9>ewrR0)XN<5%nz%;K0HuDJ>-@q=CxGj#hw>1+?>v3Rnde zHpVvxF$t{<V4Gb)7J+20ae-HVb%CO<tz~I{sAeMW=~LrT`Vsex5m;K^y5P<%VVi%) zL=oyCxi&R8IKRIkH8_B$apC^k&I_m!RAU`mn>*`Ec&~0}`9?4J3h(+yZ2jx`8(g{B z34{}iTWdWC$ghbyGV(WzVtgC%N#2$ss?XLx=Nuq`!fkZwC-sqbOFykgKR!RW`UeQ4 zGw^4^1Pm-)gJVM*r}KN}8)JHR;XsciJBQYK<|hi6w;##e^vv84&e`z;<`LsF@8(NA z$N#s+Q`pPPs?G1Z^;3QM_dp-m5kxDCX|SpOXT}2dBWr7V5Iy%iPcWg8wFR`E;djgS z!1|Zphd&_p*AnrWpIP`ZEw~^er=|s`AIuzjj?@nFBMVvJ+pmo2&@XTN7Y_Ni4eAR( zeEZAq@T*+(dyV+}%RBe`=kJZR&0jn7M>n7!p8=qsT?SVm&3=Bj=$3-RUz+Xt(ZS8@ z-}-%iP*(q6^7r2W5^$!kEm$J$roKQ1W~SdQ^L<j=eP|ZNW+1FAP#L(IU)KvgS5|G5 z{GyhSzjt+ozn0|w0U;Uh{N9x(=%Z?_zs)~eeL4c#Nx!7O>cxJFW{JoPsY-}NpL5*L zdWw;LEszzR8^2^P{89-`%<p<pehk4O*Z+X=Vg2L@L1}O({15Gf=+M#YeuZ282I{}o zv}O^H%=e+^-?f>Tr~06O2>^aI&cC2y)2r*VM|qlxz*w7^UwC!DCU0XlS663m>MMRZ zZ++mubI*Mccu>yZ*h6)+n^=!ujWUw*;4A-~m)NL_C)XwcScpxGwJP+ZceM?d_u^n{ zKYDieDtKe-^rIhh7j2FfKR{Y3FXqi?Yw3j)i0%=xd&0ugQGty@tJ5Oh8}m6DNlC7S zi2J|UDO*8HCx$A5t7sakOSB$A6uH(W&Ou$i#ka)o>BkXLzk2Z(Ho4lU(T|u-pitc; zKTk0%zppoe6@Dfbj(Hcjm8LlPG&DHz0i*E49CxWiAV+5V?ke^lf6w=c^TwefRDUht z0r%8-<b76H;@)L!M9U|CRBYJ$(`l>5;Sz})#fOOt$dpQBqo!EYlMiJ2NcKgU7d8ex zd7vly+kNak%H9QQ_BC$93tKF~1+#v(tb2!Q0+IW!)T^%0rrQm+NN4&`hbsugglCu+ zynk&8QrJ#;+-;&-X7A2*f$Bq@m=R^~gJ|2SjnF&WlU%h8Soi^MpdFDK_)?=}mN;!Z zU5$q3CmGZxhPhCy=f=0^`+=zbxw!ybZ%#kLbRd6?&)6Vo_oq%o&~#k=B^=@kst7eI z$-KU;EFaIz>8FTbP(ub2bB=Da3Hhd{l+m{hW;6ScbG4zrZLSWE<3KsFR3K6G#!n6f zkSvxe^@LU%dD_tG!Y+J$PACv)Gsr|;fJ!7;ca&zT=wAsLFvsr<jEl~2Jq#v9a*Yli zTqB*)DB|sN4F09dzu0P97_z4CLup%XFIlf><%{2#KDfS?U7?x^yJzm6*jBN(IX03o zFr~(WvCB!sd)rFB#Q<5d`_bU?p~mljiC__(47MjaS0VoLHnD5&8hQbvNOGiP`DA&2 z_KOteZ+mR2S;zz2){=}hC+bLxt^D?MnrQz6d)Ty_)C0F%Usi9|5zUJuH~ONCw=G9O z5e~a>5n~CVI*wbRsi@1hRK|6y1r@Yk&dH9wu}hIw&FHy86Vi+Lnj4vW!yobD7~|Du zfm8Hz*mdvs%EZ3sDhjCV=nzkQ;b)yd<Sq0v)*~_ric<2FMZ0o;p3oE)y&p&YLVY>~ zLqx0EU`nVMshkhb-t<$EUr9)4Gq~G9IO9KcQ}*-8rbq;vl~^h|sVY!9JdKBRFx7in zyRJ3G`$*SWQo9pLN)%P*`t<cHWpx?*RdqG9Ba*(tBX8|--qmlI;!MCAwV%QETQsZK zhm@3(`jDn@?^$H8B&R=Sw74;koobcZNQyTMP<`C?w-`e@m(!-sDL-=JixvA*hp*Hq zU9^#^`ZC9#g!jWa9*MZM6isp>DE%Ivg!P~R>MlcywqLEvaf}5axo1&&)YzI`ARGba z(X>I@QxvCvPu`9e!o8$#(yTY&EZcl@<Jw_|SwR6pIY{ta{=_*oK0<@KcR~y}ovjF@ z6MrL#@~w9-K-~Y!7I~j|9~ND-Z%tl<C;hW`7Hze_T*o8_84@f_Z>SELg;ghKfVzW0 z3lQDS)6t7D`t}u&rLkDyiWV5JlO@1`KiXiN26qa7m$46Uc*oG3<ommF^YI|}9NoR( zdZd6<Um$Hy_%^R+u4el0py>kVznN>THkZU>VEpLu9(<w-FMQ_hX)+^?;~HF<OIl08 z8pR>yHl9o@AE&CdV^QGEViOrHc_+b8D1!S`1>3<v3M`zmgb+AL$kYM;V#*#Y(y=O7 zIF)f{W0^`7=$r!}`!P;_=<C>!0@CjR>glZXm%41cz9lGZNPnk0=!WRFbj)XHbqvf~ zUR?*CJDh~b;6`kGoxr10;l3?q46N|IT4-}dfp(k%nI}TD1MwzUBmN@8Inf^Atdkg> zL}0TqZNwbdanNPKGzWz`JAp$*KxD<^$v{30a%sP+sN<9M9eiKrOL|E86jq*RilU6| zA2<V8rbZ~2l&@Ori-lOpu2ZyoLbukoD}=Wdc=$H4mPP*V_TaDb1-e$uYru}N_U#XC z2abEtr*+lG{^KcNZJwgh>5^4~^TCt=JTRDVl5_0v+6(kl4XV!3byKoblAsU?X-H4= zu4uR5iWGvE5ZhTCF%@L}L}o`uVwhQtgrIh>`I+u+IR>hr*<~JM#Ds#r@i_|`@wFt2 z_TM$CLaiN{_z7+~tW&r4q-RYZ9Ql<Dkky^$qsC&p{d!Pw!DGoP?t^aBF&oPO5=!N) z5fnR4NGousTftH?Ib0V#B6$3esvnzmeSR0bHP(=IJ1Blr-wrLMoe$TPilt421(Rc% zyY`Hg!tyf=4lXt85Pu+Kh>>^%F>Qc>>yLtaWP#lCI!lq1`11sxe42sbnV_CnQWXe@ ziUr@Lc=nO)MEUQPATUk9RELQe6b$h)dc8C<bN6YpjGnlj84X#V0RPGgMdGQ?6@=^w zQ9PT6O(XLCBfXcXSBbK{5rUL0vaty56m`5HHPJ2hkR!qY>7=_U)(&}{Zn!8Gu26_g zvO%t;eTe>2M#mF7J_(Zx9REcNC}r1u_`?wBCqSyi)OnFqful7mk=}*E4RNG)K4Xmx zuLy0bYASi|xkA~BNjnp5__rKR&lReiPi0MGuVm5S+WDHbhxHq^l-i0u1x<Art$&<$ z*T8+xv8JLo^F@V=a6;P3C*X-+vkobvQN92C%!A0)3a3!R8yqkW*ChV4+(J0)h%HR% zNLBOK@C?D-=2fk{LjX3Hf!r0*N-XCd=HD6gHt`#(?gk}dKwN85LlZ<ExU#lx261vX zBLJOVf*=`78-%f6aOlKUdD}FywdUyT8J;zFQi9wRC3z@7g=bakYY0SNboMf9^Mi$1 z>*1L_7y9{C^!X*Yag@o+eJOq9MlV@55YbvwU$t!3B^P)eEETy=ZC*F+yhcR@mm>5( zf2PD(=>(zwgCkfNsQOn3{5jkO^KtKDs%Aa6#u857h#g-Esy^Ya7D49@d?k1>FE)(I zbz^R-eop%4J&x%e^7wU|w2d#=v`{$MR&ejuvN{q$U_%@k=;60EA#^Bx@j%WOXjm2N z!YBJql9ha%YQ0!7kHLAla>4|ruh5Z(Ej3qPygUB}-FM_A$$FT{Agz?KNFdfs^x)$3 z18RKc=5W9wj8wFdo5g5ah;#!R^lH(3y~p8+(sjn78%UC*F8CCndl*oA5fOyQc66wI zx1wEgO>{5&tJF_epMge^+AnK*)Vs4pQDmlCMd@XlYMf;oR#|^<;Vcuz+sclh`$CmQ zCuQoz`uDIW#0O%FC&|$H9ceL{r3Om-d4o0RQlcug>KVl`O?5nzv~)L<lWwyQ9(_8q zQ4~YuI{$$UU%ePXG85@sP+pZN8;A%lg#P7D9Foj0?X#6pkAJ1|d`wpAH&%C&*5!UJ z2kEgW<lON3sW+l*^ygn}M4`$~@MjBeI(1;-tXP&?JF!!)7E<0b_^i*amXYlkKqNL~ zt}jvY8ZRw|UEWXziSbG{7ytdAIs|lo;wrzQ^sxssf5Mp-Vo1{&BMZvq1tgbj$J(7; zlLqC>zz!TL<cYdh$#-#NeNCRgeOxKcODiV04;*nUtZtSzU2Z27PVG4GdAVq?(chib zmEr?}!=P1H8xwhz@p*7y;09@%yLTrpl^+0KUX($sI;cpOPFhjn1-4rrd7<R`DXV0| z1eCh}(aJ<kvKWg@D~Hxrd>3jb-uG4sf&Q-LUf~L0Ta!ZLl@x#lcjAS(QK|{(^$rd3 zoE-mpOPw^=LEq&!w5*7pP7kE{T}>a!FN~+B!QFjhJ!YVG<=ypT=QvKYwN)*xQ2--B zKrQR91?N!6g_={90^5=&K9oYZzjWJ7uyLsjMnke@4z6iNfQUVFNoCjCOnx?R1Q?ex zPEB;#w*<ux9J!@r6Je9@1-@T2H1s|v-mYTAR4FonWT=8w^|RCRE{oYx8#W527()i~ zyTxA`UfyPO55VMN_E*q$$t3+7tP(dIlRr)j++W_at}QwuH2c(Rq=@$^e^_4o%l{Jo zeAKC&e2c?_T6z|KiE<+)Hag_fGqre<#-7^nNX*Oj_#IA)dv4_z(U;{?LxX(j*JI~f zinui6L}&)dc2OnVFOhhzg(6xF!uy=%MaLS#%Mio}L2IgKZ;qvbpdb+FW+WMWMUa<y zqwJ%94j6bUs@48eju+T(21aBImQk=Oeu#7G^pAM=4y?1A>`)?<q`Y+{<@94x%x#Q( zu|<@LGw}6H4W>kM`}zvhUAQtR-<o_nPIX2zPNsr^9GD6cFGCq4v68yssMYo%(7?(p zgwN;Q=Ar#_;5dps)w|x)Z!zy>PbV}5&-{o#qwtN+f%IH;g$-60B^_ifXSRuTRf8Nf z_J!rhq5p{cT8;1q1VK(X)S~#asB}p;_{3Y@!IfgYSE%zyVu88^m`n3v2A(P*e$x__ zLOsqO>s3_uPo>05F^2*7;{ixtbV73FcYbkAciFs!+UDL&cIfNm9TQ5(6_<RIT7R9o zm282x&uNBX@nT4G+SINx4I(aZporB?wF?#AIb*r0#qd3P$hEl97Sj{pd7;_!kq=uc z`4G3bs3hDxl<>fUf(2YA|BFOwy?){L)~BoFzYF^#&o+HU!DmG!D+4c`?Fc-rMcTQ- zgRF(-*U*$tHSJVgyz{CZIx;=0b@zi@Ov(3%Z-k+x&~#L}a0TidhXIQReowq_zNpDN zc-_r-7dVkUGMLH&K6p|;Bw9}#nVj3@;Zm%KYEsEg_!vcBSWmHWOEZz-p9Pb#r}FQ! zZiM_ZIoUDs98@H3o`gy_I<kwTuOwyWIBiKqvWYhn8N=f*tDy4y7?N&{$Q3nxP`cha zNd}a=@?<lV%ca*V0UHwQD)#M0#`wbW^jc+y1BGmJl6+#_Dx5^<8-=|d1+9kqGpPKH z_{Hr!1$FPUs14COS=dg$|K>6V&K1Cg?jm-oBB<+$Cwq@}1%x#wF+~ZR#V=F!^O{PA zI|s$X48MAAWY7K*%7G<}D*PLiPAJ##kb39&ex5ZCz2SyyP(cgVQo7xClg{FR#OTD& zHd9p@+=`}rOP72s$vuZ_fwZ|gMf%4UlUAb1SjIzU*~%QcKUYrCJg)euUdLe<+x=ar z?P0bteyj`~mN2@;MCS9@gLQLhWS(~@B_u9Z0}VCdO|BlU29!Q-o2i)5V36|iijURo zYjp3gQ-zhRa+a&Y5M@0V7pJ{<FT1W7gYcN;z3Q>dm5bVn8S<#`ozms=Nn!aYDBb^4 zRQi^lR7+9&BeNb(x&9;O3Piypthraoz%FaTq`@noeN;}^aEQ~vh;FsyPdaGoCm{ll z-w6Z4?hu=2(<_=q4)eAx!x7gxjc4rD=EpBW{(es{c`aLixq%_~ChfD!@Dr>?YV~G- zs4*^ILr%F<8~XfwA9_LRo{LepyreD2Z;g}FEMA~6P<isxNMumqWwt1Lwi(22ab&a+ zfFgu-BNAhG4E}_Zgi0CPR4#1Rt{tL;rt{|QZ~feL0<O45t3@K0u)Kax@M$xzCzG#s zHP;%VW!a)3rp1<g9aRC1Q&I-5p~I`X?}{6K;GcO32<Ry`M+_oou>kb!T7=4Out;Cz zgRs!(WlZD-Dd%jY=igK@#vv{rk8Mb-LKqd(8~0cBp^r4>n{0;Y`FDkwp57^4GE&l) z>h;dB(yC7C)U*-tBXvkyG;w%+c@Ni)6Pu$)1!WEpGEm9p41fO1Oyw2TbbB5uHsB^d zCUedKcQ($EMXZub$!CZhXM&pfwML}V&0MhYj0rQN#ePNorSe%t-47_X?%_z@g2~?y z^|EK6c7sacD;Ma`M)Dq##A7?jRCRCMAHioJ@!IeWSe(#L6h&RHo6gaWYjX@;oRLSF zW?OJ3#i0=){J@mxnUl0=<*Yy}T2TuZmg(=5eJkE`P)M0!7k+h@m~D#D|AYA`ACrrf zN$L2U=`TXD1Q(7^JbPe6q2E|>XU$s1FET25_rkXHjV-))ealh7);iz~P-}D7j>=Q& zkL+wfIO5oeeUNWxYWj1pI3&{&F(qtef5BD{FXi_GX1K`nwyoFKcT*s>CTs8yi=oPM zpw6vIadP)#6B6ob<KB$(mr)MiYZhD!yp*Ab_9oQ0J<D^Y-Ol<Gv8x$RPJ1PFC@+*P z<FSt`BD+%d&X<RMPzb?KM2_@M6^7;N7)SmfS9TqMM?G<BT<cSZ-(UH!sp!i)X4M+8 zkNrORUTCIdpJ#<w_RqF)r!O7%5_PF<FIR?y{EL|8LvfL>8xHL6V!S{cKq6q`llyCt zB81G0JMGb%bdV)o-BKqb(Wu~k<z)eE7SC+u9`cp>K(_k=<Y$fuokEK4l!N;)FvZFt zx>Z#7>5)liH}{K%h(=h284{s-U?FM=X)$%As(Z5H*h=iXyBVd;0VfFY>dhe`0#5`4 zGci2yZXjM=Fy~pCv2km~zz7@pk&?gWO^|92jmLBJEV|(wfmWQnLyti*1u<0S-PM7o zp&+xV<7T=|c~OZR4$-d16~!JZ2v&;HG+9J9F9kjZGHf~UqJyBUWv?<(b1r(TO;a;P zX$sdtT1$kf)`i1JR<3Pex~r#mFVq#EGIiQX%_TrQf`2!NaJbfnY0DBHWz2@dXV1~+ z;^W2{Q~9IYix1*9q7mwS7plh?t#ZXR`J<73h%DB~R;0BBFyOdh_sL=zf@EalMUJ>v z32mdF#;E9fcR{8uSu3}L7<}SD5<~Bl;x<fdWRAQyVDSh`#gz@GJRMFcMU<NT{ZEtX zq>t=<Q4t@^K!*Uq+Elx@?Q^DOjRShurI@?@6vuDl(=*b$V&3zK+e^bl2xlJmE$f(( zF+dQ*bkj#jgU>C$uFESg=N<YC2|bNbw$DekeAoNg;Z?=G|FxbTi4(Mt*K^GlZv#w+ zn~1U8)-i?cN05wg=UhdEa=JJlSo@xj4x7^)T-707Vl`?fWZ7M90BVF}`*VS6P=|l1 z`n;*N-GEyF{q-yG9~MG{3Q^GOP}RJ@SE#0CxF%FJ7WvE^@Q-!(B*;0{kD5$9KL!iW z!J~XyKsr86y<xWJCL{pBf`m9*^iI-p;5I+`ib|54oVWPeAQ8BgK(gCI^_Y?Rs!K9G zpNp?P9JHdakwmGKXaVUPFvIyt)<P@Y%2yX5hNj|+C5XUGQa5iIW_aJC9ODTw;^EAw zIwHU7<>MPVQ1^?d8qi$9?jByW##5;jLld5@(Mlu4W@2VVON=15r5-6CbGs&Wc8*Vn zm#84A1|!lllR0P6QfGSs!M&KS_HT~tA6k(}MWU2X#ip5=TH5r5z?~p;S+S8sQK@`! zE;3k!Wph+n&Kq<NHynBO+U!T_BXYQ>Cub4SS`k}4#n&Za?_x18%E)M$KTKT3%PN{! z#)!tr97<b_3hetiQg2>obzO8{0vlg6haHKKlo*MO0r1Z&R+71l5*t;^kp7_K1F+M5 zI3h>FOF&g|4ox;aV$$-k*Non(cbEy;1p||uN~_dN&V_9qu3U>JJVog!m|8EZc){#f z1;i_X!E1(^yFi5oPlpKX1I__Z3+Ep;)i)@eYG}=hwE3J}G~#Y%yd=+nzimB4j0*(R z&u-w_*GMnYXYvdcv31~IgiE8#e}%M1Fe_mUyFw7BKSajQI%F8Z3kKXqy$L3Cskmit z-_H~#BWt=g5)7xllEAHqO7x%50&q`53hz3I8=5fxJl?+@Sr=RO>rJt#6`kG=ad>k$ ziDww4fUPY?IhG_>3q##pj(9Z|Xjml^=65pj8d#8nB9#qJnr_T?Mu*gOdnDpWm9Es( zF}h33a$I(~KzuDZgCDS=toHJSPWry*ggte#4~=QDSW+~z&mn%M1NKjSwekc+O+<>z zigmRoV{(#i)prRL3%3{(N3J%_KS38{2665c6s-e84}a=y%P5*gCQi9CBC0b*J-<j? zTpz~r2vbx&%=>B+DfP16P|Z}cyMcF5;ijG<&<=|*?|smW?dUG#(rd|N`$CK8Enp=P z!vmleWe<O-+fiZ<nOL!X_!CrX*clT^RLNHQc5QMWHb_U7Il2d4*R73w{76rk1-!c@ zTvziQqZZmkZ)s^v#dIb*VQP!?d1Fsmqwn9!P5JsnpoP}p;y=+&jWT-h0L7U1|8fA> zO)_@{G$H<yl|D_4gLYLD-r017A~8;n8V(5$ge1V?6pFl)?bt{L)=*tmex5@V{cxZ+ z(LV;jHRey3odbT;Y|&yYx5ukVe>zG@!F|@K&4E6y4qF<mU&IUH^~B%@INQt&Q44cA zq|k1R-SSMOuiBvmE;xt=nP2-0FjJX|%C^=H5nuyj6oAn_ICKjn*{Z6IwM?Yr_cd1B zQw8~a8D=rGXBKxp%iC|)eeCZhby%g#hj^4z$1*f$|L#$s&|a7ISLuQ4{w0%c;|5I? z2_CAEBMU`n+<@x><lgZ)wH7oWH_y$!udgR3qgJ7ckabcyqnjifH;9qm2#XAz@%z~z zL;>D4)2P%+JQ{^AA?FEcxL4sO^V=$iU(@sT=xgnk;8?+8i^MRKvULy!jq*>4)!Dxd zN*y?PXeD!`p6^Q0t2kZdj5={{yvbPDP&3lGAOIwI$L}aG{-v4A67&mr=(TU2G!(Uv zvof?4=_PVJDili-y5|K0<EW3t;6XG`TTX}VWp5KHMCSkgL>|c2RaNX1qw|EAejaTX zzkD_)K_d57T3`nuSB#jfLy<ey^M@?cKypYv|D$eCMY|~}7{)ptK;ZQbw;OUGQNC|x z!xt+(Ke4|s^41c0|CYJjY2yZVqL66HbN?!lSI0P;+&~Twln%A>f*5#1z@{;{V_F!^ zTALjY<h7q|yzZN*amSk}7F3Xga6yT&t%$Yahc8w)eSR)7X8E*p2@x@Bp$)FMHT9P? zKi&(Lf;SM-HJNBjC~@KE1a03Wmf+&j_buF#GgSQTaJ&?MolPqUSJ6x0H^=>4RuRzM z;SdMF+V|)ZK<C|)9!evC|LNo<Oq+x0dnT!)99i)rmRj5=f2#P=Z9gVbpy0Ua%biXy ztvKq-`#hvKE%S3xv2h%^sbBAp1ShX>1qHJv>BhA#&^Do|7Lb1rsPJ2*G~R~yXMghH z2|F2H`bLI++&2U%%2z&9k!h_$;x|v%Y~I9-r9EJ?lK?_9<L;(4yZsex#NeuT5#7nO zL>R&y{uZnW$G~f#xw6#4sc`C;S&FCmr^&U;QPk$hE?CEj<@n7c7p$EV#zPX+<2@%2 zsDSjGJ*|j{Ru!&!j(#kozn^MMDNg=;DU%x2qH+nv7(h@9^1;1KSd9Jk)FK7d%lUIF zZgc&oAqbKI*8YYHa<3{|Ah$~eUh9wTbi_zYKY_9uXo9SG$*Jw>*Svw<3GHJae6?4Y zQJh|0IMp+ejd;DCCRxqK&VX=4J7`jg7N|GR(#)E)N|NKY(#{`P=h64#Z=vjU+Uj{4 z&nd3OF!o#oZ=64Lt={2Z#w}r&sOtp1`0A-?m10D0tcjh)r%~VTuzj5Ho|?LaZ83k% zJmL^1!k=1BlP%*}sTf}{%;GEf=(_v;(}&k{SwnzTeFYO*j&|e~Xxov}M~tQOO&_w( zdcEJ1QY%Q|Q4&Tu(%yN3^u3|utS!!~$z<M40~RjQW{JGT<zXW%y7jvjteNjjrg;|g zhSiMoc3l;T<33)!Zlgq%N-x|?#4$J&&IHm~NgK?)<1|7N);bvdrQt2!^~cE?jRrE@ zO+O!iDVimXc&g)iVKqm{Tj$eazc9w275Gz%k9GqIipJ!O<f@8Q6v`>3kuPvTP4kNr zr3QFg#xA-FTWH@&Q%!lQRA(3lOW(?RD{v5iB4I|nFIyw8*!yfosjgJdQ=gA`OA9oF zZ_*}2nW}S|6dcwD+!_3UV_^~U9Js))Sr#Y!^L{jfDD&(?#lA?yc_v}Dz4fBRMlDyH zb}f7;7rcWK;ugqwUcJmm85;v#kKStMvTrMd`KV4QJ>pBmrj=>4J18M%m*>!~60!>Y zG}BkDQk{)lxG1o={KS8K8fRY^a%(B&zc_2<lW!7FV83UboKFD6Jf@Zkm+9KR6Op^s zm~Xmona|yo=8uOOI12@-uB@n&UXgS}P8!n&bbVcV>l|1~u}!W%=~tu1idx&8S=EgN zK6#2e5(6Bl>T8HYzgz2hEL)}p7C{6liI+|VQRVXm#<CJ5HW4=15Zn72+{Q*0O+Bl1 z$?!9<8Y<yaM!{M|sJc+WeSGhK>eEfx?tUa%0W9a2LibP1T8hQ9jYqR3tS+R7x~#Gh z{3Q@_x-*)T8&U52HO-?wOk*)}#M*_(NKHNrRdomnvz};2JT3L*5A$Vhy4WulH*bId z<r9(ICs<Lt?sh@Iz!o9Jfc7oN7!ebEgO1dhz&=lr6lAV>>`9>_*sY0cgVxyZAM`mO zZBnJlG6?$?jIQ{jOm|<^URi40YeL4j=-#w9rca)v*TjFqHb(9@@VS2+N+;C9*iZO= zc9H5CFm!dF2Is9?RlS6w_MW~@TNk|~kt=rY&=3%xHZJa*f}hbdaRV9>Pk?xJ%kEm- zOeL<^&%OQyD_Ugh%*=j-ZN<|^bB@`U42s<d-qPQyx}+sdZZGkXcH9B9$o`78;TXp5 zLY84jk>bjcD_Za!>>7`uI_N4@_%~1S-(X;~<n8{*y2?TAuxVG>YV*8Ok9xyTPU?0m zYKjhXsSG!HK}_orac;j#&lE-&)nNm?=kYkkHKO3as@bjlFTffRfLe&oj4+9&vDqK4 z{T2C^K3P$=GNv$+Iv*$J%MXJKQs$#G_Fqb8mz(+M-t!zB@7SnDcP&ku@J{7Ud4TI{ z996;moy@qmK^@0W8w7s-k}gKLqCS!M!~;i2i@}da<guPoJC;L)&J5u)!rZ?IpawWy z9<bU<MI2eF3CGu$8wc%X7QAYGsYhjysQo!#`k{co_+EDiFT33@5z=u<3ya-4h3R3| z=<zHhHEXz8;uQYZzFAyR0Lf_|$SU?Q$=+`Nf~<rvCBpNQvCi`^tNPN{U)Yq90YU-` zQjRon7(1Tt)<?o4kI0NZbnRtP69a1_{(ullnjBjT2XdL4sEm;@OkPI<r>GJ|j6(82 znr>c<wIJTY=uWjx2y_1Hr`XHerK9mgeucgVg(0TDt&8!#8v=vRILAxpzANp(n~A{d zpglZb>DzTtwnMT7v2FH9B*DyG1S-2~!;{S8S}ePi$UHa1f+`ou>c3KE$&4zZuO#=@ z(Mf8M_|o#X@M>CTR9s2xx+z}TO??g<en)sGtQ&79i^3;9#{1ZP>F1`CBd##Yv5k7H z0>(MmVSzf?LWQ^G-=wg55%=<G(!FVDjEvmRkM_{^Z(7C?tk++#=VKwut&uX_&9#t~ zM{zskAG8zW+lT2`t}_exFiy6R6#ar6md64trJ_!abj?hHvL-Y`;=D%dwK;7u*FMb- zIte42T^S`s7@Grr5-#)J{<W~OYs4f}hOHYaMFmjTcf=X%Y@^IzV2?1cL_DsZ#d<t| z7QU~z-rO<5a;0t(SLs&i+39>8ndoH)7D4WqC#)~3-kciZ8CC??d4~@B-jOlN;1oh4 zv0WWh8cS;XtzrUYqPnwDG))iVo@=~+Zo5yA9RIK)DA`L|Dp#hVPfjYc6AZl$@B4W{ zVs=7<uZOGo>f|#0yHUZ*^t=j*l0O0jV*FN99W);2*3W+`9dVQWjQ^6aqC3bvZbt{} zjg@xBM_0td8n0RvmcAV#lh(8Hc8^0{PLpoXdM!7Ft4>_(WpgOl^o?2DNSZ|&)PS*4 zNEEJ#H_0bC=E<>B?>i<<%+o74RZr&~w0Sh!>mY}@Le&Ea+zZH_CNQ}??Xru=0sn`w zb7&Gq3$|?8wr$(CZQHK;%C>FWwr$(CZN59{j_8Ot=;8SV87Fh^wF2PxjgT~X{V~?7 zYoW=mPl_tTSX`xWX?*3>90RQV&FId?+GX1~4*CrI`uR*qW^rQD8wZ|Fu$yuYD4XRF zq<ocVn5?ez;6<#_EHWYAb(*5Wqc)?T#Z?34F89V?riGUaLNw_|l53_Ygv(ozHCPL! z9h|omP20A{c&dG6B!W;uc7%u&;rb>`j706oo%J<hU3K>Du-C|I6LDBeE&Cg8!!<$u z#Jg!yaM?Bu_9ns%(E<3EX}2~K+X@%{ReKMaV>Fas*G=AXQ(`xbtP&-aq8wv@ydl)d zO~0;E>UP^v9`LD!WAW$Zx&!t+QK5iDct43Ewn=f#9KL%OoH^k^<xnZ{{9G6mBcuyU zCDa?i)Ngiej+dq9B^lzGUQR54`Amr>VB<E(vHWLvpS=d?bi!c4^`iiV?pw_&&-y@` zlNbfhLz%Lg%2Id&?O&iz?ko3TkI&j|A1g4HBTNY|^H!D;*o23yaxvL4Z(IHdpVp6w zMZZ7FQVZryP3?%s5i9^$;r<vnHNy>KR$uPq-yXS%#I}cCO0by^yh;HtNGiZpc{qBw zkU&t0{2F{l|ED`RZFrqM!8TZCo#p?1>gyA*@Ly%EnCLGV+<z!thHxA;q=fP{66%GD zvJLs|`PXIdQiCh_7Thw0tZKQbD!b#l4F+@l^@w(jT_0A0vN`1GSS*2$&60EMhX&1j z1<hP4?=gAxsg{a8r#ehdT!_MiMrC_`7vOl-HaI<(8s7nl5M|$PHHWbk8w@<aYoSgT ztDGGAZcnkAcjzut9!`$IoyJ}qqWjl%bJ8y10o`mxL4;AhXSx{Z>(xem6O=D~JIre% zLG{<gZXg0pGb(G8Z+p#^moJQ!Rqq<pbv=7M=<n)biU^`%1;R>kWp9nvcJ3$iY{3nG z3~Nks1Sa!ea1AUeL0Iv>JAtsSDYM?iXHm>M&jHwXw6UGTeg4MrUCdhWoXJTY=9|-G z<0JStSnN4LKrkYa5P`Cm-RW125&@(e9%q=zhVA9Bn<2g^`<pnr646zJ3#}J(H$^V9 zFBToSH`I;q!k!n7WQmE-h_a^JwvrZh7F4M1GE?Xq;*PaUgyW4En-kqew|0Uc&jmB- zyq-4y(RgUoBS77jIxPoU|IlK5LWxuh_9lJ3xH}1px|-C!Hw%Ql9>lwLN%^pXc?E`4 z)Uxo-71`<IxKqgwmT+JXfM=^39B=&kT$i^jXj1}}rL1N2OxIXJOK14RuN)JotS07_ z4qoRvq=sQ0jFxs*1-n>p8E-MQP?u&2(vExs7x)y4PJozqfbL5FV9Al$>0G)<Ncovk zpk%NV3Y;;*pJ|h%0Ebl+dfQ7|Mle92qQm$bIRUTi8;TK&V2Y{Zq!p&SSvMB?M+Y-t z>L?xxsaf?2GJh@9MVKJberYoz-#fSR&hWfl8=t`Ib`kRIjv_9HU8bBunq&@}k<}LL zu!i?=Ho?Q$FjE+6XPL#*o=tp*Y1QARII`zE<%b4#g>>;LVe%dWDkVP|jZ5(tgtDS- z^z$Hd(U7fE`zNpAiENaxew;^eEF`R!qyEAIEFlEdginZdlK&{rKQg&hEyQq0?PDAH zBrX?pko9q#x!O2=1HK`Wb}ZS?+yVHE(PN$$8je{iLHSiag};N0(60mT(LH%yr>jKA zj>5N6x-V0ondO)3Mk=msoKOuwx?awwxLato0QrIm_=)Q9rrsezG-40c_mFq*R+<`z zr{2C!TTe-qb7-2JuPrOc4S=O%8ncxD<vV0+W*&*@$CZ)ckj<t7GQ(xyop&bL3V3Dy z3hr(BqFS0XJ~Q?1eD|jRJtnAIsihng&7Msyqn}(V_S?_}nvs)>x*xWkmt5!yfolh2 zg7jQ?c3>jy2%n6rpS$ObT3{ixz^@5(oksDma{>^tpp40tyWOv)#U|sQDBV;jw$}cn zN~%xSw{qOcO0B(R882cG;6&gR3%jStphhYq=d$3y4B6QhJlr@rb7PIQ^8P6hZf;1C zfVX^u>V7#yld_c8uLgJ%hp#BJlASBTqkhrNz4El4Ysamjyv6KqUUtNbnNAsH&PFgo z!`hT;ng_c?wG+)`Jj*?N6rdiFS}2u5VGd6Ue$)2ZydzkaJ*HKX6nIdM7M*#mZpicy zf?>Ct)l>{8nNTfSa<q5eEP^K;*B6vWb<}F#h|jmd?6oN(F95EHchJW$V}-skP65BC zE~brMz2)|SXTe$;8y<0xahC;>JE|-m;c#8C$Rb+lDnQSvuLb6U%3R|k6yY{5@T>-& zTzMxWr|7w^0aar|k!drX6RV&zSZvX+t$n=YS3gPd+m}<O_Z)uvl}_oJH99Bn9wW?8 zP|16ltiDA<-xJ5L3#F=La4TeKtWQs<>J-0h;5BOwyBBFbI3CLhYQ&BM!)hMw0}t1# z8_bfE&h)NLuTsjetDWI#xE~S;e<2K)6bqnrcHNf0lbJLM>61mE40PEHhr{EO9P7Dg zPCn;De5A#{K;yVgj#lZUT&9i8>N*koK2|_Z`9~j&M1(p+CFPrXV;Y#ejlKMX6ne?^ zfIs+A`Z62{UTL<PZH<A?<ylLOpbpK?1U;N&JLU}5o$h+61|3V%Qu7;aUg$|@)IRD8 z$5`*1RZ3wpGS#GBZgglcEso?0CF7scuR!zbR^#!@5Zc}l80zcVaYc>m96M`6KBbiz zch3I)Ez58%GL&Y)NeEt^L6?c$4Scd@hCR~+Ypqk2CbZprp(J*B!vp5KGXvG%9cQY! zs!u7QSUW<xx26U`aK$q7{eggTjqL(z8k;KWaGwD5JIf|*sXELr`hCX`B=4qWRsoS6 z)NN6mome_$yLjdP*2@5>LB;u<ZrA5l0Zz+z99q7YcU(NqmL8B_tZfj9(cu1%>AJ4t zSJ})?lkJRg`E@x0a&C#U{1YNG&tb}22+@!{(i%XT>mufxdgzw(v{7_)cj{@yXJ6Xq zDAC3CPb^ku7g5z<nz;hofVa0NTMyb)Y_IN=)3-_?+2g}lZsZWOh(9YN2PEmg1Z*2j zihiwY6Lx=SL4^HR1Sg`Nsc_V3;4dC-Yi_DG7;^A!S<16>b1p&}L*{o*2w!_OmhgPL zV*2}mkjFk&mgy)bcFOn$jv1h_I&GUR@MBlihsVo<n=!c7mJ|w-CQnsGwmI4OR55|H z*Q6ogdPeKq+XBJbsQR0X98i^Z)w{*tn2KU}^*{FxWHFaH)tlf0$(6i~teR188$O;W zBME&Mt`6H#lGnqx-GUEAW%sa(WHBno51GEqMBTU{&YV-_d^%$qB~Tpx)R`8|-}eQ3 zCd;QzK`qlxDeteQWNq=tYw=QU8B;*SnZ5o&!JXk#!K{n8dSp>XMZyjadJ8MWMisF_ zh~euO-$Kz~>l;Y^o<bSkemo51_7eRY-ILZ{#daJPd@7h+ho$DxAx^9U%PTEADr{&H z-!a#>Yvi2vjCEG@G=~#b-)A~gRiPA2ylT<a@BWi#BF$SFe@GMi?AF4i$NPoeq!SM) zaenQ7*H83lkZzcD?v~}X5fe<4Aoq5tgDq-N(uYK<Rh0(K)_DnpL<sToSL(fS_!8); zxfh|14a2ai0`xzJ?u33)(-E28vB3192tbO4oCU6+Vxa+Kqr+ILnh=RXbGgUbh}Cte zmP2|BOWK>Adv_!vL6FD{n@jaYow#GBR}R-K@nicN>ec*m-Ax*B@dA?!ZHifDs{V^- zES9S_e_1QRr%W!K=fmi8qxE}7QLmc?G2tpD%9A!1Feo9KNR#{`X0Ddv5YhnkQI9qd zsszfpN=pMX%szUXVS$ojB5PuRc~cwV<^8{{w``<roUr>Zg<>QvKJRP8kb_59sFk=n z?2@-;)bcSjW=Yv4T3R9`nUzD3DY=ng^fe(j4*1m}VT`g!>yZq;f0QL`9wkrx2KDH} z2w2xm91n5N0%e?Gnu+oPRqtm{@Fzurxh`9gQENpn`v{5_x0?hdl`NZ)>B7ugwe+w$ zq7mua$q}R7CMyjCTHDcCJ<3yu%p~(+qO2pVZme^0{jG3I@Abm0%IPa!{^SClo|aH= zzQUM+Kv_294iocXL`1J7j!RDiO;ve~(Org+p(}me?p9e1Uz_m=l#jWEFF?H1>Wz0i z<nGz+mDJEWC);>(tN-zwNYn6A=v9$r8TQ`M%-6bhyOuwfquAc78?Y=dz<a2l*m=c1 zB-`tqD}6s(KMFSU3HG2HI73=a_~S3w1H6#3Aw+|hkv^rkBpPbiy_P2+VPkgeP%?{K z?-6ScE79Q}<%uhM1&b}Kej*^LUegiugL_b(57u);`)#CKdy(D?NPW=;L@-I+uIe^g zwR}4f4A|KsEqJ_iF3jm=E0UJY!^p_RLf4sV7%i^l$$DEH7>qFv4z&|nYMyWvTnL(O z+mBY3U;jlJV#CGqYmcL^41X3rw~K2z^N0aWQ_~hKEjNGS)k)yP3@P$ER@nwtd$@+b zetP<V7ciZdRf(wM^|Y6BQ$kvYfSH-R>zK9c_E!%E@&7>fAj+mB!NBoda-il;l9|l6 zp<kTw#0Lw{Fxj7%>!Jnw$T0%LFj<#p8Fn!umll7Co#%Nlc$A6C?w5)!HkYI_9ZqDw z7>Uxaki>0Dyh1YU1`#_k&Q^Lxp4`&U2SVdui?q1sG-=JJW@BY{bqx8Fh%}z#WM&R= z<jDLOqE5euL`_<RU)+1c-^)LCCpZkM4gq<)x5`{NCP=;)+V%6WIR8ioR7^)|ok0yi zY<KHgj_5B&kU>jTff&2`qSLI2y4iAjqR~y|66Pu%wQB|hb-r%D$hI5LQ@pXhMl*Ql z09xFyX)bGnUTGbnZ|qsk5M(u4!-GP1PMBxWVSSKj)YFOhjx0<O-KJr<X}9&t_^R(Y zp05O7f4xAPh8`NcQWw7#2Ol9M2tN-DJ2Qo%!L3Ro2Goi)q$v)bm1OZ!Zw7#}uh?Q$ zx#6;Z&vzqR3x0U4v6I6w3*<Cna8*kioDJ0?X$K8ZTrM~09PkvV_+&1M{(V8<Pmau| zT%oI^)X$}#sWn|6xV<cso-^_Utkhawgdi)5*_eHY^E2pPaXNV|QBmYT8zAX{%m4ho z5xG(gD;PH(3%T*Sql!<G#LO+dBFB?Rs(g@A9uFcUaidqMb1vR%{yb=E?`yb_jYhMt zVt!H&QGVmK+x)j*|LFTr7imc7=W5Ws3<HQxXG&;V)L{XcLFGr1$5$h@<IDKSGj)j> zSMORgBB)FrW|!Ba&Ad6flzFn$BL}JaT0|Zz&^lGxFqQiJN)tkRSaxb01<nGeU$=7b zST}*reN}D8A_Dd$09U`SM{h_FTs@fP*C>+;>e+gjOdeo)+#!f7$ES*u=7_c&S9^Gd zFjsz3vLIcIs>@Vd$r$hNC=@{H69Lxe(_1;?!0j@ClP%oR{<jld{c$Mg#8~fX`J-`d z7ISfYjG$f7c;A*b_nGf>ox<Hs-wjtj{7E9IqavV8I{{KL<;u@%kCoPpW=SI@{Z60% zr1a5R@9Tw!P1=UVg!KS%Mca`fFI#W$u5s>;o~VZjvUoNQG9kaL(m~>2w3_*gIi8ni zCO0^{EZgjxwP+akE*sfvpkyJr!aNYj&`{x@Tjwszl0kC9=a8Kt_#YPsr8>%U3IUYA zvL^*towk}TV9wS>$y*5PJRp45s_&I0Ie*`vm)RG9Z5bFQ!qBh8m$A+*<#;JZasd?4 z3c1r?67ociZUN5`UB9lXN(};3Cid}13G>?&U<Z5!<7bs<uss~Q+L^)4+Q)i6uzGao z+nc6HYuvXxu_9y*cm=E-P?<tFT5vg8`h2+0__KHnnlOSk{x<A<ek<P#r>+@isM7?- z8I^-KXAT6)I|$OBe`9U`Yj{+LPfAA_s$3|D-0+?*U#d`T{9OGcIhV-~er?xENM`1Y zEH|UK_B`grIFmqZ=r7ZrKx^{ioX9H7@|OE{EUaI)VcrVZe{bOcokR)smB@SYL&=1; zwR~`L8kNzKLG=77E}TQo={eV1Ge6R|GgQGn`2lQNCtR8fbgBJPLnGcIWZ;AaZ5NoR z?hH$jp3p=WuHC#ydvK|=7g!J*57(#}KrDn_eN}7J>YLA)+u$_;8TUex&M~VabPI6u zhhmd@N7eRfN|+6*WA;O&fChAQhfL$+nCS=G#T2hkN$OqbYq6p+4XGhVm3Z(nT<@Ve zhoQ`5EIb5WR2N4z<uUR$R$hvDoT71zT+dtk>Ri81$|q5*dEk42kT1KF_g<5q75xt; zNSHL4t`vzH^RIH1Q>SaSEy{?P$fol$=lDT2ez~Q7S$P}!559eC=)psktApv$TS@=> z{8nX_d#`$#hA3x;96!|==5Rj+6x=H(kpwjvN(8Zp7l|iQ6?VV}THoH3nxz`W3e-41 z1zOUJwgb>Xno<d+Q@rKse&UAFMe|Y$trLeYu8fpwI-#=i3_*h$$i9y*IE(&8sp&zh z{vV0<lALO8JXO(E|MrTP!X<OwumC!Q8qXli5|=IFVZBhj^RIFo^9zCuMI9i?o>GL8 zj6|XFB&IRE=!VJ-Q<xbwf5Xo8o=x=YY#Kt==WA7q=_k|?j*emRVfpb}qq=a8*V|Fa zCDh7w=hEHc1&+k(wX#zTKzF;+L|b<me5pq*%#3xa)5L5`Rtr|lRjE11Ax_MNvT}B@ zf2R8*t%7L{hlpBiptJbi<1#kzu8eN>K|94N`bZ-G$$7kf3Dqpo7LUR?#3<j77XOhj zJUilSQ-T4DX6ZrC-QsE>^33tw#J>aWrTAe6@IvXIAk18yJi_?Ot2s~ZDN!Che()~k zlJnu^3UVxsi(_yCm2}p8){OzC?0|=A<OfXUg3dJ4M9z8XP9#PYD55qTRw-CgtmMu_ zNzI}?E?B0`tb3bcmop457A|oLh4Z}xg!jXEP;px1YtjUkXwiYa4>It3OL8rZa74G_ zDfLgL@8$-X1!2iTkhXfHCBxMEl4!Q(G841PrLvo$;N0HY3L*8EMCtGH*X$CD;9&VQ z^@mhB$@?>b^opc3f%DD1ow5JiDRXT3s}0==$ZA)7fwC)9$LQ$oPNes8ek#92(H&ka z|2SRh4F<%5M3GK--0M%w@fjfm)k%YhtGOqFJ?|7BHu`6AZd$Dt=V4+hTI^A{|Bc#b zoMe=NJJ=LeP7%rI=dWzSakV7N8Yw4yz{M)e?MVu!etN2UxaO3A@(aUO^@v+MH-n~# z?A+kyyeC+}_Ju<$O9bOA`Fg}*a8y0UzB*hl#zoKa3noG18O!m&OYi50+S9dSBQ$pY z@%b*c#M>Fiu(t-Cjp{l+RGUjA!Dy36Di+IlHp%K9y}M)lbs>{SZ~pDT_^Mxt18{Um zqcpd&OlS`14PonXWcBjjKxWW#s>6%bxb9&h?1gzn<x(Yd%R~P;(*3k4IshIN{AfA- zXp}0sdLIE6XUCB_AzC|;mDH&xI1}sl427-wV`+}O=m~)?UB(Y+f}2wCc#6Rm?a#nH zZE|)Le+zjK;$GM@2n)?_6CT#?tnte4MN}XII6^!?qc<*>N&P~d$d+Il>%QXe&_Ik~ zCmR_u<63GybBu)#4ELx)HZ>HFeqh(Yf`$pbZYqGs>Q7^BLYCuKg<|tLF;I7I7aRps z!D6h<LA?VSV-l;S0D@txCHxCcp^mIio68~6onD|Pz3eeNmzpSGwy*l_neE<I_V$i6 z46xf<ksI0_Yp8cWN+<Bl?&Rx2iFp>N@HHlZULf7e#z@<v^!1vx%``BkY|%ECA!uaO z$b(Qmh$aN95a2HM;vqQRdr_RAN~3`J$#nMk4RQ#AAs`Bb0t!S|H15^lAhtNQj(_e9 zfkNp0?pWJeCrd;9v&wOLs_K=ikSA(~^a;wUC^pI|q4U#Hfj_!3>D%IhpUiM~I`Lds zVImcM|JoaCdznUGF%B(yo;HPsV;#`sDK0X^eomk!qV{bkUV;ETZf*k4`pU5&YK1F{ zkmQKUgA_*zS%AU|J!+>m*;c{SeF)KFLh^mV+xy|d*ulR-#3||Fm+|UDLX9skxT&-* zbeF*asngd}6jJmPEMF*PdlqU5zfnjZlWuYO5^~LGfF=1}2>`sJi`}Uw)381PU9HV? z)HY)(R-+uYU*mm~{OUE-VHMyPHJ#ON7AVi+?A#swDgq-ENFg5R-uTY-n7GN5W_2xw z&}SJiQQQy3ftB4I7Gm&}{P&~?(B#Tpz;W-NNlTTm&y6nJN(cmaGQWgVCn}?{2*@bz zI=9=DV3P}+b6IeW7#HnbnjeaSLQ{`3;67Nr5r(<<YZI7w=~Rat)CNbD8TVzG(9QEf zhGfBSceW4pCKhne$;t7FDva)h5E~q$VXBgZBXa-+dxLEPs3p>%L2Qs%|J=26z_c7U zt1(=M#d|~_5*~cdsQ-wnC63~uw(kx>axFq|7Fck&wPQSPc`g8!Yn*j~XaXCCiUIeO z$gi}K2oR#eue;xCh!emtX2X+mR$H)K{DcoW@!xNyY|dZG8^qTwmA=w@K>sTSt>|FL zBVy{<s-h6C8CaTn=>F{_(~7`UXhB!a*_7B3?LP&#(D>FKlxl}H>y|J;YCbob>xoXo zaUE{m9g6RPLq*tP8B}HW9e2D=tiDsR9K`GlEOL!~JLd?{md&kwU`;oG>^VUf&WQ2M zHTUD3)o-jWK3!$*CS83&VbNIKOo~3z&qJ2*5$)j-RJ(G@`_4QQ#`TL>k<aRcSd5fm zYz0B3Ulvho&S`aZh$P-Wc`35lc{4mYtraFfvE6UTK2JzVC{Trd9VfD2e@&_k&MF51 zq(i3n+&oowaZ4Na;#rEa(G`H6`!WcfZR057kkrCFJsVvCr!r~O(O7Z()05ET^;{kw z1U3)XdAf7THQVpF?&Cm846H0pOUNCfN^Zv9;Q*`*BP_)}txrCfHSSi(aNaaUK{#T6 zJU>(mZAE!DRbd$|Do;tFOfA97ha+v9;dB%t{8m7-C@I$X_HJ=!7L7s(SDlmVpB1aX zS-w56y)1G;N;rq@RfYpfr)FuK0F+IC0(0M1zW(9EOb913CRv+&gOOw1&BE}uAt3tw zt5N4c&E*)RdlFEIB^`!;$O^-`?<?-0B`NBRcM8=%8O0I+4$A0EDDy?B|L*urZ!Qr* z60_I21oN8mIZ5<({G=TK{uqMn7e~i_zFS#e|3GE{nEqIqsyHigXp!l;AXarp;~sEf zjj|2Kvgi}Xm9@`oy$QDG@yOaso#YMX%>{kTUy(UtpJ)@oV4x)hM@6Z(ca`#33D3x` zbn5quQz(S`#xHh9Kl}cq*jPJ<(L|8do~*k;@44kj2-WkOlkrdeqT<j+p3g0XEP*RL zuS(b#8A9BmV&%X>MiDCI_vquLqgIX+Id6HSN4AD~;P-2%fU2CNf(;L~YvZg3(-i)> ze7lB4`#UyruRP^AGdUUk(3Tc@VR6mnLfnhY#P%!<JDCXm?;r`L{}m*`!0~^i*8hPd z7+5*}ukrf-0ZA~jFmU{Tf+T9(Ock<sQvcl>46uS=!QS59qUi*&&4YA0w(bA-xE<Kp zfutMI1p@hU-{WR>yYzjsKK(tfG@sJ+y6Ji4RF##itezw=f?@=d66%M8p^2XE1`v&J zX(;NcMAXO?L@_dja(8wjP*jTC0F1#AK&Wp|0FFn`hhzZ_2bKk>t_DEE!^0zy^2Zn+ zU4b*PI{?U6Q(q`9C@T6ZJF7$SZ@BUk+m+i4njQeCY=bAyM;#u;f^c;Yde_HS0R;kt zLlf}F9EXBHP*z$^RZIp_kfy8zF7`Lb&q+WP*jQMHG69MQ&j1*B6~OYx9ELM^fd@7K z0?Z2hwVKI&fR!G`GXSY?1I+Z_jRn+|@n`c3IR|7D;I@wM`PpIzFo9=iV+P{xp6Le! z0tk?;#*zIax<6$P`j#CZg?mgj{6X^qRt{a~Ue8(&u)zVaS4|lq{To;s7#u&S+kDM$ zV*oIEO|^t#bo{O==`*%xuvY{pMp(z&2XJwGuS#V^Fo0@oYhZHnsrmskGyV_g5L(0w zVe=~w_6)$C-;t10fjYnY3wsLtRd?~-B;W6MwL3mKI{9+96yMkM8wET*fM;Pk8a_Pu zskStHP}9l@5k368RygiILjZtw>h~^-Yx~Q53ex=LC9v#w12cmSNvsU9K8b1o#UgB^ z6wJ|`0;2GDr(*W~7V&K#|Gr0b-zU2Jm(~7Px!~6|{I~Y?T{oW?tELtywrUT39|sP0 z|2nu1d<^K<!}zCPo4`6g`QkVJyCx#L&yVpdPrw8xW^arDnAImaFg^YaPd=`PbPU9z z3dWhP0Wck1y=(T|rjKg_)!YOW5MZzM%PR%|3=KZkH@r+EK(^QK2b+_0c87pq^I12& zcl?pXo)n#2nivhV)7M+-XHMByahrc?^(1!9|Eb`g{+srI9$HQ@47xwtKR5zrU|@Xe z*<~|r1Aym>H}_YtyC*>N*NhsCb1gszu+vtWq4{g~!|(go{QL(h24n-o_+u@vf*ajm zYG3uDAKN!b7VGM2ANlLEwWswf|8++S4y5Z(CNTw#fXwGNb=-^+X4PFC!05P>ONW*o z0FYJ4)$*;ACnZtl=5$XcpK+k93Sj&LayJFP_CcI=rmMNBFRa_HmdA}8V9qI$d(5)a zfnlvuqvO)&ozaU{P>N$6+LbpqVc&o0z-0ZsiS<?Z*m4i~yCg!Lwe$7FjfL-2rh{)2 zxyOdzEt6<f<ght^wP&byhKs8_g1i0myUotSF~8>lxz_WQK*tP~kT?f1M|}{^vOBOc ze_J|xypd6m$WBaWkiA@N4w3s%5DC-~1@xLWE`A`7X8t(=WP@Em7Q^3jI{XR=Z>mYo zw{p%sYQXy02EVih5A6Dkm7^*OIZ5`ofgcr<vFY6*p?r53ayb)I4SYq(@6<2-@*ut) z5t^=5D?ga-^)9+j*fU$NY&Pnp`PxugpMcLph|EctS!Jy%MTpGP(tdT4y{FwrVWQ_C z@XT5k9FI9a%pC2{f3Dk^A8jooJLEiWtrz9B$;QwkGZq@o(?WNIlgSs8_V(I9-G++n zC{+PB8!@y*CJ$gCT?npn8e+YQK)QI^E6&L|`(KJg(qt~ZsNMnXRalPmFMSZOGtvid znd~GMM~A6CEK4jNP7;MYKcUK;{Gmu(H;ok6>zM~?2GR(r9>sQ6(QmjcQXt-7<i7)^ zWSxd)!3eC2U9s&P8d9|fXe;D~TmBgzU9Rql@KYuzQ%+cPItbcbC%Sh?aJ5AdOhMmr zr*?c8kP6Nls|St1H$6!~D6Fc`P`_&Xs?(0E^(eOosg1^CHP%4hZzgEV=pwP_N7Gxx z3aNKKl7?=v>ZE5tms{9)uf_5-9&n$2#$yw$a82Bh_Hk7iryr38bjm;Y7K3pb<On87 zq)0P42zJ<^!v>)Ydh?%%IA4k@QF6ky+jm}vkfpj3^kFt2eWpt)gJbFw3*$$s#lPm1 zDEHzZ)Z=ew%G^1;KkYX3X<~0^2BkDuJMzsFS6<Cq(1bR-1@tpuW&h#&gRu;tR3jjU zST_{DWN;X121D}yYBhjUOTx?xX>jcskGe;V`^h)!G%EUsEt%uT`HFQCyECzQ*T%|) z1=~J_5AMjeeX}RAcfQoQu^<7Z2Ij*UaudN>8YPf5Q6z)r{Yuk5DMvdH3EXk2YRs`O zDmBC~6gP!qx98&`TIfbRBtH$B#CS!y#RD<Oz%|r#5E<Fftt>lsXPTliqLrD}pzV6! z<<wFQW@~5pxe+Wy>8Th*iGqeL@54%Em1gyeT5GJ5)vbaW>R&b;i1@YTEx5dw=K5F< z@gQBVBg2>%nUSe=I|aKGrr`!O9<!Te4Ha50q77Oyc(W;8A+p%a+eFS+M0%$@Rp?Bq zV}Uj33P7~TN^j^9zZ2NehhTGD<_k|DWO>6C<nu@Gh;tO%C||6I9xaE2o8|3(m;x^b zu*qI7kQ6qow(96|HTE<-CI-J$*(70}e{c_GoR|0c-!37zNEaCL!H7y57!J+@0Pl2N z^PNj$l<d6u$#Q`K=sl<P{RKeq`s=AEU^v!17GAMh6~$akyA7cO%Iva?`J(%Vs`}R{ z{sA2`Kc|CV<b(-~xnB|RIXu?oL!b|%^6e}u7CvUyJMAAP+U};FtTty}R(FOM6d3AR zI;m3W&H$6TjZ}nF(#j+TbBX9_@5v-3nxjnCjX2Vw2cqH4Nf0MXI9Ekb=qNlu{lCJi zX=K8C&Z1ozRYy{7ZsfY!q$bc;Pd@0P`_6<6vACXky(Kivp-3>gY%@sxvf7OqftK&! zah`=*L-qKM8*RB$hYxeL@K_V-du*+4l4E4lXm2#bGEw9<tSK1Ns_w3acgy3vPvWe{ zVAh~EE&upwP1%{euaNu%b2+6_!z)MNp=&CbPWV6|T}Mm2OllRbKm&+~tPjXrQk4!~ zO&#Oe=;_iGyRJ6r>d-UaPi<Zeyg)QGB%a2|<;T90XFsilP*i`Cl&0;F^r6J))w?-K zCqtp(^bP1)WQqoxy`kM3E2)fB5S)gOZGNtVO@^f|JlI?C1sw8vIthkEkh0IbYJvUw zTif9xjLT(Ma+O;*SAyqXhcgFi<J#ftq?OPB$TQJy!7ZFf(#icsn!>~*5HcGi3Xd5q z9X>1jyNp7D<bvzJrv!h$6h74ie$}ivo?W_<Xl2wj-c!RJC)_8SKbm$YY4z>ZV!bn< zn2e`8uwy0}&g$>fPji&vl82zyn&()<gU4mOxBLxmH{y=|l`M6qQ{FiKOCxpFmBQF{ zxXGAgi3y?{OXdy}yxt&g+(Y$7brV<l0gD}~AqkuiBC}LIOwP<s=3t49)h?g#>v?+p z%3;@bk3QWQMIVanth>!urVnWGh0)O<5_<WP+X%g3M&IM{RjSII`cC)v{E~V0-qG2y z&xpYWQ`N$#p%qzuLe*hvvRm55VrTOuV0sGb?u8gJzV7I{+o{_SE!-RIP~h1O*9OY_ z%RV3SoeoE1zq@L~cOM2vIY$)pKL6D%kXh4<N2yXSqspw@^6dcxg<q|@x-cPF--|C> zWw`=E*XG%`@g11V-Y&(pOKo1Bi&8O(ycsN|i~A)S(s81QBwE5!oMlvYIsbzt<vkR) z>H2LPpppu{UHMg+^4JquX1h=8>QZ%|POUO;@_lCXZMWus*dSi!5T#qj3Te*`qx~_c zqJm-OY}!zc+RI1*0av0^3jrJB3aQ|Id9fj@B=lMr=~@0QC#=SFnN7*K%yifj6G=1; zT+p@iwX7{W0t6D{zZ`ukN!kj=6bDZXLHeTJb;TaQ$y$fw_yt!ju>q(N;N6@WgOn*5 z$P2Fcr;FLtHYJW3HJ1JJ>7G|)+kK(Le@b7m45^2$7{}R&CIybe!f}miTO%nL3i?vZ z7Dmu)-X=KU!0(kKa`%+SJfJfNds18W?Fu|)rgT6R9lSU}0tDD?xnPZLx8|Ahk&TVo zq2gSm80^(r93xZ_V>;*c&azo!Nd$J27nP18&YMz?SL9!8Iryrj&92&<m|PGj9zY#V ze}NQt!h|@%fjk>VGjd^kO5#j%b4|vq%eV}dAq|wGd0u-HdAX49VFL6A)XP}<8NZ&2 zA-|JeR`whzt7gTbj?&kn@_3*-YcU5y??E;|_T<A@A}g0w;x@Cv9J~fh`Q0hcgxPyf zOZW>(=}w`yu&G?!jUXos-^)M1{cZ8)fmFC)J#!$3+-I=iK+|YPF<Lp%f4gFK7553e zly#4lR%69;1twM`DcL;2v&WMC*Uqkd3rbB3WB_fOcz@wy;fDkdKYS&uKB-~3HkYcE z&noF<*p!ZxE(@uvcfn`t`!{4YaZDvLu`4kEUNoamKP7m7L1A0q5r?Mq6B#X~OY2N~ z-xNDZcE-y-+pX!PT?x|b<9RB7mz5fSTldy-1_v_X2v|}9j$PT&fyp5<wO~FGsUAL2 z#%DIf7jMmw<zX<YFk(0Gz%89)7$xD~IT*~R{UHeDJyT#b$JjH;mR6lS$el;mKosHP zGd*seBz2|gDL-c-nKe^N<P=uMv@RCn5e`3h1U`-Xz;WF#V8z?9Qlc+y3e-T$Rj>W* zNS=sEUv9qlFK3pEM63&A0vrni;Vc#jsoYU~o{vxWjvHJWg1PG*d-l@c6@Gprzc(J? zuDexW10x!bN|e$y*KNQ*CrQN{SrX9J0>`f26Jj}AZ0RV@_G0NR7A;xvQ*|?&5Ige& zAJ3FDngg2}gWzf!Q;np9A?2DQMO?R;7mU1?n_T?3Rnhx1TCKwJtG+zX-U1;yjdE@& zOH-6mj=m37ko7I1$%&M^(2?Bziu1N!-kzYe?3E`*G-h3*ItL&JjkJsU%XE!0F(2}x zesC$b_qPDp-1zt(rd~h(Nmv-~O4~Rd^v!0`Biss{x<|4&j%Uygob|OPkwY(_rLrB= zNSSW#!RH9pnq6|ai`B)lMCe0R;AsV>!j6}(<|XFmL*p9C&ES4-CnpODDSDcRD8V#d zS}BMNA3*(RFgfxZ=)t>(e7Jv!)d3yqN#sD`s*ep%aE!@hluyw7hV!S<e+5!szfK8= z1B?kk{6lp=Fk&9Yq*F2k3A&hQjQm(?yZg<Q<Fs)HAMC&@)%@ct%W#i43VIm4l~TZa zogVi4ABPb{iUf-v+>H|PN9b>n4<Mewsvh{lMZRQI5p2f84(;QTUKqx%x-#5ZliuQd z7(f2}Py&UtEMnozVe6J~<^3jYm?HgJe)|O8KV(r!e12~{<KnVy&4t9Y94f~|iTjaA z7Zjb3gLJ?^-VDz9mMr^Kh#d8?X8%?cH8kBgUz=T*H&M>hwUG19o!y63(6P_JTxY8P z&`OD<t(r)ADU?bt@58)Y3$@~j#>x@3{bZ~y0u^pj0lus)kL0K)w^~0kH+Ggu8+VK7 zZt!Fus{GDjS36O0+Vrz|3YNaQE!ingBVk{ri)rY2g(Lrz>$`o?elL=X>Gd=M5^(_r z@?sPTger^*VbPyc;6l-Af|Uq0g!r1@odTd}328^T!jRXZ;%>B9;_1syFIP!qu1emY z1UVHMGjVUP&kx5PBmcH;s^o~JlI|V!Pai*PD;|IjSKv)I@mw1@Kfg6f>XyMqwP4~B zUY1llQNgeL79Wd&h~6{fDx$!AgDN+<@7wOEsA>Zu(HWSO)JeW^2&Hn9wqDOYy>tqq zr!>-_{PDUh4TV+hn7Ogi<cF2Kj(^#K2$KOf@nR5q4tSc&*BK#>d-U1aF?J78)gK-% z<%eX=Sq9zrWhk%LO189=9!NjWw<@4xA2)H4M}}dDB`sffnyx>7_ToIK>BJ7}dq{Fa zBe?TQNl;F2YRV~uB@-Mx<2Ya*4qymnhA$SgS?4{tnyBG!H15DD?#{l$4Z4{(3fuV5 z%#nLE3M<=@{e`h^b<ATJKFE(WB1krZ`Jj}6)pjuLq$qSqmKr2)e?cOAk&@ba)65u) zFcUmwh5a9nq=F6T{tWK0b`7zaX=r*cr{nD4Tq6cA;h}}m$gQo~Dc9nxC~B4{tVFCQ zKVw;e#ete$d>UokOQuckNYkzqk?}kyN>HQ9go-G7m&(4D2<6XrRrO*EBT*+wGl4&# z6N{K(mA3O-@PQ3)V>2j%^JWw2QO7$I0l64Por+)yX3iBepke762Sa7kMc2uhGmwD= z+C`^1Yts7LT7!f$)vniul!v0BMwZsPeRX<aA)I8d6{`4~<`GaX<kyL8*<Q76o7|M? zz>OGK&Lz0`J_C$7Hp(Hfwvcs3`Z`khja$9cYQkdsVSHVyrQ{Edr%JtPJV?x0Q7A%V zjg&5QH1lxHf(A#{L&vTkjRg?T-xOcz5H5<YzCDTRFn^S-S6cqSMEwza_LL4PRmS@5 zL2pmS$@F}yna^}JO5jmF(Ld=r=tt4<MNqnxMztOn!c41m;Q<Ka5mU|Gx?D$i@GQD5 zye;v|9q`u$<v%a=$XUxub8T^MTTD>|3U39mkP&MfOj(CQcY-Mg!zsdzu^$N;YdFTQ zAn+7}vY;wQe}uE1;kNga@Cb8{VMh(^mEfOLNs|yNZQw({$GA;86&7jAjw&E@-nQRB zjE)($5^4a~>Y>cqC$fIX{M7I?hl-9LE3e+sv)RPQ538F_F5ciZC&;2m8OE1Na9?TS zH|+c#^WL0O<NvE$?Hk#KjZg7TgrpE(pYGx+S^YHrjN3E6%Jq<rZ;VKJ{vjtG0&IlM zSegkjFK!pWNQP9;i8RA&1R_^{LH;|G<9AhMNTCY+X-Kly4yl%-rb~_mHD1AQ`GVv; zi0<2P&xcnW)95LOIUV%#s|d@w3f;vx(_a{5Q=>}hvT~oSIvY#Kz*y4EPyV@{7Cf^$ z#FjPU(RDuMztq_Bi)1~w<{plZ;IrZ~M~yBpA{KiU0?c<o`}f)^Gr0LS2|lb{+jC6? z5vi;-2pYl@l?}RBu)Zj^EG@GpS<6Y9C}F;O(a7SHTu>AVUb&*10fpq+3?t=B?qYIK zApbLXT)FzO$floo+b1Km4f`7{(aFc0jt?*cAC%B)ciKMxO~TjH(aR5zBXxr1WE{c% z*JKrPLU5Blo050+LjtY`Pu`Rph2B@$q!}-KHD&$7*UtSB6;iP=Jn<z$9P=`G)3wL~ z_|OBxgp^MG6jf-yCyf4hC`2DgUv=qp8(NiYh4pzqfr3!USK~xM>&C><gI~)4S^@Ap z9;@J!5XmDw9QBbLdAuyL9_xrS6~^J68>{QoLh5k>yQK%Bc{Fjg8IkmBVZd4U<P$wW zsurV?_TODx2A$w)ZT+`LTya<V?;+ViJ}R@U`6t>2F3}e$_nBA^4FIOzQrPqw^1HEE zl@%3s)a$EFzJxpNodBZb0adPZ@CKJ~*I}Y(x(r9w>4E=qg1r$CcxD_FTbc4W?Se|6 zS;4vT@omhDu#uU9t#+M#CxEcHfsCEPHEQDD)vvCbab93->TIP5bJ0BUdYRKw*=yMQ zTcd!sO8h1S*F6Wp-zz(>ytDNW`)4Y@GKh4VGb%m!cl$0<C51n*yh3i0ZLV)04zB6H z$P}xVl5eT%(y(!~oo>}CC7%J-ME@wE&eD!fAH>^d)FTfn<%MxWP8X^2Z-3x*h$&-B zOx0_o9NWo>m8A-QHp8A}n22rV;cdInEJYlfM<2G9V@-}KXUZvZfzB>Nm7n1Gnm5Zw z@IXWRz5^Yg7{D!s>tV#Z+3zx80<yWADB^i%&QeDFl>X6%uS6P({ju$N%;r?RgE26q z&Kmr7oeL6|j)&8Wg!_`+GABcj#2{jG9qE~4$nK6s$J|YJev2nOe0c3XKV;sX1P+;0 z-C>AJhpSsYAY_xuYY18CO_=<-JfArVSaf&tqYq|ns@I|Ia4msn4Ecpeb^i>nW3OmR zjH2sylcsn0v?wysvlO$CEqrcGBKLOiBF~#0GZ@JdX!H*7nI=1qmn%8NPF=2V8I>bj znYV;WM38DDdgXwhQF+o==#F<`iL_ltY4O_MEZ<Z3nQ!Iusq9d?5O1X;v#MUQ<x{0s zM3tYVxG$jrw_z3-mF}X4L!i*FNPog09~H{F0&n3P9POKDYx*!(RP)M?TqgwCBmt*^ zg)6U_{SOja)Pc0S)g-%LK!(Y$Ql$#BFh}UfHm|F+OTO!@vG6+dJF%%C#mTE4PBm-W zKtQ0;3d6Z$VG0~gEvsK*idkUV4t{dlW|e9?kMgDkllzMjU}omM|ALbW3`oYT+mzut z@b_qH0tkKEGaI%AHw%%^4NDqze`Mtm+YJjk;<t7GWRrf(beOieBo|*Y%DOY>YE&Vn zLLh*y1EVJNN&-EVBBugO_FFO^!D~k1=2t+PXFLsj-6ndae+r9M$Lila_3_Tz%)G74 zrT>j^V$_UyflS@3eI2GR^pJlW`dBl5c99UHF9$Mm(n&($HZ2e_`bch#${#>HlXfaz zWf?xd`p3`jq}Pz2>_S7*www1rD&HlW>#WPJKu^F0xpf_tEi9pU@|+7E@%0VeG_7bi z!ng@|-(}Sc&xSmrk3aJ`GNLqipOj6*#QSB_=bIA5)NGYm0_~|b(_bIX&V_TQec}>B z`J_07nGp%&UN@}2as+z^w>%7!3Y1Y@%zve3^7^==jVjk?(^}hsC7Tdb$m;{7pz<U= zL}+w`rbn*i$615?9vViRY6A*Sj3Wib_>8>kf+<BndRTW_646~?9fM3QZBXRZ<+RuB zn-*8^%8MOJc=a9Qz=P^aq)0;Mts;IMXK5$#`-JxztgRD~dmi6y?QKlD9sRctk^<XH zo;YeS-aBvbbU)ND?mVdr!BhWt&q_qE1$ps$m|cNk$Tt5}NhNI`^|-~q%Uo*H(bH5f z@nz7|U?MKpPnctt8}n-9W?E<A_T!%cTerPYXe@$Uj(hOun+cFQND>2|PX5)A@(wYd zf1vT%MK8cNo(-+_+fRN<5G(9PdD|i<xV_&i>8SnX6=%d@ZeGyl1CGz+h_|e{zC-#f zl)8*L<|BdFsXnR&;kXwXJ<79X*2-CVa9#-TFlMrEVzz>XH~CHs?limqQh_uve(Ga> zx+u!#+oIgf%P7=HJOlOtsk{G?i%L`!MQZ~SlmA~(W2dPE;Xm@L{<0hlOl0Yz40Y56 z@*+ELhKb@e4@wuL3|!Nx%8-1f8x>w0N81suanLju`bRBJeao@V9?V@Cr+U2?31-n5 zm%$mOcJ3L!cC$VjvtS5m@quw`!ZAgHO`=y?_^u!WOUc4I!K)IVsXk4E@5}r@8`Km6 zymbA%d~iB#)kwYf2&R!5gv3Jsdo5Z+_(js>oi?nR|Ek~7im)4z)mz`2bi8@z)(q(~ zpcA&huiah^hCJQ%wPmD1?^z{xR@F*!>&C<s7XzP9lxxwUoKMMld_{#!-Q?S7%3~KQ z9;pVR1gJ>Eo{v*O3?OiVmlg4ubX(Yv@ZFI6DR^A3l+?Ph(udcgo2KuI=&+rkv8r*G zU`tYSWyXKr3hG18yj;-I3=RIshAum@FD+1N<6Ui?pUhcS)}i<ffo^@vR<&#gPDB*3 zql&JIJso@713>UWKCzs_MV7s9za5rSn@D<;P@Gn|?vin^M_kD%j)&B2$&$BGe4qa% z<KEjyZU!v(n|w!=J}QzZ?N_;0Ix%duQ6%mT4s_}NF(gTnfB_g_V?tgKjo}r=cC$Wu ze&5d393201e=TYWs;-n8F=gs@idrKza9vF}!g%eF#GzE4DNu(x8W`_Kj{KSCYEG}T zG!?bMiUKcbq>uo^5@f!Z!XIprn}~FV`_ja)e^emLF%sw@H8Tjs<nU~<aDcyv?PtPL z&#-d1(y_exHx13Z!c)P3dNA6Via6T0q$S<~$4MpKe9^Y_u&5ry-R*j({~`zZ)z>2+ znMd^z!e-gdw{_X_5X?5l&Tw69*8-KV{mZ$NS%vFZ7F3he>EhTAQy%iy+{d~)CZs5i z!)qxw%MIX{@akdSNH^m#%~ydI)Ne|^e!v~2{ai>eh`Bj;#i*@=SYnCcsHT@ISF8RH z3iy?eSOov0F|p-r9Rlap74Z`Pd$o+$9joSbMSyfX{*JTm>ORCH#vBW893Y;-xgTuk zbwIR71pUO}j#qS?CbCB4C=dB#n!1|pxIa9Wd<!(f(#H~(eVb@NDP&x&($<7HNhTbj zFZ!zD9lp~I-H3A*ucB8!-{|7|yARq*K%T2`NX?=E*$+O<&Fw`QY(6O6{qh1nV-z{f z+9#oj8;7ydiw^QL1!#FM!P1=NadP$xgiI+J`t;5+Y0*_Ct)P?bnX5aSi?2~6X4LSm z7VFN9l35BQ)(q9nV;vUuzd?PWj4t(rw{R<C+}>_57<T~u!xK}6Hyg3QU2>4zPVhJ3 zSC8)Z{;sR4>FDLD$zO%buGp(GC;TIFa0J@PFq&~{2Q*PPx0$5(`lyAMVLciZeRpQk zEP69yNPk1>>{*V4w$;xk16_)Hybf327pgo%+0)w%fK_U??YtF*?LoE<_5Liv`}3ZW zPWl0Vg>6gB_<X4>Ls-M251R72f{@?gz~Bt##)&O`9emtsgR8Qp{NSJWuAAdhZfSxw zPQ6F&_@8#s8PqyRh-JAm9>xwT<t7;&{ZQ$u(b94RZ<(MCTgct6CBH7I(O7k`*UkEV z=z3lA_iX(qL`=)q7Sv3>yomp#(2U=O&QWHyQ^7X3)s4Vh&nn1{SCMf5w&$U<|Fl~1 zb;63{o}-q)N122kXb6jEV}{94yy2JC_#4xixsX4|OI^iY;n5ZW5YbN-{@q8ksCsP8 zol>Mi#ssi+Butxk(S~%;RmD{|lg6|3Nzs=~_bxv(woVrU&Nk2^EF$N|X{rEr0K7xG zo*o>C{rzH%oRZrum<#-y3SZKWY?l2Wmk|Q7GeEV1#t4hAj5OD!%DN2uhaAbd5<8tQ zPKG1UE3GCe#S~S)tRx?s^c;Ye_)rBinQ`XPr+IRoGBLlD6%RAD0i0`tn)s|ZM`45s zgF@Vkynzlf>rVEn`4&H>Nu~cRpm1G!Wr-;~a|LDEz}zz|?!<c5QFg(BPCyYz5`|$6 zNdc9f3RK{-g2v970;kg8%etj}26s1hqyBoNw2CwTSZb@w-oUnf^7GKjUB9gel4ueh zisa8lP{u$9=z!Uz5lN%gx9dH;K~ebiq^rHFfwyAjwpaD}RQ!K6wXzev&Q<u<<A%`m zMzDCm_}<Dt1nRb@dQ@AAAA^KnITK1|2GxqnGaR#j<*_zV3j1%~GPIK(1ieCs)1z$! z-FI8iOcjHrqs|I<eKJ&3mM579wkoaMY$5b=`LAAkc31<eK3;e^goAx`N?dr)mz8n< z?IU~1SJ7u)j<KuT(P@U9TI6fR*bpUpx$Oj$e>vpb8*zWdq2vnU7-TKq6WuDZojgsQ z_T~owLt=cyb(-r?Cv|BS+jZ|%7>_fHK<(~x_}PsJao}JDjFZSD8rNMaup!BYPY}Gd zP|d~KDiF2$0{@bq1cAfhIm^@J7)9f4UuJZ^488!Tl<P<w$69)bgoJLx@7{3`H;PHb zcw6D56q$XwJQp^=J}xCHXF06XLewDgWa{XOuan`kXu^zKm(xvI>Cr;EFFSknE4Q1g zjYWYtH*a`H2O{c^WH8!bT8xG>q92~sGU*@%Bi<=-=F&}JH6QaOS(_Tm6i&#h8*M>a zZ75_hqmxZn0>zmtIqC!hBY<R073<wI+cjX2*>2REP|ep3_6!314F)W%k4IPskwD=4 z=NVh&o^K$D;V1L}U$41mk`22jx5iiA9`Uk3S1fcUhxD4{Z2wa_A8#S%9Yuh$&Sozq z@obEuYAe+OuTekBqIm~RQXD?WzhZlprNe0DooIH1+MksJRX|b8dem`exmvK7`fSE4 zLmo<98pVunf*}^gc}n40H4_a_fI0QY3lDMg2)j%i53xPI-r-rN4@5{M+BkXdIulTe zQyUP<p_Bc>7*m*7C4q2|IGBUR`>E;E$Okjwzd(>F<973)at(MhR_DEW<WDl}STbIc zx}TA5GWCWG*NiUbZ7ILyJHJa>Dy3C}xz%>C?9PZ~&q+36A9;uo+>N`K@lC!E;q_U) zp>5P`NZX`unT1v2xKQ4T17-@O4Ll+U#iDcBE=5q(Lk?fY!agk<kXyLiF33@r7!fCQ z#s3uJ;9>p|ul3N;#XJWTdyyjJ>%eUXXk#w8cL<tDyRfPg^GdzH*o=F3cR1oz$6%&5 zn4`=rM}X)r-7m)%7SKz4+CkLXNPkrkK-pWuqQ?CXWB1e}3=?GwxNY0EZQHhO+veN0 zZQHhO+qS#syPD)Ab8)Wf7gQ>>v-WyUyva!1<5ow@BTX1#4LUK>I*nP|K00}x;6S;z zFRS_t<<`23eiz4}nGmj80J1B;B(gil95U-M5oL@k(O$3^eN!<WE05BS$`Vyr?Wdrh z8$?4g6BT1dQ<oGn%u2gd@@Kb|3NrfSf2^oIh2gndY@O)lWWWasu%B}kFq*Dfpu)pG ziuy4{{{cVX+K*CuRyo=s6I~KE^#-MAG>7gI_f@}9x|8{2Ec|-J#!!O+N*8k_@?kZ4 z39GIq#U|F}MYC1^0W>$$#xtal-7xuK&DxcAbuazFV|A={Zm70K2RP~ehcjt59<tM6 zB!aj=2S+fov-<+L99r}y+UXpK2En_e$-oB@d|CO@d9KnR`A`dyr>AgOVPng>q=b|h z>%ba-<@9nK!eW;L@AS^xMEm@e@jQfqX_LQQDNXgqOxl#-B^8TshkyVe8>Kc+`RQ7P z6$a}WP4kjJ*n-W(#hCqkv6T?38gVc`YeJZx7M(Q-c(o3DpH%t|s|$e~@YI`#C!}4^ zr7*q!q9kz_-gds<P9VP#?b}psfDL~TF&ZPny0tXN3D3ogFjD-w*<FMCk&M;NMyc9_ z#l%ON43~!0ewQc~L|!<^f_y2IB>|o)*0E(ShiRTMV>Rd<RnphP))YwY_Wq=k-N_Ff z3S0-ns>CUVK6Pw~EHz;y-$uuxtoT3ram!;@s3a_-i56Zh{&00&IE)#6o}hQbrO>xk zpR6Xd4W>mY4vuuN<!LpLE`p%$(WkWg_i+pbQ&f^Snv<asVX_Ck1`0~bpGbBAiteTx zz-S#ha}>}Cbs%;B7(w09LXe(ut@T?fTgj(6?m8`{ZL&iBTLQIxWv{s#{8zc%D9N0l z{ZJLZET|Xru>WPe6WkyA6jC>IeUUBm1o<K3zmH2NS|zJqi0DX@@-717`5z|NW(g;? zW(7Cf@y33fG?}c>*0*AT12mE>MWj~8Qp(GW^3EZQsWpcHlaI_YN<7W=7mW+A=PP~h zkNPlHT52WB9My*)@4sf@>SNiO(h50PO0CPcmC}0EzVh?(xxp{38(5LuEpJLWDxXCc zUWj*a4`P>}0bc^@Db@k*K3G2%R9l68d9^--{@XraEOp7~6#N7Lc>5{h_{4((*E|y$ z(_|_s(x7_3uEGjYH3~h};wFo(*<`!>3|-UXM9TcSE49nI64KOpG{)j;U3YQHtcxE{ zvnF*QLph?tqxU<KBzxy0lIK4rebMU;8J>~FAf4~!5x^*@#1u?eRlkmWPziN=)X&Mc zU@ns`j9Y~c{kSR|6z9aGbzF6|m#%ICB}ab%Qw>(Iogq=UMwB?LBwq>CNDqrVJPl*| zt>p)2@90UiH++y~;Z>6dH7i6orncv=5Yb8&+QV1$vndfIBnNKX{=BeKdAA90YDHyJ zuA@$%FrPaI4?$m{;8uL~Vf&-Z->AbEbW2oNm+AsSQ?=TvGE9J#{8<_HJah)}@hvZ1 zhu41lj6d`AaI$n394n&`R0SlbljqRsczC^Xfcoi2!smXzE55wVFBy}ECo7GPsY5~R zFW&ePMC3rCe%15kM6g>1QP)NVDufaKVq_7U0qAToAlNp4cvW*XtZ~8yv7FFv{l)4R z)8_mf%iG~f-!I-0_ojntBbm5ccC?pmrSNEN!+(sl(IOxZC6Rn6Z2|A=7%MEf+2!>K z2YNRyOVkW{fQXDRG2YYV2S&_5EWft232Q=>F9PQQlZ>E9FgpO}>}1w|idQ~j2e<uL zyikNqI=&g_zwzv@fpek01AMiurpf@}`)G4wXc`62Zvf5?R)-UMq&?SyRp|6RjTW}X ziBYd`=CCH@#qxx5rmlpc@(*%uW+7$4LD{F_9U*JWAwlN=-W@~<s*+KhQz<-{Ac1*S zl+Tc=E=8QJbesM6q6ojJAFqH8zz9j9y2pJ|0H`}F^jQoab&y%tAGS#TBB+fr8(fRT z2&Zsb$-18Id|{~M1DyqLeTo^W<H{e*w|^_k(5#?;f1kA|f~qM?{(?c<`$Z#IN{(AD zn)Y?8t0^h$;%VkkAGPbq&?KSl8>`NO7Y7<yDDmz%fH=&$AS-99u;et76(;6*TdLYL z)3JnuoIQ03om_Bz0vOJ=B8{jB(M%cZ&Cp+s_<Wah&6%&A2&Z*7F@9_4ck`45)3o>A z1Ca<`hE*x09=ePX9^a=G^J-qEJ8-HZId0etFFp6x|6qXm+Vr>Ze8*4kzwWfYgccLF z?08JtP;@qh@2^fZY+_}wmATwpZ;q&g1C55-YiLRRkzi=x)Z}NP$V@ymDH>7pd}&g0 zUVnbRt->P1j!cm5<}`a1G1@8zrpK1$`3MJO20A+tYSTmEu38sgk2TGVC3L@S$@*3U z*(z?zMo8I|qQ`}vrd>HYojX;g69Q6e0v>ohClUe4Oy1656Ov+1tPB}<!R)qa*j24B zB*IzE=)>y#e>1}Mll#%F#cfll?u|%N`c0JL{M^^ZU|t*;T{E7X)yh$|j(>ooHNMJn z05xEO9bjZ#RT(*->w5^AQeV16QrCbUjqO|}nyupNb8GKZ28BW<hTQ45#<#N2SM=a} zrTD_zeP05K_Zz$^)AD7zRR<}>7{iN`2CFXp$@#VDKtUccY)g2!y#UeS>P0Z1nrk27 zDiifAR__x*cA5Mku9sh8%Hr_A6<L+)yvl*Gn%U*V<;E=@kWrTw4WDtHZ}RHtYAjWL zNL(VcRbU=GFL_!k%a@{<2!^cQGvAm>KJio!G#{nN!9*#2^)X5)VdgpHHIk}h`)aBu zTX+*6gCE|)c|4O7O!P*y)x+vntQuSo-%wOz-~NQ>xzPW26q@D#j6yU0FQWHf6q=ch z?SF~A|0fE~!pgw>{~d)kPByhoGF9D7VYBO8Y>koH(zM)awdHPFY_<LGlwJLjb)Wkz z^`Ci;>ss|R8bfX%cFS(RLO7ZlSAMwAzQBUe*4$KHP+V#RE|#Hj!M#3qr6DbUubF-U zt)_Va)CWLDVQdJf35@NDOex8a?E&N#*bu-cu*e6`F9V-%XlM{b1O}<D*0qt1j=llp zM?FcNprD}mn|fRW&A)oYA77K@Mkba9m{<!g3hYQ}2@NdyQIGgLi+ThD1MoHm4k(E1 z02C0=5>u6t0=ZWfkwPReGO#qLGKPzHoM&ZU0G3EU$JE%wj0c3Nu>m~&;{tf@tz`Mo z&cuCDr{Uucfa{;#6qq}{$_#AE4Sdm$Kr*m3ur@R@e|v#pXaL68xYXG6f9c<aGBBzz zzs>(k>rdO6zr+_>ZB^69L(^YZXTYT9_U7i*Mz;3uS69OnJn(;LW?yai%i5Yfh6dBX z^z*#bzTo_(y}-Ywo<_H-Gd8jWuV;5?{mYVG1IV{GGPkWgdQADEPH(B1;Ag?PmZ6FH z57Z;=U+tIp@1@!9pS`7?R=@7s`KaRp{1boST3tP*``d2)9J}J@Okdx^OvhFdURdxy zS#J89v^6n;6n%2n7^Z=(0dQ&lYrNvt_ya$+F!+)W_WRAjY@|ox`cz9jr33H<7N)?W zr2eW)4#@knr&9i#i~Qy%c=(Ix|090<{fqp%!}`IefB3um`o1d&#hsohaiQr2+t-%{ zyKgbQ20#kv^9H+jU-%}i{`22iY+zt?|FFOP=_+a*=xhIleY;Cf@0nE>ey54)6)7kw z{YhIGmRld*5YQhT)|<mHC^!CHsqw%5r!QkOBTEC@tMXG;06@j1wdp^E5-s~YP4m~9 zccC9YuvYlZeyT6@Gn5skFOe#*mV4N@RrBXD=`$116BPA=-tng!Rh;tckM}!zaMtDo z)~>j~SPxi^VWA07t#6$c6FPC!C;1_d)A`3GeYw7s$pO6FcUfBURrdM!^HrC0+82u0 zxZJe($IbHi%9Z-5@BEq<)>oe!TyvAw{n!1eulhIkkr&C%;J`K?tfg1Kcy!M$D<|Dh zCp3kHfvj?OQ3#9&QBPN`IzIPOTYvd11-ENN{qv)SDWJ<f@Vju$<ZtxTOD@;TzZ_~M zx0zw#kPv($D6yIoRWG+VDb#Q$U8D+;<y86Ku#1zt0kUvZrmDG*myEjX<qQ_ayf9?| z?eH;SI%}SB4Ljp}0Bcs6zJd&@1h)4U+emeHf>LsO;Rx7r?|xsv|BTh*4G&G!426U- z94^y*5Yn%^XUcx7OREQd9$oxYzfB&omsWzlBzf*+)E@Rt<@!ogw%oJ6`IgK~T%&J% zvJwC^mJ9N_;~q-_-opg2T;ilMGQ`)=(?pV6ygNDZ@VwYEcb8Hbea^)P-guDEZv&A> zs%aNFzDuwvUZ+^<oDN%T<m`%^&r*P5^A^IKGqFzzmTqon9JXaa&F#1wY-Pg&X|=>u zpCnP&F-Bd@@Yug3ixx^?J|qJbgNA;ISKAV`@NrO4@4vPQ3i@jlf4OqR4D=Hy&zKKX zcP|aW#yat85A$PJa|YgdQZrL1wI8;toBOo<tl0<Rd>13=3U9Dp1g{-+)#-Srditid zuFbABhKyN$P~eWr77R1%rD&zP!VZL@<S`h-@=+m0s`q}a8LSn06)9X{A%)&G)?d%l z%kDw73vhqB|5B6NfI0HSOWWlf;Fk+hF{7VTO8K5cy~D7U!qr}0vi$hrASJ{&P$}Q5 z-qAH6aKK_xYotr$oz!^-v$NjFR?kWF%pUyj?gBa4X0dRT!<S}O)?B*cjLJENWmD5| zq;3s}S`(!~B^C0Zh=06Rhr~XrnK4q)^!FJBMH<R<B|D``05Z38@SZdvoz9Jkcw+t+ z@z5Q5>La|A?3ZlO+0y|je6VH4kTo=e*qq9h@|9+WO|TmWDcMY!P<cz-HPoPP?q$nP z>$Ix#;b6{Hy2ko*%`3H7P;G&CG$bRf?40d>I<@XCwQy_`hN8AH>X&iVYPtqG4~BCr zQE58a_vaRUvx4cXNlUk6NoFpTJG^uVLd$`kOOVBTCD#>h>Su^cjud0eS=zH|4~-!Z zU|FLeNa@KLA#vEtjwg|0*IO8Ve3AqmM^)>s^tS?cyhU&Sez|y*upb+tc9Cq#CXDgV zjE=gK6fzcD@K1nM@0hi0S<apDbvk;Y^^l%rfHslJ8k-TBKsbYR*f$uU)c5A*kqDkc zBM7QM^KvF6yl-IKl&$iF;DT%V&|{Cpzf;tcGdr(D1?ip^>phW?^7)G_2vC|7tpJlU zaldfz$SrvXDt<}S4%_N~Cl)4p>p!~m78Cd8rA(xI{`Q;23{AME-ATp~2!}Qyg(A>@ zYa3K_GRr;Py7R?oO$IfwFie|p8;C)(DPZIGVSOqf27<WMaM!)&X|0C7Z|3oO=Q(DB zwg#R?xm5?VsFZ*K*XpAF&<DMt+T<3>W@mak#12kYwj|S1CF!<!V<rz|bSC{+FM{r& zZ%)kVA<N~ZXlK9d?QwYE^_@;?&^p|WAtSP|ma57YG{L_nvRQvwD(rRzmI_W%F|^yE zcZR}U8}1wfAl{A^Scls~xNu&qI@?ek#t{7NW(c#Z^E2f~6BuyUQ63d;a2Ce`FTs42 zxI@@HNsEx+q*4enNE29tj}$q)9E?;*w33h3g)D?lwzzMJQXU2{;uu|b5_#pD%Bf5q z1av+&X979=gNdB7?VrDa9ANV}a1V4M*=g<1TzX3*WxGEo3Z3&`9n(8z<H|>#@qoq{ zW#5bLA}9+QK{Bv86$72R%YHrnrFlER7C46vKKHr!-ClM^t86JiR0%7#<n7a-{p+=B z1RLzqtJ?PEyBL*}JXv5n`J$K}h*CNMkjQZMkI%3MsJOis+@PC+K_5!(b1!0sS*lnU z)U;PIOZUp_*NptUG23C>X3l3^KFadd7t0yaEJ-`Lr1tLGK4JpS55AbN)LN!@EIQFM zBazrorfGZ2cMps&eG<<`JXPyLpITy{&w}X9<N&kGj&llRU*V?xVUU5u!$^iPO40CE zZ-E|n^x@d0D}KY<yJbe%ghjI}*q;}mqO**1jAPcT>eZ-?xeD@11*j)y^)T*@Aqw{2 zw|(qY#9dQiPVPJgcskr|JUFXvrpH-eg=iaLtUggYMVFkAtG!L6Upv;_snA)yB}Pnp zOhXMNSUk{$8dj1CN%E8u4F8<73(y=MbgFCbiABXN1FA}rso*t=pbUuY4q#_9k=Gr? zKY=W*K`4FizIw&du~A_+yH<kJbF6;QIwp`5_vRT(GCF8znKiyrWX!*rt01M6nPS$S zA>|n`L<My_gjL~3TU#+dCc+aBf!`C<P^q*Ck)2jX6n;B0G@BF)^=j#m{X18xl;}MY zTkC&*n~Nw`w|VWQkfry1z;B1luz8|if&6gp-9R_u9mlMlDK8ndzrB927{m~B$G{EU zgn0<&iRIVb!A6bDAA(8Hjo(8f8Mw`=W3pU}5{A8P&0`_k1%h{D!HLRhQgF&#&yOI+ zmi4?aAbfBK!gT?jL?(3kXLZ7?)zJ@W$&i-`-x&>uoOvsZ+q?sDx#Jrs)>1s!`ZFPb z0Tk7rRQ=MQ)>)YCWezR#2qO{%EqcWC!SZ;qSu&L*`Rt0oizGfK;LJ|T1IfU5mGRMw zBllQMgO8>uAE1GxWWR>Nsv|E&c+eU=f07lsf}0`~`?xKa4C4H8>#N7P-td&s-Prbc zO-QR7?Y3Y!%chsuP#S-BiNE$xa%A+$A?zcU<Z*VWF7?7!s%DBpb}J_neajW@va+p6 zS^zuGar8N<OkA=>;92A{!lO5AeDAI9`p#g&lElp=1I~WHUL(U=>KSOX70lG@HTk?{ zfnL28&IG$xead6x)%94+F>5~rxD!R-vd#ZgX9dj5o-c4<102YG!9O`tB*uxL)$s66 z9p$CO!*6-nAMo!*c)f%-(4InJmGHG$6u_Yi5F>oRB7!#|$V)p383rb^7y<`pfp&qu zwVUmNU4SS>yx5pKSh%V(<~ByO66Ka2FW$~IC&4_Jg5O|c8|$%pKr1Jz3Hub(A4TjP z0gNY(j$Qdrq5%p{<gMqJfm_=5$~X;QXY&S;k0CYmx-wa0y{OnYY(iC08gO@V|4ddS zcR)wJyLRPkwPdQHeIKGcPkX9S9U);2G!$Fb)f^x9tChs9_X}|e6U%IjvK#UI-h&3K zjrUhBlc0owW(LAdJ(<g;+6o~_mgq3ngC11-Tz6m9s<3SkXr7GZVp&-)EJKMvqvmF5 ziG&<Fs-{IVDpiSGQ-Q{)Rfkiy|8Y1Ly!-~bBch;L$eqiqLEnEan_?4}s}dK}Wv+9X zZmI&}B7_OcU{3hXV}LyY7S_F<mSOI9#(~~}jzb7arJu-P8(OV%#(brKiR-9v=qa%+ z|K=f8rzKCUejey~T!q9_{9>J|EwD~G*%%$Y_}Z|!7nx@`G91Siwm9s)b>Udef{2&F zIlj3da|;zu14^{e*orKBe#&3nxm~UXZQ@wSuJm=9Uoczu&l*ikQm!q#UM(H*DhLAi zMU|pHSkR5MyLm>qR|=V|ld;f2H*5wCW@vm?qh86I-8mFO-<JLM2-}82c%O1tM=*qu z<y#co@aI}G=0b4tX;}(5uFiLil#;7$w-6nj>?E1Bik^eW54_rSb3zwvG=+aQ@gJKC zSd0a(U^A1Y1dm9u|CODxB7Brof)FsrKNf9Iq9l1W$4Dd_LEqw^<x^w|xIB>t!1K4T zf{W35j&=q}su&V(z;m0#@oa2S&b`O0T+?x3l^X-`-X{DKj`@ZdA`6m&0oZkLbFT*y zPg=d<?fDQI@R_|L`#f{9WgwWKpghJMmB#(Us5QpsjZ<?68;|wA6U;5YF9Ex*(Tm=J z^}Z2B1RN?7ULrJzX>}}EC{z&w*8AJ3s#86WVvejg(a?8;g1P__A`c~y)4j1OAQ8NH ze|Q$4VRP108Iayc?^c9K+xQ=-?LXQ~XKrsnz(%r#h9Z3QaG;`+y{3RkgNN)b`I>)I zkKnXn$aB*i^rx5ddjA>8+XwGrUCz63Zj$E!`9Ml*!SEI_w!Xx3mm=GKv`-N?>duWV z_7%Tk-Rf7C-yfS%;Q$UPi>??D$_tO-%1m45dAX~%eI$8Q=Hh{g99fQ>N(M#h2k#OP zogAfes!ii^pkYR$yS3t<LE;J~Pq-R-8FB}h6sa9AA&Tl$xWG*1CYpHuGF()Rh2heD zv>I}We(HX+V%6U=UyMwHX^~l(9e&WInv)N)n<wAhcNyo}ylkUfK$&aF=g#9i@(1^= z+${Vr49TmDlx~X2d3O1c)`uzq!Y@fLIE$df2w7Iq<^k9zaXCUwN_U#jWrYH#681>j z7xucZM_Wuk)fLyZG|@+NS^+bDkDm)bkl$33gAOh5`jUlu&;@sMct^SjH4_y|%GH}6 zCq%4_*Sw^DZ&4^Ad!XSPVryk8@m;K&>RVNv)Jo=D1*`XG_=)K&c{d8q>DG)e{*Nuf z7l5T{!Z}0^+HNyLlaB6QK~>J_J-^Cy%|`z^;Ne4W-LL($vX7up)X^J<PLl<crNmBI zxLLlyGLRb%{mLB#R~^tOKtj=!MmKyt%RYp>g<?LI7-$Ht`He@%ZQ1vk;@Ix`PN<J4 zveD^oOEGn3opYS>oJzs=JA1JJW89GAGX6T$&8Z7qxr>t@;(%6i2Etro)wnZfnVZ7T zmRd<K_w?^YXaGo@sBI}-S1;*`$;kn!O_FaB27{o?AOW2Dz45%~ALj6O5T~vWK&q*i z1ygKr@~#)L+HxbyuX1BJk%S&v;%z&H<$H!9K$mMMvP0q*BCFD<Hg8T|P4_|K9VyeS z81*bsxpAWV#kDfK6;BEkN`qDAbD<!<4P<*Ku`qj0kJ*o!m)SfYatIlc%OJ6$&ON#< z(v;b@9gUb6mY!!rb&yDiz-=T8>yHW{8sCG?DG9>2v9W+GLB2mJ=Y~r99+;w%=Nv1A zZCAS7<Q)k2cO1^*D~Ep;0k>vTyMG?5XE(1LSu2@ry0Y5*SOx`^J@zr`N>HW<mbAd0 zI09X6Mqg1(;hKY+gXPE|>;C&kE-#C7>D+*PcxP~PneyPAmbWUOte;Lw8dDp*DCIh8 z>aWaFwBhLCTbB-19%J({)t)I{1i;%}w9nM<ak_oPI3{5cK;;<f5pieW*{j1oD;psb zz9pXhPAgr`(;fG4O8^MNs}IIA?Qk$~bjDI$w0;kI^n&Ya_P$qyp+C6s-hGY7Wb+l{ z>eyP!;vkvu=`Q<DALbB7{k!1pOf1A2^n!~n01Lx>@d&P#ACC_E#pHj#SZ?^^l$&M( zDL3Tjyy!0MRar|1a(TdA>j&B!|6<NYJicRfqvLYiE|+raA=3-JVE2UNS@-UaznUY@ zRecBnolZ>{9}>3$B33rP-W|=hGa)FZs8s~|XDYLOKCyY(#y5%U)nsn2zj13gU(*~v zVo@^uan|#aG`%bFX(o$qAT+QMkXcESl4#j{dEfQiKny_OjqfG?z6Qg8x%<tt2E(wk zl#W9+g`mYQTF5W1n(C094IPxVw?lagSKkTTrlfH8h~S$8nU2Y~rJJQlEz0m0#pHDI z^xx|Ehi*0~D$FVw9DkL$E+M6db1f6Q*+-2p=VAW*<&%ZQ&*5_iyA9KlAh+eRr@P4# z5T;&Zf|`)SA%ualiP>cwP??_MF)IVB5>U+*HWNBy&{knz;ohQlb<QSpr%DkZxE&0r zqY0>zSa{+vL}gSm!$E8_DRz$69C3frlHHmPnDy1$3&?i&j$;)bu5DCXVFt;lq^)C_ za9^572??-Y&hPTXlfY%_H>`U|MI@j4fK)bO@}bD4iR>mg2uCJw6XQ5EVat1i;u?Im zrHRFZ4p2!-<DF&<BW)5NJNww_9o+fW1*|*6=oe+2ms>q<Z(mYCQ{%M{U5KfMBXXK3 zkGo_MEO<;eTV7Rf8CbUeqoV4D0q7o{rUCjZyC}7h#zyp8;b=VxhP=ElJ{S|xE<$z3 zEFkWOvVgzn+eX3&+%91~WXY}JN|G`x$WVVq)@v;JT~@|~EDMvqP68&gGI=@ov>#h{ z)KCP%LV?RwnF)fvBg?8jH=13)!<ATmWJTMUb_63H9|Nrytwb=2Wo!cLNs6yh{}E`Z zbWEwzJc9{kJ7g%3wIN+)-KPwN({}FO>o4910me#MkhE%OW8Oby=Hdl#$t7L~8^D71 zvm03@1Ms6sj#t*#pY_36gmR`}Q68hLyu8YuSNT>2@BUY#<~Rmc=wo{U-mK4Vbf)bH z>4VFlG$YjRo9FAP!WrNC1iY*``vCSz5NqGU>a&-u`a{+8)!R;RVsoMX@W)gK@kCnw z5i-QlLF1BS@|~}%0{CNz8m+k-k}ZWp2l20g7K5wb8_a^L18g_-YF@R2rMMgvuON+t zOJ;w!4ZAl|0bT#2uh7o0lL2!$RY?*m`s;%!KLc@%GsT~uXXmsTr}FRrh~$y+bxzE% zi-)D-B0(aoqs1%CZd<DPiA>N_KZGd9ja2!viy$>@CNcxEBh@V01vR;HsSmMCF<5gS zQVwQurpvg}K^TsUu*0%^{Wqh(;lf5DFqFlEIH6q!xJSSEOwbv1);st)o%+E=zE@S} zBX>iu&0b;7Icst_m*m3sQ8ZnCN&U^#(zsjUvVfhQuZ(?mrW?`WJ0`i6E7wz}tn;f< z`<JMW5+OxyH5elV+ejsT69jZS5T*)~RjxYQXr^?JF>74=8Sbda{QeKeR49j1MZ_QA zZ}Xl~%8c*5cQLw!{*U0vh%>2-yd=TLM<^U)5j|UN-zj!PThKYTC!C7zM8BTHJ~&>} zn%Z)<o!U3*Y+snP-5KY9(v;OD8C{%YE%x|KfQ+-JoUh299InunM(_0ay4y`%-6<Mk znJCwhWk`D2y^VRrb!%w&z2-MY7ramyIl<Db3A!BbLbm!nQc6s$m-LF)?36c<dFwt; zXLzVnb<K>L)EBsT>>Aqs=#&T3G`(94$q3Te`JB~F#$-XIn&4P&E*#LN<n_*-l@)%8 zJ*lN>v<ncLQ4yRnPRgDwlW+BnsNWMze@Gx{15omC7L!R_Mlg8^8*84&&;*Y-D0Z=( z<T@7<KJJ{Gj#^@IaZvQHX88GnZ%P{hBYK3_@3Mz7c<va>bWewd!h2e5s8o{G^F56$ z_*48<t9W6_OuI&uR`<VZ(MUl5G*$59JpM%18Bz7cn<N~~C&V=>Gya~&xq)344!&N? zKbU)A+onh)F#gE_*iIEgRCe3FtqL=riEx+CbJYlEyLP6CtN-Z`(L-8-h~>3sm(E6} zdKf&1cn-0fWzA%s@M*`h>e9Jp8NBmD;Dv2Re}#%p;HKIrCL#G2H?Z#rK;%bgmfu{e z_|7#iXq>1EX{Tfla^D^XF~g{-n~Ml)j}0Y=Z)SB9W5f(_UTb6V3pqZQa7XeExmL8l zhkj<zS_@p3t?Tg!n|9fZ-x@9T&w%1~!s67hszZP4tnW;xEuZB}yg?-q6$H0B+E1e2 zhG&ShVbZVq(0fZ_+<SNj1}u%VlZg~?`XB)9o03SW3q_dRLImnDLd3dl7V|NqNWkf= zN9L}S(d~`(%;#EfjA4>_CoviT(Nh2b1rkM)QVI&DRR<W~yph-)wva!ENK0<?BAJWk z=O#uyEkL!wo4FvWOFL4b#ka2B%$1=)Q+l6HL=#MMLVH#qse>eHXAGpveFpSU3oAZx z$+6s-8qSVjzX41ZN80v)i~Hh#kJlD}NmdnB=)q@`<Iiz9agPi(;th+u#Lfy-Yw?9v z+S2+mt2#lT=N69dsFoRoBgD$}Ww$ejHX`*SP$&*sNP@8<R)V%;9i7_X{A2QNY*H73 z#~|@g1%&1Sp#|%R@k|OHc@{CHFSUe&!R7la|L-akF!^l>CWb)Oj4n<tow-ldzn`c6 zCJs2`z0do7XO-$VurkTvf;QY~7IHr?+ZW2s9|fwkhC^3rAqB7SgRQRKDkOVxzq!)| z@IcdlKri3hA1@EGP6!YO>b1X2QVw$AAViT!O~LCFHRLx?1#+a5fMFR4_x=tmPHpV@ zQiNt=4&WdSTDob&xt7W7f`-{TEHw=YR2}O`VVE>2`-v*$*lcI@Q=gF)v^F{s6_!JU zP$aM#`Akt$v;EtUt@Sg{E%Yr3@YbiR|4|b$^LJvkhO>#qh|8kRv_v&^Yg6fqTt?`@ z==O<|Q2%dfU5=iAG)2IVMs^ESx;%IsQDAEPsNS)v!K)ZiTSK*zo&O@j2sF=5zlxj; zSa+KfCShw)9a?N=5rJ_qN<w7-Q+)!1*{s__m@WWDT(rfy%^O*ac4LBq24B5>p&dx^ zD~IPK#q9oI$#oBHXY8@W;!j+L@H^Wp1tG<Ga7@Q~I%9Y+f2E(#lj{MQq!r@^-z|3L zE3ydP;AXH4SNDU5DMn-i{XonD&}qlM!Fll24G4tEy-@O)fc*H{#3(w?GwrY(65c}* zU$X3*Yp^P%8f*b=uWsxw`9!KV(Zd!Z$gMFptT!_U;G;yFizAe&%syuIWka#8w@o;V zl~&O&3KAs=5%1)lcJMSxQd1%59itj}`7}0w`z44&u2hznc|zw-Puo@{ohi459loQM zxb@UaJ$U|Jle@ohlx7xc^GlbsWAyJb`DRzMULL_hoiN|x$4_ncCx@&Pp^;`dGw$4% zB~gGHAOd<*&UNZqY7Nw5Jyb2JVux-Ni+j-4Ehg*TfaF;ySB9|HJ-QgiJ-_n62Ja+V z?of`RxefrpQ2Hmbl1y~vY3K&XtNJ_H@rcYZXf|^CNw$Q|de>qAy+f^8G<9*g9}SPV zdfadSaHb?nP2fMPp5R>)XhfP<hw}REXVDB-kI2cq(J*0fj?Wg$$$qB$gFH6(-3}F_ z_QMkIOD~rhid?H5J<Z$TZSg;cIme7#%NompC{6ve3AE?f9Pc?sf(jK%(Gb&br^^o- zoHPnUGypphHHiX@A=mVaC<gqvC9pEu(|UxXG>8MlHwT2U@o=`5be34O=WwY>(ZqD# z?<=<|zIiL<yb3JV8-gVHH2)Db#2Oy}YQ=qhFDgKh9LnE<r(;32HSCBM&6+f#V)DPf zZEXR&$5@W4GMbkpV70)(l2TY}s?p%-B1OQiyC)>*@iC1@hIknp6$}S7SKA&9>cTdk zET^C4EpfP@pSFM^J&R-REk#Sa?0SI00Q0YHOp_Pd_qe2QjJ%Rjp1*61s}oq;oSV7p z#+YPouu$@aeZ=PX`)aLga%oXl#bhMsyivuX)!ANM>I~Yma&Rdf4hWXTyt?}82if4t z^V>Oy<!OvLQ{txB*2}zNuPGnFWo`jL$qS*;m0cGs3LI?-*{~Zd7;O&A*pwTgdHb+k zk-daM2v-QhJ-}UMCyCd0lyzns0axS)45ELp6GjHRQOs2C71aOM*d62?g1nNL25!^E zHgKSIWHsd#3#JA6H*aF`k`dSMNsCVbL4Ksa?va!bI+bO>O;@*8UeuQ(E3!_pr=f4H z_3%`|e_LRCURAj^m5L9^C@R9Ah8nWMho5;XWtht9-xA%|XY@WykvU`)XMW7?g_57k zCx|s#Q^JRdQ77Pwdj`H{5^7kHVMcw`KG4&v)fSRXLoIW7t7pVue2NM4r-#>(%9GF^ z%F?qz*X*Zgll+W=L(HZzRA=RZrfYfa5UROts)dC-MylP8+0UHcsrVI}XAwQLLSNWG z(&{{nu_<#h*6y!t<V&2MRhy!b_BdUHed)-5bly8tTTnV#fG4g>>iWrs4mA5c^H=yO zfJXB5$h)1L6GD%Bt74NlvooYyIt1^oBvLDe%WctD3D)HlojLEur_5YNhykL+vgprO z(}zo;_X%6j*RLlXt9CH&!95Z@(YEE(*&}~?y<XgHoq}jGysvmSSC$lc%8KO-pu_p> zo-m&GsI86B!&`|o-CsK`kk_)_vg%2BgU!`gtBXT~Gc?jGw63?~Q@O?_64?JuN>T6; z`2h$IXk_NY>kfLcis?Gn!mEzwr^&8GzujuZ?d*_dU2j#iG^eT+$x-6u%u7y9=6#W1 zhd@q<ggM+5qh0tK9>tyb5RZs{k4v7^@r;{V7V=olO**@M6mdSe?B)6{oM~Sd=-?+^ z43f;I!A0PIY4&gAk|=9U9B1jYU^Zh;CuOM470sBf!Q@3)D%jIv;54F8_~P7Z)jOHY z4r)PM5u&f09MfYWQ$V#s%WQI<=*yPMl8hwwM8bRuMoecsE~v|qQM%_mR@+?L>bh8; z-{hACgre9I+refItGW%YiKf_h>&{f|&y@h$Ym;Q?l@G9RfUuwdVtS1!rV4`4)mfwW ziI;Zy(y}52AKW;*OQ*ws%N7*7Ba@~gAHc8bbmc&8VKKy<T^Q}B-wo$f!n<JI4e6@L z28%>6B6WX_E>XEpGuQm*i^+SB>;s~=n~(m$3A+MK!=CKPIcu^J!|@Y)rAo(_+mNTd zYA>`jR26_p`%Q#b;~(pj`tctW@M+=8suI}#hFNziVMTO>kK{uFfg4R*bfAcpQKM6j z_bjB7uP!&zK_5v!@)ZMhSNPqpQ)%lpfkZzy9q^XQL{tO6eB5gdqs8i;I!2D~M6IbQ zF=6YD9*xBbPDEc6pxBH`Wc70!jkbr`juvQZiZ^649{c%Eu|0ZhgdCq!qE6V5gYOu^ z8^MOA0YROIGnMDg-3|QOVH+*vA~8q*yLrTY?i)jf(}cd2UtT>8<fLy)GUD3Sts$RW z=3H@NX3bz;d3$STN;;QvFgFGcGNhYKn!+`UF#%i~Tqoq$q8%i=>ZcBo>8dxDd2ADb zIl5=m6lO(O=u%}qWBn-H)uh$-_MZ+qQ#)r2c(j1dlhE7LI~+R`uj^53Jh72?+WT82 zY?!&(Kv`{(s?K2-K$A(}{m;e4$14xce+Wo!oS@ifT>dJ^`bX%(Kc!bH=J>oTfTgRi z*v-^L1ZAbpy(&}h9TWd^4vo)W(I?tRcxHh9?-0=s3yI1~ew*PIcA;>a@H6<baRcsJ zUiIa4wjq%JI`SJ}LlmS|oX0nTj3SUJ8h&~FU$S{<p*!V&V4m=KeF-q<cB;(qTTo(% zzEVwQL4E#-(Y9Gh0=R;lX){lHCZRxZUxcw7D#dbl<rvoxxX-fgiM7x&$3Us8<d8yY z(o$Y~`Diue<tQtlMhHZOx)IS5(sAW+?Rtp~zAFQ&A4cSkp;Zma9D^E`mK}r#S<=2& zF&pUOUiH$c$H)tgDmTU@8oE|KdzB`v>YWqw1DpN@@U-isF<m+hjiGEFxNy-1`SCu> zc3Vj$-?BZhYcRfCGe(E_Y9X>UkNHSsA1>))zpsHy|N2ipK`WG8|Ht@=;IVQFrYNJM z4E<MVs66CSLbfxT?SXaq^qTzT6lo^zGbd%=gSHTAcD|pKUVF6-3#rD3_$r60ZX#>P zf`E!lpJsOjwGzCZEM+JWFTB2g`uwowFScg;b!!!W<MUeE(1vkoY+52tdxHsBM4n*` z@?7i^cXbU@bdr&ieVI2lWQV}f!Mso=Yny^S<G9fEk{B)(;g)z}?uLsYHug^Hvjxp^ zs_{);xg(Ny16Fct%<*13{(ZhAIfge{H)4o?ib4b!UgU*~=p^;I!Se~*md!Psa7b8^ z{H@h$9j!c`W=n<96Z<JFZxBnV=xB^L977SJiL67mCS5gTff>Q_DAeD@lB#}*@ry<k zD6|oRD*JgLY_T89tO_BOBYmCaXSws35GtCGa;7YR78U?_JvqE4z#S+$tU*<_p`Shx z7Y<C%62}M6ejeo~!#}R*@<Z^qk~}$yEoQ(4+PFvxzR_};3^RrZ*XdRd6YTk6au`^x zySzzL1<H0i!jT#>2#<F;Vhi|4xr7*F(nh_H!p-aK*37h_HoL&8NrmAUr8bqX2M%Vp z1m?8w8g(yA)pYZWH=FCMXK{Ss+!0A$z#^RIw$vo7J)VutuYwD5Tv%ch2kwBeCGn$K z#x5x>vhbi@;Vp9+f0PMmLq%#K{e(;h0ENWc2~K|A=@9!Y5zpbfh@c6<DzEYHI1eo0 zZQuioqUU)?-lY6J%|kaX49JIQNM19Y4)D>D@--+kgr>FG7Z+L~3l-lcmYhZ%9%OZ* zdQ+dD9RGV)L1_zp6<zV9m>Zm*!w-xDe`9jB+`{SO5JAK1=oSvMXeEU>oZ+3s*==jv z$ae7*#E98%f+`t&Gmi|_2VRxxg`I8$(_7dYG@doG5m9TPQGm8c1&gZKQ!RwWDkdCD z*5?ccLGr)yb?NGW+6o0;>uDW6jT8KTEGeg6+zct`6ZkT}s#t<^&I+4EUHW?vo;cK6 zf@5|&IM@EvOxN2<?%Q$<vghO+R+m2rRwnkq3(;;j({H=A6~@7LlnN9d4~T=fN|Q`Z z<w&k|h}x4-XgO(f`G$kp;<SGloJ3O@J19I9CrvX+MP~MkBzyA*C0tdTxZfoAwp4mS zKpyxZF<q~jXK$-G-r7j3n_66Y=lCmuHD7=uj{U~IF=%-*`RNR9l_budkN-ZHOhmDj z9|c8g=ihxa{UHp5CO>iPqD0AfWK54lVLTVu8LU1E|1<-k?y37TR|HjwBHjuAfnz%x zHluAD&J=8JX)|rc4l{>-5vT>^#gf}UH9jZLTj|q==yK1*l$e9KD4}N1mOZ)65NCk8 zx4HssH!B0#;B}pRh<XeULB2p<&DjO-8s|&){yo<|1|CwvV@QqDlkAw>k%iTB5gql@ zcEbraMp<r1pfS4%5HmLX$@x*fN9VPC9Li*7UgH}qI4td06E`e^L(x$v;*rf?kpvQN zq|FfwNhZKx>oWe=q_FdOKI|a?gZ(#O4bs3oSw(LA#+*Vzl<^)t30*A_u2zMD_i6mj z2#exl4Cc2YxdaR=B|+0y8$HU-f6sGCb*jo&TcYWmwnXwU^F(g^3|59uxT9K7ldaHy z`Y5oBGgQkTR7?6`xG{p_<WcglXx{+L+j3dPw(Aae4jb_+^U@K^f8RV-PANti<B+ef zMZf~_x)r%GK{|z_Lv3l+Z?iI%w<s;e6jwXEiq8cAAZigYG8Uzx&MtfeW%&MYtA0L< zviQXmT4Yc}I!d`)sdq@~aOFUNKK!gHyuXctc3jwDH;oBp@)%5ZB*RidxWd`6jyK*| zs;Lo*UG~6Wh(8Be(w)X|9j7^ISXnJew57=ZmbAqyR)L^6aWW;IUV*@nIzn_Usj=P4 z!_GPMC0Ap8Fo}zRM{kFkjKo$cVyL_FuFR;u8LLG>2gR9n^&JeaFEkys02%TmkB=<> zclqJbeA@CcuLi0fyFj<RX8&~i!MJ40`6_$>5g|~}Rz1vFJ=7%OXWrfMhY|_CBF%Iv z$pBB_V0}E*i2fa6jwm1$)1iIEMvWRHngOyZyTqu<Zvu75yg3Wd6h6~AZgeGKP()G2 zw9}a_A4xE(mZXKu*_^L1x3h5TU8&r;QaI-t&A9m<$`Je<9&N4!D{2<V|8d6Mb9MJF zYERj^4~cf>mG{UZridHetz(+Zl2d(N5q49C@Z&gxmITl%3AKMGUA*@o+`8SnrIsZ+ z@fg0RD3PRnYAd)VG~xGUhBpTXo26c>hY!Ajm*0f3n3ev%_;~JzPQU3gbJno0RT3n7 z<^fEKLlZ^dRlN<%=Wg7D+s2CxO>~Rl$8d<PV$vXB+t1ZleBj`NE7C>1CJ_e>sVbB7 zrXmXxHs1g2m7LMZ=X@S5@Mv0MnkFODD_H;M7qJ5LW5$o`cF{CEHq6mn3M-PO%-Od{ zltVE6i|(O|Cm3FBmwjH3hsAtZ$tSGqqLx-CSlPOqO;#D*W|co=y1KAMC--a-*z#mE z8xTR}?Skk9DxnSATZt_Gzy5{PirdUv=1Eu{a=*mYUy7J`)n>HYTOKEzWAnp##{4~a zE_4;9gc*0}h^`>Z8wU-O9M`<ql!yKLf;U-OAgh)fwT_bwFP9_KQv*IL=3=7YQEzIz z+f`_W<S(J{NcUre{}dWm*KL;9f-{cVRw9i3-|_1xxujAfb)EFhNY5+Vwuk+8!c_*W zRvWWzN!EDm@KS!TdTuOm_5$sfnUdnnYI@7>hR*UOY0Pnt|3p*IfhWmuimrx3`JgB= z2UJo&qOr2noY+Qu*#~0(0qjD|ji>61#fp+>%NN*4%o$n@y?q>B78%Le)+k>h*`Nf= zi@lFv6XLKbI{ShR7-R1*&caycCJG>2r%k(LGR>y&NL(kS4Aavzmz1wr8e2ZLaCK<B zqkouTt?7q3fsKd5uS#=YJJzw+9}s2r#rO}l0TqglItNDT{z_zUG|}#ku{kcIP=bMh zt<k!N|FV)F-(15PTUO3X*bC)IhOzOw^TzK_@1C8C^g)m*#L}hL?Ss6!gPr_46S9_{ zGm62z*^3pl#uv^B3RTIc%7N64C^Q%(P1z#{V*8!nOY2FJJK>_wy{kBD_OL5a$7$<{ zqpkz3BDy4NKYw|s5u-^YHsm1fse}w{aPau{;*o;|d#hAA_gVJFE=Jgck~Prt;TZE< z@VYbyp1v~JRvV<I!17#>4KY))+40GixWA#k`3@cb5hr&K-ie=(sf?Ez3@ZoZHK2JV zl(G5gssly*H)nzEnht}ld%c9{q~alMmp6M&vbI`1s^rAQx-v&+csPLd*mki<^1603 z4o7$;$;$l_&N*!}a3WN>kfk*|G;8|@Ch}PbPKSbs>;NTsj7H5^agB9qbKOw|(#SNd zJ#a1@#{qFH@Aj1-5RCdrRcpu9r#?;Z89y4JmUoN$bafhFF}I&_jG~JiW5vO1t!Eb> zTv@(G7+zyuQ-h*0&b7&!Ai&aTN5o2f3am{sG%Q#dbeLU@eVPKlc8b019U~?^fXRnt z8p+*0%cZWQ2B!rYJ_PE(&=$O>!qN<044|^3V``d>cp)Qlz_Yu^*bHS=H}P_Gv+j`e z>Kd>neS9FF^T3V(S1I7fZIE;xG@(Q{JEXi@Jiwfs7O)`)gw@980-iR`V%{8nEnGKx zvNapO(!&IR$A3~a{WgUw^GOz{_ZnT6I2J6&4n10A+~?wKu(WfB2T0{|zoY6cY6MjH zk>ZD)1uUpkHMDPmHp#gyT;ixu<ng%A-!Akh$A5m6_e!%pV|SoOYfRM&8k@KQXSc+I zu8pSVqcs=EkAuQt`Fjlia-iQ7J0IHsb;JUI3ho|c*3vU$hk}G!51FKWTi8dkr<YG@ ze!wGYQnaAem?!EzqMZB%eDwLK=K%}-S(@vthLVKg>rDG5*ZH0tIbJw!DKdXVLxFRE zpaxLZ+br0Hp;BiO6gfKDPe`GnXBbmd)S11P(sM(0B<aQ`46I&9Y+PV~^16?Mu1Y@S z+hX|S$xj}Uf-2kokIO`56RRwrEe;waa7=5g2<O7<WdkgZI}N01a|i`@9w7IbCgYS| zX=v}^!%XAPI3gitZ3Pv@-!UXznYfco3jGnI)wUve#!X0fwe*;XIHU&u+ss-<rzz<# z66S}|7$X)_aRT6-1o0dYSd<#aBxNU3me(mbjcM)#ogY+0?P4F_8EVmDKq(|<>0Xab z!Ouuvc5CXOS`#eKZ_oh9)-VcRVQHSY;+znh>Z1{!8c($DkngS9UEnjqB%W}9S4)8n zu+GUnWC_tMxo%#CfrAsIWtlI<<q+??t+M3af%im3)mZnJ;NO2Vmh+G6t+WEVkdm#Z z!Okk?Y8U%%M;+>t`^@YUxizjH-r;q%{q@vsSd$FN`E;Lq3SuEOCmyV|X>&qdzPZp2 zwDLYu$$-5*-%0*KmI;?1`QX~=C4cf!dELIt7MKvpF9<a}HEB}4wgsU@M8|{WXnV3- zp>hXQZqvubEphxc7-`b4h%eAbu(|9Td~@BxIa<Q&<ibIqw9^pceFIXyQJBMFX8;6h z7HBuEw|94I>K`!6+XnfMCU8y!bP^!PEavQT3q2Lvf&dH&|4B<LT(FIjX`_ZB0Ynyx zY*ht)f|u7UqVsjb&(#w2Tm%I7aRJ|x%S;OlG$B9F8C{5eQBezht&w5;nISoHh>fF^ z{^h!AuhQEOCrcoloyq0B@n6g2oN{Ja+W-kT`iUWEb`}_(Z~i~<K-QesrKrJ+c?iGD ztR0dv64c&(Srz`I@OS4%Lk~z)F;}abgI>lu@BBjdVw%g?`6JLR&m@|Wu<1DIrVWUs z;BSUY#ol24{m5}tKa19&dRYQoRBSHl+Zc}JbmWAEny0{30~#v90vVFu`CwlYzc`n3 zao@$Rb@W}`)2jwYPr#9!+4wJjXtH~Z>j)s&DPwP-1=4)QL68^JaaGCb)>(cq-=Ok) z9Yy1z>$m2oQl&I9hhug!0z00q@$8)`PGEc*6scTrWYSx$=iXM>SbRtde-W0UvM@nn zKN`-+_S;;qrRJ^%kCHkBSZmx4zgnz;R!$ABnV-v(YzQcfF3dzP_3(fCHHUfWu0%Mm z(IVc~mE7udS2pWM2%hYJ40J(&TSSEQ8i_sTe4**T<*?kwj~4cqD{{9A-2lv=siV(i zGtbI<Evzj+c$3PpVssOoe9BmbUMome^zRMZz!NDkz=tg;a<t8{d}|Vy05FO1nLLol zNJEbZKACseyTLW;EFP4d@+kB!qtLuhImzcGy3~(lB-*!+Fne=>GGMNk4p^lwvm!sE z5ND?+0zWnQ9lEAH++gxK$mUd0qrKq|!ZS-V2cnY(27M)kvy!LUmp-y4&mE<0$r;{E z@;*Lw`~Y|xTUmHL+dJIID*UpqP#hi{SJ&B;(;A^sI}<>?)Vi`F@<OxU5U8@HH!WsP zF42(gh0-_juYV{*^Ilz=KH|8?mt1I5PM<9mrztm!<5$DE0V_h8+qic$JsmI9cax82 z+Dh$g6BfUlfFac*n6s-DF)wiUaNn&@!~xH6CzL2C%NJ<iSr>*4e_NAo4J4U_kxZ&H z)UB5Wan_4Ikn^Ve$h$e_(>|CBuUrk!zt7rZH4r{Z>vFBGnQkYR?_k>>><?`$vA`F$ zEd%<jJ*3aX!ia)|Py}=mTGbR{80+>08hvWiHl8aAr1oJChN^9kunix2n>|EHq!Wc8 z{<bZkmMI1y`RVO)Tu|LmDomMp+RB1!My~GNnE&->$UZr_qSF*PKPMHomqv_SY>>}9 zaZ!-fiDy0+*7Ek6oW9yIsubT>Fn2E(`kNS%q6@gPn$kZZK|L$SkMnNf##XOmOUE;s z1vfvV3;#knfWU<{N&a~-+P&gv;i19~_;C-|h%88jm+`w|3G{^RJ;$xb?UKaaWYw#` zDMf>AGV%DoIp3MHg$%n?eQGfE8vsCHl}?~wbgB@&VO|u_IB!T@uf>Wo#dUEsm8}?f zz^>?d!1usSN4^tV*qh#xV$AoN?}|nJ7!J^}xIlXIU=Duf*oIi47m~2UV9B07L~S`| znwsIX(N^GmklG?RhtLd_j_|}^rBjhWl=MDtCxWSax%zWb9H2rOMI21-k7|bI_Lv{P z42*d=g0NF8Yc`~gKvwlTL{C#x9)p9#U+N&WF)76*^`3D0fflcUJw<Zd%C|bj7RSup z{5#n^8PDJONka*3nQ;gYB8V~c1j194_lDfD7X?tW%#)E?&r6R55iox?DH6!=0c%eq zP+&M7d7M~J+9P$BxQwt7h7*iAMvg)JCdlfje5QnrQC+U)qAjPcIj82bB&3wH$nq)L zB&@(3CPO4tp~os$S1&750=J%JTp>&vBs=W5)6oR(FBF?U)fx?(?APja8k&z1yaWEG z1_m^GF3`iDX9<oB18uW^!%q9bsG-CwQn8xEH;Khgvq6>m0iJLwRY78Va&+H-HUJN! zXG8oS#@?}47$#`5-L`Gpwr$(CZQHhO+qUg}Z`<}fIXRikhc}t|2mPhGJ5|?ObrpHX zgYlv|vr{xC#|n8`741q%J)^Tno1wM_yE-z7DS>jb^`F5xo4J41Um{cwCTS7#!ZA?7 z0?A_V6qld{H0xfk1ESdXZ;oO1mZwHvEY`owuJRc~lJJ41i<H%FA>jRB_Fw$;MM6us z9zm9+po87GU536(YJgFWIw_P|Lq9cal5CQCR&^N-!H9jdn}J)7S9^}J7%@hjevKQa z*|rHGJ72e~;FWih-`Yb*BRdothA=)r<Ub#BQRv|t5o-#@ce+47QZo;T{h&^gJEvBj zkA48d;ZL*wnUG}rzY>z{Y^?vAm;65gNe&iHhX0R`B!Hq9v$SzBbt0e_voUlr6)`oo zH!+3c<AZW`aWXZuh4R>{RX5d0xoIoY<|++KiYvqpOQE~KF$2Sp#0<MdQQ;~j0Rbry z6u5u`6coTJNlZ!OI(L8FJNumbb)EZVbncz+TJKu#J@l=+GBsXe{Rb+jYimeVM~BxV zzy~N9z_zoA7Rdn6ZShFe!6mrLGawh>EdUZ9E4zpb_8QRLMG?qrkOW|ifl>ex3;+TO zC;$lw$-@><RGl5qy|Xt6JYZO1KQlQy`$Ru&j~-Av&!6xm0kX3PdVl^qh<ti{c?#qF z&{6)*503R;t-^z248Yxj08?C^XH{8N197Od!U9$?pl5vfB6dk=lXHL+K!y+KATY=U z<W_SJT+{;t99{y2{?Wk>y3d0O0So|yV8a0Q!v}i`8`$*|;ss#O>|(|V?C=Bsg9zy5 z-WWaV1IMca=zt!9g#4lXw`X_uDV~tsebpQO#Oo$sb`^CmAh2^_hZpcw(<MdafAQ=9 z;Qc)p8?ZkNpx*5*UqKD>(Ots7!8^-)2^iK*0D#9}AHUyeV+ioy5Azh{wR7HA{`3^? zj~F;IpnKy_8W4T}*9_h*oNEvv!aK|Rc7OLnJvZP_k#}QucJfTV<qE&v-zvbHz(CH; z$3tN7D+eL|Yv<Jgo#%Idy6DvC3<?11+ccbL_czdUXy=b5;^=M8VJ{j$SXVd42S6bM z7q7pqdfZnEVEoT^%IB|>@DE(<8z1xD-=ycS|KQhG?C*&5_pfi>zg$g_i_<bV_YVDE zy)>AE|1<$WR>1xn%)d8L;PCHyga+oF$+LZspWQ`_*Yt&b9slv)BCyVlefbb{iV5=j zbj&z~K=0v#E(iDs-~qU6m;D-kH(_*&nO(?Rpl<xje7`+#z(D`uJdOdvIJ*9Bda4KT zpiY6mx*tC||CFaIY$_}aO2@zM>X-QP+aD+oo(IQZz+dgG#x&~Z{P2AqD5$zU0DirK z42%GE2>~Dg5U2=15|I#~U)ec+kpchQ)&aa*2m63dfcyXe1c$%B`2BvlH2-2nx4;e| zfBM)!@C{I}e)B(;?=V6M_qVTyU(c7j>EH2>`LSVxJqC!qnG|Xfs&7j#voLW~RlB=} zBu{g0gkJWc+KyLALqCU5Yi)(kC(}r#?5in=zAnVcZL<7H-1cl%*SeQqH!1ShHkA!O zJY4{2b8)`Oq2hR>ovXrcwNZE`KaBoo?)R$B5JNI5gO)y~nsR$pmsnB$N5u);vwu0v z8Kcbn896UAu?z@FYRKXbksWZMEma0*<HaSlPt32kfqi><ZNxKitXj7@96D^245|iG zaLP^L@v&c$w8vx7?Lti4l!wg7CC&KJcTGvC{kf>dxFXc@cMbNLbi^$vz?K=X-&GwS z4%)g7A$?m&nF4DFdrSk$>;M|A7WYgF1f&gkm(nA#e=As2R&B)vPJC8FlucdsI3gfg z2vk9DXG#i1@&5|I$ID};wZ(5@bUHPPGfXs^m8~3Rr1Zz-HCU?bDtbs}ORO@h^+hQ& zz>Kgk0%7LW*_|r!UI(Sv49e+~Lm-*<N}3V#1mh@;pxI8v;agY}pIAv^e3biGuCEz` zLBmr>dGIUv?rf@)*>9JZaA;ssH$8oYA~gvJ{g>)&O9!*mAYV25VJ9^w`4$`k$*0IV zx;`O}C8pg~;M&0eAYUe&AXRc#oQ~5}Z7nG2hbTj@{SWhb%J=&MDvIM<K_nN7d*vo6 zNXVvD)RlYjaDBj}MEiJbIh9#GT`hzcaL+83>bLs}XXoqkT^{aVr42ec$es*^S(2sO z$6|8-dq=^?T{9n-#XMUmj-5a0r_D4?X8O#;o+925K)WD;=QY`CN#PXA?PS<Q<E%jO zm(47b#Vnc&;G<r<#X@ENYqw$elpM?PZ-|{lo_F0Zj%F)O5WFOZ28gxgpvbI>>zwN7 znQabI7SIvBsE0q|-ieGJzvCnPs9^5LK{^7hwYZ*(l-y1@9WpV7V33gbzp?JiqLO)M z;$f9r_fY-&O)Y3@plhpINjBn@voSQWa3$z<&)<LbC?^#}L^gYDj+IaZkIvYB;K)|I z$0UVtWoSE@uFwNiymKKPe$-S`wfPOtqggud>$7&BH_im`eI*~=ZIqiAb-w}%azS#% zM&AkY#^R}jWYjK4iE5R{<4+U1Vp}{)kZh92AidJ+&mGic)-+a?fOxU<YR@>>4{KcY zl~k%;>fqM9|EXMeO*^T-ABMCimS^URyjLGrF==ZJi#a3ec7t#u>bd72bcR&<eh|ej zK|#UYR(a`d+`EW-WlCJfW*gKA-mD8p2Uy(`SOlO=Rk%#gE-a???q-FeDSxp5I~ckZ z%$XO>r>l}FZM3&T^m9D<vruH|o0!ehx%Dilml<l1)gEO0ZLK5qV@Q|&Z@qd2Nuua@ zqzJA`R`{)Y;rQX|GQRdM0Ta%tCez|^wSqJnSPgOD6izb!YQ^yRI$GV#VZm=S`Bv~L zl?L#cN2t)lEu&q`Dps5d1!_>N4Wkjo!2y4-i@Tee58)F+dTgRle)~D2oYv1EV7WQ2 zk+PqnaLDRQ#M>OPs<(h?8g17eqtWe(4Slb{-FfG+xztq4$yFw>duyaHp$N*Ai<0q( zbMr9?*IjACh9^IJQZc*@nB44^I*St_P(Rob$0Bz(4b9|mh_Mv)i_~eWFivmwD<Z*V zAPAhD(nln#x6b&2Ov6}#m+RH5BT+cp8#;{UXzzz_osj4@4^dT$sXfqtXKYsBCSv|1 z{A>=-M+_^&8f251>V!p)so}`o1F7_t4PFo^ee%n(dZsi+-1G|XEW6e@SZ*5$7sS|c z^s){|@v4;n;p(iUgb>O<dQX%Q6<c1G2oY3s0o=z{#qmDf!cQ?hRR6vFQq^ThL=&d} z>ZF~2w_Ip8w9VX-xA!NR82se>9I?=IBlQkC%AC>xJC#KS)hPWqF{_$`*c{{PZMjf3 z&GF!S<hZttDQWVTJ{I;LOJFu@6r)bMBe^5By8a%*V+XZw^WW<BSJ}LZpy;I}k^!eJ zQ*;9Jxb!Rw+4*OWJh0|aoZ8U5#!+|=Efa&a>d2+6v(K68iANOXG4lT7mD_O(WDp_6 zQ}CEt8P};piclK0*k!pe=vNH1y9J+%bBu(R;fI~}cvHmPI;egiq+ca_z<iX4u>PPC z2K~km&jY)-qRXb`LDD&%j?WY&8{`b+NJjCH@=<WOUB*_|6bycbE~iM8-wD&9C*hUq z19`G7?c=I6w=Fu<E%nW6HY6#elJn!J?$6Psrw*<0?9iaAsiv!<L6v<AX=Y*t!kAKH zBSOUV?xNJ-YNH(WtPbtxD1v&YML;M17fvH-d2~vALdMDb-!6)4CATss^l@&KDBJ@9 z8!2uzBsSAO5j0QQz)HA&{5(&$8S_^5C27KI@pU3+%@cbD%>}u*>jjl~T9;IkH+E!F zOjCZG2g05TQy-JbpcPy~00?RUj^40OU!+ty+~Mb8;ow#;`NU)@<XKd&i21CZ*?Drk z#R&rnLQ%p5{M^hCo(>bnO%dPItJ0x%H}kq^4=2!ySz0^qJvC7bm^e*=rbKVZA%_-= z4sWcq+ZyGW*%9*QrP@CbfDsoZjGDZRQ@E6bYt55@3j>Dxevw@UvuhTCsAjIFbL)qS zys=PAa9Hb0Y00X6t1=ncGlW^rK3q8__xAq;^bWoom7Pq?@QiCy5O!Xten5Vlccq$e zsd0lPibc(eH9BEgfP83UgYR)&RN)q5dnsmFF&SgJQX{!D58Shn1lScE?(!b56br)s z4cY6qfhZDLI~Mx=gp(`voq(MP8dj_~%GPe!)(TfW*?v5Xu9l)cF<?pkAPX`mez8Su zn-ZYh%)?RMUYsZNoj$5L>apKwIF@uNtpv);v4yPmL>hSWVj4#&y9G(z+0Hala^Q>V zVA4`fn{n&R-aTyZb7*YW%=^XVOdnx_FQDUjLnZiOw$Uib2L9nyWu6HPja1r1Rk2J& z#WHD%E8Fcf*9ggWhFWT^s)r(PN~-6)<~K7G@>GKR$L>}?@(;tnO}Hw<I?Mr5#&Tf2 zFIRM^*N2{Q<_D>15GBD=PxZN`y3IRb<^uRb*zhLB8bioTu`H$b>svXZ(BMa%z#2Ir z)xGyRR>IMzPtMHK)XCjHSLGh`G=cG-mGsfWQEcNFHu>r7TncInv1Vk25Y68T)Kv-d zq;g<Qp}HCokF>>LC5qLhbQI}oCc5+Hyl5x<>G5bwrRLHm=CLqDaQYP`<NS2b{%}2r z23|I#$Ww}zw+&uMLE>OgO<Y(U*)6zH5Tt^^b*xP#bM->%WTe$GS#E6qyu-Th@O-Fg zA28^58s!P#E#sYJ`t4AW5QCu}-Me7(kkj<^TtETJNoi5JDNVZ10?_Uz*dqY)x>&i{ zUlgoqZ+lYYg=!03Ob8QDNQ5$&|GM5Tdit^3Y&8et#lDP$AZh-ZFjk-s_I6M4rJA!J ziv$Psk#RhbM<>ZeuchlZQzh_<GeWe(dM0_$c*^#x;&05GK>Zx%i1@{At^0IP9zMeM z4l1RD<z!YGKijTQO!!<l&xJ|`1S^v5KXSfVBKc4*>gzG8xBLEmkpwU_4Q+Co&ShNO znnMP!M2D<5v&fy8wc^lhVUM36)vu1NRBbLH>1Qhy=6DUl#Xa7sA<Or<MW(hYOs6jm zdV)%kkihh7uRB3+UrJ8`dgp5@%kvHp^ZJ&Qjj>XAf6HBws(4q8#wBX0M~DT{LDTw5 zZUpJHJ(&AF$7Qor=gzp0cX<qb;)4E|KCi3mW>^Hg0Q`jg5~^rlLueX05r#gO4X|5T zlBINq621Q5>`duxcI7+gzmK#i@3En`@yI4w(eh({f<V1{aN^n#nU4fhzK*Q{nKgcJ zblCYIHc&FV|IXnxzCZj7=dn#|_Nis>3ARP0Ur%T>uSBbQ$@<)$(k;)sT$dWs9^W-% zi5(prF1?@E;1Rl>0N(<(>r_;Ts^gZ=^B*%6I6;*Ja*E+wRD)uqQJ-H>=JLFjGcc>5 zr~&Y=vgDZlOycm8nJka23Uvd_UFsiH1*}_H+u`OYKyZHw<A<j5Gby5*3tLK&HNo?h zZVY(`AZ3*SB}<t-Pl->LVJmNtE9djjRNY(7N?imjf6h9IDxxB=eZ+r41aEnkllAef z?_(Q%W{z<2zYOPOoI~hZWnOn$UQr53bl>qJK4k`v&uq@8<9M`-&B&Lks|8bb#I(=J zuyxIQVazdcpC7weI*4P2I|B_zkuYMjB%jOm@~}BNvg%1ie_E#D)(-U%RGS}hs~Q&{ zf#D#jI7P|M0X~8R&))<odU&3TjY?D95XPzD7RQ;hS;x-a#&EC{8;bG~7REB4;-mZw zOPk98IhaSGVaqSxS`lqSDKMAU3WdQ-ES!W;?QZo40g~jS!@g#sW7g?`r=zgvW<_Xv z7gRGWet??szAaYGgpT&y4*=C|rEsw`^Gq6?|5u^SgcRS1A@b+6H`XQpij;>|USX?Z zx@MI`D4|Re-yl*|%-a)K(su>5;KS1-e?J?Vy;^4&CHL;G0?w=l<Sp*=7}`2Ay}fn= zu($+5PWMU8{@6A=RPtZLnmf=?diRvsy1qoS?^AEYznNz7T1U0`f@><@xwItUlzT5< zG(W-ly<meSZ_rnuL0#W1A-yPwuJ@3U4UkH7wB*X7VsSo1-?x_EP)%dM3_jrZLQ}jU zCnf_!)<wPQLiBh8#g>ZbvymUj4FxF{9BV~|WU!5FLSF+zx@^flJX5f()v4N`rs}aA zwX>Q^dg6t#JZ7D~(H~Tb(l}gOUuBkt+8l94>*LxxlKXi>z^dPk(c6_-x2zeZgAhSL zQ>D01fD)=;eOIoN0uLKH?%T03%6V_ZSHF;XQMaC9rR^i1;txqUM1e|33(sXoU(<Ry z_XkQb_Cz-()6q%g*Sw<6w@bnmfNMqOVjB|UUtmm$ZPQ#ng{!O&r+NH+JSn=KA!?^( zS@BILvJAeuXJ;K<PbPMDWX@6<>W>Nax|JF&>lLubI3*>N=HEhY%9Jh76-H2ZKNF#1 zkIgI<{$0awEa9a`n=t6Pw-@!1D(3l&%neJhHO6Ni8iHgM5;d>UQ*Ps7N?=+#XwDs5 z_G$<sxJDz7x7i$gvL`~-Raz8}s(&y;nM>oQu#t(JjN<{Wb8KRG(g7&H2c`&($H6Cs z_guH_rJcsp^j2bdhBiji<z`bnHLhelbfJ>r&2l#}q96&59UZNBnguZD1#hL3WPSpW zdux*|=wd~!I!U<)O<z9$R7oj&AkBmR5(M20%;<EC;{QC=0e3&`LQW`o{{tEJNP8Vs zQhs$N+7d5G?w}Uk`9|Igz-Xi~!z$orU~-}tr=&>RS{SoNgRd7Y%>b^Y3LFPg__FNV zH5k;G^VBDKj5H4j<SF*panC_dX;|M2=~(h@EYeTa3bXc<?NoH5(Dd~1+75$htk3|J zaXhYRU}u>-6Cb9pZgFU{@7t7`AY~`?C3`N*#Oq&vYce&eE@L+CvobSq@;i4-Ahj?B z%D~`&a6P2l{tscZxL^lxhBU11i)Dgke2ek@N7^Tr3XYg~h-2JN)W_0N9zz+|feN%+ z6%j)K?9r(dvda7waSSOWfey?inn)8mRtps*)Z93{pGQ6N@!&*$+dOx!#-%-zN0&*W zQZyoJ_LWzMyCAY30a{j}M`oPS{n-+nUa_U6^?|+35=A09D(_B@O<LXT>s!;2&Ul8h zb`6u_)Yi*kslcDX%De(!K!;a9AaK-;VgO17AnIx%53%N$=!;}H8UH>aJYN9r@NA<( zmP|iILK$z>HJ0qp+f|$%u&O#_gGMXqHWZ$~%Ij_7YoQo2oNo)$+TLaJS^!^kh1I@< z^#lV|1-rNNaFvm#9S;d!Dt1LD$L7kUYAL9nJh#ZXZSl}I{VRn4!ed`#$hl%X(LDyr zO20YJtR%V?bU57@^%?<M<FG&PO(c@%NFDsnVb<&>)kwZ2#(@2(tq?3VMS@c1Wk!gS zM-q6_tf=Uod9uvNOk*cy6=&4Sp={ZwuFE|*QBM%scbYw_fG-k?@yq@y+}mq?C}Z~! zoNj?`FyOWF@lb~3xsCfDkH}zfc?i__QHK5nB+u;WpvOQ`zQZ-I)a*`zo%KaWsA+XO z1DQU*I{zR_Av72807E0kkI*(@*p%roeu;7Mn{%-%2JFO$Hy;yBu`oa9VWP>TxX2#* z0XwSBmHc6PO-|O1MvX_(IM(BfR!2zJ#$3-0I?Y_WY-cIiyz`TERg+qWub{zTV4&3% zrlJA3XFE<qfGics?$yChjjDHAzX(+W&-1Ig`d3OF)xBJeY9R-E?Ae%0wANa7^Q(~J zHcbvsj=b-1xW<x;TpUC?oLRObBeIDB-mbO2zr1sas9NVXYhr30kK>iOw>q?F03Mx} zF!Dv<oR#T2kr4Tz{%W*f<^ORCT9LD8#>JEs@|sRe&nOzwl{EWRl%aStjv8vMb(EAG zH6QUp+Kcy9q`T%TL;C{$N*o4hl0Ii`VwAzou264T!ZJ}JTShtVd|3AMQ{_6x6OU)5 zVL%qmf~7sjrbd?8QM}zRw@mi+x^y~vk0>7%kfjg}hq_EA2XLr-;c9^AJrW=nAT$)Y z#k7h&bRR0NFM=bPBQJp3gzRjJ=5^(MQ-00+QZH*y8)CBugDIx<*{~hSOt}ec8`)3X zE&Y`=!Qr2zQ?w{C+7(>WWamLLhZ$xl4g`|>Su*bW{=A<b!}QaG%vEN}&Q8|pXaZ*d zSqVgY;wxa_vJ@GG2lJ;A-sF2jeTMh@Sdt)5*iIs=pTKTW3C9|k>(DBB2_dVUSvl_@ zBn(@osT0=~T^U_m%t6saJ~$UMMBMy5&?7aUa^fupEYAe~p$5^>-(Hsg9n#%iHNxi8 zghfoyIhu1<fZy?YY-HoFxR6E7mZ2?YJ2|!@*W2a<i&nceS&o8JOoGL>!>6iGA&onu zp=XaZoqWV(uJn<d>{VJNN%ON25%z#cehVFiKs!z`D&_m44r##avxpT4oZyrbY#I8s z5S{R4KacZIbNljFwe}@Tt(@~}fNc=G<{Bq6gS-B2&P7V52fME__=2KGXPjfkrmWd^ zgBJ2KAIDkIlXZ8?DthCcc2pShUl(aB&1&p|#^kn`n|j>_qIc#osOu8Q=HkvZ?~))7 z<wFgsESW+e_K#YfAUUFM1<rovT6jQdn8mB*oMLX&@AyEtcFIf8DtGNN<(41i)}gE` zv5J@dQDD4XkoJnmX0NBlTLk8zEH;zo))=nT0Xn%KNBzF4i8`Zw>xzAH5(DHwQrI5) z>V8Huygk@;i{1R5f-ApwWTjWKWOJpcgfAL?^-Q3tr`q1*5X@7U0wey{bDcu!z=7>r zRJcwLcwNPYpfv;|9FPNvO-`=xk16M!peZn~KG|CRoM>U>r3&>-mKFqL@uMj8%_M2P zV4K0xPHDfJg8W2fm1X?xzb*9+);)|5vgE~~tWocSd`uI3c{h5e3&!0TlNPS}Xlj;T zL+OYn&8<OO1GR<?@--x0yukJz2~<y6f2b_HGNe$V3vqQx(Vnz+>0hjoG~9K4<bG8Y z#QP#STQB38*>_943wr+mNIcOF>WCgJ{{K`IAR67BjWclkt>DLOu1n$^-P8LTH_$a? z`2)&XiyS`NiCS`_@eH=9&=y>nJo!x5W~+CqYy4J~?PMBKdVfhQfa!G{<%JcBk&(uJ zp>k_j1jU7jAB6z8q%7w6l=GJ!6@wc{oiSO~KObF$-#lsS3%|%>eGP82@g27V3YQwq zm+Wx9&cx^&*tI2Gn_KFMyLe_S^$!^D6H|3Shm|X9eze-M@mlT}DumE5DDj&pLbZ3_ z5}_f&pCp)IWiuCkf_ePfNXuO^za6oqRpUAA8aZdLw_w?knZqcc1dGbnLoJS#e;$_s zIMu}Ds@+#=tw#XeHg1A+Ba%Jx4p)x->gbfVqrgu{(&IxNdp27lQ|NNaq`d8#u{W-& zGyM>KmZjWl+t7WqRcs$yBpS{YFVLcY!daMw(7TwA6PvjiMCDSLf7cJM@r<^-EgjWB z{gBM%l@zb$Tlr?T|CY^_jq)rETX+BCly8_cGe7P5K~f&H#HZ=_0Tj<w&^ZfRs-gGQ zmgnJ=V3`4gguCLyTm5A){srx|(yYI+7^urx5S_Z$!~oAfwYKrgd3NSxHG!$0$c5~f zLG(s5XZzZKsp2CD#SU_d7|L7OKg64-dTjMkfbhL|$rgG&(}v`%%uxZc#@s})Xn^Ja z`&6!0pcRap*@YjwI}TDD7t@dh4R<Mk4?e?E!3Hfv8~Qrqa1QJ_{8eQZ??RQZ3}mlh zCC<Ub#E~|2Y1XJqA!{1o<$svBqH}HzP+z49G?8z9slw6PfG?-6+jYwkrA`u`nrH;< zF+^pOO7B-g!-A!Yqz7ZcYJAV8<yA=KJ5_9$qK$IOgNp7R1aoxd#S4<-f9c^6uy$Qn z<&h`tYB-!9?Aso&m172lz}#FplI-%ABI4AeS*hmJ?>WJKb-a*zSce^~Hr!YaM^Y%q zX)K|r$V>#!ZkqG#yV<fFS}!+AZ^j-aj6*e$W%}e{T=0y1ZK^4zJBn>4p`A4BA{iFl zO@@w1SFXpFBaMl0dM?^2(dD@5{!-|)@@DENVR@#i6nxdFw`u4NgV%>ZOs;SsnL`XY z&J4!_GQm@G8LhG04#eMt|1V&}N}|Z4N&Y-{o;#>|?RY=49t{cdIpxv~r2@s5&GR7x zGt}gV_fd^mE=mtQy_CvG$K{qAmDtB=Z?=sDFYh7lbQ7Vn99N$i^%OOl=t7kV%j@GV zH;{^XioE(uH{)c=CMcKR#Qq7qCNy&3?jg`)wL?)BKU*LErmxx1MG=9ejk0iA_h5zU zBUAIvWIp29x;8dFl7~9H=ma7PRsGkoyNiY2`e3|7{@GT^%GrUfJcN<+0v$P29wcJt zL$u7*-`G27s3jN*Jr;TSHUZdtS}J*Sk_%thUa(U34krD)<Q%}7@zPrnkQkawM!m}C zq<oyyeB~QzK8aCRF;}_z4V>+j-zUi%b0wB2Bet=eFROYt0xHS7zcDAqx)&gl-x!m0 zSu%a2skwB!_Mf^xdfu11Z{ySLWwUHXoG>gOHOC5}p@tn-DSy1_@SU_Ve(C0HdGA1F zoA*{6fTRsuEI$vpN--cS;CaF!l4?zOOcvk(o|mNiy}(Cfm_3%1boz*$ysi>9OY!`v zHDXlNqfHwlH?0p*t;?`(>OCh-7dJa_kt)(V&f`}?l}9ie{wc=sERTaYJdpC{_M#(9 zJ`7HND+>{XUBHqZKnEF<Mg&Z^L3Ic9`Qz}Rs=<<-L#Z_Jd9eC(oX=jR33)ebGD3$d zR&}SGxSzyqLE)dRQeBK^Y!3*yCHV-RZ@d3Vle)X2@xcU|<LMkq^<7iYfmzR(aC7UV zB>Yv>(+?V=#wuz;olaJ%q7ohba+x(A$<a@7B#t<0SyNTa$j*%F<og;4ohCU+k{$NO zVl$MDZi}3wKMju_?E2Mq^GCs+QXsY^AmLX;z2zz_VirsDz8JbR!kuGTfNnXrLGcru zH`13F^D0eP)0&v8k4U?|;90Zm$#b;n@|msIU!%NV=XfpiPwCw!HLLo?*|MZ_dpCV7 z*($S@C1}8n#F%jU4@eM-G2QG#R(^LP0J*c&a|O}l>_<!mxu&_s?`oUnplTZ=w~Gt* zX_rA#GiiZqu`GAmX>=T;OBP<>M=v4bB^|W#kvYomHnm#IE$s%E-0y3DN5ZU1d0LTY zR|Jm+X_wq&q+FoCu?jxt9m=M8eaW`<56rps@22F5js9{i<QDl&3%SddwdgSs$8=D} zj8PUPO@cajU{1XTRi{wu0_<s2F9>D@=zlUhQDGbTgCc8rOTGSON&<d-RSCqZL&Vx+ z$$T+)bjIxJT~TCS#i+A5?abtd8Eh<FLP8#Xb;~CKbo4O#-Brsi4ia$cyO#5~;3}l^ zOIo$v%ybK|(~Yr5VptdUICHx<AeX56y(x-JeLmvhuZXBl7)F0^ym}mD*cDYZ8Lg=~ z3S*E^M!o`+6zr7GJo~T)>zj@!!q38**kUjvwG&G|VR9#uXuGp7mGznA#)6MJb04qD zM;k&lLER-!5Nq@kP5Ij;_PMr|yN*}qZLs%lu<@{KyfDhByVy?VN;1z&w0@is@V--} zl)sgP5HDF27bZg^wZx&qXD@QcyH+#zRe!)Yu2#MOIitbxKV~#o7@_E8Ozq5FEdH}t zGqAJ#&lYP&*8e}H@&6FgXg5{KxoM(}0(Xa9>tMURy+x96$Px<@KDxyM8r-Gr0E0#1 z>FDn62J1N1cE9l*>pJ`8H2*ut`&p^UV!f*Ly26zeE-ZsYVQ*#!o!;0M47jGT0Rlj! z)>cM0mqq3#EePq2%`EB7&Ey#w0lNotB3@pQ;0lx_P<wS#B132Z5CFFUO8^Q6z`+4< z^YimF!3rqp4GvFE4J8E;sIM&?9vB(<-cRfQuR{>;Pi&t!r-tSRu+@%VXMpVuuHArp z9DDf3p@0knCO|U?;7pCpAfTjrQ`{3p6QHLiicJ9B2F%@yT6k(?Wef^Lp&2;fHfI19 z(AkSTaH<aua9*oa-CxSt+~XL@4J-pN2WOD5s*SOM3*z<;%?OM$AlIfgH)r1us5S=x zO^(bxv5hNm4XEZufQ{bV543lE`uYdq<j~~*)Zjb3H?eY^OE^bBP7Mz6kG481Wv1Un zh(?yc-<eyxcM!n)iCv!AJ7Ic1>349?VoxC=GBuYO0LU%;d)5>REJKr%dn3c6=fscL z*`euEJS@67HFwmX+5n6rkX9yV#%AEZW3bro_}icLUx9qnuV!;_Y<PSl+y2F``&%{y zaRl4WXeMlO?l}b!*mu&_TqkJ$!Nv6CcJc<~-srnAqlfz&*BO-i(?$H=%`o&tGB7r` zH$MPm1kNUEs$LV?QvyE!nd_Q;<Xb=f2}J*iV}0{4?frG1{+h@CriZ`(y?Xx2TVbMO zW1}K(w*$Vf7XkLzVwndZ{ky9J{MKdj2h9fjt;3;S_#@vKS(_R=@<;y7kK_91FZnzD znZMCrF?vI@=LLLhe(;yRI;A-_g=<r01`4PNG$U)XXLp0&{hCcgj!n&dukHTVsR59X z8+*ggKr2n1(7L<N=I{p%w4M1={@fn+L!6_ksH`R_6npV!KmU7F`^pB7KnoAf@b6Ey zwAjY}RX@C62MOu*7J#0B8=V|rVsIY(pZOWc{nNwOxBb%Z@bK@xxhZl)aw@k#d~9fJ zEbjg5&)vL#KFn{h*cP0L{i}Nb3n7`CnLYEHepo-l#OUNj?do4mVEfdc@2~mipn*FB zgs0&e9tp-bCn+zgl5D~*J5A~O?j+nc`k{hOxoX0hzUBTwI#S=9zS(y<RY<9y%D>W0 z<I{x$PwhZQ^8)1kusUK$pDgJ^;n9WE@K&Misp%Hv2`i15G_Mlm8&|g47O=O-@SEYe zv4*ZN!$o|MrT?ry<Ri`8VE$C=JpMYD+Tbqw3QjlbJ!~^x6xWyE!^B(fKi%40d4s=w zdvVb3b+$%jHT4oKL1h04{lZZo5#Wu>uecVVzl*8k4_ANE2heiHnNGu@ruk#p1p-r( z$i978*zBpVe2qlI9<2llt0jvB@XGk+XgP%;_~b^%NviTHe8P@reHqP6L4~?p^#4{K zmciW~whb><HLOa$O1z9uZQD*6k7as)rd1f~gT_*Anj<lU5T(6*?%_GV#~Q7AmL4X! z6Tw`8MKECKPw}xyc$*QWu8}(hQy@5KQ>FQ*{g`^rJ<f3-l1hfP6p>4Al;pdd(U+WZ z?sqI5-y6cr%KS7KjL^My1@&5ze_fUO1*L-{jS6+kX+V@L8|sj)^xGJb?1U6T9JQB` zR{f*|%YY+KJH}~zJyZ$FmS_21gglv0&^o>flWQ;NbYFVvH*&Lb0{f~`UH4w_a+k5F zpFn@S#Z2jhY3DZqX3xrr@=C)_NR>mVMm@Hg5)LrM`#MF(ix`<oP9Ir?sX8K_@vL+3 z%KdoWI_A>p(GNQ)on$C83xKr9p_FrCk|04Ow_RZq50+N9Dx)M|YT2TsTb@DYWQwd$ zVbO{^whGs3efqI>LOM9>AUPTLOfAD9Tkb!#gHzo~#fl5nXxHu1%D@WsWxA`3MlKFL zz4Szw#YTRYxr$-Z(vGFxKFInnhsb$zs(kak4xme*5@9Fj@YD&KQx%PO504ovjURWh zp?bobixha4If%j9B#33^V#NoSHW|u_^hGvd>U8Yq-)GWd%8ite-dnuvS&ZTr;<nPT zi@*4U;da=*j*@ro?~pLy^R;w%4&ikB<CgoBU$q8oAk&$z`>Id<%&Z`#R7&+3w9<P} zz^EGLQWYAHNw4^CDV*P%rukKeMWc*hB6J#Mn(mO1ZrPU=3nd<Rd}5<2K)sqM%bWCN z*5^%prL2kk^O7cug2cTS1?o;Yh7pW2$(>pP*}{dpSV>H8zCEpWhbduZVXX$>^x9nt zlw1x_%JWLM;EKshA!YTL0XlEXQ1K4^*pQfeLetBflre!c6^e+jNBG)KUr-VuUKo*k z#)qjdb*0>n;8pz^^dm5&joI-9ryTa%c&bOnG~-1*B-Fboe4Yo7{jKD4gV>s4@xs=L z#R3whmd$sHTpytk=TG6xEJco@p<phW6nS4oKeDqdL|a5CQW55CvL~&5lps&YB85yK zIYf8zvjFXxLuyqP2zt;)8I;jZ-u>C_sB<9+JAooZD96)P*(`i>O$tULlJH;SKOz7Z z2_G36a8=J4+Wxt6wvr`lgF%bnAdb=Y$q(zt3_w$@*})B`jbb{s#5M<T^;^0}1cV7~ ztDe}fF;G4D8N!ki<IgDI`q!PlS`{Fnjxmh#jeCOIv<e!G67pZnER-T9g)}M;LX=H% z84547*LE{>pa;Tz#3nmEPA5pqxTaLt25{5JBg3@5x9}aGs$e+wGc@7JFB7bKhgZwn zNn*FyNeL?DU}zW5XoLSuH?=@}c)MT+Cic#b!%Ef4^N+!<`^u%ldYh5vSGKcJxnrN; zEgxV2Rd_4Iw9DLR2+=FnjIQ}R^_i|_SJqX>@LeVmE@fIz3fqsx|LSzf;ueh7|JG$~ zCSm|4E~K|_rS(hqb_@Vjxk(Q`KLEnx#VZ3zOIGL?ZJ4rt%S*W<G+xZ-Q==j~@>dMR z5mih}#+d<e4|=dvRJJio`g&V>EhLaBLmISt+?Njj<EgDUg}a3eihoK9or(JwMyxjF zC@3oH7}i-Z0RnX2(J&dA#Z8xNfKUSY&81tqxs`ryJGvp=BlB0qI+f>D^-*aMOd><# za}ybW1*dX`s`K!VLWyj1*3xy%Lrlc?ynr5xx5+K(5LfjP*n-o9Ha;(ksx&Pg*D9=5 zUZ=s1*l$;8W^i{`{!{0<8Huc6^lUQ(zN|WB(i*Qg_uTaO_etE}a?qLAzkWUfU30SG zMXC>BjI&PC=4l%LiRY>2L#3z5+~4mm^F%Xw@Wag_Npht&-Ct!1g)AH0>EqM#?q{`U zn)l7JYUu`R+a~E>>AYKElY3ZzO|wgd;2R#Diwx>Y`L}~MJ4%>uf6ToXYu)QU%3ZUA zv0M539yUB4m8Tx^#C`1mq6KYaV)z+h4m8RFE7$E&wqTyyJ?iV)y%--<T>#I#?1pel zfG7%~!i3HviWV4jCM+7WQ`_4vrCHfXD<@HF2jLv`s$ZB3C<T9EQp%OZMseYUBho4O zVNYeI;o~MVG$IKG0*gnWK2`)@gdV1Qdh}_6wB6XMAMvdvj8hqO8{V7t2hO2S(2^T9 zoUd7<0pe_Nd)x5gn?xl?@|WWx;|=!1Q*2K%dfHxoGUlY<3oAw_;GpRo`h-XKmY%%2 zc*{D^zb6B>SJ&0`fP=R$=-CA*Eg=_n7Y7_X>K-@U&<>il709o*;=D@Z5)IjXYApui ztjc{<{(+V3mPovqK}oRZw^O%Pzt7Mi49xM>xM?(yYw{hIcwgG8UH;B&f`TO&OL<il zdb^b1-!LKG%Lq*ut0xN&3Fn*R?GKFJc=p#)=NY#Sn0f>h>JGmQfh^8HR}E2{PhZsf z4qN&#=JKq(b-9t}A7rJwl6uHKoKIFYG0dVg*qz~o>~UC?#iK-zm05fehj8><n|}i| zMXDq_AMhpN(&{7bL0#wlr3a#n7_vpzbHgxXyQw5*#8rT-B|ZX1EWroxq1UO#kI6mA z!n1Nkk=@gcHhK8-hZ;@PM=yj`mcT~}^4@pJ+EC%zz1Su9MnQCZ8;eXD%)4z+LQV2o zI3ed$;_3Rs|21eNhEz|8y8z;EHX<bSGj~{ZyL_Ia|60O_2eFcljMBqd{oPzDYjv`e zf=0*eEqx_=*H`LR$E(X4cRjX{mC0jMC$ykG1YD0BO4pOCKC9V(xD30+S`BCsM46pj z=ONy5nWc_eSwsk-B%Y$u-gxk*88VJ?_3WcncN%kid{DX%avV5lXdj_o1RZIGIy$%! z)HCgG`$7|rdhKd!rMZ)|My{+vpDvGM+qm0?OINvx7UT-AkhpJPFohAl?z>g6w+p@@ z6`9gr)MsP{CD6Lo!e-;&82U1^#9WTvnb*8PTOmuZc6<DbPW|K&JMfspVyYW@-9<bZ zB0v$>`=z1@j33R?+hA=pUrmxQNhcR@d{S2|#BFKBmI79n!tE%+uDk`brnU{}xt<nQ zy_a0W=bt)qjfQhb)^=4zMJw#TZgo=~!}?Ol*6Bur7BKxCS|+#RA!d1sRgi89Ke;-& z`t<h}kz?yE2eUleFu`pWaEF{7fRo4qryeqjh8XSIc{p~_>&{sq$rupXgOxAF4|JU` z&mxx*{PnU9ajxw%U6;&5jeH`hOPvf%vx^r<*>mM^iKvtxf|E`tqo&nSa=D1&6fX!R zs^eX&I^8f*piDyMKEjlCylS;A_g|CZ5T%si5)&K#^G-r^h7!Ug@Ya-=5UqwW((N%R z{BXp4r;5pwUk9ZTgz%}+8F9BK`@go^LN28uyzq`2*|-v!JkRe%9Sow-${e$M!}Q@q zx=Uh({-otp2g^U*@W(mPRNi>{3<n2vVjk%7=i#C=%@Nky;iy+biOsH<$${!gV+F=k zdi8C*XJz(760?3Sk7u4qlS?p_W9>cd3+_V)>GO%LJYj$~E{dT0yHe$ZDCKZ{=-_Tp z)znJ!I%0THE$Yikgs<~pL~8DVWGkS1gbUov_vN=2S;b0`wx~We3zR`(<eL@J%*5$8 zOCf>)qLopWSQU;TYppc?=Xof;?RRDtTAWhyk<KyhiInO<fWtgl!v0s)GI~AGNFvzA zRUMO=inDDsSUkK%wjS?DcC2~9-qlRI%>6Tlrrh;bhs8baa6-c61qw&Miuen&IUMq{ z@cY8?vNoifz^_(F&JO-DOsWwa`1zl?I5k==tmp6{33|$doxp)`Z$-LF6CLhlf{hhw zILgO6^?i|`*-+H4M0_VTI5pF{Gaa}s`Dm%S)8kmTb%E^I#@@q1>6g@(Rt_y#M>b5I zM}alyx*$vinmu_8)!J5_qu+lZ5h2SPDahpT8*%N4m<Aa023}^}t&$|~u_rm*?>TK# z=}|W-xAM~xzKQZiy6-3vN5yx}xXZ|@%~(KPByAaTPvI^2XOB*Js~ceRrvSQ0JQXjw z>9y_fVh|L@u`*?g)%i*OU(kWO#9%nyLpT4UQnmxS?RxBHKZ=K|J_5n{9?ZBJlbsct zw#=p;xbA`&X~U5#GaVX)usW=(+rceRrHWLtTjL#Fou99$6rfhQgqeuQC?4^iW1oS2 ziPT3?)i!Wza?n?wocmH5mPUwEJ<nC#Jk*K^q%j6FI&!ub;hWmA`j(-u!-_3i|Leg^ z3WsR+(pGEG!f}K%t-NMy;K|vz<$q!I5Ck4pHa68dUL2l56GaSI*+LDIM~-%|=j6@g zQlMEEb!C|lq<)#NXZ*VW7Vxflu1*x6;w4%5Ky1!5a9<PBx^?=|ftGWad>BR*PrIog zE#nJg`4$qZXXN*%?Z)nu*UK_x2G7OO-Y^J&Vg}+a9PLQjt#~Uu<J((NwMXqM_CQoW zqLNTv4FQZ@yc0PpjgCNwbQ@P{37T?uS8?+$;-uL1<Why#B<3^1)VjwHbg^6py%d-? z^({DXZckPIZh~qC9<93xVZl3wJa0SBi+u^92$|BSD+|Ch%T1_;OpMEc`Xveua|UOq zt<4ck=#&ZV(_Fs5>r_FD{->Dgto~;X=U<|W)U*?XDC4!2R1#?$^C7~Ug4~56tVHZz zW$klv)RmdYxkgef&&SwdKCGl=Vq(io<IDuVCm#%ow0#>4bd85w?by5qy6N$Ocox(f z&`YWElFtb|Z>*G8yRPiTC}&3w*;dE-eHasF4H`_l@G%`su%nyX*K3erK49f12>vwQ z1=@)bjnI~`M%3=ftyZ!M9uHG6VF}1<Z%?&ad!*8=h&T>wuu|ce20eAqS`8tcBC6Zt zXk$?<WKPdfHD?^^e?Qv};W$*%KXv{CyP1gY*>m1emHZ_>N>0||d{ptas66;F^Z>Aa zWMxIYM3qCG@LpEW)6s=^<tV~`&6lItX6!G*Ws5~+OK5JMjL`8ZQdHN)_@nhRV?BiS zf4Gh*>ialnJN2dIn#9%mW>b8@jN|uj;ZS`Dbz8Q=Y&UCJi&8Hx%HaAVOed08l<eah zu;-kL8t}R=H116>k9sh6lA-)At!PWwrnx{Dd5SO`jP(i|;M=RM?T|Sf!{aF`&+X%D z#@+pXc7Z+>P-~;;f()3feHLUfb^N%$x#!h}JiZn#eP4{|Vk|$=3Rz}98P;IWBn&*@ zxG~GoIe$!Okovg_Cry}G@n5;A&0KgmSI(c(>`+P6LDN>cYGE^{J$wfT%XuFOu1RWY zF?(R8XIFQaMO@*4B+(ph2#jjB-EZX!%4FE%RBjn_FVNfpZSrw#W<jNrKdP|yM+Xs| z`goPIe}d0)g_~@H2x@UKf;E<+)C2DzY;5xLk!0&)mUDHVR5gT!hrDg1Mx(g#Sr?nh ze-^LJEi;q7I7Wh>Hfi;s^0)SvrX<AGwOopLfl8%X0>v@%w1F<BRtl9#MS8>C9cqde zlLTPPW^aS4k3huR7j-6=+%4xd$PHmh2`RpQ@Pc!m-N<~N;vj+>d8mT|y0=Yx3kno` zBo7}9)-p|4|8~CeNYx5~EA8GI;cB5A0baS4@`-1DxT=6=&TRLg_nxB{zLan7j}Ss5 z<OGwU9=pc@SYg%&5fc7LBz4rS*D^#ObFDHMeL>07KjD2#2_u}=T^-#QPO1PPIqmR@ z_M5L9#wf|+KH}$`3u`m3eHWQ-rP77YR(+F5S7yYFOH#9Sw;MY2Id~~>b&k7!&T8b| zL!3$7Q;eg3FoDI5r8XpYCIpD2RX*`7QI1$+XiJYgR#)g!H$WP}Ea!PS$<69qiwRsM zAv@O$vWCLNJ%?m2@Gk$G?&Opsf!twyY&4{V1-i~JjNW(EcP7gi6e7>)a6(4&XK*YU z|2K8CBC6?8M2hP<bgryQ55)Mr#M<O|1gYNV>|L*i{b7`4uJtht#;5bumK`sY<Z}$s z|5<TNLOv8WL*iDIxexph?cFZ!gKiBkKuc3p5>HuLN_<@Yohd~MHDu;|Koh~r*D>YF zdZ_6+A1^}ode4}J^xT9ZgpnBiyC`Lx9zzH6(u8WmncB~Y`7=C0`DSn?thjHnbmFf~ z#PsKUF1-<xW`0xLM15;gJKvprE!<-?js$zrb<YCjq!D#e)-J2HMRdI9u+nxr5x?{n zSaUfQw-;FC(t_T#UA0s0mKur_itf-X(WfNaY%gyFBxp~NADy3|ZOl-cPJSKQcayCD z45rs#BD2ZmM~l|o-5seI^~U+kczQOj)qwjbmP2IRfqLqM==X_hWMk{B*V<brGP?`v z?l>X&w<m$V2fRu{CsC-hM)c;WJLV!Lj>7gZ&K<`jBhSeYLW`qYo-A`~MXH;WmMQ|# zK|O<nDSup{QZIo&)H482>8~|q-;d#1X;p`FG31N6(esZHIQcjX>@qUZIrod9Uqi_t zEG}wmNpYmp8qe+A_9WW^FASZWd865GQ0Fl~?L9zCM3Zq@)T@UI8)~Rh-z##^E3cRm zd5Sn6ogr%GAA$#Ob9I77Zz$?l6c=IwZ&{9$+f`f7UO5Nb@}RMim!~f#ChWL{_Kptr z@SiP=cst!zP2An)dvR%Bo63KpQ)uh7?-tQL5i4X2SHK;-+N-L7rsd=X34!mNaSxbd z*Y_v6<eo=pc4U`3g}e8mut>bMSU=eBkV(gcVZ`Fe3hK%}W4?T4i?Nj>KHw^nG5nmS zS`)Vs8>-t<E(ah94iABH<dt^zh!d@jWz)W)s?$<pQ_z%tYKx6|%>wbGOj*Y@S|})r z^Y^#tmacyZ?bwxbX2K5y)?imV;JlTD3maqc9er{%!jfewAeqKB%$-{l%kKuC=}CW$ z*n11#-r?jr_IdV4N-QSN(y9#_-aPw7y@p@eMOJP&7vj5KsO^boGP~@d$oY97>d5Zv z0?ol!5%0)sW?TXsdtI(luK&c~yNIdS-81slh(iMv&O!;nqTGa4U-RXuhh)6|yZc$q z!H3KDXCkWTV|+Y>_4m3(MV#ELCR%iq9iiz8>2+Gqv+29@AyM?^jEmtbH`d~aO@kB_ z7lfuHayma(*n?>k`#qZUZ}(UmhhdPT8TM4w0r6>#T652T3p&;9M(WDE7tl|A4G4XV zaubEBmp@7T>-FwAIt!$f%3Zyt_B7Elvfs%SeFCI2w@Fv`c<AYw(!zMGfLoWfF-1u? z9toRKBcSeDgnY0OEG}3rbev|G>g0BTS(grER&ZYqF$f(Nu|A{q)5ceol1BvO;;_e5 z*1xcMjq}2B4;hSi-lYY7;l1<N)!Az)%ykM@lvU{^^{2TNee+%D5`lI2afeo4;5{4~ z+A4#@Ie6qpj;^j24Duwd!8^wxsy1MfYTPscjW`7B%n5UuLmX^esnk^3Qr$lMd|<iQ zzCYofJVsf@fZ23>?>TFn1pNfbEHFQ>+tLrXStQFzZE!b*BlS?%hSQyA+b&I3thHod z^Gr%1u$p}y@n;L_MhN?*m@_J+x;FtUjtHcTY|yoT>eB|@h_VVhUCJ=yxm3hZmDqOd z|DIOByEhno;-;un4>y<>>wQM)QICo?sioj*#i`bp?DQ@m8vBK#tje|%T9U~O14c*N znBT6I73~0DaRArHKu*>ut7ZE>0+k&Iwyv?Wz4+Tu)40|3Tk$Ron;HHT-^zH28)9ZM zChV31gmXBqI?BIOo~1tE=fbVd0keF79LDBXGqz)Eg1#msfDNs5_fu~U08|gcS=vZ> z<8LWSsz#;ifHHAxIeR@yvy_?#_R>oC>zVF*@)SwO+owohP1Ze2YrJo_*5KxO*5Fx< zupuqWK-#xJB7p~msuW3FjZF-cv(I~9j%o~*<mKpC3>QdE>8bIV$CS|;#UKZT)!(Tt z!web)Oe8wW(R2Tc`*GA~@am8#o++m=H^m`u4%T=-j3W`ZvvGQF%i%!hNFbM0*_N#3 z#tMdzAw4OFi~yQXIa3DZ!;G5{Z&O6$EqLTP3OvWsY}(FkMW9(zT~M;IK1^LS3V_w0 zrm2EOLeeX03*UbuTy7fLSIUJCsa)7o6@WOfUdC$-rw=epJ&C91TyYqx1%EC_j;5)- zr5jEhzHeow5cK;A#c%heXZq!IxcqIZP1Z1!TEnNJo*@{~N6ucYM;Ybnufxf+)*Kz} z;#)x;c)*2@?0NHgYR8GV>FHQ-`epMHTndZo>LR?|jIWL)|Fd{a>#EDAMOrb7@iwgE zEksu;9lQt{<}3UPSTlo*a4z3yJ$Ivb&Ug4CIp`3PEHgo?l)7mLC&5|+2;n---k0JH zwJW{0as8;ZRZBX6$3N!g%5i5h<B*zDjB^d^%2Xou#(6<@&QlML56hLbn!gbq_-`B1 zB*~X4Psn3rV5v@8`VQ%1STp_ei^yA29JDTXTIVAgd^C(0+oyA6-=xz<50@hU_vSZD zr$bLTeC&Lphw4%Sl)CAzEm7Y+TvUf7Ucw?RAVKrLu0x~As#v)ce87W;7^FOhM1B6h z+ac^`ROS}W^RsuogvN(Dd~$z}amp^;Hp?mX3bWI$+1}LHf7jwZwvn!1(&ffB;>3-_ zTSc<?Mu@A;E91WnyaOGa%xYd9t+{p;UG@C6h-S?$DXrv~N<#pPGC(6+LfSxuMC6Ct zcdOQWl;BRr>s6`a`Ix-<fuj4O9L^=B4?}fT)8B5hr^S5Nd@*WSJgk*JQl8nGgDyPO zMDzc}X4$Sv_?&q-l7wMgpp#cU^8!36tnG_9*pf2$#5$vZfoc+)t4zA^gNn;GXAl1u zVdoGd3b3Zp=Iy?1+qP}nwr$(CZQHhO+qTWQnPif;c*!hlS*xo0>-)~>CEh(o5P>12 zz+8Bgf`_B^Lgj)Aqh#-;iG1K*7}U?c`Nn>5DoE118np#moxDv~pdySZ!JMJtcO<Ve zoLhnokPsTLLHvp_-D(TwdM#G|y(#csOD(P)zmeD~HCC;_I#KMXZa)UjGRXCI#{7YJ zV%F-+bVC>boJpE?xVG;WNObsnF^eq~{}>($cy}}X)G9|lgt+qA-f}N$=+3&yWRDVi z-Nct^hul2CAUU~Y^pc=wdy&9jw6;iT4qQObde(Bq6o7Smg~D-0l;L2r>b!G_bS+#Y zt-7*&a3r5za=Iq&t5oM%khptlWDt_tnB`(ufHGo%a!P1nTUzXGVfz&?d|7T|qLV_E z002%Gm<7W|-zii$HMl1K>KHT76~Ku%CnuDjbsRaRuuh*>Fk(VOYTBqEso9#()rw_V zjL5!XvPpKzngILH|Lt^ar#JKE1RC+OE{(;5V<-?_=Je)9rgMsIZ@OO4Irz8tb)Dwy zrZRj-pD(~$_Kmoeym~;Dpv@xz5T~#<^dFF5+L8{zr+Dp9=#tNffMOj_0!qG4K-6ao z!zY=AkR~)_zj}i5x)4K}cnX2Vdm%7n)(4xH+Pr613z?Gc>uBEzik55_UoSsks{J%R zUinX!N|}6`0hJl!MmZpw`VdfK7P}l*GIz=>akdD2-FDryXQJ1tZ%pu_xcrQpM-9of zDymPPh4XEuox2@}*NgpNY`7gJIkA8jjwpi`uO@-?0VGW3!+}Ydmlez}!saG(9;;u- zJepaX>8lZ49+#Hqr7V5o!sD`}yjM!VfN{qeS=GaEZSqx&198*bIZB97=jw{Zk3U4G z_gtD-*!+}#UCdj{hm?)Gs*=(S1ZwIBtHnn%6i&_q>*v^QZy?n(L=>T=qQv}uw?;jE zrz-^p```JbR<%^ggeB2IMW#(JF-wHb100(<OfmvNju{<|6XjwD?2Q3b2FIb$t%oh{ z%c#5#`>M7lfu|&XmH?l+%7#0woGwuB<U2)9&esMD^In?trjE(_o?65a=S1b6y<AK@ zcm>=DzRik3s#H&cfOJ&zRmpdbzat&DwoeB}ydgnZc^#{W28P4I)Ry?PZkR0_%9gUZ z<peS3N-Oyt%cqd!(;boRvr^O-Nv?QJ!uIM(yj&b;8@5Stt2_ikxs0(Ogzpw{6!|2i z5jIEJwQJk&ZVbGM-$^7Is#$Kb(`27RBowkc@L89q>lmV?7sv+2MofFuXD>k(1$=FM zULqx5a5P22eu-E5k*8LJ>G`inc*O{R;Y3^nQF@+b?P~l46;C^ekkXp$&#vW^ipI-o zz;_kk5AfITKTPKIQl!p80P+!~&c{SJ<m`b>zvPW4^*H`w%W!fN>R4Xx+-bsBa8<pz zH>OLvx_lzA`%^2*tTkTZw@1b4OmsQnF@6QVf%Aw!o?hXV-<e3ZA|G!oK*BR}5LWZB zRa|<m#^_Hh3d+$EPfA(oOohll*Y2MOzY99{Ta<CG{nN4b`*#Qx>`)~B3A2yScena! zV2%M;8FZoKntpW-lvQZ#Vg_@mlUS@H4P8h8%(|ykj{q{}m$)@N?acf((9*5x7=@NH z6E_~JOG{*xIbkoxdbH+)D(S<#fLFMSn8YBKGK_~9-*7teL1FL#BU8|F;}JJJXyDgm zCCqR+MK`R9npcSh{n0A)s#IE=tFzOeRpsv9#yBq>o6A7yIrmPJA5H3vCnYQ+zl0=H zo+KGWNbXiezd~k<R}8ndi-e#I-S<;ge4duKB>8OBy7hkue=x|m6>)(ECEv0`M&!nn zfE_wW;7xs<su-8`jI&OwR7-#k&y!@F-t)|$f8tbA6Ox#qefz3zCm@>8GtNP-iN|TY znN7t_XmWRrc<X7!JWZm@m$b(1-=+7-H>uhfeSB4+CrArZDr`1^l88T}E{guUHQKH) zT;KW?Lw9&a#FL;+-1_4Xyjqdzp?JZn9Czt8xpDBirpF5d)+{4Lcum3AoZF!NM(9p& zH2Ey6EEeRVKgut2@_9{qA{%XA`ay+dj`1Y4S0Qa7<hUwP1fg;=^4y|79|&%Xs83(M zB)ZZmy&CH^{6Ls4a^VEI?%wF^8B>ASTR+D68cRAKX{4lA(>g-j^9}d1^*YdgCWu!? zrw|bfl<ketO&Pl<ufbPIt!a~p8RGiju%wI!Jb(Dx51;&cet>kqbDS`CjqM1y8Zu&N zh1$N3KT2i|;$x65%&az3@$ZaNc2?NqlueEa6#9Kh;`pq{L!kCOV8$j;N<~V#dN@6| zxo(g0bccUNmG$7lTqk!t@Ho%#QW<>Rc`XSsj7K_QH*a;?w!x7|_u3;`XAGSqK}HH; zKi{ymgnXZ$X%a8;c~4nCS4KFe5s#+g?H_JyQ!0uAMWw%CH3jq+KCu5Z$x+z&Kv;N4 zA#Yz<W(8}FpZjNC-rf!KXGbE37W~d{^o*=Z`#C(a$|8r7tKip0a^kh=z{nZA-DAY3 zU&X0#t+VT8pm0cBrfbhLd+cIl;`M#0yVrN&?%r%q$miD&;ojn+cdUm#WdgabmaVpw zY%2odz4SQ-S{4_NLwZ}97I5F#G167Y#ZHo|g#*1qGT`*?QZOi2Bh3|pDQXce#4x9S zzpmv5sKVX0cSx(R)DI&tQzQO)5YGx+EPp42)~~!MJJ?}Bfrg?x60Icv3%zf*fR~Dp z))-Tju9y|}Hx7-`vGp^6RjhRbe4|6on|XP{8nscgIqOKYW_B}NnNk4(x2CF2KF2Uu zU6-6Z_G~2uT0#14En9_nfZicD*!mo@1<qTGEiG7Zl{bf7_;EbG#!mwB)NBX0yeau* zTZ(?xwPKq-z~ag1MKMsiYn<>qoH@_Xb$#Znu~2&dvA??>l6ZucQps~tIHpp;l1H55 zT)@)}OeFXmIea|xm^(U*bAHbZlz0`p$47iS4AMIx<;1-rLU*@*^KM8VTQA8^`IGI3 zhu0Vjz48{MW`LiU@V9N;o10nFI$=O@{?^|M%ASq4tBUK5`03>J4}}l&f?<`mii#U6 zUGtqXK{NECd}hBO@nBS};-<j5!e^cB-PMRG$ZM-(#RP1SM8XNftE=JK4<ib4)uDjb zxc&`7eUxLWYVz&nkV!)_qJC<^X>HGb2Kr?I1p(wq)BLivSFJR=!QvK^n1bp`#M^V_ zO79(!;7#9kf57VZ;J1sFg9j+bfR4tJ%_F^P@U?f6!!IqoX2)8H{5gri;5IfK8-|Q% zu6tJajhQi#WJ|3{7lH?Zcu^@bVt=c8H)MGIZtvJ`UPyI}{?ug(dbYzYe%(oWF6nNM zIQ<^>;%c;+0;#Pxgi?`<nOve5Y*MbraK`N3><=`G!t5dTzyI8m9+S|#Gmm(0-jc$- zSM=kLi;nzQ7Eq5#C+0&WQS-`clC-ocBa^4ith(4tUPs7MT%XIwzQv3OYGXINf4w*E z*<XGX*t5&{EG7KpUv=>;?^#o}b_|?jIDiy-L?I=FPe!gDDhF>JH^<?A;b`T7I0q<( zr6bO053I7VvUclGb|;1~4*dMod?IIv&~iqK3L2l?ZMM#E9o8un3Xwi{MB3)@Atyw1 zS?abCSK*K-17El-oAarfsin8EyB8m*8^iOWJl^O_U!|_D><o0<{G}Mb>HN1VI^Szz zp)-{x_6V^}H~IkhnP42cc5vy6QijlE^VQxIHUtCm$Bl}XKdOsj?xT?bg-tIM6^i}N zA@$)Ha7IFr;v*&4H|i-bG;b{MfDxzU{T7~XQ6ELjvGzJK>%5|(0NptR%F>2obz;+- zN{O6npT`P^vqE$|!sE>%wl*No5*pruf5S;J06f5o1K5iV!=hJD9Rv9*z7^}ZZ8sy1 zYU5vzLOy+2M9Bm@kz(aWwnyfgDLM@sYBB0pl-yB3OV6#hF8?%dEDIEobo26iH=<~r z)qhok?asCihAn$AEhq7``Jpb#a3Vi{D#)FCi`|muA4uY|7o~QAqfE$D-U~}?VzAgK zqUR>dYX>cq;m{I1==Sn78~ntjs$Y&}JY3KkUnT{6n2u!D=-r5rM&T3iC8YHBV7Wae zmTXwiNVOD(uLR%p5s+`)Mx>sR>uZBMZ7j-*Gphk9bfhf&1U9>)UM351I=vAt#E2R* zcs;8t`Y3`PGuw9<i3w;Y`1*x8ZLGl-=_8QSI<xS2_61yX@4-&X!h22#Nf%0=fN?51 z=Sb&-f8r&)br8^gTulFsIPp8#%v^sW&iho8(02%M+r=4mmouzR!qID+hHbCym;R`K z{v=Jm3p!5iGkAT6vsv}t$d$3eeH{<{pdTrL5fnsqF<cOu)beGxrY``Sp}&)@vq{o| zsof&u4>F-ucQS<i(&E%Vw_~m>Ncw8mO`Vx?rS&3IoW+<GWY6D<|81fNxiWuape2eg zSKfN{XhV{s5iBR-QN=U7n|*J43#(aLBWQsoL|~j3nR3>zlopBqvx|N46@`)rbpzy+ z87T^$l9CToF+1uSPt6oQ!Xg3t%3ZM?2;W3h?Gm;keVES&dly%?{jOA_5?mUQ=s<0U z8d_TlntTqtSvt^jNJd*JRly9`q@SsXKtql}9Uu$=dL74&R&+;9n7yh}n}70bqr}$~ z^SFi)C@KI?`!rufAy!3KTiWzTa`m8b`deOSIACG>qRW3FvU`UtNx>BRj=2MXp|k@} z7L6}zwXeg-cM6?nLEJ?DG>QxWCa!Q^Sw~Z9aZ;3v+v;ITjbTE1=5vpF!5Dv$bo~8T zQCr@Oc(}zB2EJ~k{uqofwZT4~6IM6Z#`?U}vZPPBcR6{?GX(6i_N3!E%1)9{x#FA% zRRK=d7eqhY?p~g4F@QvA#;6IQ*>RBQ+Nn`CrcCtqAv`vJ&}3ToDs6xf2)bakO;(&T z=+OxmnL)X?rltx0`3}bP{A=L0-8;JR^8M(<eSv$;Mm7oH-00!c%b7INO!CzZjE1G? za6*fVC{*)fAZL74gfIqFR;y;=`&5=5%&Vi<?L$&<?4wg$B&b=fwIu2vcs?gRLY5&& zQ!<;;A{2gMl$B-6V138w2&dBqr>N87dMgOa<u=D>Ko!P`ojIduK@D5!#pk9TIpVj$ z4$9f!mwLyQDp!gzDVoQv^n^00#m`Ih6!(Tbmxv~snfRZVb=2Rlu;<|n)S9Yn%oQ9X z`REt+Y7=MdzXrHj=>A)Po1Tg3KLXs0j7)U@xBO4a9z7F1J>&mk_Wu6>w{wS~n{j^! zHP)t!iWMjJW=nHI)tbv_i?wEU%(DKdOsQd|;pxlHXHH{p<Lr0Ndtt?h+of`}$Hi<B zfug)ALbDwcumn3t8+|=};{$LK-;2pj%|!_egp>szrE8yV+$55Jgaq)B3D}qJldixP zsM*CI2d6kX=g&z?wN79pX>EY3DgYK09~B)RnwDNim6%@!C#QX|vNpdfY;OPxKGwWQ z?6G}X;(fCl8(1ehMORmc24FzyCBK@O8=4b7RUg0O-Kif}CBL@9#8$|$i4ADJ%JLHF z(Z0Sn+o0&!SXjN2Z(S%ppfiXD2LQR>Y&U>wtn457^IAyrJm9%w+Xa;0I^}w%<R*aj z??Nqr>gLQ$L|(|q#A5P0+L0@Z@hbo)!~D<8vZBD?w!&{-tTuwLLQ@1h)V%lIf-d!+ zM%xycm>ig%U&s~^cD1iYB1l(K6lt)yMou}EgI|o_V7Q-Xb---^t*Wakuc|A6JVt;s zW1H!R*f@+GnLghHt6x89Y^pEsY^-d6loFR3KHoUvyIa4#ON$FYkhb<V;BW8W-l1PD z{JMHTD!vmN0LHxKUBkE5*Iv502VF~HMOM@}RKDEg^yFmdzK_`3Uegd?*rkE_{+Z9+ z6N!=+K7h!MjG%@jmO<Z@pIsFLgBV|JhWdLuptLpj_8*GlT2UUFnBS)|1Bj1a^!gvq z#;U+#Lcd$x@Zak-U*cOpC;RV80f1{>P)V@2+?*t=ZN3vefa_jigT9I34^>=Wu$JFa zw;!<I-=w*J)FX%1#!u7lre6xIyH*EPKcGF_=FRkuFIq=M&$#T@U&BFP3=81j;>TZH z-Ugcz7d%IKFv`wf8^keXh$GM@Il%UG&0k5h-vMT9svq}5KZ=-|Jl`#K07OjGO<y~V z6+A~xu)NAk-RJK_AP%)JQ895aM^VVQKxDq{>)IbFZK@y4H!$m)n}df|?q9CFUe8}k z>%SkFcyMQ+OrmO<E=<1&7K>OL-%Df?XX8$HiH2dCkNb<+Nr?C}FkZ3f26BIATO#5b z&vIC)Wd)2EG|F^v72pxLxZ>p)Vn!EJWUE5aQGgktfCWe*_OjZA`NDC}F=AX^U@zhL z6{vJX`or5^%chXkrvqt{<KCD;JlY6d@a_|L=Ia|7pzy_|#j(2{?isLgXC%jp8=|!R zD0rt1+-gB8rNxB)6lm#wZZSq@;TU|r6PjqlhKw&f)S)q`?isW(1!z7tqvzWo!}{Jj z;eJLs$99R)y73ySJK;~yQ%@otjJ~ja6Cgn8NFdzP5+QMQrR&jve$rZ=*afXi4i9oW zHXVv}RZ11WkeHf4=N!#z@+iLtBe~r`)GcgwV#;PKUL{g;SH`5Ys)W?%^VW56hUPXl zr(E0nPGid8c!a^eOx#{c`!l1*`IRGpa<CKyxq)-E<bI4-V8SLD*-Mf-*>Bv1r$A^m zXXph0d0rwuChUvJK8DAdEY(KYM3v>ED_h`%c&mcH>|C_HV<Ag)wwguq7#FD~VWntV zBJ;^#ej7*?MbH!N>|RZkJZ!JWEaldExS0oJ;tu?Q$HI9EC)*CCD5s@`(y9P`8qHm% z5G<!g8%r$-Z`m6H5$EYtA6$}aycRQSqAoa)z-NUpE|N`gG0f2^TxuoQ1Y)L0@lgj1 zfG{M)kB=}<>XX1!xMPduxd{FP+<tA*q*#tX5DMS>2OdIaPIUMS&SqjHrT4YZ?1(PD z^Rb+15=rS_h;6CBT*Bvf`*P>Oj23Bs=nc|bjeCv1C}8ITu*MxAWvwG)Qzq>LP*#7T z4cQszWL3&T4Mk;vRVxvXl0WGznK6n!#RDnHP0g0OP_HQjTplQMploGg-L>~egeb`2 zj&NSRt!$etzmxFAT>jOEUfYMBGAG2CS!#slp%HV-n5reFYFtKNhe)m4NcMz=OQnYE zD#cb>Gj4~cI)}$Ab)2O_)n%6hB-SA9k#K_{Mj)0qi3PL0qdPwU)yhcgE&jDP-rJ{F zuP#HpuVS<2!3RjKFG=z`9NY-bKTBxZ#uk?%{^aG{0{8rq9FZft=EUWd4&kG@`K_== z?gbo%1n9xDwzJganbO0#H{^l^AEQ}DUmk6=cJ|EdEo-@&JaP?Tz4TkYTH*)86QpOY z?;#k4a0f0V&_hYn{`4yb{d-s=o@C7}1Gehtb+&6F2~_!X+z|Ok3z_Kt%y=8~4l#%n zq-)}J)ws@0==MI!R$JBNa-xp0m8ewDy)A|H=0jUf=Jxh+7#V3&vA;<gYg_inGghwS z%Tmx;pvF7g`Y4rc1UY2L2XT7eT@SM_7bMjCBJ=Nyu8Xl%iSIGDD{-W1W3?5;Qha$v zkm^+q5v>U+qyK!=N?R7kr}V(ltPZP<lA{8=aOuj_pjU0Ev1un6?c@4xky$MX4v`L{ z^xAXjh}JwIm8+g0A`{wD!fjBCz_$7{A(2h6Z!?AaH$T2v>lw+Ma&j%^pwjI%+Sau8 z1GDlS0hi66>)C2fgQot!7~{Z2;vPc)Z&0jFxAf(0ebur7_h1>0J_dX5*{kpgfJg#1 z=9q=3C<I$z*4J-DJ@_Nmj@`Ie=N2Bz3~=KdwbzZ)RU*!bVD!~ffb@(la|WF)AyXNV zmQ;gSLQ(KW99dz774ied1z9juPqS|JWIf8E50{nM2!2)G=mHm)`*jF&w2`KMeJ~m* zcV~mFva`<e$o-(bUZ#UwH1RR70>2;AKEA}+Q_6@CwTQJg@Rn*Zy(D(Pjt`OIA<Qk( zw1}QlHd_@Vw?wj#;l#jfV<uG}<SZs@(p3Th8UhgQ@d9|kO@3~RSa(WZd_yjn4D(<x z-)}n=YKkKh+7B0vn{Suwsdm>{?u)N<Sl}D;=dK2ul}SNj9R)_Y5R#izHkv4v1ATw- z!zBwXZ%}7I^-mC_45WhkFBy<d4#;i;5fiqjW;1B-YwaqUIaxWerh|Jovi5t_CH`3p zlur|XE2t};bQ!)MmdkD(cemwQj@`szy3}u91?aa9_rb2w?6pCYycKFNd9m9>C9_{T zx+!in9_UWnlbJw1^McW6rxmh^SG&mk-laupp6wDl7HQbk7;6cC&-h5`RsChI5<J~3 z&cj>=BF*rr(FJlqZp2@d+{D=!<UsmWem55PWYCW1AX3W6u<~p$dG_J@A=ak6-v<zV zSL(EDUDrrRRSzV8)5#DY&U;LwO&Ue$b$Z)R!dXbV+#U>p8=by$cu|N#vi!Rrv_gTI zifGxJqx>YP$qvN67yO>k45pbn*LB<|oqsFqMM*UYBVw(Cw?$2^IKC*$g65IU2-nBY zWx)88rcQE>t_(5936hWm=LWKLSUkh@CG4~0r^f&#$=zB)h2+V(WV(BEAt%ceIE^eO zb^*b<^WO}sF7dkIa?)1fgvO*~`@@#ez(Tx>Q|fXV4nCGyfMh#~8Cw29YO|1f;U|4q z&X|YDo*w3hf|!%a>(-LAnJx;5X&`V2QZUy-VEIGkYr7!xl!*lSFGNb$W9v}EgpQX@ z2RmtcUQgM?-Ruj}EbVQ>O?Ez@>j%2v``t*1Wp^~@hV^<Xt(k*(7CMh=IoFdB*3@(H z+>*JG%5qjx7?eGpGd#9p0V(~4GTO?K>6<*NaGNGc?O;2atNcnj?~V?$8GfmY(oG4P zOm3&FR$d+P#BAiW&8Vc95k=EA;SyM!5Hiofhngh<D~ib1N$7QQsfFD0-zhpM6zf~- zzKY5M4@UB$<D9qzDYw!BoWaAZ`u59ahh&s(pT+QanNFyCKXPz3tV}TJ12Ll%>rxnD zVw+PM1`#mk;D^VzRu#BxyoIw><NE>JxIdQC6gf=}hbR`Ei%$a9DY!V5ONqwCxiJ@} zU1d6d=kj}z*mtrqJG!rz;@~A47#7~?f2C+<EQawIXR|MwasSXMg9%m#aFhMEGq~1= z7XA#c<Ba{j_HXhlsZ#OBE3(Z==|CelE9OdZH(khaeiF>5rNtmksTPO*vC)_EqF|`x zYDb<Da;jaDj$3a^?!st2SjEYiE+qIDxl+ihubr}t>l`jjyaG6{>_R}w&q?r_m>7_Z z@bv?w$7!MK-oBuFKDzw$bc}d#t!crTW~!Emx@a?(M&<Bu)0b+i_AVU>L*O57diH$b z!mNT~FaNofh5#?#2vDuV48B;eUG!Z#kf)(<!=?S+b#Rh-6k&=5EwbYO`)B?34$rFq zz+_W_sP9mlb=hUG)2RIK2}A0US_46|j%j@H`(NYrNMviBXGDYw`QeRx*6paWwWf_O z<Te&Xws_b?(4}?GpUtZGR!li!=6tgJ>I=#AVU7#!uYB-8KK{^N5)Q1Th&TMy%hc<w z=-1Y)y$%<PJA;g@qPMfd6G{`FW}_$<LRY=&9p>aa*@tdggzPmD!<9%@JGH+HISb}f z%T>k7T!DS$8xr}EApTGWpPvjMk=J~%lhU;qH5e2p|9sDdPUwW5HMZfXmzupAg1BSp zeF_Rj>69d3-W$PL`hU=I!Zz}8gF~sXn7_a`S(fz`rVk>+a%I;l++w^`Q#v+|aH88N zdUOhkpAN}tD{BkgZQ6MoQ;!HE&)Hw~3Jo|IB5CHlS>}ZroOeF+XFwPRho7aIQ@q3` zx=Ru@MnTdujMy9`{V3fp{Yu6%Owx|OHN{zITNQBz;V_{(U7SIhh*@aQ;%(=lYz0Gk z%s%a9XQ3!&jTsQcJ8?!4WPvSAQPis9h)$VeYQupBhX}$TQw1a))U3d+(jka8%3F@N zdV`FJ)~p7u(JE{);ZxEbtv$^&SMRkbc>dw=inl}#9z`0@;s&i38Ka%VpEbi5-7!=5 zU1rG{qnyN2j*hq@Gj&Tc4`w#H11!Yonyp!htF%YHJ@7-39kU-)U{?qhbl~?!6gq7_ z4$3R%&QdGNhUWNVhl6ff8{oA$Tw+>Rm@^T8ZpKq=MZCj=gydD>!gx|9o48Ns0+J?x z2m37&twNJ`F%URWn}gQh8JNdLvaoeh#XK=w?0}_?G1x$PTDOyIdzyCY^)NwX3H_W7 zj#2)E#V4kY3G1|jWvOA_xP5Gixckun+z21QtbNtXNHa?vCMilk-<ZJOUni_ibO>~$ zSWS=Z?mTj)(RE|jf`2@}`0>8MTNQJtUM4Oxcmbj}J<QkVyO#|9?2SbVxI(%Bwb)vP z6+Cetj?k?Er`#`bs<6}_E<ezOg|DErQ*9R&t5&Iq%^4<BMG;d_wMbf%ir?&l0TXRf zBPyyLTQewF7#&RxHt)FGt@U@ln$M2{Y44#qet7E__Rvut%2^6PNZjY@nk-#4D$g)q z$l{#*@SDr_;v)z`bdY`DUzcGl$S^N<g6)0aozDPr<ZL`)S9x(`*MPj*-)%Q+kLS{n z<2(CZ>T^spU#?xN&FfEN8&Yvr`LwKlntxgkv;8u%$FxgMg|29JKj|lfDz{<bcxPE5 zh{}uA3j~2J#BJ>Zn4>~l*Lp~e(0&d)HIe*UaiqdJ6S79>RYt8FOadj^|I1pnfA=s- z3|p6TMe4!&`s;3Kj_ME{R{K0_DJ@1g7K;rZ#|6zQ%tgDG7T++HoxlA-obE^435uM@ zmWB=7%07B^%|}c9!gWt;Qmp31ry4JY6We)K$^kjEvTAOc)Ty*tk09>5B;yGGDvD-} zw3*qNDi5RTrpL)^uOiT#bIMNVDLJ?9kO`H1HHn3yb{!fxcJ|U!A^YMMc#Y0f%)wg4 zA^K1q)oEnGn2$L)ajRmkHnev1Xlu91y}8tVAz-4Pz$;COOs1e;*t%t!4ykClO8#&% zPV?&WfqQKYT}_F&+1J8rmTJ!R&1JqZnwi%7Hy!gALb+GFn(e>$3;HWy$Xd(;JGIKD z@3IRk{;xv=!=+9}Ro$J3KoM1{#N0PN92|8;ao;%69TBeb^p&%&UspsJ_Mj=W8W3lb zjVx`%9-x=3_k5^0knh126)SwqFC%Xm2lXZ`xhAjsNE(+QLExRu6*^N!vWcOjCF<KE zu7>igGq#W?nan|E5OFKomdMiPk=}Y#!VEvkDMdkkcN+4-2})bE9$*5|I^k~hu)`Fy zTy5WBjBA_)c`$wbG=JLH*2811v>mJa%q3UK5GX;1J&PFYJ_ItSh0CVtb$5AomD1T- zI9(il_y_ZN!$Rq;{m}W0GPsFtR1nbZX0D)78ao4vP&t^sP4RS$s{UW_3DSc!b+qw# zzA=NPX^8D5!QU=aKKJ%=Jl8gMdeR1>44eTJ(cD2SP2?>4>Da2-=w#C&?_d{Ke>%Mx zX)Q{LS9kCi$+3rbIoq581SC({5{!!KT;T5g9UT=lM;cV<Ont9N#n+{~RQ%tppaq{l zHbUWZ5arJJ3V!3$iNHu{r_^#tZ0V24A6b;9Mezb=%lqg#B)w4u?m+cOBZzIyDPTK) zu=B9Pu$v(E=y6gG%RXdzl)84@3ynVcb_6}HQ3!yTPU={c#EpQUq_xxJR=Dpbt@9?! zc9&3xd*T*V&6&5@qi`4TZ=q32ov6$6Ze@adQ)V{kU$HiXSx36OKN!I<n_O?&AbH+M zbtb`k1&#*HLF2=(yKIIX@pqi7(zCO&q>G2Z&d#J=oJI>H23xdvs^Uu(5?(1jF2kvh z^Zk(1HNKu%1MuJ3{FyH0{A{i;P-+@y@U#qPY}pE8qc97e1)31FdQKKadqCRyc)jSC z<lXXW=EpD&<R2Yqbc}a1g&?n-_&zUd@HJ5!2(!eDIfMk>CJ;bR5k?OYZu_Eyeb4u5 zcXOuwW7ckZF?=spi}k*7N03*{^051GK*jA!N6szX46_NT%L@6?DI_GLA6_r>5wqso z!YWh})6u3vR=C!!6{JO`#Kko`e?tcHL9p!z>ErjMOL+p<s<mfraNF^ttw(~4$`{z; z@-5M023J?`%#`?$oC{lItuR?M_+KEJa3lWuyE@IjjPVN7g2|lA5Z5U80m_01K6gi} zzodq`7uKi!t&Z)al~%n-JpK+w+~pi=Yf9fecv#TUw5EHP6AWg6M?EnnD4UYClS|65 z%4K&Puq7q(UdY;vgH=51OCB%i<yNM`K>znjR>z=eP%5uaBUCm?t`>4E?7Pg6|CN7y z>Nv*YDN8(qw7SHxk1Cn92;=KwtY7*5D=^T5*r8SPa)sYkYO7vaKT{<#<(@d)8xKFx zw4*b@`keqeix&B|hV9E2`iHS{ZBAKoX*a4|m0Wn+6<mf?5<6w4{k3?-Td~G&tN*9| z%$4{uQafnlh!vNrXb)N$44Sx1PbOzz2I`P`6JDrKII^{aD6;sYMB!*UN^m0m;S>79 zaxd)$^>1dU3r`lk=0_Ld<*k#3gUvc4b!<ebuTeK?1Jysb&|d!bReVrL{_0)snhSq3 zg91~29Zs@}8S!q0zEu@Q5~of}hABGt0Gk#o6EKh1GX*mBE4?OB0@BAEuAG3cVVZ(` z0QdQ-rI4FLBGOu>Ne_~U^4(FD{v7+7qizH=N{Y~>$kL9xt#9K~K?ZvgEHe1c7xrT} zYksHNS`cXCI}9XXzc1$yY<E{HWN)m4@KvQthyt`Rt=7rE8W_gE#<|!FcLP*k4UYMq ztfi`;I@ye4|GP8OZh@Zv<|{KY%m^yke4L+K7{W=ND$;ER+*%LY>tkD|-Q-7qA$`bz z8bTJ`z4G%9q1oc(B4%0O3;Zl7lg?);CjC*aChlr{L$1I#12JQ;JN1T`<=YoyiGPnY z{Ca$adT-4psMkQ~bp9zrD#~7DV}+jQ&_5-N>GUb^8q*qVUR+GVQM}d2GFD?-EWOWu z;A^?3mY-lC`VN`*mw#W?v(D|iG1YuOvL-6!0Da?rvptH+abz*w&EJ|mEfn%%7n6|l zD%1vZSYqMLp+*@{7H+&Yk02WUy_F=mc%j>>q!)cAFZqFpao05r22tzAY-ZVN3ME0t z6bvxkdh)1Ptl?5AL%0y6w3&UYZuOkDR2;q_db9DGntSs0@fy+0fqJcwR8WgGBK!0? zW+WrliU339*0-_l7gpu=sSC9<pg2)Yt`5|lQarijLH-CdNIHG_6D7zP;bSv$dt68c zpD>VXoP)g{BV-*yQ`N4GHB6=ZA1u)DSEU3R>cs;gy0Y;4u2YnSevwTYrpJjUY`1WD z(eDCoC<Mv4cov<IDIp9iNL5N4gyR0f-1671qcMP4o`b=VXb%aNH*zB-V{~hV$LlRL zN{pDM9sH@EJOfIZbRzC)>4XWc9(de`f#;BxlM+tCf0SoUVf!Xf{-=-vY#wv*twVkP zwM4Epk?+y5)zIl@l%jY6^Od9-aVue?ryfvYb~-^=?wHx9_dz~T%JPu@)*}D2wuC8a zbi=VBezL9E`3}Jj-kyy%;-9J3h0*dDwn7TnQ@IL+s?>G8S{ZxE>_LMawtBVo6arh` zFC+kq@;`I{@dgMkg3r3_10i@4<Nlyall7UR3@sMGU=xA2a<qCH5|tu*7i)_I)sQ>W z`fqMx&pXK~YozJzA6LFg8(s>IWzE=UEs4BvLb`V!I*0fML2^+I<%!%(k{9}nqmhOu zm1ZOQtTCZO<yJVSG~j=CYwN!5(AtcImC~@`u_XQhi=r<aCNCmUdR%RO<1K(=ljnAW z&_F)#0}vwksN+VZ!4i?4tq7eOE@`o8m-X&R8Sm93XjrvDap@gBsQMy2#xB3|uE-z> z*?@)$*tUrI0^{nfyQ^fUyb1<bD)I#Nzbh}FOaxKis|G(-#QcGs9x-vqV2brwhSRH= z=IUe~O`^~g=ertzlW2F6k+=7kciauOUyebJwTCAOrz`17r)MxegQDpg!T)^<JCJjv zA}4ELgBpWkYX?b=I(4fO8^5vB6A-A*<tIT)LDsdH2gSPo-T_NoMIvo6AumFpEQlt) zG9ZvUI`KE!)Yz;R@}9?qamdR)v>&l#@27(D+2vSLx3{G}CkuF!;uO?Nbulz<Cl^L0 zwgdA%Riz?|FAqomsj8@<awNVDL2wf2Y(f=<1$s9KTq>jy;bT4==!Wy{CUuM;iH7`Y zSLs;v+YFk00?a&Fuwyd#XQ)~A9|X!Bee2Im&{z-U7sSvEsCX+I)xV7PE<G{I9_XG) z-*dM=a6o=?vc>0hoeDT*-8k++@IR<r2m9C|8(1&Sa5sMjsL-~0bo~t=nqV}hy?itb zZef@D%-ta_W}4%++{4X@#AUJDLvi8k>7Rxm*`{E?4hA-sEdJhf7BN<rAET3>14py5 z5<&{PhJQ&vja4q(6##C~%iHjtwja`XL_3j@jKG#?XO;ZPyC$*v9x<orzv)$~P}XOf zG32LZMd+($Mz}Ti@-$PSX%wVd2d-zCJ$@BTrIEjz+<MQ$8W4=uOKQ<MK&SNf)oM>K zt$FwPy%aJs0-}ve=Q=+e&OPM{nLXo|qYO2`>vPlCGR=2aI)TvE2(`b2>z?j_S!gps zq2ICVD1F5@F*aH%X>Ed4?cZ2Na(NpQ7AdCfnC7^THJ)`P4eWHA1AglR@7f-!ja+lJ z@OYbbJS?P6xAX2aXV(N0{C%&*?l=5GIg5}{E+u(oKS>Nd5D)bd&~jC->A;u3qNn~C zRVDEn>n3zrtSFHRYlEO}(_hDWG7{qWoaD6Ny5<M>>~Elevzq(PzUpO+_fQ34a%7<q znT=a0%^W1oGY_m?HdSY1Hm<~OMB1$SNJ;-v@_P7T^WY$m4<Lwt2Hlt`GC;&AV_Aq{ ze6q{dO+>dHiAsomC3xIW+6F`kAf{Y>8C9_ysn(gpq7d#9e2pu@=f#dvoKzZVR?f51 zl+pbs53qc1K%s29pB)OSu`UNXskVa4AV$$NWy*9&cfmS^e}P#6Uv!yJJ@%F=kJ|Eb zeh0fz(xW`Vad%{^NTQjiDd3#y^YMF5Xy0<Ll+aL%$|DstXSnDPsD{v;e@RaKc2N7I zN&$Z9A#j1#(tV?4ddU_=`BZh%Ao^w)e3Bs(kBEG?I8_Tg(|87jCP|a?`-WpH?S8D> zMup}Lh%kWXr#}FkQAujNv1BsnhmF>+Fj+k0!wjzqkG|DYbRD|nRVrU&3zSdlcTJSy zBx(E*P0mbKE*q>x&+mIJ%7(h}?Kp2dXM+6__)f_e2O_@b><ORtm47hc4UtN{nO7_D z3gEDR&1`8;F#fHZ4M)_cK7~J6nEtyv(Ez27iEF3He;JAmi2EC2)5+-0c*&U+(rLQQ z-i2TCuO>-~{oEv%QYX4$X7ooM8Gkdlfk&Agvg+vVJd9X@jf2o2n}#z~;hZ?hRU_tx zycKyO<B1uSSOWqoOO;Yqf4&e=JcnsP<Y6B@vkp~GBIFPTcKVE4pHz#@+CQ->a~m{H zP?A*@hs;re{oH4aIWE`pICcNBm|)vddbe`rqSyPMeUmC(S&-~|^2PR$cF=uSoNO-j zU{nA$+gaGfpz4oOIR~_1V1*PxFN*t1`I39<LaEhU1|xuvA|xNRALTW{$UH)*iT9B| z>LOy9fN!k^O~21IU@m$HmKn^;;*DCp*|Y<EE74{--OL_Kao}O^F+F+L>GRp{-i-Nq z%z>?j6OliTl>$zWdI2X@=FzhY>ygI(l5Pj{Li}L=d7muM<0+Q`uf|1<AEba2OkTCr z2Xu{ayv|^6l2L!Gto@ischN&!8*Kyz$w%mtt9~nJ^#?@~Qrw<Db+f585G0Z?ZEy_V zp_c*PPts4mo-%HdTvclih?>x_-WdCdR1AN=H@?u>_{yb<5r@5RN^?ac5Uk@?R$8() zMLpZntqs&B!r!0kDgx7=Bg5-M?$?Et#x_95F*}`?5a^sWNt}lrfkJ;(xKqqhzunn3 zhk0TvGd8CCO>l#Xfq;&0ot^jOIS-#z3(yx%iDpag5xR@RxKC<M_Kb#DCFB}jWedsU z5pZAef1q^Y6hQZ6+4XW=;KP{ad7Nl+)5*ED%uWA~Nz?)SY1a`u=7q1It2Pi|eWlsk zm)-a8BL|_wuaK&Al(w)e9G<~^9a}-&h&@_Eiti-HfG3P7dXxJ#HX*@os3!9~28k&L z5c)|WsW$m@_d0kA83ts6A2MRLD6^R4dH4Hh*Y$)3q8J|^T8@=MaMxgccaRD*W7~bL z+cgIJmdb)E$?R?KF0u@PZd=44-)j*0I3vp>S)MsfJ9Tyti{A-^$f)dvztN#$qoGQ< zMg-4nbPX00x0<<IbZSs$YaKrs>SCMud?3C37-8HSBH%?x#%9K6_hGAW6b?akBWVjJ zBlsT<YNu_gzeAL}I!^JYt@kO5)wYwwA{4vl2$+s&^y)QILxG$(RXDomMBR8?e(Bc8 zcs`DHrfJRSd%rh<NmsD;+)?3MAernWx<r_VuaAjqS$-$(ZxHHpf#t4a5?0J+$`%Dv zF2DXs&b%-iJb$R)PqQ!&dEB~wS(z`XA+A0ZaG+r>(Dy8Na*Bta1Z!WFCprV|?ZTL% z0y<958(SLd9b=6O@pOfirTQa;5dBLN0)4J9Rqwk|K+OCOwECMD|3!sHxUTndc;xDZ z!NXONTrNcW=b2GCL79QRTO3QU(jt3gxi#a1B#+fS(i{2bflZ%2m|8^HL)Vj@n!HhC z#p`_HAu`#LrZo)w-ZY5Zy)d>2ibD6<si*xnHcia*AGbyE*m|DHMVLpEc%A`6rRWuF zxR|Z#UiS+MPF~FIwg0r0*JWGC9K<2thd?4qwClFV3Lu=zY@0+ACCm@0yTg5|AFUdt zMkC4xA4C`6{_zpf)-U25h*y&R;MSXEB}aJpl>BnsYj8~x!u@RMKnj&mnL8`1mGL~Z z73Pu0X$Om*=N{EYEorU`Z|3GcV5#Jld=g?AVuZI09jz4gUPADOJwJMMQb^k>)@*%} zi1?#=XcjU=tJupXR!8g7&wKp@o5aGsjG4@@!i^qhpC}cb9F&FA(XC?a2yrXNdX?m+ zf|a%aK^*+)=1Y302$mso&J)9wS~=u^)3hs<?uL8{=-3SoT@U?YiYPwfZxnSN`k7fs znj6u2-IQ$gO?Kfu;<ET{E-bqX8xXqyaM|V?kSco6KwRKWJOp&Z9*$pO>j~^O<$W-) zt1?GD`BB5av9`XxdxH%HXB;{Q1)2XvU@c}T?VgT)h$kK0i8@(@^9*G98i=;o`;M+L zKZnDW7M2?LY9%;!622&y8U8WxD-QQ4xq3&^*i*A?w)#2KlNFP{;=Z@gFr+6UIXRfd zYEvJH5auxPYjZOk$E%EME_jQ(Qs&6Q236<9hJkBE5B&J<UR*8Kp%5JOozUl28+aii zfR#W|@pN7y#i^Cn^PyhjQXcCiB>mgS{29gl&K?g&SL6%)LQ@zq`yH{?CoKFzQzb?< z@#8*h)4=O*VaDVlP;s&OO#TzEZ|vH3Tt;H|gS95Flj>ij8TeO+4wix`#9r2x5+IZq zJHv8tm4X|PGfj@HI7&WJ%||HL?*oZLGF%s^a`HhMMHh3sB_GoVpjQ9{LHivQr4fM( zfByUEy^V`1b&(OvmlyL?CH7zKK4i~5&u=v}V{VfcTi~3#)3g4_u|rWAis!!fW*%RV zWb9K!@wI8Q(ZhrmpZ8_vnW&bX^#d|mKovN{(XYaEVdT~#?pKxzn3*KNk$l`sE@2(c z-55NGaj`zvqR_`|d~nmX22bT+J%u#QZ8Au35g{D6MW*47av4{=vwYFRH8?^z;~u;< z4jm<JWpmRqx5$8YWo7R+IO)e+4Ao*^gzLP<p*^*7L+k@uH-KoGSchqX36i`i3$)V^ zTx3|wHK{q1C9xlEn;qqWgWo4eEXfLgObM7o<WSW*qZha3tJ2|)l7d=f`@An25z0o7 zcdWQ8GG2S{MmcZ3Go!Kb=rpYGsuFanC}VVWBTaQ<Gmu!$pu!#4g_+71kHpOYwxnm( z%?Xa6=DPD%g83SS$oj-s0?}Ku`>K$3qb__Hrj8lEEqPXYFar`EbR@6Wn*QE<jMVTB zT6@MalSIYvHL`M!7W=LupZnZe_qL2Ybr&)8j=Z=9Z)X~&OYq4T{0_ErI35f%)j+ZP z{0)7gq^9U$jI=2yi=Bu7ic3#UBoFU?J4JZ*{BK<usY3ekgMLuWbt*L)wWSt#DO+zo zUy&Mvz69cfsw>8O2jZUM{X1WY0c%P;zc=cwb<uFqzj3zFVbqHC__@xHz8alUENG&q zc_95ENxHaDW5(ZB{S_qL)j~Cp;~0KLw_?<SLU2~@hZ)@x^Lq1}rxBE==5xFcQX(d6 zTwU>+I>s~z+So8aBtRe`BddSTY+aF!D+XK)Y`28FilmNa_>~Au+(*@^C?r!@G_ix% zxm_YF?TjPn3C^I~*0i?!1E_|WN#_~2IHRe{zYR2&)|>$&co0kOPJ8w8v=0{(4DlVu zpj|;AG5ie1FE`NBO4=g?Q?;yr8CXY2Fsq!zl<SPS&UQ-?sbyHwEsq&dvLFCsTDB^Q zI?H5S0P7Hv!lJ()$BF0(JE~)HwyDbX<9%?6nl8CpD*}USZZJtfdWEy%=UdTz4A}Ey zv}n`sUI)VH#eW_4#5TJz(ec4T`SDbJ@QL*G!VQk%<!qL7jrJCSvhcoPqBYtyj@w@f zf6qLGCXKuy2~j4N!}j#F1%>CxqpUps-LQ$RoA}l9py%3;>V1Kqo5(>NhTnv(u2?T4 z9Li8I4vMZr$_Sl+*T(}Ls<a{*;1#)p1!~}G*Cz_3is8s@lgX~!e%<z^!5jPSX;4Ol zOy;owIKU%<w5<-jVXh1IMDYfbQZ|8!@jvJi-}s==xoBRVG4=>;k-vChKJs41Jq+Il z@ehES%eC9JG_UH)HE)wQwa#Fmh~#*zQQW;V@bIv$hnUFvs{RZ`D84*ejS>S3MKUev zJ<qsF3{-Gcpf$NZpZDZ*qjrkmHbr#7e9$?Se*ow*+Y(Wi-WBSJb)58KJ&Dxti%qoz zK9ph*d-2I{aPSV&SmBvaGddsE9>!6_);$i!i%TQGn%+n+V0Ak?AL+t_B}1~BWg^A@ z3nYGRjM~^Nh>T~xj7xfL-=z(U#^o#$6~k$LMNfR%CBiqPPWDfAqYX=8#1;bmIiStp zfG;_i$i3|B?XX3nCr>GDn5y`Yhe^AoqgqLt9OBaJs6@0$F^Od!Ypd!_v1~OclQm5m zW3cX|p{;E_neq``ude=Z)2JnqHUWa2Z5ePO5?^N2o@+coBHuh4ttAZzf~6}pF=RzS zczE`^02p8q<To$3{cT{TEUy*sQsx2>6voG~y$_m@u&R9_u-f$qBG{K9u{A%OK>mdv zXLgN1o>hcDa2S}s6@C+`<90BtrwZb~&GtAjXU?$1dPI6Ya1(d;E}uYL7Y4$Q#}OMC zL6!GgR?>>K;55WOH<`n4@Z*h0CwngB$e0ez!Dz<@+TEXb0|RZ%iE~#~%MDW%I8Td$ z6eyu|o5lOpTXT);abjFUtoP@LdqWtWgvJC~rhiKY!ri^nuuG(-nr{EpW+8VhqhoeT z!Pj%K$}k$FIv!bA1%NMib`}L~g>%dmR69mIn5a^}wXAT<(T2m`<nqyZAmGY9#~}}+ zJ)HP~+MLqBdc=o=?2y@(>+N;@TUFLmH4JNt55Koku+V-@;GIk5+mrW@Zzdf%mP(mF zS)8Mqr1T?P`smlECstN##t*RF)`$2}q{hf98+M2igYrO9e5Q_GB9ABD9wgsX5c;E- zbEg(Ox>niq3CHM$1NQx<L=f2KoFblb$AjejYWcmh?D+A1;?oA7eIpQ}vK97-a8u0( zKc3j&S`_MZ&{=lp*+^;@thw&2jTcULB{pbE-Thady85$%X<vTC!~IyS6P>B)7vtGD zf;841>3F@;#~d;B09Nsop(5~#W;rTSkHuc6>QT_+b}Lr7z_E_jJ7}|S&AIO;cZE1> z-m!nLt8T?O!XODJ4*2%i6c9EO3AtrH4{r?m9uM(l6`ufbzDe(&?mb0v2~t~{vM2Pf z%aUYZ!AVxAS-lPcU!Z3j;o3FEO+TFAbaLM(#>g<p5V+T;gf^Th7fP{;UaJSGamv_V zHA<V1o4$k!nv#iW;f+BYlBG{TnpHgPkRKhx#8kixTl`9&sgL*}g7BA}N5u6FuF`8x z&?&5msH@raWRDMBYmZx6V!v+N07O>fq3AeQd2QXp5FP=Vpp!1NKRZsA<IPUcllbME ze))L}l^>inI9|I_fICwnRrR#^Xhj0=8e=(9*sJI2x?M+3q?(*&L#^8uH~V<taSF1^ zbWJ#+%oxpY!axa<a!+O0Qil+g&7ajT?_uzGY^yDWpe}u~1@W)6px4qJysA-<u;+OT zArxn_K#aZpx18C_dGV*CR9`M+w(e&@3nWNukR&pdyukWF=F;sq(-MmswcQ{+>fxRu zG<xUfKr78H9yEiIwa2k>9hH_7E0Pt&VLld=*q02a=d!fxxH?>fNDZ5OHFD2QTZ^G> zb~x>~@8V0)k&`+HP<L%?>&KN21wJy#?ZI}<ke+#ko%Ad^1;)@SzMJ@NAVCF3F+*cy zm2Y`}x#<OJyhP8f%-Y|+^{1EAiDhH=kCahsb7>-pHziu!6&;lrad0U~mzI4M4VU(= zIFD<08u8@!H3Y4)?+=a{LOh8&Fjh&!v?y3PFbI&VM&zkV%qUwFRH=EMkHHz&V+`#O zbL|&e!Eg11w{e(Bte=^XrV;P`X@*g9@c`JAB4y*1v=^+M<*kzE-U*kGS&C&o0zVr} z42B{Bh!&TU16r-X51;C5eq8QNM*fhYm1cx`C0IaMGB;t?fNk&pl8<W}6q8vm%s^*M zKck^iR9pLpK*tV!oeR^L>a(GdQ1fPviN(y4$X4N(Fj$w_2A}0)N%`!K!V(jD5xD2> zXoOH)T#B#`=Hjd2ot#h<%KPHHty3KBM3X0IRSe3$wj&^6L}PI5M{c~4bW4*=Oe)lz z8;L(A3uMd4K>^=#K0tPzFfUyJOo!?ol=H^{PhYvWOP&mggFUmjC$1l|j*NA~Wd^k{ zbvdBG&0!?lepxbNL>NEJ4>BZs^Hp23jI44<yJ=_2L=lyV{1C`HE@=-Wz|PNH4LZ$% zuxy=m)y|Jkt4?IO+Ic3m{9Qn3J+IwI)kP5TfM9!!sUwl=2N~L_x%S%7bYlkM&CYwD zB5|y7Bi~3yTE<(RVU4q%h%{!E2}A5QzHxzG$u&TWRJ@00S46lC)qk$)aH{*q7qSu} zF?Ld(8XY$Ja@0RSrs%BTUTb_|avF?Kz^57d%s0{6Pm}y($bVb%avYTZ!|Ekbp9{e! zM(t%P*N2Ry%}l=1L){%%b@qqn=Bdar{twm@IUhFz1g?TGOT1QEdjDf*s-Em2Y|@3h zIjWhmVH%KjlQ03iW{p=`7echgfPi_!u912^25Y~31*DD+@4ubelEnFZeW5M?s8`gM zs<PO{YlRFG)J45AD*1;1`AHpf7I%Mi)b?otZ6WiYUBAPeXSM{$8(#^2^{Xp7r^aw? zXGj9rE_K-6YFA<@_wOEoF5eAJ&<FTw9t?FaiWy=O&i+Q0obDn1g_cKZS_?2x`LR6k zK@@V%!V(NPQNhgtArCP9gE?<;zVuV@1cIp(>4Z9~8>1ld%hpTJ{AGF!m$lhLr$Fsv zQONo~jGbeTXhDN++d6IAw%vW&wr$(CZQHhO+qP}%Oy?$dG9TV#CfPq?SJkuDx;UAI zikC1TjR03HNsU7fZ-l{Bp$FHM-#t%jy(*&*r)Jk`JztT=_6Q0T5o;Cs#_2CMV7M}J zwH`BL=BBZRE1b-p@1KC52^9x!3>bH(t}ccd6{yBB<A}K#VB)3WlXsMChnAn2oc2)? zJe;UY3FO^YGm&+qSHcrO&e@$&+%8ojQl|56@gj%^`+KTA<3Tvm>e#6VItjh0fJ@)o zGUH^V0QzA*!S)h$`#8k6s=dK%DD-VjVI69eLcHJuLv7#m1ox`7{1$p3EY2uxxSKC| z3c@Rt{O?0tr(yRikSoAJ<?iYmA5l~YNhu9P5r@c>WJSOze>Wa-#WoeVba>y<(A^Z8 zr6Wip&^Qbt{xsK#%AKnlgV+9!_JhG)wK(laHlex(SwEiEOPlz(^g;AGJ|(b%hAa44 z`gpd8eP3`SJg(Md=uwBX^^aS~7%372$zxO4mYRt{q2iSkqw3Ba3-is>^JnWQ7v!fF zE)b?`CE{&NxC+mn*)%j}Al>3Fs5Sdxnu`Mgt%lRJS`{9#1IA@P25G;2VI1csE>d_3 zu^Epf5=PV~U}sD+^rPYymOS8gj+%yyVF?J-X%H1S0;Xu3TEKUN#Al0;I|krnTE8w; zRn^VinP-Wj!SOf4eFVHoOu-fH>95u@AIo9*ijV$p2x)DSCGJe4jqj7g-o)B35}n$N z`i1@G?Gic;iQ!zja_mxIhH0$~kIf8n$qx7$q3k||W|gKS(#KlUX14rq$Y7rg!ycr> zd0Vr@IAamfUrL`iSbhp=<9B<GMPUS8GE>nJ7FQ4|bBleKWjdr}dzNPL5cMV^S{0q? z7*^XbP?${EzJhA?qb+gJ2rw4L%~4vpBjNESvr&&4m_*7ZFFb(Qz%K^Z!`u7j-q+RD zN3prux6V=Vp?67if>;o%AjTYNlauK2tM-bC`oJazlIQ1$IUy!Ugj>C~OLm_lHa&gq zK2U#^IS=h{0zc(*UEjvxfcnnve9{KQp%Hoa>EY>F8kGJJ59>6!jF_<8AzW9@*GyJP zy9`!2TktZV6zQKKTof|5a4IFj@h1a}p-R9(`-7e?9<^8CdX#NW`oe!n2RxvxyzvC3 zd}vfrvmN^}YpD%k*Z_Q9xY;FrSzbzRh40M)pKc}Vr3~FJpg$4z=HMf<%oux#c*pEA zk6)ygYntU9g<%cZ4+>hs3jSi8v@I5@vJMBPy1j!-wfS><4XBo!1}pM?;;W+MHd{`( zEL|8G*nWWfM?uq;lH4Uq$7TY&nNptQdLQ|fex+?4DpRsmY;4*nsh&Pt_o&5~r84(- zKzhS(fqp&U#48kSxYSy0xwfObfe7=qK!ret&OLMeM-6O~A!9vw7Xy;XrY6NstlHC2 zfjw$g-kk~yIr#X&Xj6A_|M^H5S?udXVaOHHya)wclxHV|Q(B}VVE?wZqGr$<d!4r6 zk)_M0in;2aiNFZn1CNW4BSIH-u+<g%o4$2mI$w3U<8%_{YkoK4`P3rsye&+|pam|X z^0>6EJS5Qs(PBPxQ8G$XQ*QvlEdh>VhK6PQ@Yae2gs?G<)!pK_nQyeWaE0Q(@R_c@ z%snRTFS5zPrL0DUKd8z_tzHe_r5|qw`y%>2kLoGA*BY@3F}*zHwdSX>UtTX-(6nW~ zU*zLPtDP|_ey0!IW35oVjU3ECJifilBo$sHN;tI4kX%b4@#)rkaT#zIM~;vg9mRr` zM@Jtg4mkI5yQ=PN1=5l2^nB~)Xr)yh&U1xK6$`5uWWB3#HmN)z9%}HBv9ZELW=DtA z$D~{bK@?6e%axdE$NURvvVh*AdZ*U4c-K;WZlExR=fcUcZIb5bL>a)}-vB(z+RE>q zubSf~`PpORC?I@-(?-3j>d!2HC?dP?Bt3!(glRfR@|CPIP*h{MejhKR*4YQXWVIVp z8=LPN5N2H?d2Kf;UmT)nIHoZsg2zis;sq!GNcnJK6%p>rKq_4m^(p>3cmou~HnR>O z;NKGE)(Z4&9k*l6RD+{}^vPTO%NYS#u}|!zaGtA&{pRPX{hL_VhlT#TH#l5BS7Z@t z?GiRKr7k8F{rao6O;Pfn**wPo$mX%J{eKwmH?G3S$nc-pJVp+V|0|nk-D0e!E!n{m z(b?HpxA)stvFTUu8`#DXuyaiXaV2Z(M9SK`0a>N%d_7-$ecGP=VyGN(>lT?dRfsPy zV~WV&N&_m!zS71}Pgi>bkih5qg~gnaJV8ZR@`^L7D#K~^;QGx2_=JlA9hyOZ3divj zwlK^Npd9K_>FvJ_3-yn|<e2Tj>goa1)Zf(H-q_WCs?^v1S)c7qfy>#0t#h~mEBV#% znQF#;<4FwkPff#`-B#S3oSFRr%BTd?#@@=B_M`Ozi2RH4<7nd77Fd|dG`28-!dLi< z=Sj-W-r)r$r>3ImT|C=@;R8AWs&4@Eeyg_uTjOB=n|L7$VxGf2`zp12?6p#+mLi_! zukme$$*XtxJ%AgUxHQoN{`9A5QKwz`*Gx6}MkF_}p}E$5Qu+NE(0xn<-~gWfVLloD zl4WYDcfG57eHWboGP3=teVN+EPG`C1m$Bhf5C3QX22Ah;-U!kG#IC-k=BDljz()o! zw>TB?Ub}>;6VvA#U*+3R`f}pK8v`2y@CQi~Ee~%D=<PIk@6g}?7Nm`{6Y$&X=a<gg zCa7xwn&LO90Z`04&Lw)6efmp3cW~QX5MIeNhLkruFf=d#rT2dMzMI^iJILZ%*ZTYs z+nx}P1K(FwNmg7~E%{IO`(JHwTH0W4T~yT;H-HE$E-V1mWiGEf$NE36iU`Ov-wK2G z*v6{vU|_%3+k<~n*Sj!nz}ebAWr%!_bO?(;Keogq;Hq&L@O+PW{az;fM(>5mf9Y0y zkr)2$|C5*bmn}Fkz4D^Vl=t50-j{o$4FKiW`_cOCDEyNFICk~#)Yt&L;rRo+_aEyL z*bmM3KgieJr`>tsYZ_~R01=gzUjDd9<S`_(8XyOj#t%&r-@}ZTlYbo%d??^(bGoVT zv46-eeeE$-@R_hY^CBnlD1IV=HZuRIDu{bBfjh=^lkjan$D&JTP5(oCi)3|lbopT_ z_03+w+x5Mr;q#RM0pjsDfuM?nHTlY4dCtd)Z7vAHjrvr)`qs*L#j`2GhG1yf>y(1` zmT+S=4#Ea?<)+|3q&!p+SpJBMh}+Y@4@zLz!e#9;$d;-@Pt&ExHzI_XNy7w5dW);s zGc&1C|A0g+xL<gP`Bn28(T-EzIF|<vkufX{V%GtO;XT8~W+mxEh*L&X>?Oydn!DTQ z1kxoLTYW3P>!FHt6021O_LdM#IJ3?2%1@pXu;%jUsW=;;|I@;T7d(MhgGdyytL|ka zS)w^Sxy-mS@oc$BLOTb#)qlfHm-T+jbO*ZkwoI}Cgao6b@OJ}-1ckHZ3{&in@g0Va zp?@^p=R2jICP$oQEG+B3FE@_{cR!-LZP@aH;${O?JFm`e9$kTKxi6kE29MlL0h`Ys zRCE3~`9tLadk_={V=8x)0BS(z$TCqREu|#^W5Om@(b83C(Q6fDmIbjA@mSu;fa1TR zk{;s6CL5~<Hg{TkG!PCM1T;R!%8GC_hB*WhrbwKTu9rZ@XKyUGV1iP~G`^1nY<}^m z8n4$%z`Gx2rJ*wqC4iB(WzUi8boQ}ewi7BQAcVpHGv98mW-|IIuYFUJ^2M#zXQY^k zROUl2NY5VrUZ4IIf8c1big3(XE9LJ<&R{!kAM#jQHn%2d2j=;<j;<lp#XewS^tL;; zTHMQKTtY>;&YNUWVDlvt&E+EHg&t!cs+`G8e(IlDUKMf6f|#!}Mj=!aWt=%#EO3F> zjuHm2Y6*dNqyjh2(=QCZ_<JkQXIw@Zcn#N!Uzcx%(M)|+h(1G1PK2bWg+%FZnjf|k z4&nZlmd^UoPoouCO0a6r?=+jA5Hda|x<;JXgFwyviv^V1Z!+FC)3#IJLgXj-5A=ZU zxT}=vE_B^8v^K`^HiOO6E6<MV6+%)b>fs^kFE#VC)Sx{Kj0WCh;5ccbBf`ngdwA!W zK&-dd?6lEoAe&kw>T8GTC4dHBrf;Wg##8!vC82RhwK}|q()jxitzuxcDZ5d$?FH-H zbja;oj8!ycb$>WCOHm$2+)KXAq}hYxGK2)R=f__-E_j6vQy32T_akvInupf3{#}cb zAcEQ+>pw%3lPm+*QC(1<u0g~lB!P5x?S*?;T<X!D(3Ezk8ab~NLkU|dBQv%DX@i)F z8z;-q<8TXSi8(DC5c?u!xyBn;n$oWS<J$H^ptcL`0~%U%fh$1*m_y+u+tt-+hgxUs zAuF0uWuYcHN(uRO#f1W1x;b7-u?I%Qvu}6Mm%uGDvm&+hl;Y5z$}+NYgv@yNrLfCV z2S$q@(iNTiCBXiNhA%fb9aW0vO9|x9)vvLCYZ#U+I}m^E!k&?yH)9b;UCSFTv@Bp* zVOib-;&}qeNx)_m5}OUes%o$VNN|Ea9~LRpmQ!#@1<+7$&^SH~NdiKUc0a#CYZP%_ zd95c5UCtUDrt&W*D*HP53!SF(&Er5x+pVmRQUi11)zMug04^3lY2Mxj`o7zdVat{M z_Li2FFMzQ?wfRfZJmnTyKif5j%8H2SZU1UO(U_o|k4I~5Z6zV{AWepBaA;ODPDQ{| z1t={;iL@DLhzQK_`t(eZlmT$);h%b$7er?PUpJolw7#QFvKuT@bOOq{u8|}00MbXs z9&utN@{<=8t3iayU@Z13c5}FM<Oj$$<-pAVoa;ElbI>I%to=P`>cmEP*gGkM6GHH{ zMGG+fopvGj_OIPg4B;naT}BkvO!Toz%vH4$2ChKv_2<<n3nqc1k4Z(rD&jZV6F^)% z>P{6EFI>gpPpS{GuXb!uX!g|lzv%D2(2QrdE+>f>^hjR(OdDCt9BBlBOHH~nlByQ8 z=x4E>wJMz4U(&W~q;<~`hrF_OLrN|2Hl>kXGS7}d+4(lQ!*kkQyKK_eltR#^P5h>) zj!ooV?}LEzfUf(`IuCZ%&|v(Bsfz33Q6h#mWpE?J*n%pgWW|e)=!K9`cnF3`!6xtB z7+;paJD9=yBlkYOr#eJrZP48v-fz-FJwjD_I#b$#YGmNbT1`x{FDp!49K{<H<6B0K zj7}$*MHh>dW*5lq*tJtTk85G`UPwc>Wt^3%#lZcnf9bu()Rj1Fh#C~r!b%{V>iX43 ztzyU04oAxD7iXf9oY^0W)=itwS}IAVylYb!&vrP<JvQtA%)h=r*x<_7(tI}C;l|GR zs#Ie#qq$uEFsZjB1@}Etv^3UIL&MmebmmfWj*Z3)|E(UCwGnE%Dhy%Jkkx1m#6JFB z&$x9u1-H4STGjG_$Zbvln_gW#Bp9)C;-gow9B?J;W$B<34~Or_-AD?C&F*Z<Y8>2) zePDi@c`|XZi0f$+4>n#zfl!lSOzm?cV10-X=KFK^ayAn`^a_G)bv8yBrWzT`>7;6J zBmP?W$hD}9QtNH(sLDI=++6xrFlf(zJ3#l``DA8zuu4qEYwE0pNH#?IgdI#&unM|s zn5YZ^WZGxpSDECFeC}Dml#N9FlU|A3O{I+cqexIz7_)Q)B}Y*+S)}P1$f`q|2Od`b zeatJV?1d3?_`RTJYso!_9n0wa7O{=jSqHorxtpaSy<an9G=Mn39@T0XANP;v*s5XL zu~0?9)mKKr@yW}A8R~u_#pa!ftnMcZGPHGV02vK)@h-%3-1&XjZ;>_;=3&aP^@AC> zP+caNT5!k)$X+y*BA9c=U;*Q?^qaAY?k}5p)Ym)R+jK}uY;^hqREGBKoaWM|YO6G1 z@X>G}Y<T^QWNZP5EQ;?u3J9%pG82R0<qj2Ssj;1+5t7Z^uXkrlNHxVpDRbv3=B=(0 zVxFQ4HvfPY0e}F-Mcn-k@Z2!H+cK$y$zI$1x$$w1=tNdO!OA8^g|I`NhVFx~DZ|uS zhNqwywLh1TSaJkmZ@D%@ry3pTKr|UXYKq$tSVoWKJA8j;zb3|nU$X^eA{84<i<tGc zc{Ow(y7NzQ5_Y;qK#6={^^l6w^hDYAs3zPjlb64U&zarVQKJ@QV5h0VDJp`<l-5}0 zvlzz7W`o165oozs(DA9ANz3RdCwZ=#J^#|@aJSK&Au;37(=M>m-^lioLJ+l!_cw|h z%Y>YsBqFXE^zi9MD7V)1F%d~G+c-MCa{9p;tn>C$^w0SlUqqO?uN%2!;7*sUC<s3v zTZbHRgNY>U8dUh>&w8;SpDr(<w8$_3SS+`NX=W?Lb;3P;&eNO_3iFh%fzAPMTsC(q z?@zafpkQ=8)0=4pd#=t88e(LS&eVAl|7j%fTW+eaZc_qab9f}<rysOfzhWTcIBn;> za|p6<nb3=v`C8o()eEUF+Pjihpm`I@)RiYwdPv<{<a&-Y5;WW`Io33wt#D7%EV6zq z#|b7$pzswT$!5=`hM3q|iEieGNJksGyvg$@J(#9cyw3GjW#iGuhKZAm6Z71<Cy0@X zG+z&Mhf&Qg5h^m#pk<zdu44QSTs`l=Qr=A&F(kUDND<j*cLs7;axeC2zdipwUC;o& zwk9$?hk$ZbIvBmyxVZ@+3pL;=AD4u`hrNUEESz?S5O(HSPKC(1922|d&+RY2Koi8u zdSi7Rf8oI34J*>gRC%|EKHIvxF1qyFA8HTk`w6!wp$HF2qmaq7{4Kkqjoug%x?$LU z@TIS-1ZE>KOWdKf{s2V;&kAF9<!9=T?N??~hH*FRv~9dQM61qIJ2g5Jn7?>1sC<o& zNp8b~%{1-&ZhC7qSHF4_d$dm8B?W!Z$u{)M2fh{Fd-JaO%w-n4XV6GOyD|susx1NO zw&xBc@$p2}>+!=8-(eU^`*IpNT0Yb=sazg6J75#t%~`j^q<J`HWsVh+vennHX6lJl z8ov{6fh)HL=YLd5hln$vcGLOUiIHrb%6{w!z@Og!x+Z|?cC9cW_fHsGFRi?xihpwp z7**VSO`6Bq1|%%4Om_{d5cOr$Tt_`spwnbRmoNzQWZ9honTGa9C{#ry&5%M4hg)FS zWo!Rrhb;X$AGL~aW@Xdb#b8ID&f|{}e#4iX&dI;|7_?bJ!ejlbM*r(42TH>bA<|Tx zIgCk_MH1{mJyKm7)Q>TSh$wXX-fJv_usDzkMT};2P_~o|F`Sd*YX`Kv9OBoA)W%Hx ztBR*scqw)zP<|H3rL_FBrs|eR5V%E@=xI>rrc($9yWJ_q3QGp1yWs;;HXw1upmB$% zyubwX*T%aZbMviIjbJ#?N+tHyD90%|F;+X~FCD0+g;g|fJ9A~$nEU}$^df_c%hji^ z*bQNB12HtcXY2#U7LU{yv-<1JUU=dW3eq9YKxa<7TG|QaPUYMKns+S)+rf8I`eJgp zY;}qg??6abe>Y<jb$!)tKnt8|{X`VuikSL%&EZ2^z)P@y3iG_aKr-yeEum<>rET`W z6zx&GQGki`qbDiKP;B^oiM~PGn*r@4WVhg-<+i3ZbM=@3+3A##))8EbOnqFQt{qvX zzcvkabx|eXWuw6KzN6bJQyUDg-U}TVO2k+vzGjSev%zLN6B-?jfqUF&*KjFYgFP%S zAfp}|8xdx21Y1vaz;)#XUDBH3A1b3NUT>55er(%}$iFEXCsc+<$`k|Tac4&f6y@Q= z1(fvI&TIT)pz15T7)?&B?h|3i_WIMtrIXMA(p1#P(b66J!ec}3ITecB5*XB_7j@>v z!yg*=zku*s`0URE8|a`|y(0L|?JQCOaqvV~(tB$ZD3XP%T}|r0*1g6NGsgt}lI^S9 z**r>eN_N9F?cz<L{`@_Yyoi=DE1OGwMZGI|<ymU={)F+KAQaE(8Le$?31Z-O<l#<# zm2i?Ry}OPg@ari0s?Rd}N;<iGZGLQo^Zn^AQ<~kbi)ZxhUm)$<Nh{@nJv+)0wiD^! z7m~a6gHz52D~Gbn$!a3;B2Yj>h&q3oe5dXJ)Vc<EVe5A>#O|wwnU<18yR`I31qIHU z*_nefyr*xIB;!t2bO)tTC7-4C32WyhRcOROZvDZ{$TC`H4Sq_dLzPd)Iq2f$f<c>K ziPoy1uGGG-(7FL5o0V$&QY^9qE1TdQg~AhPhC=A(a%5KLfOs6C*y+t;vgI`wh^9z{ zV(tbi1q({*3QTvj+ai*%>iR?qFc%z%Ziy_{Uo;1`dkeOOG^knJIP(iv<c$)|SpTdf z7Xf^mGXc8A(nFnU7HlT6yQ)JT<+FDe23h&mloGrx=K%zF4p|qu-YTwsK@h`&R7ZnS zUCd7_B&<JVD_Ec5FM>mjC-)U`%@OjdHwA!&dcV=1<c@wg2yVF0n$dP^3E8bgbuY@= z_ZANLJ7&rG&4{At)4$t}KC7A&=i~l$ijX|&FTtDV_de%&S7QgGDI?p#7ZBFDf+}t# zE+VKVlh+~ZwCpvj<1m=zx%L;d_fc=*EUW?3`?IJ=Lb-D?6Af$k90l(Nq>l%wkZeGI z8?{>a<r0@!LL$Gzb{I1Ek7HrOfqVR5EOMB@PVu7d-~{JpG=mrxqP#+Zl_QTld7$G* zFutx2RVm;dP+fB@`Hj3AW;5yXurxZkP3_lN-sO2#<t=r6V^dRwxOurxq^kWJG}#-8 z|J5zOzc}PVF6e*!PAh9^2iW<4zTzv4Pp|f>zDlpK5eD?S&5L3iY=aYoWfm^AJDLje z9V-O*p~9ZMEi)LY3eprCWoz62XiYJ%W0~RJc{5*A+ZlvUTq~ZuzVQXME5-6NJ`Gn* z&W?Lh{du35j8fu=w3N{}#6)$5L<7I`w5{Rs65D`5OR5qQN~)(DM)U}N0TD+M+PC!X z;XH1ZJ0;?Zf7HD1Qdr-^PkmIC`@4hNfD%=Bwl>Z6je@CC1*M43YZ6QD-tt>&bGeok zh-ydLjBBwKN(C89>SBC@tdGqK@3B^CF~56#wbF$OWYrBaQimi+r3iFX`X0k&B1BXh z4TXqcdT@r?%)Ur00yLh0(x(d4=nU&v)w-(K6D3d2QzvjGS>ex?j!{}%J!HZ_A1_Hq zCD-~I06XBiB?^Kd0N;=nw@4^`a$&m-{@Rwvw#Ydd>o8f)+8`y6RvB9_V>7rAeS}z_ zfKZR1s`0}E|7-n(gf6p>aT}^D=ljRB=+CMmoJx!esN`#nTFbQ%BjbXT1o_UUl_cAI zi+d|c0yc}#j?A>Gc+oo<;6X#UMFG+oM5~7<Q$EPDNpoVK6%qM`-b8K+IsLwe{AlGI zw8FESc{PRDAnUGB?S6$pns&lY3^Ja&c%O-w<C-^#gXulp9%~Oj5%<+$gXJJ+4d61^ z2szD@q{y02v&SSzZ3wyetImF(P>}cCxSpP3npTzCKa01B&BT#U-Yd0PEClh#4>eVO zDRNcXyTuwhB+?YK{0$%YshNvF<|c_AplsUl<Ib#qrOZ^{ojd1|r-DOHP;1Cb^@y`% zv^2kBtJfgC)-qj3(yV%dCpIM@*x)-o&1Su^V`x@mbsFl24FRU66_W<@9I$gb)#~_e zAiUA1$oPW^>inm1hFxcu0XJ&6NR$$RNQGQo$*>;CM*(7?!?2`Sj{JRm<V`T%=xWT0 zIG(aa{$({u-r6!{lPlG)C>h)vo6`t@7H~qlqP#=!q0Iot*#4d89CKhRBZ)sn_p}EI z&`55R7loU^oyDE0&AvQ_T-R=u^04u^^+a~OStUo8%J<^4&JT7C=LEgv&{q4ymzKfe zAL#N53@sh{CM6{(Ci?vdX&0(FCG{Pp2Ra}P&sl>upX7_7UKv6-%FMSD4vM%G1wSA* z1blD626wBZ7xBSb-R5-Fd~YR#iE9Ggx~QFf?79|^pDiW#<r<|@6{=(pHtZ!_C0}eF zJT}`mCcoTY+MlW^vzOP#4v;X32pJbMq+3<yhuPf%hbXH%YfFs#qk}Qyua0Uvw96%O zlpdtry`a-w7Q|@dt@U(cki%U1Dz#^J#&>lYUDdJuu|ls!2PDKA)G9Nx{V6K7UI;C= z*PgS?zmm1t-}lK4^`p#dp}N^pLMJrP->CDG<seO{mo}%_e|{XEcH}P6HM?{WIP4c| zr>Oifn(&2`UI2K&yy=_yQVvIkcecAOg2w~`-rokeO_V5)jywFOADn>!U3L6Ui1x(z z=1x!t%FQ^(v96++iSW`UkO4~Pdr_7It)#a>x!X+?fVtA@tGSxo@xx_y<}W|Js<2-@ ztOoDTcAAs7k+wQ<Y;3LcqtP725VrJo{U(QtrL?Jjw_j=}l=9tHoDFY+Gqt1SApBOu zb!&th>!I}Pnw)nTq?|UEyE6OD58F80$M4#-a{pX18=bwLD*_ZH60TekKRTA=hr@H% zN)!P1Ytdl!3m}H;jXe;Mn4qW3c)R*`vCv*r?qE)5w_9=(qvOO&bkZDN4+hB`uvCcV zr&jrIa%xvF?6ADbl4u9hTXR~gNu1&)(P(*tHS0eSisE|r=bVI2i$Ab6t<6q_n2}90 za_eK^ncdCzL&9HKEETM*NrqRgJ0{k{4s?KCrl=>n0*eQQ^hx9?461hCKYf`+#|DE= z?k(_SHXI8>i_HqEIex(SoXc_q?o4vA0@?*H<6!4N;i5bImVv499em|E3IE(H8dq)v zKPf%KlJU{DT9M^GT~KE=5g?Gy^a|0!(~VP9&CLoA$*BR6(&ea5G~4jyYN7R2=ZP>6 zHr-;DBmUY|rjYw2fxvs)!`%d`mA9AI-su*AYYZ;jK6lI17(c#tYy088y=&F(p#(uH z!R1dC>^bosKFe2qyOL?12p&k|)TCAVwKs(mf8E)~Ey=F2DQTsBOOng;vZ>vd(&OJz z-CSS$iD^evdC(W$2gi>J)4H!-H6=RE1<`aS8tJIh7!?@g4)4`|o&^;KJBnB%7-Ve> zd-c6(<`$b84A;##Fa5%`7UeQX>mD1{3b?icLp_|zYJ_3!O*o=v_8tPXn4OgYf&R)Q zc73`@$=dl5)y6dXX{PQY9tCk<NyqwjbTstc+LvhS65-7He9zaAIEg|IJU{34x-a@O z!KPV8$@B&X5mxf`T%DGUrIVtuk|T^We9#CB_}`n{I}}AIQrE_y+V3bnX*2ZC88&^~ zr)gR`dA?`C<N+g_?Uo-UvGvoQ?w~xUhrC~dK{31fzIf>}CX#Ig301vM;#)`4$>E8q zYhYhK+yn<≪!W8S}#6EBY^BY<WS@f>4w?vq3TR5Dr721uiEA>_xP%EJ4*`Od0u? zTLGj%)dEep{OfJT6?-E@03y>3g6=(7mFB^^^+cs$F6v5E(Sp#=q=f}pU*QpJraT?P zEN9_6Haf$k+hd|og^sCBd{<p#i@XyMwirSv_?K9Axrxk;0H{f+kCENn5Aa&f<rDl0 zGP5rQ#<o`*Ubs<3jl8~mQWCc0B3yC7CrHzYLuSVVE91Z)*9{SWsG#4+jfyg5D3MWH zVN*Bc&=Bl3X9rVw2|9%?jIgHPfmLy7$PR`a$(}c_hm_^rwr~UKE%)r`+I$?Xf5M?L zw@JPuKQ9+(t{j%r_Z{5^9l$Kl!$G)uN2uF2hl;#$m9@~-l#ca8C1ITRjo;FiU8GXv zM=m$<1&YlW-QGtkQG=y?bxuMW)<_xGcF;jT<_58jnZOcd6^utn<ppNx`k8dG@xd?D z-lXGs6ZVO7N?=|=KnXSSoYJ)mMh0fL?P62(RJr4`J*2?o+(TsOSBQiSV$2x?=bQyn zl08>gRsCK=+P)Jn+}N>9woJDmuwmAdEX$b3tm>{QtGs38U|aMGW4^W@4O<I#MgCU0 z{G&fYGl9uM{HnW_wTYPz1Zze#@ydIAy$%S+=KuUjTl3aG-R2q;ecRv3geE$)jDV)! zxMC%I*b^bVqI&f}P_I6kR5SB27(+iZ&k#IfBC~RJD<=(<ekvZn?B2olJ#i?2^nh~{ z9G8s?BFGf4Ti;Jr{phl(Nz^EE6wQriTX~0Ns{nr)&aKPZ{$)5($p8M{tFMd43Zl)w zBPJzDr#VwlskYf_=50}<PTue(7gcN<OgrA7h`Ik8(-38ilOV?2ps@;-L{{8&Kv}Te z`1#JveZZuMO;i68FT}t?(dvuLN8SFq8rb7XQRcDZyN8@b$H9hSVx~J&$`Kd!FINa+ zw+3W8qb!z6L*<Nc+7rn+B{S)ca@>sa7)8~<1(nUqz>~;rI2Wi)bwoO-H$EghPNmq# z!hE8Q_Y<-238}>}NpOzK0&giJKr;QXU(8<e-jy{nu#uf+;98pTlPAx(57z{zLyqwG zSsIIrS$qq`+-w|aW(qn-97eiaSkaj7qNzZ8sxjUJy`A?rBXf7xg<9f56;8pP1XUq_ zsLFa3kO|GJ;M^O#+mWM#<znYK>j~gncfe-U|I;P0kViEBvmJt?l#be(b1V-|B2{{~ zRP}+*;1Yt1&gr{v?_vvHw&{GJbd+@^D<dTW<`<UUz_uD@3u4NG@=}L_P2`}xTp+k# zwC<5cPh$n$YZAR((t-;FX$`6u&(javXWs*x8HS#BgH!3X>DV8S3?)b97O3{j8=IbD z`>Z5io@@Ctzw9&46wvJkuDbqOe8@U9{{Gu3Dl?tavJ<sft`f5TljIyUHJ|LeF^S_x zCn%{(l81PndxM(P*!~t6AtR7ftYz?~_y^Pq1d0<a@H`T4RSax%R#lXEs8+Zi?as6q zELK-QqxA%m=kGk-HaUTgWq;Zd+TtlJ2wa;-RiBiNLK3wxVcOx$$Y{};UlV6g`o>Iv zP5OQFEop4cg68-rJ#2)V`AJ6XvM&hiL7~`g-WIymhZP1jbtbye#E*jyyj6DnuSV>z zyf{8q2x2mEyIC#y<082SM0)K&(Ln|WS?Yy_5d~Ou_9fT0V@mVs3A<HZdw-9aZxIrb zaF?<&2yv_}<!zmWv9c$;`x>Xpm8YlzmRB;N-;e)BI8dM&v<vl$Ux)Q;IItyi67gny zIl#Xivy<#*98cye8OvPK<YF@PObp@)MNTK|yptXMtF_$Olt+9gDzKVurgF5>2=@Kl zFA=(3Fzw)yz(LpTHV*0XhMz!dKE18yBhAtHCG`*KDp#zOW>Y)y+C^SGl@f^$Mc{B^ z=@WNtA=ag%GSCc39K7(q?>$sr0k4;Q(MvdV0=7>C2hGat1-W4$SLz+SF{M_(BC_Q* z8HzHgXtDdIe<lOqo|}Mt1g`U*UZD^tY3O)pT{^s^nGVfkWg#C4pCX_*gT}5%4{N_p z@J>6`q|vqS4ukhgE2D3E=qW^1DAf)u=<9PdMX&+X*uQbw@MGuG@0qf0tM|uMhg0?0 z`ks`Md6w1zD#~zwGE|tXniSg$k0hFy-Vt~EU@e=vzRI{Svtn{fDhW}g&KEVsBUg_o zDxpshwL3966Bjpobc%9sca4<JBEh1|84F~Tm_qE?XyXU*$~<7zYa)OJ)RY)>Jh;fz z$Sr$NVI?BX+{qx$a)tmZ8DhQX5rR+ivkJn>91M%f!RCN19h4VL2>TM^;xFK5Ow+f| z7rBK_IPu=l1)j)FE9~kZtq$b6$S7?WC_Ks#jfkr9snLm;1~K9WJU5(b5K4fYbH{0o z$?3v9nYGgR!W*Qk?py`~SPhJ<reIf%%@a7fPsxHt@-GshGP)Vmx|jm&3@svmn1W_) zVVeL?fVI$yub?H}^7DuA5V|TGPuezMSO!lgq6Q*E|6Z%>e^hLyPdTF{TTY3%lmock z0!EbQE0CQWd>}?`S{V7D)dBDa=2(gH2A|19E<BucIUR$TMrzA4I*o9uG1_2-t`D_9 zyd=CXaN2ceT`ISgUBN!40fUs6?_WJC{KmgMq5R!B-vj^DsXv8uk^yeT-Vid0WDU_+ z($z0`dF}}qhnN{14l0*^DUhs4Hw5P=0|^A17U$cnR(_9j5ACPpqi;_Y9tLib@f>MY z(m1s?I)2XR3VE7bV;v6aFsS3DHN^V4;wA>ytFV!j38MKW`rW}9^(N0I!h<!JcFUu3 zAC5j+>_*aDYDt!shAQ_uf8xg&8?>$z!8h-Bb<t@Ru{bgGkDSU{m*6dz-%B$Cas~IC zgyAPEzy47?;-V$o2d&e;Pm{)-x^#tLG1h~Rn_RIlij#Zq3qJ=}MGkO*iO!h7(<i(L z9lnvF_)Ab@j5`#<{N~XY>CJjP6@n4Mi1SFAASN$G-kd`^-SmMSjH@3!Y^~3EON(Pu zJLmeA)ZIjR>t;_$8-km9KXKs=kD`R*-~?APvggBsS<D}gjN=A2O>e$5j6IE1Nc5a? zM=Z09PSX+Xn}20CSXXkcT8@SfzubQ+p!U$lBn5+O<Bt7jU1cLZapv};DYK?axwuIi z2@(6euPIRk4^W+&e|I*bGm_PEbMHKLi}wA%VDw%d3rK^LKG39<7uV+<{b&9JraP)% zUZyP6sJOc1#x+AA_fVR$l^j|o^fA%cJf?1i00Q$h{we`C-{6YN+d+e)M+g77G_+%o zGrroz3se*@2H}s&waG&$g%h5Iz(hAvV={zWBPuwUYyl}#J3b38VwTQ^o!MmNT};UE zlldL~BuoUpa*OlPnO^5kA4^;vx~wH02A0@yL)-3jXx#TQP0bnka-#-Vt)m4g2uo^0 zuz3OnU9>Tm>3vwb4wTZh%Ts!%^c`;xHxx$wNrhA*j_~^U_sapO5)NfM=3_AVv&JyC znHgK?^Hq2~OO8ujTOoptFdXi04h}Y7Wg&%Z?EP}Nkdg+{p8sf^u#|^Ks;VdHm_hRe zT@#=lB7kHc+xeh>vUj4D1Gtj$q3^WSewtB8xyN|mf(S-55+QhpLA)%}{Cvj>tLrW! zENDvo+)N|mCm0nB@UReJv|Fg<_9R!gA@eybf4>Tl5$t-e72Ja=;g;z~ALi|ma4yAR zoa$cMvQ=?ajD&}Q^Ev>{#mj)M7W^+|C<LqRt;q>=Ewx1&ADRvmJFt#IzAMOz<_zK| zaWT10zH!4PcpF*+6Bid-1np@hks1I&PRF4V@Ey%$<^luF#zaT+T*B`3)1X$5TLg@i zPg6rTM!RT&@$NL0Pos>LF~dErS8ZD#n{DmIah+SLe|w3bIcOxysupa>x->y8W9T_p zi{oh}(u-#Eu@4133w)4RwM&^#lRa19mi}pH5t&`A_iGM_tFL5a=V_I>PKGKm>#R(l z=Z`h8y}veUj@|%Abor0`q**Nc7|b>Q<ed1+CRM(d4zB=t0ttE78&CA}OQ3TFZL1zw zu4$#eJk29c7kckzs{hW2J1rdIfUN0f25x6-b*Bfv73Q(oaRVcB@beOpsq+{kStLNs z{!h_rc>MBfy4K+{1-gSdm9f#$u|V~WG6w%ayfYjmp4<_ipHW*^0Tu(BTP7onyIG^~ z{Z<$Q&H&@4V;se%<Yn0L6iRAW(fBBe=IDABcHkgGoDICafr%6~C`(pRPE32M7eS&o zDYuKU1VuyV^m~DEjkiisWMf1NVBrtW1QJX7aag9*S&cV7xQcZ&a^gL*uC-tJT8u}k z6QAnf;G$yZhj&U(b5Sy-2M+i$E#F~&5!36dw*v^RMjDMi!dYYXNWtg1UXvr6_C1?d z0LxXbmrF0r?`*U!U<9#W#CvdoXZB!2JPoQD*@21D{lT%J{CtB%dci~t)lC*`+sEvA z9+S-@QWGv&74C}CX;g4JH!I1e%`|ib4NKYkM0XfcSmn&R^ey8IN+$ihgZf)#(JR8+ zBG<)v@1~C}Vi~}R6{aMvJonzuQr$`lusHMn>&iLhn|01Pi>#)vNtxYQ?ivoPFygC| z&gkEJq=#&mmFUDxxWF@)W&gn=j9e_Fd7&ucnm}Ikpk<M~xE}U7zCr^FX#+Dw2{*Er zJ<bA6U&Mo2<h4SjUg?jYIg7uT<0KV4d`UMdlh+z9R!yRhf#sW9w%e?C1kJ>|rTo%j z|M=JBEH8w+1MypjdqQZ%@&M`!Y75sV`P4i2RAXgxC3BNzt@h%B(61tiB4)YcZnK(m zUbRORcV^3h^Lud*l8&Qi;mx8?RWjTHO_F3I{vu;tvl63~;A1Mz2x+qwx*3A)xQKhr zOlI9Ccu)IoM3MU(j2S&i=q=ZImt?6L2jvUY^BjR*%CoqkjA3e#Z9N69_ErYiH&?~1 zGDp}*jR0i-9D;c!!wBD5s5LKn0DB9x%SNT;kwr8XuU~8*H{Auq`7hJ+Skv7UV$v|p za5YBsDltFE06dhk4u#L1?so{|1;rWk((F<7)NOD@9_uU25IO&4x~-CW3CJ{YQrR{l ziPwEjnCz1_SnRq^^l5s6OPwSE;Di^hH(KEZn}CTiN#l`bon?#)!7!r-{6kpP1!uR1 zfA@&Nr*Yr&wjk^^)+12mF<bVQ$er0w4?NfbZ|&<-V2~pSxzbu9pYhISJV&gEb9Jtx zx_rk|qtP+sC-;&jqV-FK&~t-*NametH_4m~6R6I5$@n6VR!3L{BI)cvj95byQf{)y zirxH4!RxC6PpvQ!UG+*=LL3+J4R5p54X7IFQ9k!!XzV>5sXpU}Y6;k9B37ZL^-hAB zJh{6>jlONGcbB{Oq7a|khqmZ5j0eUG&k`nXo4yIZuG#)27+}?(rwRgYoGG5r=1t0; zs}27AmcYr_Oo4LW`RMvqn8Gv`n9a|lALG_&!62eSouC`8jl6*Oz#5q!=q}~K;tUp9 z<EWo;m>Uv(w~T!cj+QAx!WV0j8;KY)9@zu?lvoW^1@$^J66OvwVoa6ksvS0Z$W7w* z$;lDM;@jpmJH}06Rtm540UR)DTJi_1>2_`y#^T-Ps7NO-8=wg3u;M9~WA6re=YSf& zex%MTq!DH=7R9yuZ_~0g(zoEu@Ybn>ewmhPuvSWuWsx&4y_u~l9>@9Be(@xsu%R1i zYhDUwl=r63Mx+kY-j;q?7Cn@TaC4l>;C`dk7Z0Uj`5dTEN6vh#IP3;BugnYki6@}C zb<1@R6uMEjdhhYoH&43DT{ZuweKJK>!p&2=-5;@)mzcG#U7uRL!MeA00`b*{Xk-2B zcr#&f?(UKNo~XD<4$1dpW551LUM5SL{h;GEax+1ouxy3SC_JY^mvjyBK#?ucmjMv1 zpQz(cDf?R=06F?B>akZXf*Ur$^AX5MlCD*ie8=3Bw(KHMiJ(6#m*6j3hJoj9NAm1A zTy*K)0X{C04s)vU0!j$%a*BQ3{-KrO_x6b5B6A8vBUVxJnH6iNKTUjd9J;tyHi|_v zy~Hvl-h)-kG!p4Y`7v<Mm2;^d$t(fIM{Fsu_ILWsRTAmZF}f!hfD1)sb0a8T;3S;m z4aF8>rk}V+3rsSYbQ+qxtbv~PfBI*#+ccss{IWp6Py4;nV@x;$+CUn#9{XTovR!$+ z<;%-k4s{mvy`H6_JGEZ6dWKY8_gJ>6s;B^$V+fllT6_)F3)CjH;Y^FIJC+ng;8FTg zWDbo?@hxg~muxq>*ZiR@M^DBV{2*p{y3y)8k=zsc1$XzxxMtH6K-8*@#vs<utTQeh zy(Sz`TM=nS9a`Fhj(DoBI~c)_hrGiHn(jl8rp{MP%5tgS$Gqbl-?JF#Cz<tna1AQ) zGdF6QUKvH?qe3d}wBibjwP41+NYosCji)Jn)UI7i+TAUa0YCV+9h`Nsa+wACcJV>g z;6BP@G~s7?C}2<-?}}S7Zd~mE;1N(oFV1;)mL79@yXTD!651DpMDOGWJqr5dW;Nl2 zm*gNqUi27#JQ`44H47e#8#a=hT8CbRTSm8|>(zW-b^HlEx~fgwU#wHY@)MUyHbx>< z1g}Z>maPhawcA13i1AngMxA#WCKOZf?Fsm`@<}>?SA&{bV%ZH^&$h6O;-0hsj03Vz z#@BTsY@)XY%KQnZe@<WFX!0Nl&PNb4XYM;qgAtP^v*t$IFIx#&KpAH2ZWozdc_I~H z%&q0`ZqGq;sd_n}uhyo2l%o25+2sYN2sg42`L>v4oc?Le=9V)$CAIHh(}GvGkFx{t zP&JJNyP3rgXukI0Lj;aGA5thew|X%o^ORk<=K(_y5+W;^dMJdz1gI20xAQ3Md>Ald zvBp<#&MT76JGOn{_NdwNQ?MN^2bOS6Qd;}8^|WC}5s9;ds&gDjXX&@w=QSx4ogp1q zz(g^jlVhzdThRN}y%1qBjICrUenUZnC_kC!%GjSl7Kg`SMv_O`@`oCNpBo}c;aG>@ zM_hfX5ZmbA5PTmcd~!3<|LaqqqccU|g&WR3zKQXc+?yQ~Gd*R~F*?dL-1c+Gk4ok? zSZ>JP|9hGG*gRPug_A9bnx18_&GShmO{8bD=V%wU+BCiSN>c`vP?<edZRkFWOa+T@ zgqX@7<rzSqq-5}+RQXwf^{yyb9G!3Y*Eb1jtq5VYWRv@!QgFd_$AF!)z*T2Y?dn{r zf>4}FNQ;Ab|A?(7#NbNE#RKjlf^wC=<Rm1o!h=YLNR1^to$xp5NetF{!dLd;ZuRD_ zHvFPD*+)7h2;(%VvdE$o_;Pgrll-)*%K1nKW^|~ACAn&ji%})9U1E(_;Jx2GAXU6$ z0ZaQbdm@4IvHWw814>2M_LNxko`A#BZpn;<Br9a^jdFvz@PeCFBwjG{JRfeMdqjI( zE6++RTX%-O=7H2nr;x9H{#!#`_Y;C9)gb%A-|;}(bz|~#3!7xBd>gdYy1kS7!9cSM zK|LH{A-Oo=%L_HhfjD>Xp1Z`UdaJ}eYGrmQfSLCEnf6bt!(>yimsFW$tnf1l$?Q)7 zH@11YiqC6AI{9zq2;O*t8ft`*$Z7R1jRd$CIPM49ewzB$9_pev^1t=uX?c?Lxuc2d z98lF-1<d1?+fb1mZ&kb05RanG@yWMX;kw6)7}tMpfgiWy7XlpL?b(6lrj~gT)zJ4x zNrf1`YIM%Du{iq+0To(A_VOX<rTuL|2ex(>${O&hN`|Lh90q)CkhkgBDt29?@a_JT zh0tJT^`T76i|C%@Hqg3)cATQ6WD0s@eskXg2;P`5XjHG>ljYR?9QFImH-C3uKcj67 z#f=wwJzbe<onP+iGb<^FmdI@?lhW!FhjL3ATZDIDm6oG5VH*w6^zi#N&oSfiTf?|l z(6EzXnbOZ@QSHCM{j4hI-!Ih)egjL=56i#c>e?knP;n5Jzy#6M#(@j^1YmeF3}u~6 zwg5Pfn-Vas%{9wq);fI%AbP72)Q3DdG_pu%@bK)D73#5tUv-6NfQE(-UI$p?M5v7$ zQn5+G6zwJ5x#r|Kr;eqQ_47AHj}++$i+s*No$ka)0~(r*8vTO<vrt(5kL(O1$Nykw zl-%u%@#$m@EEJurq3C4r8R&nR84+^_M<;v+2KxU_UEwn`vN8X^o)!N89<;jF(zM+i zLG*d8-7}0N-1>xpfEtp?Iw3Zvm2nitHOj1C9!sDaxAyS)PEXG+79Urjo|KLZBqZR_ zpmptOzqyJ?QBXLSP=Tr`Q4m2grn<(FuVJJ>IHnqP6+C{osRG)SR%QgFfH4%u3sXv7 zP`Jj2l*JT;Ge0x&CSFjPki=9H6r|4)J3}RG#zZF&5diOMc1mYXc1aMSZ(*d=AOx&P z!EEnmAF;PAtD3Nr0%3#)OQgKSv2Sc}up>}Vo-wvrQPOb)S9QlSqmN7=6EIN(MYeaW zfWk*;;Zy{@Wje12n<d1kIAa7$tw6`2n5d*Q7xwNhR}jM>u8;-qOC^M$1CBCe*-5<H zi~0Re56(luQ&}<46{-d-h6Gv0B#e)j1du4C;d6r{zL(NtK$<hs5Q!z~Gt>aqGZS8z zXfsRzwb|%LQjw%@deLLFL`a9#L%_l|6BLyzkVeHDB;(8VTNT?oaq>fmdO%gOoQHIp z%hM>H!vkn$E0Z-e+`5m^zzI7Zr;>_8MS(rcfY7-p1o0jKzEcBAnJCzN3u0}Ciozwv zT(ICnB)$V=0qDsi>8oFn#0O588O_#fBm#4rBKU*F2TCAj6%7EzJJ2R0;YO{m3r<>A z5Fu88SXiP0Oc@UL#n17FGF*k=96;9z9eZZ84T<NXKOe9!*FQ5dFClHNUmK`Q90(o) zOb#*)Ox*5^QXO8?y@|OEnC}%8FT`$O%pU4IOyf}}QP<51Zk>)n#9IiK?=Y;W5jzVI z2i+W+3qX*$2_*ZQSqyrVZwEs!NRQ`Pv=|I+yn4PfV3r_U2D~GZ%k}mqOw~7sExC;i zSN4SKVDG?ACN~#)G}m?L#>it!>aUm>$3x+pI5(mv9<uiu0$paI`!k?HFBl|cop!VU ziMpqrS#@RM>fE)C^Q#RBEako3gM~u)=d$Z*U}A~P`RBzbp6lK}YrQ!Zb_lm_e|!F! zGz&QZAzhddjc9&x_e^|&>%PrCa0@9N%JmI@j%pQWhmXwsJC+bmDd6To<{ap?!Ujfv zlb&=+uQCP~si@|HUz`$<Ne#-G`38$4SamNB46&$^XM}{k0?ae*%o1a@LSP#gs@lrh zF5t1m1%Aj6Ku*7<m4$f2HVCM}`r3YkrGYi=Et^1>MP<dI+jgTDAoz)8#*GH**fI^Q z2Loyja0;Kkaan;fOPr5Pu0}}PGIu5K?t+d_-!NLy8F1eKM)9H*3{a-RzK4>$soMH! z7addvN5n-=Onnf!3pV(spbbv2U+Yr;E;ZTh^XB*XKo8!JOiKVP7|q&)9?hGw^O<;` z6|x<wC2fq((^6|l+w?$2-cW9LD9ecE`UV+-Fk6~f7zid*HuU)Une4Xgm99FpA2?`H z;fVf=XH+>(?&l--SwNJ|-t6lujCuk_z<)&vrx$9-DS9%Kz6QHoX?`@%GDMT$HrsPO zjMi&l!%BVi^F!|eK4WdM2wBbnEx3tsYR=^rd8!<vUJ<E&4SrI#yI>>fvw}fVi^o%@ zI>m<ij{|ZvS-S-naz8c~Mg<xs0oRL^fyJxd`WXZ6JnFp$0FUN*uEAnJns>xXLfok4 zP%(EvH`{wgcJA?M8CxxBo@zX8U1WUjCqE6oPVj%6bB8h?SUBeqt0U47*B4E(mLND^ zdNwq75&QP_43nv-Bi;^P1b)Qb_5qc?Ie}Cb*gCuC6~_zSH$H3`a943|{A9EDyJ&2p zn(APY<0H2q^<jZY0Q!TgEC|Qb$SFC2|0Ws1uE1aKG1nm?!~JejPwn~#W|IcdwdPMP zS<ygIi0~7~V1ruv8~4u#3sBDO5}L<LW)JVcm4IJH^o=h0c`n`79fF?0j3h+-QKZcS zD~ILVtEat^tbvrq*TsbRBSrWA;rfpDa~SrMu5z}<G_D)2q9@6ywzfdZyvRgu;|Ey| zpHg*NYz2$~0#}moimFu+^BN+vgI|L2p5kIxG}E5Kj!n@NsR?E{;69i0%n_7r9P~iF zC?SaYI}_a1*Kr251JClt9@<ZWph~oj64ghhu=72TO9`OMBgmD-?h%OJ=>f!g>VohO zatu#REP?3>vOwxtQyon>iW;MiG^u87UI|f7m`?LsNmamTB{Qx~p`mG8zissnrlvh9 zXvTqL%vj<waxS-c|6(t^hf@C8kHHV=!k$NtH;Dwofi3$?Fd4Jyt_t}h)1<(zJZS=l zUZD}A%TPAd`kq3bWLrS__x)OJ5oLsGI3<}url8H#S_%A~B;hF$b(pJ533i1L=m&y3 zCX>gG6F^)i!Hfk61*~VLIPSIVuFPk7zFikv4AIXWJc$IJuI|`H44PC9i7g}Ki^nZ2 zA*}T{;H|cuEF$R}wv{7qp(_X1YelUy&1dbJ8A(4%f%n}GaXy^02s@JBUz(5qdY8VI zM6o)4H2?kk{T?s>O>Prz`L^#)#gq&_{ugy`85LKv{EcFR!vH~o4G=<tyJv6>kU&Uq z4<1~C4X#OWCj<=;65I(gz#ze$;6Z{6GC0iO+{t;)`M>Afd)8ggyVm`1-w(6*Z&z3M zuIj4UHQl|Z>%uA%Wf=&{f@Oz!UyXX3-BqDZw^`X%f7rPSmOAcNw>-Jf4)|{A`Br63 zk9HzdiE*Fp*C$4iHHpB<I#whuTt=iTc~Sxw87C|1a}d}0DSk6-{BUdO+-gdeNSI;h zQ|*j-7~@e|ZjCaGxj2l&dEfu>^Do2ZOBy|2KMuEziX)>Ag##<!nf+)(9E6ppA<m+q zdU!6XHLmsMA2zh*ekB>dC{J<V&whR@o~<FRd9?r8%IjW#j#S{)ZxJ=GL+8|C=AK_q zLDnzD8JpDSWXC@B+ibj<voWtmFICK$2Xd0)y%eC&AyEn2{+tqck7M}&8gRYO^0a9n zkTl%$Lt8|T;h|`_#x9BY8|h)W&Vtd}adWR`cC$srHWkPLlN98zYqYDjD|&9S|GYmt zeYn4e@TmX}%i<Az&(~MIFY9*+cZ|0P-zb=A&3%|Vd%4&0dg&hIcbgA0vPWTFHjq2# zUGZ<*BMmSOUr&e+TOfI5&l3T%u-X$FN&1-ho_z5v(zwhrhQhwy_t%R<3pRNtv8-;w zw9kIHN<X20XE}}^`XF<e7ngP1UxJQgr2Dbk#G|m6ZkO;2dm(CtBZC-rv3EiO)N8BX z$=9N56)*(Bw9)S~WV@QgnKV8L9I<hF0P4E>tHqg2hPqv7l6^h=#Rs|_-|djEG`^nB zA`$vNcNopg72TAP`}~vg&|StmA~ykPTxXSJd)7djpbvMVll`Gg;!TN6VE+@u_)BD1 z80I-_-^#PK6PO2XQdmH0|E5fm<gI)=b8pLXm%y<680Y6(fUV~;l^0Ex#T@xkC@Vt) zE>w8q@sU0LU64z6aeoh`hVMXw!|?Px=O;F<JJe<-I+LpW8T~Wz7NF@O#I5S<CA8ls z_43)kPP`Ulp{Xu3A1QERY;<+E4Ookgqgo1PTzZcRve5EENHh!E^KrV+CA9P4E}cPF z;t_ayex1rMcLvRnq^8Ser#N+UC9=d@1Q*bFP6>~fdcjkHv>%+YZNGDJ(TFi~<zexq z)_={8{qnmP515OPZs&YHZPzDXGQpwyRPM_Mv5{Ba+NDf9Vq>E}Pjm^AvuZvR*up_3 zV(KBU;SQ~CFMiVN0Py$@WEO%Zb<Q$NFsS>yJq!1A>Q}-`DlLD`R2wA5zn;Oazj!h^ zzS?6q#cf-(wu$2b`|!cSDef|r2jb-xrWldAt4Fr079~PU95)9b5&p&e=^|F`gZBYy zxy`q6OL4cxKvCs0N_<T;ZmQo#z<EW@%%h-d_X1Y`=$rb9S-W9t=X9g<Di>!u-daJw z06!oVC=>7oW8sBRsq|J>1!qC?ck^FnSo!77e2lGv`ES=m*)5)V7adle_J`U!)nXa2 z8lV%SPpMEOBMMz7q_-o4Q_2<QdGlX{hJQGB6yrUy@bxGVp6qAQ5rhh3jVxAUOgSPn zBzEEccMhM99<LBL(R~ct;2r*H!)yG;tA<8n?)^Qgw*CI+@A=x_X6I?Y2$=~mj$0bJ zdNPZjdcJQyJvJz)PA>#ChtE`vTXf&LN`A6*)d5{f(WU^&-n&Hho=noV69rn|>PMMd zU|Z7$8{q^4G>9-{JTbzDF}e3WxLNU|@ip);x?cf9mKk83pl-q7IviPVa%Kc+=y!?G z)D|3d{Vc=I&&~Rt%OJ<rq}S&+m%~TphEU!$qvM&JlDZw3dLy>W9-#~EXCq*Bu^g8R z-tYOMUcqj*bnk{RfwR~$XT0BfyLZ+Z_RvRH{ZE%khf?cLD8QA|ozYTeb&Z8R^*VEc zinW-EmKAtM7b}Gy<v2u}I-p&Q=inZB-a9v(*h3#5VyZ~kLEmAI`aSpg?sQS>N1xp_ z#P^dQ(jKmn__7UhYY%X9YwF2{U*8r-)HB_?SfxL%IfwHK$BjHuI{(0NBFOy>Kp+$n z1gHh@sV|?x#Gg}j)>4`ZygazCna7vtJj7K+>ZE$%WJv#3{oy0RoQJ<eTa&DB9*#<C zI6iu8&2nsvr#Pz>RWUdyrvOsfFvi8%9a~+-AkWufDO-q4M-Hj?mI>GvTFVP~C%1=% z7M3>t-XN|$%z00i0f`wBE*hE|Olerz5ZN7D`=qa!fpC<y8&tgA$9h+e*dQq#p(o{X zF?hQ~x9Ke5;zQr~J0fUPbxk}lZ1Kq;>l0g|7nj{6YlA3XHqe~MgX5(XYEr2KlO`pz z?WK%#J}=-071D+}pJ@wrKhl2ZF0RcflZ&su>lx8+nB|*#D%Y<H8z(FT!S27AkJ(PH z)?cyAn)bJp`%oRSiCj>st8;5e=-_fRCUT_|(mb?1W0qhA^c#{GuVExAwMkcw!F#qJ zsK!<15%O6ZFl^Aq55#%CG|j9v>yU974i}6t|8l{|_RzhvU4U-{3R9iVSiK-3B#Xqf z#=M8#vCELuf?2;JDKm8K6|FHlkAP#>pc^+{uN);9Zp!S)q8}AFDN!^!sL}vgX%fVF zX(;|%{@XqChB>XM>Rv9ov<K8mJ$8gJ4a@hH8NWqaDV`Xu>sU}xMd`e1BV#y_b!63h z<(t{jC_C6!&Hs#8VNjmEmV~d|$7(o88Nl|5L(u{j8FtFhuxdTf7g_p6|IwD+97{o} z)1WBwLmCbK_;DeviKz=F?CE`c>bW8k50{-IP75mNs|a?U4;#lyAD1qid@ed9xyNw; z^_)2Bh64xpwPz#sxPNzJNmEB@fCsxpd6OCz4%M1tk{g9f9!d~AzC9+yf8P0?sg0$w zdoYBPgPNa%bf=JzuV;{uxuIH*lPLU^O=&panZWADmDa?VUqhyHNFRfo2gy8Gk~uGv z;Pza;rb}N|hD2K*Jdx!jYM!FwJz7@h?1vbfbHXEQt#j#bb3%V75^H9iKgzKk=%3iM zUcEo1cQanGc3%R<`Ozw|n9^a7DZ7IH*C{~zrkrHSIFISD&j`a2e0dbt`hm9v`+{ef zUZ}wAs?R~Kf$C;L#WXfGg8X(s#k7FEo<!)<BB2$7Bf7Fr^r%N+3s3I5a_Rzq!7|zE zP68Y<T;x?%<cZEnMKa;o!)>UX?PGWOjXVcDIP@c0<}xvnC!?okx?q{Dzo~I3<~<kJ zrBYH>!Gs=^T<pn{Ax{}M_UE!MsPxcTB1dJ+j_YAMW|WgeMK#_YO@3|0?Z&zZ=^p3S z)W2l&l+sp9;{Y4a8rwO`x^%AIjq+|5tlnq(Qa<)UtiYA4PEhW|kQ<0N9KXYy{Z8EU zUuQ|gME>3^iG=w7nj{er7yfHwk-srX67g}cgh7l<7KP%v#0zEnsX&3FfNw=5kAH#5 zx8F%d;p!|eEu$k<p2PX<t%F6`QC(b#=jm5_1)kO-k~bXmwb$7TX&yguor{7+Cv*+d zl_w6)=3a>wwql|h5~YV2#dyEQ*7fI#t^6=5ztrF|DtHh(-$0s2vgkf=SvTgs^N@$u zDAL*~m4{}E^kF{6uE#?uvZRJWyccPhT7HMp-@#cTl;#PbdM~G^@sVn2&P@lHs$bZw z1D+@GeB1TFVsGM*2wNYdbK5b(<Q7!^{7im4<K+?|+xv*-(>&$*BoLi=f`;Zd{dzVj zLwoe4iI%L6pXbN>_5_^UWn_aiAFYUA%TZ<1Ou*#e5vp2w=$Gov@<xdAKYN<mX{xu7 ztHl!zU~gAz3UQP;q`fLsIWYObUS~1E{cWA3mb7rmHP<$2h+J4b$(0<%&F0Z9rQXl* zv{td7!QjuK)aHGX#B`iX9?&v9m4#<}oGD}`R-4T!q>Pe;hRuWXDMu1k2=03dvb~GX zR?i`A>=^TpvDiE)>IEaMo{KmD<zA>Kk*jS^WhSwC>_GgnHVR+HBsFE|)L4x~q-6P8 zveVh8DaAi!efG@o*-65wZ+d8`t%=QNdB3R|^+eD!5U$-s!FF5lBdKO*;slP0r{1`# zgdz&#x`}BO&*un@BD!7jqMLVUCXzt-m*wHQ?^7SpmGbH)d`o#&=)p#yUb^kUE|t0Y zD7$g~DWp%9XIl~@al)O~WjW{$xs9r13ToY*uBhn>f?S=3H5`rKo((plWMr&HizIJ1 z7OvWBXh5TZw+I4r{C;xeJ=U!UX(PNJP0|JWEc*hy514{3FZT}OdtcNA-Cjgrov)eQ zslpGA2UV?<Ii<y=sE4%t(v+$<AG6d$<R#rNHg4MEdpT$^l0P1W6PX`%@ON6_6nbKU z@m0ceI&QYZo@nC8KMs$kNoq}Cg|pz8MLrOk;<l=a&-Wt?3m{CC^3t?>{%%PTvq}fM z8&KtAe%}HcTLaaxa~%`>*jyx#lP`EHgbjy|=&eQmBfK&m96FBHgicd6lA@}_PCad0 zmb#7~SjAUL&z3r8g?s5_SOd$Bs$+i8xt#P_d5-_|l8pR42BejFwNI)F-TXx^5Fsr{ zpD#uu*-GpP{*55NF0}ZrJN{0=n5<QWQ0nv1yKNBuk|hJneW?zb4mtd@;Bo9pq(lU< z%r7ELzV*I~<5nEj!aCot`!#$P&6|<%?Z_ZD9~Lq~0UGJ}PuGOv)Vr85tPBobcoSIo zp!=7!>0_irsE#Q{{xY}o?>^ou-`n{@)<eiJRf?*xEigTw_~U@F2MG!T`ILf+#F+uI zJHr_En5Wut!M4nFD^SXtVXI))725L@`EuUi^^io$H;%zo7?K=lnqA>kM2evle~NZ& zN^^oX3|oQYr|LH%4n)zEmYRsR4@(3zg-*?aHG)QaR((~Ake;J1LEe-wO1n=rKZ5dD zTRcTxnb72^1U{u9vnA&4@6cm7)j5-~ZFg?~;I@s^9z++*7apA-zal^xu1t2?@>?Yc z)`Io=LqMVE>)wUmQ62BXpFR}jqv-4*{K2pekw1FCLP?-(^^GWR`MFzo&lX1&hMy5z zolZ=76J16~8{K_OP1%<uTBiDkKRfV!aOpUFS$g!aDRr@}N-))kINIp)s_2-}42G&l zKQSVHVtjmqaRsG3{Rhr`gYkqX*i=oQB<~w;mDy8YGXB=vapOC2vpYD<HC)(vcg<W} z!JmQH@*vwKaR8k5jkpSmPk2w*TV}-jjv=SrVDwa_4xL&N-W%<0YWD#rD>~fctL6IP zh|)`{6=SL)Sfn*ZrXYqd3toq<OjF6o&-(|h!JCQCpurwcS5lEpDPdbeoGha7k1Iqt z#6&p40IU%}C()RuGDAKGnJX`uO<pApe;Li#6p{E05ufaFhb!PCCx)8^j0SL@8esPU zD?EboP@6yHH7_KbizAH8kUw3j%@{dJhf2R`iuysvM9$=pwT%SaLyt-Zf9^|05)NVr zTVp)8?s#P>XJc0TY{A1yl(cwXzBoN3wigT?4c;-Od>yw$ZC()>OcV;q4Y3FarX}Y8 zg`Et6d6HZBwV8Kz6EXXl6NFfyXS6&k9aK7m4li^GE}?)eM9BEA;nq(KH?*T^6NZ=v zqqOrR&@M$Vo1>j~g!K-jFV9SCZh(=ULVidrti2<zW(_1Rdc|5~`jj?&OkRX~$8q&K zw?##Djq%EjKZ^x~*L5!7reldoF9#-)G+SY^jJT)~=-dc(T_4QH5+(fl3vP7%;M?t8 zkMcW}OUu^M8bIIo&vQC%E=?hwXR1G_iXd2*j0&r9a;!MMn5W6)D(`*((*R?;omw<> zCS&^{E8fJBT=+2neSM7f5dKA3^TG~!wIglj6z!N4cQ$LX=R|kdMFQjn|2;~J{@o}o z`mdeAm<7az#QyG5#y_I83UMR~&T$C{Et)7Qf!&v9E+q@?C-QNlj!Xz%3kL@l=Iqmc zQ<<z6*b#c!9{5v_=GmvOM_5EJ!T?6K7;j+$;Ht;^JQ$Fj-<W*dJDA+^0r?F(pT)s; z(G|!I8-=T2F(Mz@54SY>x}xRN&uHm<r>GTQ7JTXY%mS*W)jI1dBWr18Q&47N5tYvz ztd30>=fPgUr@BjVQuL0FU6i^)^(mK`zHqR#$GDX$t%n`9>N?lLsPnmz-lNgqXW2)I z0tALFBpfrW>pI6u93K2mj2)8(*O32mBqOC4Fa}1&>i094H(IRJzH=tgJ+`~*P}$PW zYc)`mzPk;X#doeiyq^VVA+P~=Q^kq__iJLeND2De1iR1Bx4i`#y5n});j}1~4pYt7 z2|4GunSA$sP&e?=afiExyj7xVz@S6QXoFifhPILXjSrfZ-T2zE+b#{e%-s~`9vtvd z&l_N4EDQB7HP-52H7>kp4Nhfl{Ary^ghsR!NMFoS;|5>cQsWeGlnyVW6#5Ww#-Q88 zgFR}YG+2_;wN53fr`t6D;P@T2$aUQ7`aZq;%zSE}UWO~p!GRrVH3>%;TxLHvE6dYV z-wMY&c2`k3B*xzVl{P9lH3RmWN+W%(ZeGu^uiC|G>Q|dW4VwrUoOON?joW5m#j0;& z;22)TM^`)kGkxpLz3FFT4~#OPK-6oaKCDrT;{fYX3jnEIPMA4uLlJk)aTL!`V?5Kc z^!4r871Kf6_ip4lyb&nlx9EK2V%7$|ySQmsbqP90qIXzio&^O3+>Ofoyg7nbF5e<; zjj|U`_{<tq=J4)LXJj5ByL_%rIc$HZ*f8)39(-#^-a0YBglMf4j>U~SPX|1~m69%L zGm5f;Hd<xpQoK|pp7Tov+w*hodigC;$v!5`+Qc&AxGygM3Ew7;k3sryma~oWv{srx zx6ZK|Pc8?)fg8Vw831!23`F6;x(=VZg7aqIOOda0&#K80ggQOQ$YY2c4aHQ;mEFz+ zsIyDSZr@{vTEi&RfLfP0A8gp6;h!--JkPU>oKR<{%iH=xGL#?3P%@R1pj0EIVDEe1 zd9yXoBT!th>+B}e%+F-fr`d$XEP*ZA9dB$6Wq4QBrZu~pN`Z-ov&g%9w#iBGhBtSz z$YcG<fQ#lwY%V(ZkV8q%z?o_Y)sZ60!F^tDVgNJFOeoJm#=HfQf97)>Azn_m2vB~# zDEZKnFR5JY#y9cNml4cr)ZAiY<GhZc!sOlD`tlMDi9{gpGcLKUr><iD6pMUwpYk+t zIEY?z^vRK#;qMc+bk(9a!*$(DHp$?~0_JxewGp8r0%gKiQt0$ZzHKY*7*!Oc)plZ& z#hull)^e_j{X-YkpFAgnB5qt`63&UWIjlji444=w4-NAlC)^s<P!Kaia`Dk(Fd~DC zCl&c8ci757cH4eDU!{n27YIbO#`Gvj0o+tr0I8QNt)UO^jK3ST@_Y;%sJ1%g&{<)% zmDZkq91=X%ZSu(VRZvE%$VVwqJoF+(BJcN^(x#NoUN$y;T6B5S&FkkzjGEH|1~Qxr z<&!Ue2d8MN-T-8?ggIw8@U*8M6Z$@OYf5H!eVB=MfqDf(pLsu?SwS97`+C{Zenoy4 zZcZ^>BFg!2tj)FZ)LtVZEmtfyZ=$HxWb-X*vd3EPjjs2liE!EZLy}qm+${j&Us#<u zYWvhx2x@*$BK#RGW-*|?DDZwJp8l00zd{HhVR#ybZYKUCb}cV_GD)2KGg{`S-1>4M zt|wgy@0qRTxB(LQ&-2!mF$R<|<XJHSu-L?~v_!GU=rFhLu{V(i*N_K~;RpX4hh#|7 z6&Cvy7JdLG+P|#O{zcFz)AvsV#q2{%LqghR3&V&&ON)nLjfatsjgcd}O01;DzG@TI zKTMjE?@GXCe9GUn#bS1<WqL}+>*wP;en7Y}Op0ch9KN+n@lx-FHi@ZuM?(s_n_j$u zdmoVT2KY3e3f#~|9Fs=44t7oQ<W|0AuY8L?BbjIVv*pG`J+ou+F^C#<9PeLgiiN4x zw>a`qC1-o*3}a;tfZOq1H~18ntjaG0b1aNm6UPYc2v`6)AC~W2vPX3NZJt4~R!1>F zTlL}%U-6|2hC98Ncio~Q1Rocohm1-f9JT;|_87ObdscmYPX6)JOsRX*@u{eR%Pp3p z_iL&Qjdyh1Wk5ng*YYuy%;*>Hh!D$}_sq7i2@9Z)ANtE~2rc}H&BHhoT4IpEB}YQ( zDKBS49j?tUJ5E5^uT>ZR0P}-Jo@(T0HcA35D=Z~JN{)Qh;LdyOS^2625!jUf>^_FP zLmWbDc4PT`jEF~C><X(CgaCHo5P4d{R4sN{`+Mv>3i%XjL|XGWYJ*x^q#HpomJi<k z_xLRKcjNQFkD>)c{(gKOFL~HR5_vHCa*8PYZT|!x4L1=>LMfSi9}%L*m^&QD<}ph= z(>KkQ_;uYz7aQZr4YMSfmOvd66GfFLTavv3&+k6P-&@DN(%Toc6PK(8Zmm4Ri*;Zq zD+ZpELH)-_tL}tdw|oO<gX6}XF17BpU4u5(=!Wt3#OeK|U9%p4i{BD|e<MoUJEu8A zp&s$X-%7~mJit+C{WVdCD7GuqSt!M%av{b7FxO{eJiL}X{2lkIFVN1_nk((O*T$rC zz7g(lC`#1ds`1p#Ajami<93p%S9ISt>!%QBZAr(-=3vqzrdgGo$jhSn81<Ecz|-kH zZ8yf7)0H>&rzbV{-w=)W&nPLyF9n#qa>T9etzz4j2X&=27Wfi#)vr-cD7JK3&T6Az zpfJZDN}#ZAACY*u;#l5zw;fn<?Me5?ZcF`*#q3nWjiKV+s)3Ju(U_%KN~^4&Fx8XH zQ)}mIl8a$$b@!_VF5XaM>q?llkyQ;8T{ws8@D{r~*58nC%QY_|^ws6%L~s$58qYRT zmbsHJzig|<(TcW6jZS}qG3A}JY@6<$s8TzyacqKB%0QBndlNi~qAGL0Z_YH1*=5e! zMPkIwRPAKGN8P0s3=mzUA<c`9cZ}pC=&z#fs-;=bJ`8Xv@S2UkE#*lT#p6@+B6Z|S z)~8duIVNYC{}wRYXLI;$RP<d<HWmFGamdd{jzS%vu3N2MJJwGEh=)nDA!DmLADrZ& z-M07l-JZO7{f*?w3nrPn>!V4Tz^kKCmj(i-tGcxVCYhV@-aU`&Mzi*ytC{%G+UpD8 za{CSHM8LJ>dbjcJ=5WES<$5Fip^vFq=ws2)EWkI)6lPU=SQ^d&L1idB-JJdaKwrbG z7y2xW*##YA8qi-m`^vmUDnlh0Q^`vUV=ll`jtk2RuM7Bc+ubc|;d#25OZo|1=H^O9 z^a`k`S^cov5Oa7ArLV_Td-Fi>hfn^YLFIy4KEE*g;gw%Ce%z~DjU&_B7!>;*hdVG) zPq*)<Lp@UzuI`6ec}W51!c=pN&voP)k2iH9Lx4YsVBfTk<yOKNnFd5Q_b&R*N8oKZ z$v_z;QvWei#kMGU-?WE^i4mjU1m4nKgorjyXfUQUPW$9G<HXgtryM_g%G^WrO~os> zzq#iNBK)OSlGtriBs$E{6ax32X!D{t@PrqaxK1@bsB23l?9AeCCcm<s#SVE+5A#p* z^G)(wQCNdAZ-o6E3{wiha$?t#)`u?2<+I$c3rV66eIbg&DvV?4ccBi;LI1v}b@)z@ za{yRK#Tkq=AF6->iqqREQ@CfjU~?jiI9JMt8lk9gJvl%8ojN2<=&fiHP7&GE#a0u+ zfHJ>A)8ke`cQSuq&vI<&iiQu>b?9dWvCt#{7rP`Gx-P%mN3?k`KRD-owSiH5z-4a^ z`7A}0rX?&pPD1%7tc+s-=-K<w5695IfR?;m@B@1Gr2M=;k4s1N;}V@V7Kgniq?7hT ziq=EfRT9b(t-|n5OhT7D*T_ybN>Z&$T(wcH@8J{JDQzJWLX^Durx-;pd0Kyd9ZAXN zlTZ$5`4L25QO?We6Gy1AQ|4vSv)e|>v!w{h&fSOF6y*L9aNx(52>lIOeqt?A<;uCO zdSO2j<x2X38OKvYIw)>I?~kp-SX1=^6@EX*7|=h;asDELipE**ONlDSJD#$~f?!+K z0)AEnD)y)N%JH$|tn^Z9|5N7$omA+!rR8a#a{R;=c?^iYKt<FqMLFL5)W`nRJ7Qvv zJd3fkwz9HeP7L01>^~V`<sUS;aUBs|9Z4#Mk>eLky9;WrdxbOEo4gHoe9;UJ9khIV zQGbod-;MsKZ|)G$$Ug}#_R4cGJ$HxT-t{Km@%5)g#+#q(lLUP;<sAsss|fVsM(x<D zoR(aU(VFiOgYx%(rYlE}5t=&zawv}tIE^sFbuk>c4j*R3>t<Wn0je6XO3j@CS`AqE z<rvSG@NJB(xq@r)U`W%dqDl&OBh0$WN(#GKe0S<XZLLsdC!ERR&mRvt&(FT8RvhVS z@mj%lUM3pT;h4#NBrJcmC6^DCiC}%1QG6Xp$V9uWx#~Cp@BPsb2{LQ7T2a~>)vry{ zkqgCwUd0Ud<sLu01HuaGF7oS&7LO>!gQuvhMw#m`!ynQ0akx-YsM4~jk}%gpX%w+8 z9w^{|JCyk+Cz7bKc*d0ZS2NLe4GDE*$FDK>&3Y)CNP>>RTJnh)N}^ig3W*eic<ilz zIhFWdPW2t_RBFqz+q8t~T7JP3f5c^r0I{D&bgsc%HQ&3NU8o+N!1za(*76&W)bf~Q z<-vCEb*9xr@W+WFAkb6U!=N@e<<WnS#NvN95{vxXNLloMV?KL$fEyi&QOi10B;nO( zw)Bx9ED1XJEbF*7Zq(Q;AwtRg=}g~RjCq=VZVX55dS0Zyinsc<gP|ZXfN8w(6{8`z z09g@@&aXZjN@~?ooDx<Al2ssW(WG%blr`BRwYMUYq&rFH9T<OcYL>}RAZpYh5cwhL zw1B$0<xI2uS76F#<XoY?6fBCmluPl=M^$hB4EqU2ZCR2npic9imQcOa=~&j|X{xO_ zOdF=tDD9!hNWz}itg+N302Li2*k{%j0Mjbfz4ABMQNJcU@kpsQcpD~+6iu*&dyVSN zhGU&`UQaR>%mzI3CT;;3Nmaf3^?0vCtxMO3+581P*i*z2?<C}O%<`8-JVk<M6lFu| zK3S^v<F_ghpWx;KR%u4PQAfP3IE(#~+x!>r=fAGy4Q#4!giV<l=@i(v*{xp+4?|*& zbL*ujVvU~$mwQHibu-zHvx&ba%ncZ7m|%pKl8p6<2u$JHt!E1V()~%H<P?0HhY?+_ zrMGr8+Y6f=ic}u4GPS>D94gdQ$Ze^J-2Ud~{PrtJY?hG_RczK(6_ic_*Z`$#q7-(Z zYkJj1LYF5ifJU;7j60F{F)#pZY1+-93g0>7OE@?`zc1vPNVRrkY%W-+Ey={1c(S18 zO<b)wfn%@q>u0J>5MUwyxhQ*sf{T47MMG$Tz2H}pw~gfUqz!%oz>-H6mTS5q*VAQI zoM;vLb<S4noFz<OcoPpEeK368<KDWHYswQ+9@#Q|FcU8mcyl;v7IZfw_RNSU%l&$7 zH!8Qh^~&Q0W!4sSg*q7Rgxq$aT<###n`_4|%eP}@2Dx2p$9(O9cf%E_w`-S`?O?vq zmb>fRyOP=5mEGdpP-~Lk)*p2Te;GAk_wecgJP9{U^A(rt`|inEyAx2);cHWBNKFa) z5OgY6;lL(Wbq*t<mD{Q6lEv}0AE*{c$j#%+Q*wV}mV`mrr)jfRJblO!eC$)!tg0`_ zwB@`)tH_D9zI2u5g-wWRWh%lb)jYK3an-`uGvw__)vj<hUfFQ~+$a@A;fmZO?5kPd z!P2AeYboIpFII=^*4PeVr`xTC!QGg@0b}6EoHirxv$oOj%r<rK+9tWr<?~VtFJ@m% zd+hL_H(8Ikp12$DQ?ZAxQ$CbPct{V^f8G?een{qs!^)#(pI8uaV@hTz@xt)=7W+yh z)(`j3by;I_FcQjlTKo}Mq=b%nvf-f|l&)Il*nkI=s`=j~LUwS~Vzrnfe$UGcE8o7T zQif3u%!M$8)+Po~aP#1QnZy`QTxIE_mx~D%p?dgOUj{#iusEtzzKPP+YhT?0WCDLW zZ3J%q5<ObrkV86C-I8M>-WwHFPNfxJyxI4==jcIbfWMZ{4~GM-_wonNLk`w9$N?(& zLCrpqGJ64;&#RMbTWfw}EHCW}E;E)+ixM*UA7l`S;uWqc^S>Ix1Aba#T{G2sP?7eV zB1+wd_1z2pVP-eV^?MO7<qS(!*bl$F_Q@wB+B!ZT%DXo)#B9J*+tqUpJGTGuQW|kS z_MP5n=iM{8-+gbDM3aLS<9Jl#Sa}#M-edz~Cyd$f;&z}|%5f>~4|~ZMl=<C<q!gp@ z+*t41Tc{B+^4v#-l9dunzQIz#6s2U=z4zrO&YupP!Ut%xujEaUq|oKd5*A6azr|)F z1)zOqOpb$|-HknilrPkoy`v_CA__|*3d>UgGY!H{W{aa?i{mMT71KZ-qosxmSY*b) z7DI=4Pai6OxsX60;CBYbb_RyCM)1hLy83&_1XjxSA?H?J9Z8Bfv8*I<Fg<RbQ(m_P z#)JjNB0t8TTVSe2VY+r<^x>*8;4(Afc938*qlFL+_7uesqsIse6{ON8tmy5UU#raV zZ&q~6`fdz{9AEpA7M|M-Vj31>s(yO(U7FN^$?R9O$vNTOv1rWb%!WV2rxu|PJ-e$5 z3f(=d@;d)HN3k@q4C0A+y4QTYUPcdCaiaV#y^s^n@$A{m)oMA4kFXl0Fn<L*3-sB& zDK+QLSycFo9{L~jvZ6Xv*zS#%1?zoj1KIhj{5JGy8x^Yb*_^OQ_^~PzPO<z`sxgj~ z1%}E3m9nD%B-*ZSF$c8))yBQML@ybS(UvW-%1zlZFUIh8VO3&o`!%(4Ni_#n|Gax` zbKX;pJlo}os$8wNHFJOC@;pS85QdUe<9zqLYLTd+<0vd@c-6j!ypTO(;!T`xSgiTi zFMm3iy)QCUm2yZLL)T5q3Y+cG6xu4DTI=^xUdm|`BG?b*SJieV+2Sf^)1yZVb9_&# zL32l|V$$~h2z;&fvkGoi+tWz{(z{qUlR&$KR0d8%Et4-JaCv*lBuj-2Q%qJ)wHNsc z5jEs7=yaIxNbx(B`K3)Xh;SKsx6m#|ggY6E`41PPCjLSI_@|5UvftqyUoyx2_sIP> z-`D?-m1r?R{=Yqj&KQn+C_)^3fX*$5^{)Fak&HtAcQ~1RD@K$QGfP4m;OJcZV+C!? zkL>25FO3Ukh|8n~+dS_l^O(>{i-6mOINp`$M|fl-00w+dS$Z$6wWho<jm^)D+&e@; zY*rqaQJp>^UpB#bVs8((JjUZ-CtVLzTtt^oV*S^izJ4OfO*uJUtw{~x#PLwLQ!NIt z#G3<_F{I>Y?>TOfe-KhQ#orae0(bs+7^Xs;y{@-)z1kz+yIQ&_gJHv4E9mGEe}PS6 zdU+qD97=k>jXc>!c!;&T_Bd7LtIQ)a-|$RnQNik_<97lt=><t0!OK+ARbA^(bAeO= zz##1L$wR8k0VaE<b@IZ13UH`znk<M#+;W_?PP3+6v7QzaWFhKtH04@`zqMcb>0taU zPnv0V%O^qRvDrl$PJ^yLSp_H5{XzPE{0Qs)=>b+N<qW;&uN^kXInf`{UH;0fA0G|} zn#%Djvljk<N;I(8TTK<JKm&UvpA8MJPA*$ha#M-H`7SQ+i<7%n_Xeuf)Y?BadeJqC z%B5P}4Kx?ghg2gWv+{S!QDp<=A~GEwz%vEbQg=qzz7peMR^5#^plZ(CcoWC{{2lUA zcO99VQui~~yi#{6Nl%@MiEHOFDSc9t)Y9k)ou<pPar8l8Qm3ii!{^#KU!`n7YJW_p zDHIK|{kBSsZ`dI^=f}fhd}eo-SLrg+!(39=k$1<(XWkw>mAkn?SJ&I4=v0`;XEM@3 zm#8xbbLjQ<WYDcMYEZ~5@X86-9ix+^if!ex;Q}9V&|w2HPbMxToE65{#>J<dRb$3A zU%-N+tZ<|$Mmj{7it1RzI=GAE2-Y#e>CKbeANd2?)a@J61>5iLRV7VmU?(^SCxn#a zyvA5k9e=o?agH^`tmIP2Zf(w?6h;~FXhUvnA{3X%y`DKiJIP<<9Co*g8Vw2}puIa^ z@RzvS_q(_;yAwy0N>>=EAF`cV?FwCJC*a7rlTV4Pw;5Uv-GGm6_igRt7w5G1J%43{ zskVJsKlXIj>M{5U@rt*i^6;{itemS?_qyrQg>lSTmnPr1s%^*><wb5qCOmVq{}9UY z2Ex2q`pWhl3}b+V-;9m3k^)x-U#!EwwyM?OK6ghfpl{hlKZhA#dqtVhibG#5gc;ym zc*+e><FKHxyHQrl!7-E|sN*N7t9>tn-H;f(@o;R!%>rxm(Jf^kt-hK>Zv>#5-dwXo zrBjbNOZKkZ91*;Wio#ism%U2>FfU^WU_%HBF%XbEB@Pz?vyeSTJ3s7o;%-7aieMjX z1c6-v4laiutC9$|ItN|hmJr9|{JK0?C^A4M(O*Pdq#YGAikxVOU65h&e=j|Enb?{Z z`VgODQP?@y-*%*WMdPLnp^>e<b8fM`l2{26fUF;vxs&z!EA)YiPWxc2D5->FC%+_% zDg{66p_=b0N^;bzB>c;dI9=`mh<q$DPn<p<i&`XvjuvKxPhjB^W$?5z!c>&ugD3c} zTcupmMp?fyc@g@pl)#&H40v#uf;I8u-{ezb$jLH&dV_iVUSX(Sh63y$BXjeWvEmB3 z^6kWWIZ^Fk;{`(Q<$;mx;78PP#VPZeAgTY#MyWP@CNy(U_%I}0sb2fleO$*F#!=-q z_6=@x3+gHu#I#LxgWcSMva0&b!k41TouZ1LAY(hH_oLoL6+eE)YEHVpz673r2Kp5R z>Erw68~4pE(5tRjeF`C|3Lz2s9i9gYH9($#@aHZysKl$b)PQCAWwE)d1cZVbQ+_V} zL4Yfgr6_*vS1d}}-J`Ll$;fX12ZX7q(P(ag=hUkJ8oxMS?zl&7*fPGPvX9X9@*>Lq z<$Ay>=EX(d67j?NJ1TLZHPvZJ{*&0^RbTdj25Nvv+WY{!2FM){KJ8qEN~DLT#xBVh zG`69}YvbKdtHwH<mOILAnY1qPZx;O)jx*Uz=SIt8y-ky);sq;D$HfoLM;+eJl&wQ= zo_*b|V$_VXGCi8XyGy_Y?fEA7maki^I0bxVW3p|g$$?&J{iy|11L1)XzWu!)_fu*7 zx0a&RHdCdA&&Qy^h#{^3yTg14Q&NE4wn8ZIABw9pQTX>QMOiUvUnZ=Cp`^vH5+?BQ zm|9V=xu_Ir@$(fZa6tO|sT>S%FF*?kD*_Tq+Z}|}067D+4nrVJ839_`*kQoMs}4k% z8q<CMl_fkYCjHCc6>Ow5^Hs+L9u89#3UdxGMVk413&JFYUMyw0!xrqq(D<*RQk?(q z4s!o(x>-c<Z!ZT2WXQ!WDibTAq?LYka2_Y8V6e*alHthlCPdI+hH?|L_8lp>aRcY_ zo2u32PxNklC;b{4oJ@M>8|<@D%e_qvKd_?7qAdk3<oQg*U&|4pqRznScHC8z)#7R6 zM;4{u;J>_w!q&R{D!8P}^snA&E~h`KQA+1~t<?4b^ZbSQqm_H_-d_RVljt9WEuk`& zM3>a0Ed=DG-F|d42K9iJrW)T-U2r}kHKGhSTTyzUU*SN$4C!M-jWX{$nf<!weyNy} zHu-po)Jocdk}LP!(ran*9;JW>nbF6;?RedJma3!rZq{NU3wi>WMhwFMY4YKS0QuKI z<a;|_#JzFjzQ>=N5;PS(=A_+vKt|5)ZZ21xk6I-@H~DxddiZ$YIQ(_~ga7rxas6NT z5AFTt;U>k<>M&bo*C%!1D6w=qQWxHFh9%=riPon7VHo}=1Amm*44R>0oFR%gc2nHW zUKqY>OgD7#!EEEZ_xVoF%H-qE61iwG=lmaJ)LtkG+n&6)8`-%xo|T%W<dNoKz;6q? z;du{1q1Ybf4StsBLbKOu;&|BPzS|r^SNrJyAX5lk4Ze3z>_jtH+W-1yv@$55t$luT z`EVJ1d11QdbhFE3CVhAFGia^SWd@B-kd*HR(dVn5d;z;x$HlpCK*g<=Lnp;gN1|<q z?~dbkr4Gg<fFkkp;HSRAa7MO+1vj%3Bnk{2;W!9XOalx1`WXy#W$F1csC??>a9MYg zsd~BOv6$X^k{y*J3D4hr@#!%~{AO$Cn#8_?>2C`m;AG~^aaDJh4M<s}a>L?%)G)a2 zxGF8`5lHf6Y@o{!l<BiIq`(Dq^0oWTA_V*fuG?UFA2kFnJRVDndI%Cck=<b70X_s} z_~soaq~TEjhrn9Cc^e_!VYVP+G=ROw8wGzqmK_Yc2h8!++JNx@)xdU}a;bQYVD_WD zk9azuspGtE%Tch`h8$1)x<__E#ZUPBrE&7;ncETYn3T)6eDo|aaJ@gP7cJnCs?0Gm z#rtkj3Lfxe-(l%UN)tqL$FBJXo#@~gUFI{gAaQ_J4FrW}v&LV^u(D}3x1MPD3c}rn z7o0%aOG90R@$m1JzJC<ecw;))MFITetG{8v15^ilZsw;()q{nP#y&>rf~Jqhx)p3e z+P-#!3ip5?eN{K|d4NyBR+}uTQFY*lM;$}he?Wqd`DVy~f+0v1%zv^nfc>X4z<+_~ zV4qFcA4SFgQgjimXqXKM{lD13FbZI%FJd6f5R~GB_}E(k{<=|pFJ9_oHnrE;7tw8r zY<iU|(;LvQE}cFH*ABR4K#A}jWdy|Sc-RN<_QU^);?_Neq*cx&4AE)H7-~mf1jJ3l zRi%3o9<Oo>&LomX1+Ex=!tDb7k74UQzr~1}ZcXd8-~f7nexd=4!^J<hOV2m=grRZs z=<HTHiZA;_>*VWja*B$F=^rvm<lrWNG?x`9UBCJEz~j6wB}yXx&C>X$+W^|It49nd zw$VQ}zW=w4P4T~D?0?$W5R~O}I26VOboO=qEhhvl0e|0+dyh8^{(8KUhQ|gHMq3uI z9_;nI+7{GuoOb}e#TL%~#qi%FjlkcGG@?TPYdTd#O!V&#$^tT;RWOJVhocTCn?uyE z6AgncI%x1inQ8huqcP;DBgxm#Eha%?7agub(=p%P=mbo@1WNf1bYy@9Dz41R1k(BJ z5@th3L^AwY6jq3co1(T270@(prlpzLa51BI+ZT@?A-Wu5*SeyAglq1KY<fCTL5_Ui zLa&q%?1(4bUhfXf7xDu!)2{MvKSH^e<r*xnNNX6=4>B6o&P9g4nRMz^r5*&6y0?c* z^pT9#;vEIV`ks%h+#)0!n*FVxES|PHMz!QDcsU-Y?zt{|%#n&or|-GKJ%(ZX{yQM> z4c&luE6Ud0apQ?1UJE+)Pgk~P1LMw&`NHZ*Y<Rgp-W;j7^CoVK$CIIzwV4e6<QAE( z>eK^%`0tTo2^w!w58e^FP2)w0p{DO186Ix%KLr*eJt19L(NCiOV%TTcH2#HVkVG@Q zMKkQ68GdGWWtE~C^lV8zD*naL{4a(fi;;A6q1iq|LiOUs4b!ey;0Rqb{LCvZAn{^L ze8zftOUlV&l5>GtwDn!@oM`Jvbp*+QQ`cZ5U;V0eS5!mLxR`lYvt#w>!V5Y`3CUnU zbQMW-%y5;(6WHcp<XoiEvyV>tbCLa#Gj$d<t8eG3=H?-DhjpvbqYJ(9E=+-UCktj~ z`z`u=Hn)3wU2w>=<(c-|qqD)~WyD}WVC&uGM(%-FYx~W{VEgiZV|x3|DaY=x3Q(`q zR)*oJCa09g)z;HW6$4-q2v5q>4>hVkb>+5LrUJj7sx@kuNiI_<%E6V|IirZ5aa-P% z0wa2hezxdNm->v=hvl65rJQN)xQ*?iA8l)I7rp(S9L`F`^B7dFS7XQjI+^|0%j=8i zusj3nZdR*<xDNHD;!}MQNxg(%-BAUhc%9?14h0A()3+=s3KukgGB%{34x;l>9aRtn z^7yK*ut)*>!FB5_AyKDb@sorkJUr0i$;yy|8i>Kibu>%}$m{F6A}0kL0DoVX3&A@B zv!ARa;Q>HXCmA2{Qo%MW0uYeUNnVo5mdDOjmV55YIXLBImZ{0LjNe$9-my<=+pb%s zSgmRQn$BhJflQZXvG-jn=q!*yY<F01yCnzdmvv_I?XjFogWt@1zsj|?nXUrwJyXqE zke=TRq2J;z8|V*_2<$a#d4O(kHl%mo*Kx#;EuPT_k<&W>_UgC91C_$71>;SQ^+S4h ze9ML`Q^C3``BK1Pux`HsHgM0^ZnIhqt+d@=O56R1(ht!}N8$Y6l;%Jy4f{)J*ncRU zHx#A@qVyTc=^X-pT^GQPpZm9d=mXpITjGKOaz_{8XrU*G0;I2`bDKuZdIKs^hqBA? zz5wY#X>?DW2E;AGYY`sd(kg$5aW$jlmka^9tSE_r|0!m_V#psIM@hKn7W^N`s1MDt zf+pb!Z@s8Y&tb|#c&xxr!aSOLCE#Ucx?m}BTbb7rA6`%^u>FYFM=`^Vk0eHRvkZ1G zFDT*0r9YDjl~U8B4X57pT$>g97oQcjFPx&(40X=02!a|{UC;=5)gRb6SDA8CQDdfw zEFBIkLU^a%_|=#>A-SyEOAs^3(1tmOfk2(P-Ty@D1E!^jjegU41e<lG4)WNF&k31S zlg<h8t$~X|p3kYLO3BQ5e3B|g6b<C$BASMCw2{WvnwrQd8%+*KMNRQz$eY^Y6e*p# z$>bZy+FTAuNlmUMvUWJ|3u4<Ad576{)MNACL({+K#{GZU-$Pvd-$Rqg-`?IMU{=nV zL4_DF27Nv*=1LWPU4|Qj(I!iV(<Do6h=X6lAH&=`%Gbk6Y8^?WQXl~LK01pDDufJ( zR6r1eFh0L$_W~Ky``VDP4o6J^gZ0So$fb0;a~(dT&dN0`v*rs!$ACHBm{o@J#or94 z&AuVSaOXC!lX{QC{^97MZ&_0T&ptBfm>T+I58J{oLHs%&2e^)2F>EG&Inpo^CpL9F zncE(kjmdy-4-XD|+zxvTf5Ka^G!gWXYd=tbBy=rWA$Hnx;EQBPcWJje@@$hRYt4HS zwO1t`6-(6OaeuKJW&z)3V34NqTswrhtsRm)S^&E<=(bO<ZyVDvxyqTL>cfdHYaDp? z_oBN7bd1HzjK?Cnyo4V|!2kj7vl0CsIS|+?Y?bxE*!7n&nXwig4GzszKRq7r*ONsy z-mkCWqUGu|Xxgid(3Q}VR>(?dYYW3>C?PLC@7ECk4Dhpw`Fmc@0wM2LF*H{l3{7%! zm2;K*gl=ps+?&ie;edwJL(b^WWeQO!QKlQZ5c>dK=|cQ~oAk=pfusr1YK>UBW`)aS z(YJ<qwL`J-?m&;R{FxtTcLhH001QjCju=gkx;5p6bo~JM%JKFChQ*0_`)akqy~hw= z-Q->}sF3c`3q;Wz^sa<9_?(=BHo`nkzUTEf`5KR{FWU3kC3l@}V3Q`VZJfZ<HQR5F z_D1yrMX6={+uQsvJEPXxquSB0!JbvR_!})Px8Ge}q88vMdo8(UcNbph7<>?Txh>(a zcwm6-l=g-DTMc(j;V|8(!LsHBi-U9x68fp^B!1W<?KY#{C7#=<_Mvqwr-PENZIJX# z;+eSh$ov5kQZPJ`!lsj^lvZajij035*hdI)*<<7=twB|xrkB{Pb&w$B(md-N#5%r8 z#UbA6AXTapR4$by#R&<A)+5spFXoJ9jT~J1L8;IPG$9jFUNciQGi{m-)j`rB=jR=2 zW(G{V0_%}na}L(+o&OG!5PH^p7JTK<hgUjt>a*$&eEp`J5Q3|@`B5vr)EnY|f&kAw z=N7NxieEZ2`&;ujUkC2`4bcJyO&#@TKAXN+o+&OXaX=NswY$zQaH|{a_HzFzGIW~u zAMndMR!D2Ll`5$jna`;y>+?ew)QCD1l^IyuTh$|P9q+_9qRReg%JWZ6AvLIhrLI33 zLiLdNkUFF)(sYg$F+Oipqk`^&#_6R$suMvR_IT!utX(WB%b|}Tr3ev3ef^A;ODZ%H z+VBreD=pd$uTl~9HD-SSJ+$tohLESo(wg+D^l8(in-T;YqNqOizo;z3bw!ITsAuXA z)J3u)7AnrB>i=Pxs|JU}W~AEy(BJ@R*Fycx0lH(TIP-bWu&_euXZ^bhrG<J`ljsr$ za+BykoYXoq51Of+W*)rdDXCEM<e9Hf+A(}(61`<uXA(VC|FxNVy#61}ym-s=*<sv^ zM|<Y;|Nk1iKX3DNpajwTp==-S)RG&tr2MnqtNpIkNo=0`nSr*ofz{JbXV)!py&N)D z(7TE*FH{TZf~rB!futkE%Kj4@hr=rat{Ou~P(x6bpsnvL#Ni;bh7$rrySWtFs}C&V zr$PNoT##@nL&!r&C4wAjhc<0NP2=CU^?!Ob*Iea5U<9-d`TuZlnPliIq!7Z^;orcG zf8!mEMpbCZe-A=Je{X#BA3;b=Q2g(Yk48UmE8Xis{aLhn{o{R~4B)}L6*a|f8do=( z&fdqymA}^@Z)|D`3S!<XP3m}__KUX<WeAy=%#X({{Sd%gc2(`QfJ+AVct5G5U0%p9 zWo-CikzE;4z_q(6sciYH&XOBaJ;&bFED%>zMlb%{!o;k%Nq=T9L6m)Vf#r2sog035 z(T^gx8r>NdN&PZz(SnkOQZDMSo*OFxeek2`h@MG(Zf?^&!JEE0eGPT@i4+luu`RVx zUs*eK%_67`U-QTy+`58EOLDU3b%97W_x|aZ<emWXZu6tOCyd-Vb;V&l(YJNAKI3^_ z)VW~;UZ(5%jyGEQaw4k$l9CYxxv-Lf^cS?;qI9pSX6>|C(%I3s48zsY2g_}EnL=Q{ zfBaSoQw#H(V742hBMHSN=$xJM6?oISRj3?>NVl>l6Sh+htLr4%2iYaG48EqTlMBm} z`y`A{w{BCLf$K~7RU-@x;{F0#vLh3orAIf=GRACI74`(54lzK2N#ccs5m7HRi-z}P z!-<4v9}kCAO7nddo}JkRXm0gCVaXg{2lK`i#9ll=*yBqPc-tB88aqd29vfHbYX&OD z6_}aXY8Fg}jCI_%JPz%7c}_ka^EM!xp*Qo@qf<9iGdSt+m+N=V2BkAc;76(^eQrBv zZ{^|dS5&~ElkarDXV*?{*P}d)AEz_G^>;TuxtO-yo}u{et`yZeSFbiUb`Roqzd}uK zuNUB&cX#f_x=Z^qL6=u=rOnWB=X8`NaM<*q?FMO3`fR2~n@FzI+Hl9Pe60Ca3v3Vd zrmaJO8>ipaaPbfs_SH2z<WIfPG;A6CG#v&l|8R4ra$vw^5yZG2m6mFVZ^$#LJ;OOS zYKv?c{3?=t!#$@-WJr6pjj-(x#6=2O%4FZL&&78H+90B8nb@w#XGddhT#*G<%h*?m z)dwSO=?I9qj3DyY94aXQh=BZPdjjE_GcsQmLT)0;tz1F^MrS|OHYP!Fk!jU>wv}uU z5(JNB<%p>|l5W=FhiSHy8WJBNVhOa3Pm;od49|AW6<G0wNC_f;BZ~eVK&=o`4&_6J zL<SB9)0wvAdta|*)kAfE1oj?zUq9aGuB!+#%dM*^`^ngwuFF?1Z1?nwbp>1Mv}A6b zSGrg^a%}#^MTjoYFw<^NysfTo%Fm{~rPW^I%Ah7!$nH$hLGllxs}n>{&W$GB;3I5* z1WI1Ls9_4Z8JY#!%BUe(tC(o7RuPc?HasM&<#Kia-yEtV&<fE~d%y-E`Y)P8tr5d> z4*jOskipr~+L?dr0vu!}x-b4s;rI>^Ekqo`F{f@G9|Qdl(AZ)6r!S29+W^R<YL}6= zAwv>_7PRP6vjszj;bp%}aCv;DKmUP0xgAywqS4!})leHuch*u{Pd~8YsVR%F<ryeb z>NB)5AR0AHF^Ep6@2jECsb{aHW^qWg<^emru;G!PelTeG&t{a;>JQ75KGx$KME`%- zV2_Hy6>^W;WOe()U12HMn_@y|<YpDv9&~#Wjk;KK2{O&y@4LE<Z~uBq6%@0ScE<c8 zC{)~0i5hyi)g$GnFgwr$KY<QA{e}+zI&(g0h$$9y{>D9l%>5)L$#Xpj{k5mFVXt#b zrf;D`i?R+-IKa$_U;!7p0k^6B9P_z+muh-{Iqx(?Mv2Yu;rXiv5*J7X77jK^?>`-Z z+tMv8?N>=1Ot0}CXpL-h{pe+fBpN~e0=OiNsU?Ytt!40oWHbv9u2P_{eIJ0YkPjL! z_s`fRvsj<oY`Mx%1ns((H!CdH(|SAcQS25A<?4Eh=j4h?z1t@>+Nw%reEzSZC?TeT zokQPXCdK6^i}C%-l8fF<p5p#9xXz3XWeT=SrBAm<laHA%msSJKZ>Lw=uJXF}Tc%x- zCu*N=kF@F~zowRqNuKB`JoVEa@*Z|hemz&1A=LOrTUbLaKKZqUc3BSPiOJ+bp`9ql z&QN_OW%$!-aSrN7Jv&eTFUH<6xU#P68jhWg?T&4m9ox2T+g8W6ZM$Qm&xvgtoqT=Y z*Y!N_pSS9J|Li)ot4`Idg*nC?bL_R0w%L2-;F_d@Sbwlnqs|tNNi8r@Yb(I{t~q9- zo2GzSFmN6vL`*u+kCh>ZgFiY(I;3j$jc4Dth&!Dq$4SE%2XjrMN<cbgJJr50W?(h> z|KA~#?f(rjnVHzR{*R`}!o>7X`|AJyT*lhm^>|Zm_q^+O>OEyUA<Q{l2nf({NCTW; zqxV^42*O$@KGq>wotyo4oeeea%$W)TI3qX}{v@qI&5iSyuY>QyxLz3%?7JwTU;AcF z3CV=B2S1#U91cnDZYBgn+fCn*?;|<*oxRDh2m$=cG=k(_2RTI4d?UAb_f&c9r9UQa zQ3&#B{R8^k?qGI}aupH+=_u3Y{52U5cfAa5b}6@vO&pN~HYFyeL%CtU#@|_3n|o3R z#0cBO-gop$Jq3W02fYaM>3o4PPW=aHs6^F_UdSP0eo;LY$u-nRyKZ@J$q6xQls6Yi zNL!5j38;(yIG!Cc+EEGUGmkp1N_&s%ALE1AKh@`>LeGccyp3vFtBfYbuG6W2cLi^Y z{L&k&&2J84C!#v7Z~-QO`r@j_asOK5-nsYIPtN0ql)fW_+-9e*JSB!v`sF*T&n(UW zPl7*~)l~<8cHOD|aKpdP3Sy(F6$Mchow_Vy^Y%kvO<i)EZceC%`BZD{B!z9~8#?!R z+IdaZoL#4V_Dxp8e!p_vYsExN|Iz+S%l9?koVVicqy1&l<jBd<K>IHV11$YtC0V;# z%>A85`}Fn0>_jD8gl1EZpSwMO{{mj`0(9orN6!H`JIP@sZ#yrv#ZWkO5_U2J>C*$; z8b|1{(#O^&(_$jJ$o!|&93<>??1k)S-KWgd#e_DT!JWy|=&>wZMmy-SkcQkA(_~;e zmD@(?fj46g?JX!+=GHn4`A14OX?W~`DnRF3h3n;o2e%zJ1RVyYJ-sCQ^zs{l-}Id3 z`ZB5cpHB_}Z`oh3Q}tgK0?Xyo`~6=JoL{Gf3>^la?Qg$c-wiy#7V^KYuKRifKVSb` zO}*d7p8pb@4Onq)4tR-p{qkSIclz^S;QzXx{}6KccH6%?C-~=B@WVjhu>R5k5_k<3 z<D2v>H<IpwR=vHA@6X4bG?()JltGljYCvIeMG?^*fMwAa`A)Grm3=6>lx%-wE--W1 zjagrb@oZ(j9pEXz{Mzu>A+p$>@bz|tglO@4JJR&d)_9HELqV~-G}8BV<7@mnEc99( z)aUoH#u-q-nN6fX7dD5+nopUwR37E`wfj1<7~!_4ab7~Hlqj&AZEsBMA0PBV4zYL) zBiRm`C{TmeuT3d%`}I<|<+=a0+x%6|c$F{U6VT=M`C^p&vcj_)bsvHB7>;+0l%Ff; z@AUZsc-^o4`|3Qjeic?BN6@!oZJVqA>*8ZK=00L>mdHMLJ3#YSKx=%!-p8kC@8{U- zro}OmLC$u7yMMs>$JH>;73Zqg-p7?_?^Wmhb>|D?=as;FclV>mvk~(93UPGIQ2CGc ze7il{&+pgGN*m9(&vFI#{nX4v=8Xn3#`zheZ-Q(6>!*GkvG2y%?*OK!Ri*%WX#;{+ zse=I7^B>J!RhwANzHO68v3E$19`_0fUym9AUlE^cU;ArszYGG#;u!Y@KC8Z5{-hfm z6MYQ_w7ji<Jhs258wBk8n~N9(9KNc(zE$6_9&I3fBurnXZ~wVFcc8dA&Hd}o@p=;c zxbg^i`6D<X_$50VwH@a7bttHIqlU<kz&Dh$wMxg(rj!=D;tY3w{3E_GXBbY*=;-Pk zzxqLYslj}POFFx6rDFJk8)1@Nmyvyhqgl@eY*bsSIG$mtq-J=CTZ+<<k5!^_0m1xt zNF|iyxwE4aS$o8*Ne1WYbdrmLR#zs+w{SNH^Oyl$QlE_1T4O=0i&~`j#xopU=Y3e` z%sTEh?aR#mKKgcBysfLuk$cdwGmh?+AE5$bL{Pxo(pbaI6DL6r=U)v2k!(fq$z>jH zG>P^8>Va-Qv)Y{Mra#;?qpkVqSkrHL>bJs8kF8@RH&c47uhxuaga|BXn!V7basUAR zZbQrTDJGxaDN;``YSz`~_iT+^5@}lMS2HnM`Vp@$qWd2@u5W1_y!T;^M@$4Fqk-0C zY=l_AT=g8k7P|<~EF_D#mBN@*f|N^gRCK%2ma-Dfskxi$>W=^dOdFlPghU!7vM9r8 zw-V$RDoQWg`&_uVT*<0UHY-3pDj#Nqrb4#eb*Ft;my0IL1nS@nwhB(Jjzp3s;riN& z?t+nVK0<Z~Ctdgh@-U58nEe<Fq`@oZMCV4vb*ua~s)t42festFNgRsvEorI}lVm8- ztk~Vw5$|OpSg6;ng*j0qd6V3f(<7=ZZf%%d1S{d)G`ZIxWHAiUh9@mr{)n+&v0a${ z`0*5zQ)e}Vfp2~_YS-}ZBbCI3n4evgUO-_gRynd&ZZq<TSF~$R%n*0deK>8GZ`n$b z9vemMd&JWxA47O}Qe`-RxufgpXYF!_sBTt+(>-1&4>NXpW@Fj=DYz`HzO)vC_hs3i zn#xfuPCw@*Z0#8mP|^w7@VYN|7T1TXJlthvn(){oltlH&jx(XXM#dJ8)i>XlNNjwH z(x$h1bpRdeSlGrWq#*~_&nDjYpT`o`zPinCVi{_>)X%#zXY}-^CKs<fuO7bkF`KJQ zA?R>Uup=^dg&3K$S(xry{f>W-bWd9KzMAek?;F$ew{q*)F$xd3@TBXel14_O5SP5W zosy@nZ5lNk;2lW(ZJcrgYUo!k!XFo54{F7~u3t6|{piS5KqV?d+Ocq&<3``ngximG zw!SuuO6r1-Q>sKE?pBVJbI38ZX4?9Webh6}({gEz3bgDJPn+RYN;0%;Vr+Olcyhbh zbBajm#qs3q_Nr_)Q-qu1DlceU7K(^oej5zbIm{f-{t}`{5#iJ!z6g)hF`Lej5Qe60 zyA;`FlWO-Xvazv&&eWJW3lmu$M=3jORjSFU0tdyEuGUNTPP_`nKs&~#2Ax#zD|k9> z&@=uXFKfGElK&emGbEU80F8RRnkh#MP4*g=`?~gpSf4}<GMxRF=}Z@~1>a@|Ql{RM zL=d(9;@xyJZo5d@cPE+dRY!lr?KK`hnT_06D5}+rmG6o`6i{OMs%8S%XLc`rudnIi zKso3Po$wMH5@c1GfgBrT7?4VU8-MO$Fgi?AtrvnT4|SeshL;vP(VA04Z6?~V0&B|5 z7U`;SInJPe9f;c~#5;ZN@1?U8$^z%&NYzTAn+QujKH8*s6%H(SKF}+4Wt$o5Fnx2V zTCj8>E5jAKiEPB03q4rR+NJi9%}j@<E}_`aHw4HBW*rMzD~SI4d+A7p0j`G0_E-<$ zXk2%)q>K(*gH>2r<Kw@>&!Gf8K|E^6J#OS&81h}oK9FX;ZGX@Y;_`a!Z~4kA?$Q5B zuFE^%$NDmW2%BiQk02{oGmeiEI$%*M7;*56sc0@FTP}oIVHo10!Kqb*g$j{lq`}uF zXARd!W&>^C7r}iJLx<MR(C33hRx~~=vMmTttdtLslTeWa!pH$4MPC59u#kM40i(q6 zhtND9f%d0j5d-S`Y~p=PP;F!*m%+Li=j+lp{k@iW1R$QRr_i7Mk|M2v{9N&ALiKo~ z!FqB&ybCsVWd@|Z3BKP;1A4X_DSV}nmf#r!t0kH<#m-y(xKt!Y;5O~Ad8vJz|D-K( zkTFO4wgddqdDw&%GaN}pXT`!=oB%#!5fu9;NWE6KKq}+LZ;)Q3W}~hA%OftDjI?Gf zsbQ*InrT>f9VF1HY2!bAGzG$iH-~UT9akr$*{zHfnJcX`b&QbUe=*&n<j0f3D(NOK zXSy`P{-81}tUHnspEauR$F$7fMKhFWwsFH2;&<&a-a3-uJo5Qx;_A^YEU-N-=%Yu1 zTzap4!2$I4He-426#^ahDOQe(dPw)Q!dE=~i^&d*yg6Bw#uW2O3&{h%PD~oE>xQ72 zzHKI(dBRi6R9RzXc{&b8nieY3#y_r0j=9?iW>1Qxxi*3)F)`UXhdFp^w!jJ%tsQiL zr&%R$P!$CiV38XzN?qke6zN%WQVi9{c=x@lr#gFA(`%Qwm=BAfh?c>=@UD&&2y)}C z#{_=mCJ7*tv}x!_O27ppCgBJ0F<56=9o8d!^`XGZF3?cun+S0PdOeKMVAavSh}=`# z7Ta(J`-8>`cz$v;A!;x><1;*d@&F$AL-~oblW9a~Jb_p#qsbCl5RonSn{pfZWWA(C zQ5bXJnJ+xtz1=L}r&8U4mqp*d`%b+;bBvHa?P@p`K>WRVMt&UYx*q5OG-7As*Xrut zDi*>?S#z7)h`uGga7~-Uk+3AJ1)shjnRhJ22D1XYk;Q)nw2Sm3;yoG!ye@I--uV@t zzh4KEho_dX!`!LbA*l&3kO{lPzpxD?ztD^I#RqS!a^<cHq)00)$cic|2Czt*s-|`~ zJ!$J*OY$Pzd)2Ip*2kz(0HvyQLW|9lGqS8wedgo&^X5jCX*U|QRb_4=Q;0i$e=~GL ziGZ|xaaoQ9Ztc-v_e0;PpO^;kinzva%vLDN!*_@q;#r18Wh~J#ccu%7WJc-ksjhmM z-dd?fBAN$D<Eo*hsb|$N6$v{=3sh|O-A~LF<4XQ^LlP$hq`03ivNzak(*Z<H97~4n zuPyHhj6BR^1m?N|&sX9Db!79UN=GN0WhkuT?z{vDBQ4uDEW-X|^+mcC)XT{P&!~Hl zI!>wl+%s;)wj)bUk?DPIsPOAM{#kVuJc<<m#|wRaJ6+ube2D9}OuSsD9Ly**V$i`J z_pq@i?zYX4c1bDQ%9+!3h}wpZ*-w}7(aC{`H0VFA^VYX6*9#?4Jfa(8@|@;Al`|fp zo0)M{lGyi^@O3?s-Ks(l!pR}8PX!B@vzF%ry2vmzn!<)trR_kCOX9Y8cehmDeW+Mt z5O9zQ?sU~W2;83$qhER}YUDNURnCd)UR0dtC#fA0gqLW?WZAJbGMWe7OSTP5)MnGL zF4$rl1>sx|%k)SZ>_7pI6@i4TWvQO%tQ5M#dhYb@+oflLI84BaNe}b7j9nk;#jI_L z@{->rnzZHy7$x|gXtVu5Loy8{m@nVfkhNW0MU@sHAxBtZUf0}C+I`)27k@?iyI!KA zS4$2o3zL}EQq*a-WKyC6cn!N3l}0l|3jGU$B;?!5E`ipneC-vsnVpgzdYD<!yJ`c~ zru%m|7)>*STNC)lB`Pe?R$09ojZG{tyas74$TMtmHl<0umfqzf-XZ&GbERe!0TGQz znh%M=5iqTUUj2?{FTQCBU(1j(r@%4H+AGQy@me8f`kA_@DQ%zl$;9$+c6oqemq~l$ z<dIS;8^GxmTU#j~4waluD%B61>>G7D_6f!pq3xy*?kewggwL=A^BDO~@o#O}1$be0 zcso&a!Fi_UKD)0lNFRzlSC_mBN$l(5cL_63+S%7I-K;uf)!~`i?Mv?hZnv>wi)odP z{cNh#7KedFNg)Vf{_$DeARw-#tEDTnn#EV9&bYk$K7^mld>CaNJP`+6-pQTDKon$W z9tl__TX7E|x8Cg}4_V@l>`~sh?Z+bs7WGhT-W&6A;9XnWGOmC*9&%1->;2%XZc)SJ z018+mkK1Y2jcXwM+6<&=Uv2r<fGuO|YkUK5^F-jT@KM7H%)CeiT9+m6nP!2*#lyj^ zd3>V^H##O)pyWA<sT699;!X>*krzwVRMl@hieH9IvT&xToOt6BSeKD)Dwwh8Y?*7a ztp)LW(8$U*-(Rb!u}a>$T$VxbLxC(X$;ROck+IB$B2=o4_D!E`90L_^6kE90zDV&_ z!sG}^058dYy@T2RiAXJv(u^pCm6&f4?h)-JY`P*&7Owu@3PhKbkyA{zv<@oMMXV)7 z2IS<jEMZSxjbkTbr8EVH$#rqlaKB=*;jSe*nVLHYp${05pq}1Zp)n=`_g>INulK>Y zF20dT1|7v_*@ZI?jg@X<8}S9NPo=SOz$z7Q<+cP?S6(fr{uW$P@|#7i@KBE90uj`+ z_P?9Yj*90dB}g?ILvo-L73FQiFubk!l5PDCQLlc}wDbq}8BEvj!0l{ZS4tXyXO<o0 zi8}=rM1A0dPb@jRtL2mRWEt~-7D^PYT|tVFXR^5lN&Qh0;sFj-z|2izDg27R+$L;v zaU{pNo1PbQxFS_oE1HYcafJZSbg1l*!4lO_WtlxT4AZnfIGc+}TRPD9$L}}*z8ch? z%wAHXkU;56tFslcqAS_il(9nTfH;Ws;=1<y8aph`W^|cz;G7N+{YBDaw$-+XlpjbY zR{U#bK)zr+wdkY@6`wh$cn8sah3CZ->wf+QLY@v;9){Ebe4N`FERYWYQV{CporPu| z`b5I21i|J}PQkpxa4-#5oGitxca44kftdbV0&X_xmQeEAf1=6-@Xf7sdp1__HXD`$ z-I*SJwbWg)LIejOZ`v|TB64a5WQ54k;tfhDmp~)VrtU^;oyIuKYe~S<7pv$)x3n2R z#07J3K_tCmrBUfq>*Y4B1HUP9M0P8t-J4?P8cqI4c15)**hwB?|M62Rx=y%eb6$hN z+-eSI2qxqjF;>NA!7K)-ry(Y7ZD*B^;4-|fZ}Z=jK1}4TNF_P?go1e<7{yY{S%Nch zX0WRoZEw8$Ht=IHZ7JBA1c({mBnynu86>D&S>bR?_xH4joI{wwgX@t-6f;o#cx?p# zv{D5}>Bj7Nk&M1TtM&LCj|H@LoVp7X*Cr854bQ&=btHjjpqY@{%5n@I(}%uwjUX~y zW^&kE`<iO&6!$cUZuTA@ZJZzA&HqhPSJUBhlOm8)fq@Wt3pmW|is>`64)uI!Yto9} z?$jKOj$jQW{M|`|wuO+*e_4K9QaMQeNj*_YX9RONw|?BhJ}_J|5=}1N^30|^!Jd_S zni*U^^Wc#Oicu@K#Am6b)fMfCn(a_=_1LLpF`QALYO<$;{-tlc@}#XT64=8dFerJ1 z`dYZZJ(db>W=^30MVgEm-T}N+s$cpbo-db*_-Km|)V%5L5cm@#5%N4bJoV;koc^io zjyCyX8of`z&B|0uW_OHh_(XoN&j^_VKbqT-<5h;2U3@jv)|$P^x=2Fml|L@^*>s5O zdNLCVrijX(_-#0L+=wbzXhEGIsPoCPZogb=S4@7ExXth46+nh*#qrIDf|P&1XkEQA zY3^P9o6xVO(|E4k&rqzCL0Q~Hk%$f?sp+#pB)L)3=P(<PE;Ty`C8OD-(WV!*%xGLR zMqEK~7IUl|H>qe*yq42e!iDyHLCh{%KaAs-&*0f85Tmoubf$EfVyh4rMt)xabs;Qy zX38wF4y<%ZnJIi}J*f92Z1fc(9khNBJkC4C$S6TqmU=se#wPFQj7C1L`A7CkCD;Fx zKU;N;n!DOSDQV0DwRDEaEiQ~1_bwE`0|Bi_7;}noCBZx<@xv)24|H?-AzX+|sY{YN zR+ktA#pi;h^dnO=-8&I3fUJ)M9z#G^PKT!fhf)1>AiHckFUc>JRadE9vJ)33`bk4J zajR$!=+U<Glg^IAg{G%5y34C}kPU$tk&HH>9xHtrKTfH;R*r2Hcat{5HT&JuC}W|q zXuI!K;2PjCdqB{JAH7D)$tMN1(|_+naJ!UT^CWN?#pG=zL_zNP3tfEky+H|JM^a{z z5s<U$?KH*wKOkwWZhP^{3ASy{iu4BAH}7UI#|5w;L|miDGJD+XCZbF6_=P}prKPu4 z_1nH3SD2H?8#+gIt$zz-7Wa6q*!?YFAL?t;_HS1Be$7&Oq>GtKItpu5*F_3%e%@x^ zOb{6pDo0^1QPyVZT4^PX8JWm(Rih^TmrX0xy`!t#%2fx}?ZqlF2`kUGx95oZvqa-^ zJaB;gJ$#Ts2X0}S8me!>^w&uy(%;r7hoSH+eBNattpG=~Wr#>-uJ}i%Q!!q<5H~V` z63fQ}I_M>5(*d#!*xIo(r|bKFN6LbOCe=P4jV$s+m6BIa3ne^y_^LMAG5Ag~j>7B5 z<$$>(C+p)u6uar2W$^aMD;tN`pa!VF<y1Cdi48U)70<)X>c-D~T~v5_#txDWf`(Jp zr4>ZZW4#k#VySICpHq@V7_pxZc0-;C!WNipWMAj_jXzqp=PYuM6hJTUIh9)%7RXw1 zj-~H0b5w@-f1+Zcj&zi+fRu#8or^{xi2}ap+^Zjg)`JH^_y$U=N4c*A$zWZ|gTb|C z)|Z8{ww|dAb8u7_V$P{OAV*ze*hBv8W7<toD*40gf_x4_wwfk3k+n6WWyYzi<S?r= zJV-ZFf{eO{8Uxn;-LXGWR?eTXB)8J7<r_oz2PX{EvPp#?c_8sd$3>iOBd5&7zpFeB z$2M@%603bN?$jG1zt)iIEi2B1s~v5)q(mw<obEzW^5(c8j@R(7-Nc(b$@A^*0!)2z z38UotNS4A&Ds274*rC;D@HF;9JgqLq!zMzO%<8THo=@|^(B3+`J=a{vQ*|I$#%>ne zC;X~2P90=}_9B|f0vZlUHEI?@)xJwgmFI9`h=Yc;&pE-#qxG`%pQWy0Qr&3iiu`wX zK)_XKec#ksa|6&_P9KSQKfgAv%-3ZY7P+Sg4f0&8(j2yaEnLtqE$Qj|(_!KyHcR>{ zGdg{jYQ^%5n4TBip2{Q1Bg#hL)3A#ADUKOOJ){UX;p*1zgEAuEB@ulds}4wLWIo$P z;Ae@?GNjBliR9;!XkiLq>T45HcAL-?*Km|g$SSv9k2<3$_yU9SvEcBiD_-}2$7@@p z?-HE~G*U1WLbC?G!z$$EXC+Qh%uCahnw6~0-T_*g8K0ZZ&r_6~k|NR)^h{PUX<R*8 zH5EH_^_W)qaatE!w1N$ZIZ3Lmg1lvtk*Tt698Pk!Kxi^)g<y+FVTuVuAfVnegAW>> z4`%@2LWT23<57N0-_X%IWNU4O(lnbmILLg28;E{C{&&zU+H_kQe{}O#B18uk=lW%B z%Dc2)zc%MXz6r5CEQZhxV8yCswN)y<{g`m$l*p;3Y<!AZtg>02RD-BHg)6W=HPex2 z2=$WS{=BG)DNeFHulY$t$AJLMUgpTB-4eiI*HDGpq_VZFwZ<~NDR3yOjxZ`DEpL1z zdzsvVn)HvcG!;TyWEyr2b;!fDPir>#2cPj4L?Dh9DW))g$_`i5%3%a5I00#ceu=2! z7g$>+ci>RJ%G}ugAjBs2>#?aX6R6bp2{7e`og^&9AZ9XkKD%Ant+P*}WQHpk@QIL; z2I`T|rw|4br2W7v0-?<34ReBQNJ&j@sn%4mSN=FFf>K;j+S9M(&bP7R&E9e8x<_kq zft^N8j{PZI?$gP<U9;TtAJDO%E-Rl+URyf1q2di6mYp}g`qswdnjQngm6|L&Xv|)# zn$CeK@(g>qOyVw<dcoq(AWO;5eFS%etH+kT+-so|Q=B90^IYK>Z@rgJC=t}3_}N_6 z2eLRPwwr|o%WbA*@;D+0Wl%!D=;2y-ei+=$u4~Jf8{vYUv53ZOBjnUoSCxDwQOpu^ z0lvcYJDcqFpF$$rO@A)rsb;;<kN(_l(Z+NdLNK)V!e<Xg0<pl%VfZB+|Jb@Yv9qC4 zc;g+`0=zn}^K=Pnonk~nbTCcx)*r3|&rc)1d6a|u(?YnhIOQz@o!=F5`x)qI<{Fh5 zAYeuvmRDk1H1(^dd-7XVeS}r=CiE6DNjV^xjocf(62k0`#6wBfcJLI+zei~$7oczb zPtklcm2(LL+%lEo0}~BtL~XC|Z$IZ_*0KG@d7D}}O*AxHZc2)S_LMiKPbaYUqGJ43 zz5BvNJ~n39>(Og(#`Q9^kvJlVBfe-*YF2L(XZpuTEGmrD_<4xUoc5Ti2L9AA*c&#^ zo#=1FFSZqIb>phTi-(5djA6VgW$Jw%-t28Yn+^ZtSo-sSfY72Xrv!BxKo>%SP{Aah z-mDY6lRG0SFjFR%PU>MTkbz|nEvM6Us#oo{_n#@MnpFjD<mEDjG{dpYaBRwfp4K>z z<74L7;({hGnn4|4o=@9#H^F~&y85Qz)232Fvsrd@OV84=Fgr^4cmn6iSJ#SjoN`eA ztIMdZ6Z9S!ytLzwetV>jZKc;u%b9raFXTAlI)+m&ns|az3D8Rxo}vD*>AsbaSBw`p z`rFhB_6!w15HF(W$W+%{y&B!KC<Y-kD>WPNph|h0GVJ|L86x3f9d|5&QT)Bl8p;v% zIZU_nhJ+Mhp{}Ioeo$*Y(yW)z5Ol;Q#7?%JzLr>P-w%Lz`6?xDD$%tX&r>N8f*;d> zP)g$syEOa#)qd{!pP1SN(6@p{>}Y^f*iFn+W5R#|@G*H0i;dXjTIvkzGiHunEDEFW zg<kj6OO6*$_k_WA&&X3uPo{#FV1X3za$+x$)xXqWI<2;?hpq!rdf^-&*EMx62!mV3 zYdy(td@_+w7(GvZcF_d1=!d3;f;5k*9hl;*()=ZtTfjOd%Mbe8n^5Ae)f63#<AE9J z8Jqv83S+i7o*1L4g~#UE!^dkUOnLTr4K~-_$M=rmgoNqn)Cw!gufpqDLsble9*&bh zSKi!WQwAq$mHDg#b>RfPoV8j9mEo%sp6&)WM7%D#BIsCcRw>3)XAp)*PzO#+9!|aH zwuw|F37WwN)owzG*&wYr?PsfYQ+eP(1qLt&T>09WRYgd|yCEByAoRK}lCvB6UnFF1 zJFPsz*eOmWM<S{{!3gGQuIA0mk&bGR=D&irge*XkFs+8hd)&|i{Grp@<BpC>TF7>n zu*qi$&{+hRky7y2t36eaP-`}4k{@^gbwB$tDTECNHch90yfuqcCWH!Ig`-$bIW1I| zs$QjA3zE|pG~Gy?*jzv5`u76UMHVSFfR#K5<K6J8MCYncfZ;#IU@pK=xesu)P|koq z*+dOpQ_voi(B=f}9LqNvcQI`HO*}pYE-H~NT+g*M?aKZq7wY%SLEiWzx)A?dr3dv3 z5G-%I9dr_{S?M5X@hk;|A?5KR2&Ff?c4+KOKZCy-{gIK1U)Zep0XA>x-9NZ4HSW6H zU%q0rqReLAQa9Z}mn`?(q|T2~sz2+~9+UpxoL=oe1{Fg5tE(|k0D0s$os%m1-DL+i z?JswXz|bop?6A}^5X)kFW}Ex-zp4qoS`i^Q6w;mo*y`?Pan#cWuqQ#Uv{{S9Mn;}M zODXn5DRH5i;W220h1=c1A=ic$X8_KY{7r*S`B4C@w|#EN!A8%X5tzGa;(auOdn}4y ztlS~xLF~#pr~qeLN9LvSKb4?PooBoB1X%~<Hh9R|d^h;f&2Qe#+}esJEVD|~)Px|^ z7Q2z8?nhem)xY9fd82rg$Xc6}pg5oKQL+98(uVOxIPB|zopD&I5iy611LCCWe9wbC zXz$K=r=Rz(?iacOj@>~G2@s-k%GWz~!*W=n-R+t&kD=%p#@G(tKIll;NzvF*mRBN* zI=wcoo9tEjKjIKGUJsuFzh%W56Jpg;i*d`nCSyXa1`Bs}su&iQ+c>gKgTCP_L~29{ zZ3?iV?FRv5{&+fQd^>PaWD(oc$&yzEX(y(4Cv|pMJJ=_Y<-uQSn@Ul0Q!!^`y$lnu zUVdCweWF*NxrZk!i?XJzbY1+&d=^%?Mm^y2DmT#n9yx2D0!gv9Cs${$>L1<RJGn_R z@h@+0$_tTBO>5F#l&QoQ>hsj<I&P+R6yW5N<ZeK=YsxkIc2kfy?4(#(LqLD4Jc(ns zlEFqd;G1k{0ptD0Vs(aVK}VOfgDYW=)p}G<;C%EO{D}%)OZba^{T9xbDLRBqeKbs0 z8Q@Vp6Yi#QIM`}>%V_R!0%4H$1>=y%GRA_U8hYRb+k14c3+Uy5OZsmyA2LZBujpLI zr~e)`VC8*y2BWcV!`)p2G2TU2wOSj{{yeaNEZ@cmsCIFwWZe{A>dM=JYJ4XvTd}rY zkw@FB)T`o~BZ=Hns5vHfJ8bg$V^3J0i$bh%{`B+v?*rGGE%5~Y_l7L}u4ogw<_IOh ztj@G#g=Rz|-;2abW8DVqo(#S?FevAky*cc|{}rv`YUrVto--eWYOZctVTa|sDVO8% z_UF(c>P*yy`$41<@G-0S#L{#tJzVuXNOE4#5&>mxq8IW{5}6bZuV%7KV+7sR%TZ)z zr+%UwC3PhxvS>OS=nyz+`A^oJg0XrnL7a-NaxpX5vZ<mD^OIUkp8}D(vydmoRHCIq z&AxJHA0?(HaF9Q!_w9pPJmOIPo2~Gg2MN)b1_9q|TZQ)~Sss2{%1LCmw+9eF8LHCP zqN8@~`+4WhP+&cT)AHLjc|6ad)sDt<5k!h-7rQwaJQs}D#woJ8>&glIFvTKTT3q=! zX~bq<7Bwcvg%<})zk)n@F-2z^hv2f%1b!2I<biiiW-mSyZj`&6JBFJ!P;iTfoi9hl zgkoG#M53Ls`Ezeh{rWEqUSdBO-ZAYj4^ygS=M9LI#wR~dit}km?TE407KGVlRA_WE zh(~!JN2#7agVJ!TO@!`%q)E#`t$_!UhgQwZ_6mD)*l}Skx{_e?Z9c#yAQQ0bpxzJr z71!BasfV)?ffRM;Rjj$kO9_PAE2y--`<wH}H@%+V*hS%kKungN^UDcWbkRc%fd$~3 zIM9#c{SUX&u{K>5&|vwgTeEKI{Zp_N4^`x8ec~XB2D+}MyA89azo#8zLz@Yg%kX(o zvG1E=9Vb-Ev1lwP<Gx=*7`AokhAYkL)sTQx*A_ph8ABklCasVwx?`GmL|!H18pmlS znG29V$QwoYQuG?&id(<3YBg3@{K;3T<BYPC5O<OniaV$wejT(Fvzx4&YwaQVPfc&p z))R>%;O7okh?g0xXC5>~QQp4sS13}`YD!J*&iiZx!t#Asl2Z2ec(pj%rDRbS3%#T1 z7kTgkz7attlo{c2;Ow69`hSl(FbYa!m<Xj-=IYrZ`B{}M6xU=mj02cNrOxE{q;8{g z<}swoI*YhVZEPMt)ojI@K;_+v|5a}`zT2e==^Xy;x;y!9ChOq85It*Kd$wpS?@d)d zI3{7Mr{Hno;dFu7n4v(X)fFC@4eKiOP200cpVc(m-)1NIykidsbl8-C1|0*;+|HEg zAn_+DU&A-RI={kqpOZhO-tdsF;4KJU?kMi)j}^DpYw<g1TCLsIt}0d!gXQP!;9b@w zYwK#4XNnR&@r%tDWE%WNCGAt}ay}?!NX3liS8h4ko0tD)Epts##>o=xQ-3l~-Hm}W zZ}zYfM6^85!)b3bmQun3{%qB}vg1<7k+#C)zaLXz<xHwlVRwa?$5Zz`6lu)7@{zUZ zKR?QzhQf0F^+`mBx!SnsTMd?n=SQzxQvgi&9c!#n1$eVh#Tj3ed&r8iU73ozo}|n8 zJ=&`?iJdPUB%Zy_%J?Vb`b|XIt$+2Iie6d&(<>RXReUA^;5A`5E<^KbC)wYO*R@An z3M{w`Rssty$C9{U)z@%^AGwc{(H-9HE*$L#RV^gS%Tn$#()6LSjOz=rNWH5LiUy#; zmzIu3k$R!Dud60S)33Xp2C~pE`?5&$ew4my=4Naa;0F%_$<LIPJ-U!^o{T-XvDy{g zDhg4H;!sbbg=CQxSk|hk-db0^|5u<<1}j?eE1jR8O3%IWE38<JP2WV%nRQuJbJ!9w zTRK}QR5iLwcr--ROGB`_ZqK#z?#h@$@7=nmQL0CPMwK^4yeU9@_d(nf@=%jqV?<a9 zN&jGalpuMy7M|d^5|}WZ1OKVkZw;OPJY3c9aU)~n;{gwJCs1=z*l6saP*G`wY_g{G zwkJyh)d{`Ov-+s(ef*c4HpRLvdz#&PZ;M1uoV1F-z}}S1IL!VEDetUIXGJKRz{B)S zlP=v>R{13WjW@?jziYKaR$lwY(t<QnnF1)?rf!J-%R&ha>U>BjQUFyf_DjV2qTHFR z-pbCu;=I1g^oz(c0w^)q7TWr-O|bNw^67Q$x)mgZu`U)xa|FI^I_bZtASjO;$rI3G z24LAS{-gRKN)>7e#X2FwHwkvgJosz%g85&vPu$ZiM$d_4KE6*#dYds-7OVwA<l{ws z0I#@<?Rb!+hP@%-&OFC5DiVaSix;}F3g+(j-3DpceB|MW^@GOQyb(&h>MaPKg%e#? z&@mJdHiL=VI6^q~zA4*6>KA)9J8=J<$0~mVp$t*p@ibLzP1b09?ZtalFTu6V%KZPX z{W!pbzRIRHaf;{V3TcvJk;n;1(bgH{A(G=ltp2dTgK}+QtR<KZ=(mpB6VxNOt-YH= z^G9@1TXfFeI2;MsRLV?+^5^+06OC6@@)Om5(LgayDT0QaO3I-u*Fb9jW~*VZJS4hW zgM1O{p~`3s-wCbY>_G7%fQ8DOTMlM&o|UP!cYVu3wgE+Aelnyt)xPyr_vwcBKTVW4 zPaGviG)P14-DYY*(i0SiUSn5-@1D+;Wv}5I;gqL(A;kGbz15=i!gmW7WM0NYm`jW2 z^I<G1lK9f;QUo{D68fhMIlt1g3B^6gq%ZUJ-jg@l9PZ~?K{hX*g725PiyxSjv~jKA zfZ?m(zGEGv1p{DTYXC2W{&Q==3E^S=riZ?H+hNHTm)WF~|68~gW3SlWm{(I)!)8Dh zP!6ADC9jtsUUbUAeXNq6@4#K+X8XD7fi1hm>^ut0@Sm}@SrSDl9c*<i92&OIZNKb> z*j&=Qlmo;Rd~j*QYwB~!h+B6aX{t^h&A;S==6n@{{a<15!Ckwn%r%akFVNZQIcqLv zR#<_CWb&B-_sbG&T%wjyC9-K1tCwoY-S1idvS;unQUCOp!rVXP44XTyEIm&#zp9~f zq$`E7js}0AT4;G&xIfD|2-a-1S2KR~ARtnugKb?u>a6p9v?J#Yp1HS&53g)^WYxas zJU=&$ia$X|TK^(_pgq@Mi-%9nscbdb;(nx&oiC&76;f*H)vC|xYx9}z1fOrI+{7bi z6V5cg4wZ9|;?$gMSz}JhR{Nj!jzqS6zqaB#n+Qaf_;1yDc%-N&|4mK*EV=$Z^V4*d z1Eq;|OH;^2MN|`)$nO2yo}&i2bu%jmr&S-Oa)PkfQUiWTdTf*TJHYgkc|?f&I<|4( zE%I9LF|r<X<`oTwLf1@%JgCG}k%2yBw`(D8AOk~U)%Nk;-1-o3@l$}SP)%F<^1)Pn zb3f2BZGnS~ne%@k5|T#uU`2u+p)`%{F*_v?)~cwyA%P43G#<S?LOH5&*Xd#_M8*kJ z|220e>nd>V3codQoBD@cx@;i09hveOVoy4NGo1%<o*qN#nsXthM2HBn4?~I)IjV0@ ze}c`zC&*upAp>?^PCBluX@%-bJQD*lfM`d-Vm)*S(+(N}#i#7F%Mhkl4h3CI{kKlj zXI<OBt?1QUnZ40g%N5MhvPug^+h5hIEbq$iE=V=qsNfY+2`lTZc$W_u?~-IJy^;=$ z%Xwo@qS;ws5DpZZOOUKJg&MnxROHvuo^_KRf~Anju$fM!3k159b(0Sz>!<F;XI@Z3 z{o~xQ!?H|cC+#wbf3$`4Hbc8R{CE!mlk>vRVpP_DE7YojV7gwMC3?FIz<P-XrTxE5 z8XgU@OI7^(D7#WpJ6fuD3BF2WtD3Bwkv4l3k3MG0v$312S)cRt*-YwCIXb7fY0I~8 z`w=E_JGS(KG029!`}CQgjxrT`gg5_DS_uv^u;IdiYe@xEK%P_se%>ljtgpy9SvCdh zkM&SbMR_<JppuBUb@KGP=h8S7eLJ@rT;d>h4#f!ad0*X3Xg2V_jq-K#_pjdEG2H)~ zwVs*%|M3V#W@b*7|6{FZ=KS}g=>HdM{X{&SjC0=eAM{pL2eEwUz#R!4VR$>pqFqt| zGIWqF%KZ8{>r@pF1`bXpC7x+Y`ij%i(5Br-K>m<6-c-bE!z#r+itkGQ#g7T`FK43F z^_qY;q->K#!QluO_LKbEVYBPUxraf8+|Nuw-zN1hI-)_bd+66@|4_x2Fj<`yD>Q(= zSbhs^s0lMr?1^Y1tRf&hA=Mu7_$8@!Vb%F<oZ0%9%jY<|wa1CuEw_wKr+=#P1N5k` z>al9g?}V)2zM6S8ljNuJ8%8<FxA-AJx!zXg5@>;wf@sN~1^o0MOJ0B4+n5kEbQ2}a zT(>m*^sUyh>aS}~z86sa$!-s`ea!tyne=tC{lPL;#h=DWw%_9L)BUuGrh3ty=JUxX z&on)!Md#H_{*L3^bb7R_AmDxq)nvKfs!^37EM-BBsOocu(S||dYb<B1@(@3K=gakC z_5jI3uCKTM#)FMT--0GUqyD-bs{Tf5dk!yWYEkFYooJSqpuYK2)Zf`B9t-l^e$I+> z#Mei@yRhnuTX$~MuthM<-Q-pr*xHiqyS&W{92IVHh<8_U;=$aySUmP*?wfkL=M>gm zJ^P*8;qdZ-czIOPR&f2HcX7#md8FOb5+nY%mC@@397TV_quZ0F;=xqtCinXccb93b zBH|k?{91RgYzG#YJhbTiIsW@IJe!{Ha<96|VsB9mH|;pc-G;us|1yG8{SUy1+M%bD z|M`O;Ii3^ZQ(pd;xR}?yl}$-crT%-MhEI<Eqf~v5`1vA3@eRkuN04E0x|Z2O@<`XD z1dtp?6%)}1U;3AbnD?>$pFwbbkt#G1K(_+Fq44$a@wL^OhRWwnd%$}{|0~gD{#t*) zNBtMedceo)_Lu7Ct%9BDmYPcpx%;+_i(8t|6Y;{dfZo^skJz4Z-;cS35Y_wAc4byz z#d^KKn<RT{=COR)cQvO6pUS=c$U4N3QELMJwp46gR>^&M$tb1kQtK15_71+{?5WaL z=3BVor!(8R0J73u{AcCb%M%Yxwj^~t`=bt%X|sC0rMngkHgTfTuFcx|Aa+p>ld#?? z1T(Sq%{&un9WGkszee)@*Xw}KW5KUOJ-fc8-`iii*PmCDw#AI?cwYfXtRi(|k|Go_ zk8#70YLi}`OAlrnHx+`rB;;nsyo~ua`Se^$aCx4|MHn?*Z*WG>LNA*6n{8ubS(H!% ze)m$=r3=kcm|^cpvQopB%RQOH&$?L;^8$(A>%*14uQ=;$>*?Ajm)%=hnu|Hneg7m| z@vci-d+r(k@iVf;wN*XDyPXTuSYi6<uhPQyG;Q0R%=hCS{TlFR=vI%!eO!)&jZvDJ zthamDsI`}dCl99+AHR;^6r|9?L?><6XgnpAK2E67>@l~hvT!voGB{FYOsl4fCASn< z!h$4gyTlZOi{YK?h1S$qE{;S!MM>=-TTQq<Zr)BF-`Iq>RLalGK(0KPUlIw&c}eWY zC}aArb%e{!`<;Cz%~bbL>%V@bIDY2!5`PpHe}(S-GtWl7W-yJK>^ionY-f27R{ExQ zn&ua??rqbiw08)V*V7+zMd&{2<nHp^#OB`-Yg#0=$<{UkRmiZS7F_LVd51a<R^--M zJ@8APcOm_+x~j`=EeR!SGbLv71R!~3Nd(c#mw?<R=RkFSDXFWQT9q@7tjrP`<h`5W z!naMeGtA<DEKC0xtJ>BrclXvu9twYKmu=RI-?A~V^|52Q`$u7_G9_--gkN@Xxhz5v zENs7=L)TkWE@*y!ZLS^hS7$nDfzWU}*25l+J`vWpr3(4kdA+wLORL0?C0fG$wBmJs z0vl5!n{aspHpl6-Po=<${t|o|GW1Hz<!A#jwzBxpvQE@9cXCXW%x|9=&g$?IZnWW? z8Sdn}jZKI0DQ~pMW1iW2wBwybt9S2x!&$VfJLD-!Wn($E@;vak!=rZQT%%r}0vw?U z=*qU@GOXm3y4NNqZR|g&el%Kk9<m+LafdUM0)IEtJVO<Ld#Xa4`4B@!3GUsQD`&8c z%UcER>4)cn%n<s>AQ%UV)<Cm>raq%q-Uv;4M29Bq7;ov*jYqTf$&sSn_{b3|+}-@G zh?jn&HPhem1X@d<%{ti!Vjwq^sh)>kP>eDj^6|Mg;#(<3vL8;*Z^6*dAFjrjE-TAJ zX{NEjlMg*BXS)0-g7{1abu(kLQKSB(QyZNoKwskoxISzJa`PsluxLt<?g;C&vPpAI z)WZmX(Ox0I;EvkAWXIB`-*=qs>;$M-vX@)cP(q!Ql8U}Mhd{3AXJ7s;psX%30Ymnt zvV3S*Ev?`bqC_iV!N1Bd(4X_8m%u>3RWvljtdM4*pB=&wwZl?RY^iQGtAZlfdISF4 zG>Q^s7xrYrYQpi;_;ceCs|91TmVR%;_Bt@+j2HPNbBAz0@;0WR#Z&m1X5A(%W9bv@ zIfw;P(RK7vEIY`T7){vBk&9A=GV&dSr4%R5&K&orx3a)ra+^Drml^i}p%EhBrKx>w zlL^37^K4BlPTEy^ogKDWs7EC}@01--3v(>k;@%`qLm$kBmNpU^GzEz#3Y`I}W}y>w zY$pz*_m`;1=@l>}ABZ3cdAvy4L3Kbd$Ol$*rq<=|mko%LD?*cK-!gARvSj|1PlNZ# zNxEH3Ss|hur&SEicyjg{z@e~Mb(h&L3w@0LqoMy@Qs(DICDiPA7IktRl(Ps6!)G>e zg#`Ra^;nb+`Tq722{D@IP#9i`6pOWOoi2yOOK!vpnJfGLUU2#C=7u~)bPlzg$8DHZ zF!lhtS>ZbT&M<3{GKqzrvRl>;p{hNM)nBj#h+Flbhnn2ueC19$!k%0*E13IFiO$*Q zY|F+h>Xf|_TseSA<~y|ix`X2QS=U9@Ok3C*A=s@|>|{axRoo>cvpNV75)L3<EX|HH z3J^PoH70g<fZybCswSI3OR6C7I4e<T<OSk<un<^gD0->b*~&WrJ!_!UAe9GuKb<i^ z(AO$*VRWtAnoaD|6=NJoC}g1WUE}ClbtlN8xpI|<9n)|F^-?8P+d4FDS^6(bSDmF9 zH0B>5r277LME{eg+<B+aPY6pG$7QcMlJaYrbFpvqd+&mjIfT~m78Qd!GLd&f_?MY> z*+nhNjRpQ*X`w@;cxIh7-C`jmnmy<Ms_R2T7G*)b$E7Ie0#y+Pna03B#}%i8f>4#@ z$H5_qHW>!s`wGe%Oz|tXl}ye}PDD%cOqMQy0da7BQ8QTZoT{LTvLx`$b1VD)f7ZA( z_R4S-oZ?g%|G1I3vhA}ayCq6|IXXlU_;&<Q4<|b$>(E^I-|GxMIoeLZ%I{aw)TG_v z$!1`@bSz*12XiFVc!^y%{!(?~Mou#9jIVK<V*(3w_mpNCRTR1XW2yX2Ggw$1pVR8o zd8kY?S@NM%xp~+!=qniifvsd|R8Ne$HM4I<fv$4jS}V~6|7#7BH<_DWwFtqr(19}q zDiLE8B5Fg99~Vj8@%1p9#3v$Roof=m9nh<O+u<n+k*jQ+tIA>UGVQ7-wC*Hemf5T_ zX)*OZtD1Zhg44J(-9D+b42u`HgfbI&=px@7wVgY)PeR<;AQ{R;SeO=^DXW=SrmU2W z^K+*|t(Lu4_cuqS#-Hx491L7s7J59>ocmw!TZa(VXn4EO!)FM2h=x2?vXAYY3H8I- z5&Ycj3jR$b82Qut`9@)8ED}MtO4;8hpM5D;nppd$Aw849Q&k{}I~|g0RnZixOMQM# z+Qk%lhvb(k25<WjnHR;@dKq(4Y{;QUplrQ_wu0P96@N@=TCHQLRdII6z>QlHne2^- zTUzAd!w3r_#*?~@#nK1z6<Ml$kNXZ$O`u|<J$xM4L;`nfwZ&-S;>UQYd=5G@pT&ci z6V``>zH;N4yfMjBOZr4>JZzsVJtP&c7VF4~@&hnSFvbqe2H~Z`k;McN!Br7++y#K+ z!RpNyHOlWHiWrv<nsh`l%rpSWGcaKWhu`RmDr4la9pu}_Gxm!%a6~Q5Mh{8P-1g)E z$G4|=sXfcbyib;b)ZqYD)Sb%>w@}AgCiGTGaCvD`tB@&gwHCaeTv6$^?@()J;M+3X z(<}|9ys={7mc%JW&aSC5n5+_<Be5c&;N05H1=VIEWx8f&Nfg=EAfC_qghgsGt`d&^ zn94d)5S|`BGhk;GvxBAmXDL4^EwOck3#Ahs^%OBVl8-dWIs-Xdt=J>|=h4Dd)T{pa zL+w#sro-JQqO_bq3(H2G8pXSdoI8i*EIs|tCFJxdMTwJyZ24#hpi5{6Rdu{}ziZ?n zz8@3S);B4V=HP6_5;~BqRgKx+g9>AddpoVD3^A(T0dc9ux$SPlQs$u`6)S>%wygp0 z)0?+92MUPl-0t=u!Q6$J=te5e4&tj)Gl`?Wa+>{&)7HA){<O(+yrv=i1}gcRHJZbv zM4MrrAJv$h-of|AdXS2eCKCIC#~@Hv)MavEW<ZrIJ~J4^FdDG9o1>DuQ=v$hn%;_+ z$*#hzgfNe`Pp!#bGG+>+d_&ha@hQYy5DF_;2CUV{2e*~HyQ>qoE0)V?L013#76Crg zL842y0c`w%6Vc46Q{l!E54=UQ{zzs=BDz1T3Ryx}xwg4^#_M8B!4rooZY-cF+(bjv z>5lnT?6u>j>GAF450DsY(8$vV6kgFVy~Z;>_bi@9<;rw#5_!MR%pR2en!_!VLgq5) zu-fW+`oL+4j5d*4xW=ruDwHMzxjh3}S#3L4_5{4i+LODV*@_uiG*j3AoABbE`{?!~ zeGOAi`l5{FfVVDrN%~apkEjHl?Teq8`u~Kaf^M*m>W(24JLMyJkd~F3Q*%*Cb2SZN zKT9Y8I($~F6Ea!&%j<!e7NvIh&I1Kzx-uRG2dOg<NyP+oBXcLD2&4A*YYd&=l;X7H zb$n`uqad+qo*G|zLnt}k->4>22x7r9Rva(w-M{%4aMAErF4X9htQE`ZLx%Iz3?gC& z1j(3Y+mu;tIM^(|d7G83;ePxHXP6O#^kDUDu60mlwaq<qCcPev+33rpCW=st(`!0_ zr9Ls@-d{`os^mI{TSrtA??{<o9g+cMZ<JJ)1j)PjPA|C-tplX?FbC^Yd6c@&4n)4d z{DDrKv*25yzT#nEtqoxfp^%%=8Z7JNl0k(Zv|y-TPScO4z&Wqx$R7obfTye}J{d_l zc%%$myl~8X_@A+gr~zX))zG8^yXYqIfFwl=Wb;xP)iZTPjckT&1(UGg=yhc@{cb-J z-Yq_so9<yK20^&T#`U3{__nDW!37QSp!zt<%Nj?>Z(KdBCM53#nJk6B?vtnFqw438 z#C$YF-n7knpoWMO0E<E(-b9vH<JX;na<xj1@^}hC=o4r}ZiIp_B<o>AX^?r^3Kh^_ zD8o8oyp7EG*fePap|;-ehFe#2h7pkFSl%Z`5th2Q!liUKF|nMytOR%$#aJBgpuNPS z!3cqzA5;{*syr4#{|P4dJ)gFK#-r5lnvK@bgi(W{GvNWww}}2hsN6p3RxA6dpSgjN z2`he%>YnB61l14%45a2d(6`|m1gN$pFQI`fokqB4ZLvodPv%|(o#*#VC`Y>3L<rRV zz#p!fBV;k?r$<;OuOvT@<0sy}(=v)(B!kJ7fx%f|nVQvS<j5<d#h=2Lq*CmqQ3n|C zkHR+d7=}y!bkTwTWdmUWO~8)TCKrqrxM6=uY>GndlMGyk`&I%Ju5d3B8(+4SAK1Fc zYWpc~2awDIEeEERj!*f*U=J6)9f7OKt@ErDd9=LBn<z{}MSz{YpHW#DB{r4VKTz>5 z6f8w|SH+a?$^q76O)yZzUvXMNG>dH4B9rkapE+8Hl)HYxRS>hDyWr4VL^oOX*V4-^ zD!%Hoe3G;l8&prkGaOqjhfo^<O*PT{*!9<WIwMp5tP>~iO>>|PVd7hvxr)k_u+Y2J zc&33_312UcR{}v^W2T02a~#YZ08XjZ?Q7;fe`ROfzw~acph+`89nPzNT;#fH=ceT> zxhaF3Ud))Lie^q4!2X^p`nzdX6b3Q9;$wnGh*V6LbSJgVREG_MycJ*hJJa#OvAX(? zmjEv-(_bl#N(2}oZ5IRHCK*42Sr>xmsoli)DSGHv@c(#7J$1(8Q?Wpb&m9@ZeWTG0 zaUauNf8=EP`2QIDrtr+7D9hNYq+;84Qn78@)*ri)if!ArE2!AE^~bi8Nq5im%)>nN z%lhtlIQ#Ci_WABT*zh-Z$iezN80QNLBZ+l&hqo(yv~;)gUZJLyYt3J4Wp69nC%&|! z376@cx|m`49dR31*poh=ZGbCFHMMM&2j|LGVRT)d@@tv0@{fFO5k-*wZw;O-j4jpz zOi}g{+^xi(ML7j(PByCkoM6GsMo-Gd05im)t`s}4ukdFT<bG8c?%$OhqkgD5Mz=1E zZewb#ryB|+p8~xESNDhE7C|T8kA6igW`w^+NT<Z33mCa-3-V7tJl~D`qg9}_5+n(1 zgnDJLXcyD6F)CD~!^DqH5_SG4nbJ%a!HGJ677NBy4}JnoXVW1kX!33jbO;1ze%Is0 zLkzQ@ikvKn9G9Dl!loY!M}P$Xgv-i>I6dhu=}?i5`(UzKF&nxZ99ycCb1;j9wq1mv ze_S<K|Bss=tMl;HG8AuNN|{^^<RMjTwR0c@uehWB<l$6*AyAorIVtK~IuffdS}1^w z*PGtqq$o)grqG7!4|ZTn1JLaBq~OlZbhA`v|F1G)F15Owj>YOHFtCzutT!1FH_#Sq z67jRv!%jaPRc*~}ah!tB73~&Lvv<74RsYS;0Tk38R*rtgO3M}=00&_=)`4fKXn<S8 zx8L0Rsp5S%;HvxpMF6i%nZD2l>P@bd(3F#Pt(Kj)K}*G}J<<m@q8W}SMuK{ZZccQ3 z0EFHb5Q1(qhXfd@NMJJ4gs0Q-1{OCsloI7-tp|RM#Ro70p88kGCAtl1^TYJV<d#d{ zk^7BhnTi*RffQM=ZJXL<^1`3$?DBkcNkv7h`Q@WlX)q3;^&&>LW$ZSRK>)ku@0*{} zdP;MX`y~>Hlug%OMr90T;XdYmjC6g*ZC-vqNhRA|LhKr8qjV6_3Sz8E(41;}LE+P& zzMYQh77(gU9ipw0ObU>$Nh$!5;G~<nS#3izhD-p`=rZ+ln>oAN)A14gL5Q=CGiIZy zja*fZXv1|(yK)u-ayS_K`l#5LH8X3`d1{rU@;1FAyy1p)IfeU$Q8&l>|K1d<k)oXm zCe#;C*yS0n#>pGB;ziA#s>z3Uyk^U0;2(xu9+ZthP_l8`t(L@c=J{15p@*<6jj2C6 zi?3&Rm_2FsGX6{I+woC0y9k)k7IEaLsLhWG^eJspU`txCEw!vP88Pl+e=i%KTI0(A zf-cLs4^mTKQ<jVC;-IRJ04j<m<ds6p*A9j38#jw`7XA-gHaOfu<NH7Bm=7NT-DaZ& z0n0QA^5&#_PGLL$>_uV#J0HALLVH<-M_w}37R7P@#)AkCn173TlMzZ}wDEy!(wOy+ zu53cC?g>(las{R0!<GrSbHgq*);uh+(o;Z}Y8e95T1@EELDQJ&;s45S)>J`p1pspr z+5b(qQS*VCFVp6Usp|ykN#JYvfw}+JzBmn$Os+2IhuK|CKK4ZYfupG;yIHyx14kB# zp{&W78^(RJDFC@4y(M!&+on`cdwq_2lQ=2xJ4h->Ctp?)sU!(4zGkR=f;bzM#m6np z^c7-S8OMTiCX#|u619kG8|83R%rv@bT%ct1xDS`~h)`ESiUV$gqH~IwhcsPtw29KW zf2oyAZ7TD4>T$?UxbweFC<lUkm5jDTk#KH(#g4`+&Vkb(sY*?0AP)IH-kETLlFQNQ z7!I35a;OK7Q}_TuWQ5EehrE^)iHaIrzuFN3YEH&tJ`cmyK61;eJlPuW8~E?xB7}M; zA9OI5xf1l0nh*pODyvcPPDn<zrF)VDtK-a3Krgo9QuW6&$aoyXZ+h}PWOz2@XVMM? z=PgAqKbDK@Z(mrp#{t{*-+I<k(KOn`=+x^-`z|6ef9$+7r+KN(z^On^R@X6n(#cDe zJIf;K9A~Xqs3{xmRy7XBz=VT0N6BWq0TS9%yS5J;!{$@UM(wt=!PeMuu>QiyH-=0P zdCqG~qaeIvKT?iU=<BO<=u8Uzrf57kYBEi-ivjV$VLu|AgFNLyP?mM7(6E}5JT$Lr z{xj5%&5dO}_v_`Wq;@fIy6XN#^3jBi^lcXLnPRR0K;G_Vyh_C>GvoRNdFc;p7MGpc zaYhP5_-tru5^ZaR)pZ8<=PQHzg}lkIH3%UNzEf;2TJD%K&gnXYsO{oScB(aQ^2f-j z@ycKT4Jl|T^ozTsr4-USvFcSYPnC6Q642+@r<&fAoO$4+z4`bnvkA|S76<ySn*v(3 zNXvLt7#1+POQXW7F-{x7WtJ{lGy?vOSoOmIYx$u5q0!O8bfWx8HVNsU7Wma&n76my z4G&bTX`=E?P9x%w+`aKG2mhA6O$4__GBp{;c^s-63VAOT1>?Xx7O@N#Z&OjcK!(O6 z9MJheTtTlD=e@1EY@S~|P`&tW&ZjMQw`TTn<@7S)b&7&yt|Eqr+x}$OMnMblSg0$K zA9_!YC<98y5@v4LhQtjiHlDp=QGczpY3ajYun}$kp~9tcJJBdAb_T&j1$~IUe1G z6_bUaK;g(0gVKeosV7-Mu5@ZS^SyBshs{J@2~d<7TaOXA4Ss=rlF!SY2EHsPCziLc z4J=*1QAu=QM^3VjOcZn&I;I|aRS$D!ba13Pa-I4o+$mcYVR6TB%!lR2Y##hJec9st zl%axDo&i~0l?BUCJr*C^6r2$1LZETUl`%cB0<#LdK9XO>nTZJx&rGks%sjmE?Y2d6 zjYr!f<8GHQW6#w{mi-$><b>ePg4yn=t?&i)Y)#Jn69$Td-+@R~DG;b|l3DOW0#>e! zPd0C?+vd1q+8llUz!8i7MaH>n=|35Zq>-EZUR!)BGEt3jgXEb|uPb|m@Thg;X5dMH z5d6!RCF}Xwbh;xwKDMCPlEKyec<Bo-B-A_98GYMR{yr*-e26Nk5dGn@?Z^l;YwfH@ zTtjRZeP|OUfL&Aivx!4>((T<NRO-X!8jHii;irNIQYOZYh7BxJXldcrgL>%J%{Xf& z*tR@f)5WJVEIUFo1%1cP+vWlkgI46~v>taTgaB9vGpeK6e*J`jSKW04<e@Idssvvq zhc%djG7pQ&nzdn)(}pNpU<pkfmcNB0qU^B2==QBOIOxRu9JQ}txR>G1M1JzLQ*Jjy z;zHIc0;#_zTO@A&E%7#u;FVixHK?HF%o@X@1v)Bocwvo*e@utFb*$gXwrs=KJ-g7{ zzC`3d20ICgAGANF1yjXHDdr3N!O`Tcu(5zkgg}Kh#8jRYgST=>XQi4LvG!c_vg|D~ z^WJ50PHoYpM^x8gt2q!X2N~nNdSYU4$h?&)(*hh<qE4TdR#9-?S2qdmgc{umVe*eI z_v>AEv5H#Oe)XFrRa?dl3FZV7&41;aI4#K<mBUK>-L&&VNN~18q}5ae#$LP)3ahg< zOzA=VP$?nXQRh_tJ%HX`7|@KB7Hmqf9tOlyB&Gu{WdK|3M`&*(Za#ln10;l`g?IKK ztYX#COfJk+jm7>RUHyH+m1O@6i+XKGH&WmYv`wLC2C+yfPazJ;GD~%wOCb;&x;njy zE~%M(;HBaWear8Hs$$-zods_uAIl`mkLht|Ji}s2r6W#OBYdI{-hkn4udN#gb5AtE zD!v4xs2`+h345f2kWJD{TpG_=AzxRqm7R*4*N*QpYjU}g%jZ=kucT={I%)msX+axq z#UxE>#?0ewRkQ5nQ&?`}91Mz+vY*T``k^ZP>H}#vVsCz{x}cx&mVbe9Kg5F?MaD$q zo>Fx#cXBQ5YG9xs%oy+eu5{xd3~(S9g-0N<FsqP-^yKs+5n$IZpl|mcmV}bKY5cX* zwKXQ(HessbLNoAy@&3u*p-e><NrD3&i6z|hO4sV6NjxrOXIne@pdIVL=4w|%rZXvt z`j3TnUPs)#%4R&LK~YkLr^(y-fC5ckg~KtyUOAa*Je{ZvfLVMQ6S<Weq@R#rd1<FR zF|{dfh#fZNAPsYAnWvbakHj6LY20?DAOE-0^m2<W{SyHe^QrwRMq#`of@i3locm~a zdZfAd$6Wvtc#tkFzHYTB?b?~?^MC2Vpn51YYhrFhYTjZEZirZ$<crneL>l7#^nnN@ z@Sn-eL`eq|<e*=*<Q1@*^B&VQ`|a7LBiZ4dn~J#G49PvhD<o|rE0Ynwjtr4~+@Rm| zMErv5DDau4@`|d>kU(2^ev2eZ;v<3dwJJ(DN#C3Kf4>o14#pT|B%#A)zqSVA$vmn8 zj1|=OtSpnH+5<_G)xKlb;r5g7#4vW&BjHxxj$aWe&?cqsP;^az$7FOFUkO4i!q16W z5cE>c&0VcdgaEPp4frT2%o!+qId3)?rnB4tz?GZ`(yMs8Gpc37Z&vP#TJJ)?V#WU8 z|5gEBkaCfk34vx`xRZw^6S|`J`DpU!iXFKw*-mv)?X;3+-fp!CzAs-$k0bU{pAb-= zk%hV5eV$!#Nu39V;e+T~qXWeU-vyLq-V{NsD~k0F#?q0u5#u#1O`6OwPC<jPu6aY? zIl?Gt&gW-o-P_e`$WkZ~X1B3+dGY!0>6lNG*ou&|0H#h+J%&NNb`}`Cc(m!86B@n% z1i~Pax9A8>l8==)vy3>%vtM0;n>}D?lsB;c?Q@cW;uCBaL>b+Pv5j-Px><8TskR)G z3j0l|#nBGx)D8ko)Y94Z6Z}3yXwr9R1@geHeXMzERxkmw2t+jvmx?WEZ)k_{zo+9S z0=B9yp1F#rn0?|aIFG$OxAVSU?%`{xKw|vTvet4f_oIQr7a64>{)+Bn)=YXlnSf@8 z1ts%}*}Pk`L23vA&^%6V5^{viRAR1*BUv}N4&ll))9ORtxI3{@nb0)9WJIYB&YEzh znorJ|rP{#GXNG`uLpT(qNxz0on}e&pY+NgsszC@?^|xu#rnqZ)ZS)uPN!)$iil*LS zT1s+eij&7xz(LC?Ru9dz0ypJy!NRWt;h*h`7-@<bc~SJTB-<_~1S58E_-3vX>-enw z9u0y+7ZUL@%*|cUEzp6bqOm~B%xULXW1)b$Q}Xqxqw20}K?cPIWq3e{#APc~o?>0! zt(ob5phj*vGVq$Z9p6PKU7LLS%wBb(Yy4CnApY?y>Uuup%IdKTDmUXtR;P=^&zpZT zRTF=4xQ*bm^t~K(KDK_`t1#fE5nR}&_T#Wv$eY-Bj;<~7s!cB^?J6OW0Dt4YD^LMg z_m2VH5uf8VqgCcUL>gqjBZyv<Ud=rgEY_sZ*}8_0tz)1M89f=nmKUO!(LNgwgwvw_ zFmm&sH{~L4H0cPoBPaAD<XOkp8e$G{r;mWCSqk*CvUV?>dn59*n>aKi@s?v6vZ9<7 z?5P@xoru9Cx^eO=DqOLUV!B{Z<q?7pB#&ORkJrexxaBWFW7i~7^(EoSme8tPYJuF_ zZ`PTM&rMhoirz5EUot~s+BYQQ>FDD&5Vzh>r4)9^d7wm_G%3#($1c$qMd@xzywkT6 z|2oRV-qb>B5>pXkWMhv!cW|pr-_V^18!B7RY8~t>U46pwu^!qi+g4|wU95C@!f6=B z_NQmz`%YwF6azgAV~$%40nYLSAo3hzXw>UfOlhlXHS+U(>G|x}D3=w;J@)0-v1et1 zjYt+u8?vZc(MyChZx1i(sFiW;F@-ruq2fu1U_}zqPM)9U9S=onnVoxW_TQ7CSOsSE z{{AjBtqa}FSAU`jD3}&wH>aPDy46<b*<M*CGDyJvGpN|LaUj!-y`tYuGov!uyQwHr zJ)D2QQc8`uMmg*%lFv_m#S$En^sDmKeNrOb_;8Dzi<*vzw0*vA460xbct5~V;pU%I zt}4Cis54qnjR-TLt;KIz-)T!MNrQG}x)WlW0tcR0NfWm&=8#0-H-ad?*6NL&?kL5K zz^&BYf;=mkQW}Ay@rTY<{pEbDtK3iLPtW#DaXLso+0$w(xG{w#$S8a<JWc_abr`Sn zQGklurB=Hllwlpn0mbmea!d+Mqv^V8a_t13>7%%7Z}owwUjGsz^oZ}M>pp<Etm0~3 z_Nz4dtLyW2`}4uzbMEt<aeL<8hW-5A;ed-WPqNTmEdLLGN=qo{nuy&!#bZKu-XW>y z83!Bc2~Z|8=@)S)t%`C&bgNjZ3xCh!8_)Y04j=Z#tj-3Bq%WitS(h+0kzjHvBbRB} z-|RJ4cfNZ|Qw`}Hc55z0WA$ReRak3E^wIi~o!rqga`DwZCvWggh0;=wYZSey){0jz z`dry$T)KZv7|Z46(5txHPp7@GTlv0U$zX(|M^su?kWdP%kl%kC@PC_6u%650A3t+O z3;9<4l-%)2>9|3D1twRH315pmX%*ickosqne|8|fr{FGhFb&|b2y7p;b>iVn*qt0i z%JaJ`Dc>(!=N*^GTaPxV)L@2*4Fq_TwoD$1RSaFhyoWv*Fw-4xz59?HWmY|fN{D|9 z6Xa<5rua*g)`mWu6(ipleTiR!J(qmtP6JmoCPHsUVp8yA_<kk6!5Q-*QJ*yKzX8W0 zT;vaWyspneH8$y9BV0VHbyE}1g+>9Rg>skIl1W(`Mr^l#vtkPCy%PIg7XH;Dy}#~? zF;?s6@5R<G{^j%=Oyi%AB<K^80tk{Ex%jyKWk2M?n-v{>apEk7?(y?jl<TrMKGQw8 zNZ-)3IulBjzZ&AEIdR)m<co;dtKc3x9Tl=*@Y4Ev-Vep>a_Ok#zzf`WBLG^;l=2$S z-=q@=jzAal@^K|0!!6l`wCH-2-0v(SGj>p?KJ&O^bzW9C9n6q2mTxWfTXw4IyQ^mD z`sr-UmYV@e+U^Rb-J$(HE-Ml{UIy`X6kgBsklS&@Vs;2}!nbs}9?MP}|M(sF`C~G? zEAw1`{Ed`9g^P@Y_J{A-1+Eb5HQY-WAhuTLhQ8;OPX6H*RS0{f<GU=@H+uW%ue6WY z>YEiNK5P6l_-Cpu^Uu^Dd4>{^p`^;&P3B8i4JW$Yg4C1ma_t_o<7J7}2hZBsgf-B? z$Jlj$eelJcM)AC{A69SN3&Kqq3nc!F{0VIy<go>jI%<MU)WKq(Yw&iZReVzEZhV!? zglgRe4M6+I+3RY;6`}sUa%%3Ko{D}hzW2}j)!sj@4;6UH>7q^tT&H9iR0kw}bG0Pt z43R~bhP96<5K=!iVqc^#j~<7$D~5}DVw?T=(FT19L!NyoGRk)QfF~O96RBb>@Jj55 zD73d1&9A=klShqZ(=mFew^p~kDBRy;ByNyj&4AB5GN5KPz!+U;+o*pZIr8Y_OKUhL zyQ)6|?Atb<>;#Kh5X2bi+b4Y#NFEx9HRxiDl0^Ka6%eB?;pM2U`bayEl<&ZcEW(Re zQpo)Leml$(|E2kh8ris6d{XSyvx(*@ogY_*oSXd8F>+1*eAy_TKV^i>uqefH**{js z2q2^0()g>2n8N`UKY*xg3)C~as$zGg<G7lD)IeSr>}G#@muvU*kYwb{J-!o;Ai$Iv z?>ZI@)oAjG@{pfU+w(X};Frto46nP#@qv+}#0?ShKBTGpwwdzxB%P<Kl{{QoCPTgx z8kRo}U_Ve)%HFYiiF4%pr5e2?GUxglUSi1T^(s@WvAPK>^qU-yedit*N}$ky$Zi7q z{rEmp{D2AP<90Ftjl1i4L-&5>Q~6LW+2!?SUgW~{)v5(t42>@H9rV&8JN#o6GoWOY z@V1j^9=N|x2kag%?3v5WTLB^m&=GOGh;;o#$czDzW6IC+`FN33MMr`aB(j1#segQT z*SgnGQ`)Jlg8J|&wxl6=rw=PZ!q%xXjDQAG8?p^PJ8K4t9sKLx-||iEcSN5F)KU4B zgd9+vmz(SMb0K36R2mLO_5|hoY(|Agm996BI{Pa7+5YX#0&^2h?jwz8U+JgZL9P+C zC3~@p2U&)6C>6@Jl;DSpac>TF=&%}(PwBab+6P2wiI1Tln9BT*a#-nuS%qn|nbhtc z5*Kf>44Tjhnlx75EpyLP{dWfMn~GCde)doZifguHkwJ8qj4@Du_@%<O57my}atodw zsR-R6!+5)y#6^|wRR%Z}q0}%!#pOe};%JH)r@efT`=j+2xv`>34@`6cX%xSvs84t) z4F;?Hq#ln=!NgVQLpf9xpd%916hdE#W>_*sv=?w^1n8Yl^**PDUn0QZ;3f|h2OxsX zo&OmH3VGhED1n_c+z3Du$KAr{Ln@g&|7d(!Z#al}J$XWk!P5F?!4Zmra-M#X-yaCP zeM0nUl_;S0hOrY$SX~+x(&^?lXs0n36X0<)Bn0DWYz!qhOMZT|Fn|zQ6Z!EICOvki z^>i8R-DH?{d$39$omD9Fg=<ym!3G@~$e_vk2Hy1JoPzhmpC4831w3Gukpbckt7z%U zSiKfZ#Lyfml#GUoHT25%ruJ*$^J3cn#owS(_~2gCjc%59U){=e-3U1E+pN+4UiehP zn_{^35T8faFW*iuMcEoERj)R0+Rr)0bX%U4Q0PszlC?1|MH26jir59QeR{%0iTmc- zk^iejYZ2#lX?&{UjoLm`uh8WKA^!YXlbw@vc+y&r_XJNhCRW@*0=9RBOGi?vg(Zk! ziKf4GYiFz>B(CSjK(^u4?C95;-2t3FZ7S}loeyzMH5%=9VlZ?sxz4wXH*b2Q?j^9= zjum_LJU1gJa?}8q@e;zo7x6dAy=BzY#bWW_+aJT4Gs*cR*AxO1wueiLjZfXB+nkv` z_VSoshyW!!Y(AA4jIU}|pdpYZ#;<XVH1|C^k^2Sr^y6oeSt*aTHv6IeL5Aqd)cH9e z)M8aEbzrQpEz*2?>7xRCVqW{V?rj5{9mDM+X!gVFAu4olg6(20F$QbOcFd*P>N$(& zK^(2uSZ(m1+(5v75Ux_oa|^|;Qnb$;9GD?fj1M__@BKnn?ZcaS;`F4Hq=OcbEo6g5 zC|-iSxfdo74MOe;dwd(_pw!R}u$x-T3sjWeo*W~;zHPtX>HPZX^V1YiL{oHtX@qK$ zx~ToCPtp!~<=X0VE!pl#&Vx}eBm+2!wJNlIVM-kSaUWxsWJ3Ux!sA8qOd4iC6jz-^ zA*Hv_A~$p9;uo-%8`!*r*9y5c)fCRixrEhF7xlFIkdB;_dDrZ>ZF}3!edgl&$b_3- zHcBrTyk`W2DrtXO>c=hrHI`048VXYFN4Yt?u#*~;vE7?|@pi;^MT*~yy=G}L-fDBd zR8_W(wiemI``U5vM*@kAkoFp27VZ;0Y0KG~Xs0P&<B_g2O?`AvwJQITP?#lCPcc#& z5qb_q@#A`Ev#|!U_?9ZZO7|eCs%l`=eaD!n>~%$s!I;`_`!>MedTROAw^54y=nL8~ zR1*IG=UvXi@jt9O%*@Qe^xxj)T+CeD|I=b8)xP5~<n8eX`UXG7!?nt!3U46UUg4n{ zk1z7#cN&wi%B4ptP?`J%h9?S1_VwLMy;apkvO5YA#T!k;y=P7kY(|eT?~Lgo-}VBR z4ek@@P8gpG@PU*)E0%$u_l%}p^SQghT=u^E@SjIZ8TwRRt|N?7Oka=!g`Q5pCU#>6 z3jB~>hL!5Yt~S$_-1j|z`NxUDO38(VhY@D-FqXlJ!}-vC-z=>KbC2U8Q6u@?UUlSL z#(AW>da>mFURU$$eAlyO613tIHTiePz*Pw8U2>SxTh?v}Bpn+sSSJ(8gH%a|aog3- zfx4T_3z<E+JOm;Y#g5f3Q^{I^7jnwhhhUHpPCphhrd6t8t<MKsXYBpax`+&72uM;# z9`I`J%HO=;a15rEJ<M>wAwQx^@%olxu=%LHrgjW+sZJd35vCk`nHWcGFP=Gh(tq^a zI85-5c4FL7#PHNQ=0uZzMEkQkE^S{1N7YyLVE1r~eISlAr?<ML#WX9uG}Ymco4+CM zgNo?nMs1H)cADykMOlx=4?0LlqnV2W|HMH4gP5$03i1T~eXEeR91c3>FmcwY#4i+} zyYUQ-qj(rXX{6txb>y0s>WTZEkKz(n9ZPJ>_O`ELlosqc+OuohWtXW|!NG*tq0Yg? ztonLga{_noKL9|Hp33Y{glI9;Is10Oc^IAf!8O!5YR?6(w&J3`YDCYp-S!=jle9f# zyd~Q~gJ-gJ&Z)<GIQdWR@IkW#Dun7{2Lna?;;LRzZbocJ5Rs!dqIy`lx#?z~&(B-A zy^bV*T&|Sg_$0IH*E5;@PBcX)cvi^Ac+c0H!RLj4s(+M${^#`9^U<_F<97Gw>sNPC zk1sW;mO%jhI{#nXWM^bFrkFl+mel3cpGMn<2Lc8;P#BmVOUxkZq11=w+Iv#-Lu=Mm zEGSi1(DE&5Kedlb9#5_1b)lCGK&a+LLjyqVftEy0cXFNbmYYB&qxr%ZaVyiKjwwq& z!sm-+<uCqjA8dh#+5<`y5A<d9*5RHc|93RxR&m#vub1y^qOD&K4}=E(AK);)L{H!C z*e?%|w~yIWW9^fP{%Lc=>$=%lUdxA>D!D0z>s&-W=I7#-EeUoGCAq=B9L|IYC15G2 zgI18o5ZPBDh;FV!1hP2P#*0gW-Oa+2j>xuVnqz;B7EqUHQy7<Zher4)p6}9iVSgYN zWG7wNr$w52-Ib#ufE=RmY#`zew7{v97WBW{V`WbDPDny}BoJaPAry!Y@K}neW&Gl+ zJW@&Xv+hWKHEfwpV%}A^W^H)`?p4`ZoYYt-^8vdEuxcW#+R}6)!91;j+RQ^iIVOrf zSg%4nA*5E^VT}IGkFcae_9m`5);)8(uIT&nbAG$}Km;Ms|J%D8Xv!xITw;*~js9!Y z`@jwL%Zl_-7w<k@7mQd12a$kBX9Y15M!k7pi|%b<f@yKQpiY$~s}0tA)-Au=Mpl4* zQ`$EkI^FQda^m{I?$Hn)%z{{cej;z=`~jrd38$n8E_nr%?K`{ibMC5-oPOv9A}=x3 zqEvNiP#$Y2VYXc3W}mZ?5@qT;fnrd6f}TTxG4GBimkA=}1lvbl*C^B0x@OGMKlIWZ zYq59cc~|7^pQd<w>0?9Q)kk|4R9aE>%i<Jk$|8i4BBX~jG`L5>uQkjc3of(|MuQp3 z?fu}S{~Ve5I#N(#v$GQzsPoJzjfGz4l&MCVHu6s49`I~kTS6nm+N-;}rs<8NN3iSm z_6APNx_eLN!<<QyC8aE!{~EEU?U*F!7PXlp^okqhG$XFB#7=5HPC0|ro*J5@qj@|0 z@?lqwwKtB|#Fk2()#p&6ClMfB@dA2EG68bRA2y5?PUL+3{+lgMV@}hJ$Ta+Et120` zxFrg-VaLf~C7Kk2jir7+?8%(?d~Yqt9oGJEbqBJeGW`4r^Xv=vhv>(%<y`;QT>s`n zboA(hBXinG`(@c$oeyWEtL6!0;Nx|dfD4Pp3iHI=J3-WTW*5hmmkGO9f!<ZwB=1cE zn*+rs(UwFGK?mc?v@k8Olv)x{yN%X$Rb2o{t(}`u&GB|*J_~lB=TJKNnf3Pmy7H0b zjha;K=$#>~=+<dMW$El;4>bk~`|9kRU~ZF>*{kORejew$dy@ag{U)zCHO<OJ$~vIe zxOixR>m<nCag7k*yq1-dsg*h1?q7#@ug`=W7yliPbQs8XW$3Jw>Apc}=hyNhwfV&} zJ**{~uhrY=#N^8PP>V^N%_B#U38~43!p;vP8FGIoN6f63>wIBMKeM0usc&B73GxjL zuu-iY4##{+7Yb=w#4|mqm6_WWsS%fp8IJi6HPiXB|IFmc`LZi7%YADqkwaiTFx6+` zx+cB(MT_dH*^@G<NXt#-ocQg(q$Nx%dWf%5+HFaZgUUS$5M&ObWBXm=MY;LuPxM;f zy;MBhJk-B&KM9Q?K<pe*Lzp?_C?Qo%PE$eGenV*9B(D}^-M`1A|70WZqo~Qv$K1~E zkd<a^+E%<UJ9jlI5D@m)eD2U=%Gb;H+;6ID3Bw69jl|~8-uzoaMTE}iwJopG{5d|0 z(wz~%d&W)g!LV8b3Oo1uF7-*6)btb;_U53+AwTSxXKA_US|=&uVVr($?fP>ZU6EQt zoTk;q^Zi_Bq%5`NU5r9r*2UCq@o8Lj(9t2?<jcnGyhuZw`l#>{!gKnhtxL#JIIE&t zJOScG?PKkpC*iu}+PR7ZWweVuE1}?Ww}tMwh>@d$K7}uUb`F8oBSk602r^}_275=V zwG=UUP34cj$w~cJ#23-^xmLtnmiuHKIPPN>7!$60maukfA)Qo<9PMNOnaUUBTSBHl zD)Ahh;1T}!W1`gbq^0ZMZjfB}K<V3^X)VgP*A?$x?ji(U@OTId%BUhv-p2tozWQP7 zMN_wG@%w+fSy!=PHeV{;T5{{Fow;I77daX@l}?3TM|!*<ZaGgbzw6<*F4q3gd3s}% zZgF|z)uD(WlAX6HgL_H?W)SpG+N;DG{TG+zrYCojo;`2ss8ZkC4`>yTH!;uqDURRF zPrX^IgdfGXGQPOimT#Y0IT5d5H@(kNjdiI8+XHz@#YZ&oBKDNqlei~UuRi(IKDihW zpMj>6FzOtclKR^v+#>RSH0RoFb=P7=AcTIVuOe8O<YbxH4>kQf8p)5$E@@pR8wRnW zxW)GJh7gEBGCJ%nzpHw_+8cIUOx=l2-&!u%0D@CTl%mLF1_cDm;_{C!Syzy1FrFxL zT&;c$J4HiL;L|_jfNTmnWkoYCPT}aNHEma>#qKj~mk7%E3B(u%)rUyh;uIVA(#CE< zz369VW?;5~^N$ME?<@xCt}4<M7l$;@m7BMeocegv`@*eG%eASJBE+~b5|XFdE;A>d zwYQ^+pQf-)d)9XF$J~t`%|cgntKx;8i!=s(apmS`PKLz}>Gc%DU1h!y4sqKraUAIt z=ZxS~kyvOe)Dc#dFuQaYI#HL{{^?X9s7Xqq#xzkWo`9|QV4Vkl_zTA=%@LzoKP9Cv z9}K}S67~nR{1q9Hr$GGH4x4J-iK8c6sh9*hmTzGI8ca>!q1)(S&$ftpFukvsaIzF_ zYhDd_%x`0n0c@>fdDk>j?OsE}EVGzYB@RYUT-J|OW}atu;?*y@kiSE-X>^2&pGWBm zQJc;0B6g%Anln25Y%U}EBn|Se+(90%(cI^2-Jt%L{C5rd(_x?M6SR-C&2aZ$2cjbg zchiPf47xT#N!=z)X)^OC?Bfk(V<($M2^2I(R4NuO{ig&%;Tj%gpBN?j3V|l=o8i2m z3zfZk1|&froBinXDEk-(dgnmEqz5a?D4K>f1e&Fhd<*p?S06C%s*Hs&2x!?sn8Yjo zauVuZEzC8Iy+&D=e}|9dUxCOSh}%VSC{6}1YU<sBA1+koM9YILi^2>FY6aL;3LLjX zsyHX}n5MI^Fx}|o*eH$r*a(vOK9<t8jXAWO`WMGi_fylCi5Oj-y#t)xoN6Yrc>)QK zCVsm3?*{Z71(oWeBs8{GaeUl?av98gGv^sfZ*_Dd>qK1hfIBoi3U}u4=@A=ELm*wL zG2I;3Z*bgGPk082J9aLzN0YS;m|dO~9&@=CXx`rLig;u|(3-bc)ReQR0(wC&jwMIx zCW5_e^7Nc^^zw+GeP1z7twHFZCDH;{X|yBNtXmRC`@%mhV~$(YP@gI}^t&guhqKo0 zwc6?^2ZQc~+JjU^gSF{{bw(4v57=vG>BkPjC8ygGPqID9{J02B@u3+!)C%o6Rk7PA z2!AQqQP9S6^5vk1@b@gTOD<uYUFXCPGev+ql^L9rZa++k9JjFa$U}Vw6+-VERdJp2 zWA<{qz)+w5hm4nCDN-cRh3gc*1h|9mEi4NY@bC;O8sYx$2Q<|<Mm>qUY0!wdHzi&F zENlB}azc-ol`w^>ddtI%5rF^ID06Tw%BfF|wphjF?ZCm{sJ8Iy_Re8@&D_DIvQjlb z8GkCKk4%oHY&Q^3mbMXxyE)~7KBr4+qC*_5hBBYyrYk99rx_I|?j@AMduAl->GK0R z`GNA<wf}dHr18&XD-{W$;pRLR8*xc7Zrk8nS+TCj%q$K;weWi!0^D6=s0_ZSbU475 zZcD3rDb9xmqnzudIv-F}iGg8ZM^T<cR28f0E(o<7KtpcNNc52*9upNrRicE7*><tI zKCytC%D`T(g40<#>-TBp_i?q|jZS^o<AeQ$Bk)o2>#mvI2j}H1J@u6z=jLEsK<2H- zWPf!#@#=|LdA~saF3M%$#Z)>F9I9smy`4QU?KE}MqP%1U#lNp^w(uWi3052g>3Dd* z!f=H`Nv3M?mIx}sya;(vurPCB2l-XJ{2NoYvbTbEO?mU4Y%aJbMujz2s6#)`>L3hj ztMa1!oSwB2$#Wr{P=W#JX(x7q4B*!P-^$tshK|10oOY={6nrjcd0;0yW|f=6x?oJ= zu5+fC;3$2haASlkN~qV%vPM;8t-xgNB0+ycWR{wkQ5b5t^cmu(ujDO!^<ghlT1Dj2 zIy?zg82JS(%v$nMoUGWbF3!)+a+Pgy0?0CG5(wHbDocvR6BN^;<0K!nOOpu})xE-l z2f+d6q=0*uKGqEE0dvGCOms!oMZ3DeYb%?!{20O=D=PxzB1OILYMo$W!BFyCO88W7 z708nNbE<af@KOH+14^d=Axo<P$(q1-nr3qt^E}!^DhUs=xpTvyvAzv15NwVgc>iX9 zzAyC~9nL++4KFY$VHcD!lt-P^`Qe?O!2L5(mfuU>6b-7_1&yp_Wrv>*9l$~dOoXM@ zSAxs=2$7)|nK7+!#PhZ-(1eko2g`A?Dne0H$}rwa@qK{MK21W#0qPsR_J7@<mrE2y z`%&;Bo(!=R2zLL5f|L-43S>dqO2=_xt0OWE)?8`$s+t*qCn=URiw+Eq8zPzpV35;Q zTyhn%I^Ci8m@!ag9I=fQNdRMT(v(&#fS<pZTShLK*?b43Xz6%MHGR;E#c%q8@TZs? z6zIYxUoXgiaPbI}XDhn8a1%#*MDJN;m>$~dc*wO*9%w5F{2TLiwvyw=7AE**G64fG z3!C3fGJK@mxxLi%H?X8Jlg?n=NOuAs{_o*Z=Sj0TSry!5GVT==w@`8`Y>D8$<aoGE zD8BqDdU-c$`<#nA_!86+)HWY{Mfw0m5SBEU#r&~UkqeOS>mjoEo;YO4l@M01fjlY@ zT!t-$t>Xf`7-j)mrb#GZ{IZ2x_iR_fLu<Vsy!!XRY+KA+Cx&M*Cv5M09+sW&8rOqt z?Wo3a5H|D%7w=0!O)6Kzd77pG?kP^LDzbzbkTf~S7LD7kMtKFf$_th)xmseD(|2u3 zDwCE5U2ID-I1@;bk6~frI)#nX|1a6HZp1}Q%v}#xD*mTpR-=SaipfzJ!rxH(=L2wk z@t4Q?ZY|z01?xTAg5r*zCvPg_+lYrNF(})N=(bE0guXyAMadu7J}C+UzFSC_LEcRO zJCrdu@O92c-bd_*Ozfa%roZQ}0VxJ^!WRpQPqAE37`$rYB-Xs@BEg)uQ*y<-OKgCV zRaLaHIy7dIRIERhLueJdb4NqN0Rg`vNVR~q2WJZVnLFvJ>o^iTZ4zG9Yl%v?fM2~i z(oe7GlA`aTRMGTAFCzL}YIY18m_N>h=8QP(J7(J;RjcRwz&*+62!cgbB0dxLwxN_i z5ShIjS&IS=R+4_$cO?75<20uJen>Y=Dz=>it^@H_nJt<TVRZ;4m%Y*xv+qV$>Ak7t z>9>z!R*|YSWClU54|P*&)4j7)rliQkLQ>;*CGMX~9iOpj-?A;6H6yoDcD+Rrqeyb` zNdzApbp~BOTn38QsnoCJemlf%;;-)a`eW)SQI0i3ke(HoI%n#-vqC#mB9gio7&d6$ zISQDNY+CBcg}m^$Q+KCjC{&LJtVYq)s=a`qbd<f`1e^J1;_XSX&EtwXK4+0Z3!{80 zm8k($#P008n_O9YgaiotWJ(m$7JUb^r`y?*V)+DyGR~J0d}2|yR<&8$tm~hY<6(e5 z%&&#?_fIsOw+`WTQ5xg$+>?~>K?zyhOgAC*w;B^`xuR>Xc52K1&9|XcpZ6~*RZg=y zN0SEUSe$ALuX~Vdh1*_#rPx+by^6LN5fPy2QU;b=^IW4Rvo(rEpj-TItpo*{pNycD z(2q#3iIdmZ?rL%hupIcR2%0;fkjBLg3;hP9Sh))1i{*5SyQ1GHSBvT2%~#2{c$!U5 zvZu*Nlyeu@6jQ;RB*3vi55%)5@j;p*FG_LnrQ<E_wm3P6bQdVgU62yVWv8_-OD;Yb zm0^C|H&lj;Ig6R~f#LK%C}B7(A{w(G(;CDLUsn2oU|o=-?;+G;gyO=WfSdic@*Cq! zS<s`579if>h{0WZ{b8PBe)mAw6C8VaVQA!Ye7j@vUR^WN0G|LLTVcXp&laO09@g{9 z9=W$#M<6fA9O#%vshL2bYZyJWF%MTOL6Wk2fR`s}rBFA7xQ3nQ`dJfh+1CZ5rP>Fx zI09Ha(Id*=60NZlqTv{)Y6kql4xK%Wqqq5Jo24rp1b-A@n$?5+v%p61nCx7OkjsLi zLw~BdY?0QlfLOt;2NMJQ_d-Fq428BgK_ya6O;#JZTj!<JI|=zCi7g(5jY~x#3&;S* zT^!E-dnY(hoqJS6l*V~ivyzw#H5bJ_PM>EX7cx-%fsR`rW%L}-pESs<8K_|cNP=oE zi~q3Vrh;)ghx`%5BM3rT6$fg=)P&?D4O{MXT;+GLL%JwXQ%Y!f(B1wMSeHZ!_ak*k zQt}7*m?T=K6;p4UZxS9-{wQJgSjYGumGIUM>7>^A5jE(az<GxSsnIp+;Ug?5x8=p7 z4>{uzXDZzJAJPq>d~4=<M{&vlo~;*!=F>LDgPy|j(4o;QOF+_lq__k^$x?0R^@bgv zb%>h!FHrRw*&Xn5^Wi!?zSfM=$XN-``SAA|oYh~b<yl?7q1rV>OSHV1kdlRR0MSaE zF>yag<!n!z`qAU5(XGVQEj%N55f)iRR5jfjOy1f)g!dCZc*#o7O&pmLS-hY%sMrAY zx0h<+KzNb>pmDmkN@X<Em^B3Fl}Tb)cC=3rq;q>88CR8fXkB8LZrY*TcRh9t?2)Fb zL}%9>GQG5Mi~D=<stwN6w7K8)lOdvv$UD~Yov92*Ay9N0j1<={pmHfH)++iWitqq& zjCwB!(>n}EF+@1TQg{+_BmBP*0<+b4?Di=V7IYCOxDgSPx(uC&w*$(uQykcjGk0l0 ziloq$0K*!##n(yn_zWG0B=&eb23y_ljFjR?L*u-dgTUV-Z;PsgzfOGrv@Hz)8j8nq zc?7tweW*u5O&R(R^X$M&Ckev&UR8)9@i2;WmvISW;JQ@;|72~jkUddHlO6SB`=z6n zB=&cRO)}oH_wGUas3Q(?&>;*!{$%2KHBO-Wu@@cJB}7#u*#f2di6+J1NO;X+)n>)_ zKBO4xtlHA4$8cNo+NxtTrRrZ14>?;LLD=D^=*TY}jKte-LaFLoLQ0>gVP7(}7C%m6 z$4Q}Ttj8z8i%tmyuwaN~WTE_a$e@<`2(xaIO~Mk|_Lxyx`jkW}mWUpF{)wh)OqC9r z;zNjU{Xkz~!sT`MDr(O2y|OTP4p5I&Mf561_n}sXOyZJ0Br5svlfV08o+{QCPNL4X z9N~NXmZ#-DcoBL}>&g3m{kkYto%CCnn1NJ7CnSg0MdGS%>ewujB?e_kDU!HtS{0bY zYiym+x(>L@cBjyrqrI-&1ccMChysEP817~HM7rooYZt}$*t0{}iiza}??uTTMw_@o zvwn(=9*ny=PkL*=>3m#sSNoxNY+&)s|I3-tk4NT<ns~T$BqX55ef*%w47FJ2T)V3E z&B;08oDXGtV6}hCIp_Pef3eEnwaMzkbSo@hJMf~IR_E*JM<u&pah3bQ|4ZhTjsPyP z)k1=Z%5AE4@ZOvGL|Izd(UvD6fy4EXlv+xw;E5N4Aji&NtEWfn?OB%a<_AZGj6*8R zTmVfid-=a-QeCy^T}d}J<6jB7YH2ZKijaq0_AhpxsEonuC$Wqgh4)1HSxA)0xX`z6 zT2sRofD1u4mwQ<u@h;;S!c*w4oLIs!_Z^NI;Tg^xWO02-YtEM2-3d1n+S2{dJ`DV{ zZ2lyNg%d;iyUh87TH)_5%h%Ak8kaBpSYE^o)bmrhvh=clJuGcIhT>3)zPqpy+W7q? z59lA2OixVIij-M@(D|E>xp&$OpXbNL?(iA=@=ScvpBPV~<QQ79jD8dtJB%D`3*$y# zbL-1=FRa^hlZ;%d-U=kaw{nLsd{GqB!J3Rm$~~!u{)7peG|1dpE_m%S-z@&4><xb5 z!&Q52`tqEvKkQhRd4YtG8Jk-!!uEKbJ|V$Cf8gT%G?2Pw^_MS@3s0U_Lvkj6{C=IB zopM?-x47SeBtmBQI{kX@R$KPKL%@-~M4O`MS3^PGIUp=_I!Mp|SmIB^*=GC@8^So` zdFZq$f9^6o+j*Bmr*4kYDk8(T#PbjlcQmzm;<SDXfQcjzo7*Hc6{Pob)cvZL)6mD7 zY^pH@`rVs5L+rHZgiG5H+iZT;<}T};#qj>XiSHKy@Fra}wRKuUVNlka`7V8yUjyru z>jeDUF>$m7)#_#=3@~5uC;rWEq9T+mD@KD)(hIL<lQdjDT-Wf{TVm(sgQBCKfR3-P z0y>KSxp)D9oM0eL|CIVl-U3KIaWeO$TBJ_S{AZeOPu`-wK?@wv7uMZ1ZhqI?CBb9} zZtD}1FYEr`{$rzid&ZsY-8K>}PfYLh!+Aueeh}|g*_Ju9^QR8O1dGh`fwdx<J*dgc zL)I9d;lRZpIzxjm+65eDyB6IVIs@Q4nG3Bh@Uc<y8|}9xpB(d-ok=*2;&Dw<8I+I~ z2a9Er#-j^$r0JLHTui(UZsww`=-8eNZ)!_LFMA7~NEv-g^piX9)4gnN=PXVk$BZB& zw~9MmoV~;VouQGewMVM<V1=z<jDt(?fvLu4dc89B4{JNgD;XbED>Lh<cXGOY|2cr; z>M5Dra?D?hz7%Kl1GKuDjASvD1c2Pi=1KxDx%wVRgj{nbyh||B)-4}8x<|fy<$bk1 z%2r8A?eGhBC4JW!omh=Fk4?_ba2X%IQUEfhXKeZg9On1_S)=XvW1(|Ej8REHqWX#Y zO$~WAZ@TsOP3e!(;lKZmFUG$$A~{T6Q64*36rPi*+yCx`%v<9)t5dTtr#tsw+Fh(# z1xM-^Wv8@-aRZB2UOBx}jL+EBY5O<r4P07(!<H5cw&}n@bTv7Vx9Gm6Ys`|JA`a8) z7IgD|8w?u$Zf^D@+tCFrbzYfhYtjhFrm62G*F|i5^7DY;`aH#W+|EcwfTH!!Q88iS znO)2!9$(^V(zm@5&P}TTe~X@^Y8~TohwkQV#xNgNYaM63hf`zZ9ng@U9JyVYPVA}k zQj-{c3$`@6@58-ZJ$3(&wJzqO&6J3?{~R>^Y_p;FdV86(F!$Z<4kV9crt>vVNevjP zavZJFQ`eGDu^ElM^x;K2PnwXk4V-EPRBJIXb2e$)b6cgV-O>@ZX^X(Gx-$Cph9x~s z6?u<jErPo=;t{P{HJLZ-NSXi5@f&UEWMr{b*ITep)A$CD;B2M8H?8O5X1wIiXavo; zJxO{O6m(`9e_>@-7wy$E`-&W@H6j`+#y!xoROaj5?JVB@LRNOs%=H*ue+UQnGgxC) zqNd+F;HEV}NFb6j?kedW>foxIUYv2KXI_UHX*MSDS)~@AYyGV<T}Fear9U=Ms*_ot z6^OomH2P%cvQR6IYln{coP_*)+d{@0ciaFb(Lz+M=cTi1oY=G9d5YRJjw-ZBzP(ng zv?@Qk5hQ_VazZclAMnsL24`Fvva7MvcG0v6hgaHxz}d?^{uMOA=a_{vG?&f89#zci zYK`SY{r9`s%l+N_<6JTBLW`*Se?>hM&A|z%_iJ{je1lpg8E<$>3PIdM?P^-)PS#?E z@F4+L1G81nmv4VRgE5xrW`)cQgVUlI!k>|v4zi0q4ZQ}p_Gb6OhU|oP=-8}m?GBaI zoF<_9&hy2`GaO!RNH48pCk|BYzncn~Zs;j3PjXdz<3hLH)PhRA=i*~)Oe5-!H8IVI z8n++n=6LtAyL`6tz3rK25bTj{eH3L{1Lzz=lO)x3u+|t>!E%a?k}|fc$uCPtsbg-^ z;=3<jtgzOb|38NVRu1O>VWoKH|EE$s8!J1@|J30iT92=mz7_F&yOzsL{;mpHISHh{ zhe$G>!!aI$L6?i#_UkK*G+Q;b5hChru-%#3i4Dj=ec{>ssHA_O_Vl%0DL1I*U(T*O zYE!X0=1&?pep4}r!SHldg`_*Bp=YxP=vrepJ6K#8<Ls%jCmd?I(J$U>=;>(sle`RN zq&u%+aAr6xvo`S0oN+cFz^>br2CC&@&c-$+)xIv4<Loit&1X%&@aHqvn~ko?+tEzG z%Vl{?d0IbS?T1Dk?}gc1Oz;Z}E%aag7L2;ePIK0~S@q3d)FGM|>=ykl>i*RYJ2MH( zJa~^E!!|C@EkicdUZ1x9il@JJ_>|*W^P4y6m+%;_jl6FsYkh-4)Drdt)Szm7`_O`< zS7TbVr;gqdmyTY1{O3Z@bsfg-M*AKJTCbA(A3lq0dfWK><yeQRy*KPYJPc@0z&cgv z3$v%6+8XfMYoEfjg#z0YRnHAu%$jGNy6B@wpd0;pd7cwnhVl2G&vK)zuqxR#@QZ>V zSx%nUTZT8!ATp<ZSHlvn6S%7YuHTLp_6xtVT9^oPUuZ%TyZvhz7KbmqH`s}sq8cbL z47~iCl@U!`SC<2K;%eU3PJ5$#yS_k{AFVU*|D?ZZzxAGLmZRaItoF{04YcXZRJ-yi zwURbQhj2?itq5nmgjFv$Vl)h2eCqUU?O$SnQ#K4I7y7NzE^>fE_Y7~Mf>Y|W$(a-K z*IYU^lQ@b#wVgWcEPLzXM>x60R#p;D5V*66Uc^lL(%%_Aw)Ousx#+R>)?y0%kZSaE zX=YVm&Az=DChYn6&Q$mLIDS>@|9<fFo%ikQ<MvA6`&`q%d;ICO%h$oAQ?I0jb#dDO zbbzDis*WfQHjHHi%=E_yLFrX8`R_drj$qu|yH>)_*E5HnPa!_|$@lk*(%hWU`iL7W z?j^jrZvZs{rhy2LDuv!p5rLz~%<gvwn<v~0VhQ_(G6lUN8NuB7;+`mDf%GYgPYq~W zC*XMxn*)HdFeXd@iXdhzZnQqEBs`e@vMZDjW_*RJgDPsTjn*021OgZn<!$1qQ6B>a z1S1d_6J`KLkPz$6ZF5ornMJn=D>p!W*dr?Ipzrz!8ca!$iVr+)l!yVrpXqxPBa;7H zjW(utEt0G`g2MWs*+_T`7QtSuJ|c7!YskL%6ch6<6IN<-uK-8WI%**<>Cphkq*tU} zst5c&>}VmPtawx;ANWbKlK{u4m+s{z+DzwQrl@!oVgwVQDvZfoKwS!}lzdsX9fgE^ zFcStjbf4yeJB*3awjP#t*%cZ}$^NNLIVC9n+<y=PxM#zJ%2cFHLm@3y6U5@449=(9 zd|U#}cfM&}$RVZdNdKEm#u>3&b_R}e%Hu-3;CdW**b1dL^WO5p+m#N%`HB<`Y&(gA zlq<n+$Qx}E!C*^w8!=|G=P?z!GZ<FRxqlpqdBez%ngiFH(Ou1l&!FXXVJ^R#fs}LD z>o9~T*BnnKqpT3vl#Rg)V6tRE#~jKVRplXy!gDf;(#94ARf59)UG<YsdAmNHjE^B| zmM3!#VgPF(n3?BJPY=r$z3CqmsRS*N6rkXBeiAsM1S5jQ4QB*HDnX1;3>3tY{x-G? zGt3g8NSpVXo-MHmx)1A{jsCQ&bw-DFG>{;ps4P$;EK&<YdW(dtvQL+9^FakMV{?P| zX?|P(n>FGnF<*BhkF#_^3Zn9*|6<<B2x~HBYm6<$X?Bb)Lw?q`X>3I3Y1R@-^l4T* zA*(K`?)(l(J6(L9`WqU_wbPf%uTY@m9FO^N{sS`p7iV7q7FE=)D_znljdTq)bax{l z(%lUXEgb_0Qc?m#r%HD#UD6^TNT)O^2ngOi!~dUq&U63spL?&5&%3_8_R3lFt?&EZ zHSAq>KbYbnldM$9sDgASaBdL-ZX6?1B9DuwAI2UR8zsVck3P9R3fC%|wte{z&;%Ai z_6JpVlG2YHVLFFnBhP3%1$|*hTT0Ece}GoD#&jSI`aE)Fv+}Sz2EewR0qn8ZbZ$oA z;35Hyj54dCZZ{Cj?_l%f#h&DZRuK7#<ZGSI*wf$>5&<3D6mAC8;7=pIb8!4x8X>i_ zWiBgRS<c}osrAK-xRJKJ%o}A@PC)fVL5^&2j63=-n)XMZ{q~|IIbX<bIZ$IhaB)(F z$nAfw^qm@l9lA5`*-VTK%hGviDd8C>rQYCKah2IL(i*4=`mUKcvZy9mNqoOSjk-SW zHRQ^A@pAR;uA^l2D19Iyle(r}klOj9sSYgf%h5or-b7@7R#}cV&46$&SDO`_P^+bL z^NX>?v`|~77l)}^-%M^ZWE9qpP^>!su1F9xU!IWGdH2T5U-veD@0uZ3JtLI-<ajPS zDURMN^ry>$-c@+D1Fh(jnMFwR)$u@AZPleDwCrtyc*1WL7NQeE%%zP>yzpAwkQ02& zrIpJf1D3+Ru>h-%GxJYl8a_2j-X^po9rb=_QAdk`Ph=JnyZlhoat+Vr42<IVEka&v zcZJNq-ehbic9>)cV3aWe-aQvq@4Bb?z;1Dh)5K0Wt<&Bhqo~t*KF?VPs+?5Mn$-Ez zAmga>6b^?5zFbaJj)!$qW8QY6pW?mesOhG0g##Cc-v`_6Pr1N>69I;Hs-v7<031M? z^yoMwEYc*+x6r!lgLb#O>VsN>Zbyo9=PO4iSONsAxn2fvS91<2e>NG(V>>SjsSVm= zmi+ekJR+oaQ_1`tUh~b-uS?6oRrBDajP~v5nAm!U*v?mUXJjw_9+ytW<)GaLqR@LQ zCqi3KGi(?@9RpAJ++^PMk-%smR9I5|Ib?xs8wr^foS<*p;&D98$3@22Pn{RF{E<xi z+)g3-rSqQx82m{V{q0L&XvcHdS(+Gfm~vs3v{zrOaW9)`_`+git1?^k^H6qQkUk11 zLlg0^XsQ)RN_BmMpHn9=-|GtLaHL{DEtIJZ5b>&#T#b-+SJa2}Qz!}W=VR?~$a2wx z6=0Z-)~HAqg0zZ>xMu9;hcuKUQ;!XJ)E9$z3!5nVyS`g(QYPcY^2NS?XE2DnK=o)` zrQ%V`YetOcya3USF=+ovgm;i<<0D1a)UoZMT*s_#=TARJCS{yn`sF|;;q70%3tu(m zx&)}E)G1t#SPE&&+I>^CGhwFPor-jflZ}lzlkL3aXXpw1<*WpCv#fnTJ$GxrJ)BjR zNJ_P8mlRH|Hb_Z%$SvHbQspW|N?=EDsn$zV;_D^fqDYYZ`4AOJm3gBAdbMphqJt6u z8hi+DqTrkQY;B%D@AYQh{|TeU_$_+l&y<bru@I9dQhh&jsF;GzkA;O*T36>h+>=jV zwyiGHuQPgmK;m8(faA-Cck}OuRT9Z6H)C_9+GHyUQ7f7jN>iz92aES)D+dYChJHH4 zWnLv#*~U(%N;S?tS`YH4Lq&EblW+arND@InPZ5Bv5S_JYV9Px8iqnvjaWKr%{7EJA zj~7UU0o=mDjubBEZ%w>+Vz18gysIRLQRwX(_g>LwX%mFOioZi;J)PUMA)X<E%TUyQ za>(ah%Ja>Cs(r_Sb(E%y3>m!|{hHyTNO!<j<%O>qfx=S?WOx2#MkCK7Dd=2f2{$9F zST|<gToYst#>$#%l}Yy7ZD4->#lio&aC<pWY2jyP;K?IhEaY`2HG*B5FqMZdo{nRh zY`+i`9#oq`u6YbB%ii1$=FRboU*O(vvRyAItvXC=@&;|S7z<b#@y<H)TuKj~*)qwG z>BOfmlope5su2LMF(J^ZQWW=U(W>H%tM~O#uloFu(;~i<`9$rA#r>~4E`RP$EZcr_ zp!!!#W=te&!YH~}w%jwJF#pO_V{dWikq(^>_6|}jtta$vW^ph#z+Z25#JX-{ag!;+ zSZ;q1Ys4SR4JpMDHQp4LXPPv5JRlSj;qEunHjeGE1ix@@%Z<|qml6gmv(WCh&N*@F zygth3t=6gD%U^h(zUU}JA?trQ$0l~edhz{7UD<)2Eu(UrHP=pq^7Erl4k!^<hhlGg zgUn?dU&-hOuDrMtAze^Oi8vG)aZRCS&EkS=GF3hn1j%v8c@S#J?*EuK`njgG>~*;w zV$+&2wM5+aOx|JZfl>leY<3~v16cw6hccfGC#ULGQeL9c?3o^=aOGhm+Y@;Z@}&C5 zHzjO&sc(NNVs2xeMXz)a>pt#R1sS@V&Gl+_n}A(EzCzM+1kQUtK&S3*W8reQ`c{T4 z)v4i@3IW$^oD373MwUVWR<i79uQ{AIsB4#Ro1^G0ZTP4_$#<Qr)ak<WN)beoex2s% zSqUyB21;?rJwdcGy!mD<l4RL=H+rFWM6e`4tEjp23<6oT7-KQAYFZ?lv3lb|O$L+* z^eNNmT}dkQw+xL=rc~lcOHySUBfPDn1WSk+Vf48ag{b?sL`un8_HoH7%&I9|sF1az zBilw=r!66V<0Q;3yB7ya(K4P&Q7d2M4}=7~gP8Hh-SSt+lnw-bUX-lT{+Pq3;q>0w za$rw*AhE~vRp(2`)5Wa-WuwU4Sr^8h;l*=TA~&`J$*0pyU$wskmh^r&=2x;z=C^(@ zSiy{L8T)QBjXD#Vie2rrOo{nmljHRs)TImGaR#%Tn20_N^Z;3DD8VEkgwr4rqcLTP zohH9tzc^v(jNL`>YY-i9!Fh&(&4(N&SCnvh7O;DMbwjA+J>{|`#<=<S<eWgMAXyPJ zTn_l18n#jYH|Vo{!nG29H+HFReU(Y}tt|yN1{zjY=gOTN;yDi4kI{ToZ<H#NQ=vbv zmJF0U6(C!9J_$J!dM_kMk;1fhh@LV>t$kx+4q7`RW%kzSTzO3}JYU|Xbj&;7x~Ngy zC+FLcrL=CD&jc>|=GTFxP#jj5BcnvZ>q|WBe}|qzNWEEadRLnx-Rogo4<JBHT-hkx zY+nTUF@FWMOpf7BFZuvk!<*6NXjgrZt3LNT3ZjW$TS<l7=pQ4ZgK~@fA2K{3f0Hgp zK#Cc_vUTwDxf>Hj+jdjBs{JOU`77L-l(gbi@#SL>yb?ySmTD-nkbYyvC~9mv_azIV zg(du$4Qz3mn4JFvNaZJBe;>g9?((!(Et14A2&`hoTh4$+CWotA@Y(vd($3N87O*1I z$m|r)Dg96xJAG8Fi1fuuc(FKXbl*g!C;l=K)&C+6er;VUj~!pPq5Fo5_}U=P4b|&w zn59++3Cozp-8V5Rt4GG|o$`$A#-1k*#%CU`P7Ti@DrDGX!SrOZtt9p*s0=bChA&kJ zRbL}BWBz!gMzA43>tl$zt`mbs00@89bXduyicW@=;s_<c13dz#Fuvld%7A=thekrd z6R$(CH4@Rwi=>_4#N5f%4G&pyx1Btj-CzZnfcK8X;y9_8SKgt%w}L|mN8elmy`}t{ z1oVEJACBlbq=0(8Ug9>XA9f82&fwQ2!31`ZaY|qpk;Ae^uFEq@sS)O^2DFP-bS!q( zuvl&<ez)E(ic})AO4YCjc>S;~375r4O8rVo0txGsEOVL+db-F%Qt$?k!c=U>lnkTu zK)YmUY2U+@W=UW(GrZKWd#T&guFRoclI)Wto3Zz2yuF-Wz5jPRE4q4PU(0cL&v|E0 zOGL5YkU~V_k2r;w%{yOq)60q6Ix8oso(#Of{Y`viS2anMZYLD+;JrZ4OH`Q3_txq5 zth&qr#KwRN%phO43VPKUM!|>Nf06ZAaTORGyGW-wCqwCa?v<K~lmBcNkuK$mw?|Z3 zwD317Ml_Fh>A$I{bbz%e*bbG6Z2p&=iy-(vzd}IP$J@~Z!p6>{=j82b2c%DZtex#_ zya7obVrS(I+|#hqvooakbMkhicMR~fgFx);={>D%T&x`I*m<-e9=1L<b`UmCTYI1w zHy;Sh3*r-G=TWx{@biG!da<!%-?!xC;jUoiZAZ_hAjZ!N{QZakKk$bm`~ti}oV@(3 zyu7SHIZY4S|EY)`#LCmt&X%4>$;#Es4x2|?Ptg#h<m2jUZRPH62cc)vb9C~e2marW zhl^g{4&nuLO)miA0|ReQ;1?3)<_8J=bDThVU~U>tzIOD$pup_(E}mB2j$U?F^uGV7 zCj{aL@v>t}Nx}Im4{K*^K0dGz|G#0aM1<ilS%7$X(~FAy?^iH@!NNlSx13d1j!6>j z(DUe%E6yEVY=ZiZch{(xs1FZ7i8TEa=?nz3tWZpRWPIfFlOGeGj@6GtejHWzFNCqR z#0Wf%sjhzUt~=$D>~@1J>F=DP?t(#cl;OoQL$#D(QgV;G-v^DqD+4Tc6j6B=GVD_5 zZ|1g6S;}u_cyv1@mNM!q#+*L9i(iq*aMhW;?INh2K7u?o1>dyt%odd%QkHeTiGeKD zbCt#5Epn6nskXhq(TmGz<ci;JmCo?N(z+bt=Sr1Vz*C<Jk|4_@=zT74EGJeu9Dp@& zq_$J9km(y)ph~jj!4~qetXVZO$$I#PDh|X)drf9y&Cx;1%+=~|nxGCjZWZPp>DaUj zP~Av+Z>LJx{2u8^$$0M43=jL(cxuncYiq2VXJ)#<`|aFDj_n_1a4jWTJ<9A1urw)S zRu-?`VJ^?P%wXQFUtRmA3mfkKseZ=bHnaBiv9R!-uEuD0V`)_DL0AQwQwz7{nA#V! zs3(}Y-klGdTl*%~&KilAELi;qoxaxKP#^WuvRggv`R2&cI$PTL!ORlI*^wIIT9jKF z-1TjLwmQ?*z#Bg%$Fb3DME*cN!`(xDNV46{v$=L;?g%?=rAEHmU-V0IEU$Flz*7H( z7m<)W^Vd83f!x>Ub%VLD$DT`9S1h4OP;9;XecLWu?YvOL3dl5*?s?N}9ia~)g3wK) zKPEqD4Xl2=YU^Xo!8jbe;O5eVN!+Z*IPlzccGJ*heh9rh^ZIu8=xFxf@+5ERM}#!d z2MdzN&rkn)iGE-_^4r2V9$uo+zWq)UN3|?3ybvPa86v;nj_Ka9UJkVJ^ZMxE34WIM zHjT7o;MKWKX202I6k63ATznDRA2IRxZ%i(z+&|s^sp}s7dwU!4X|22a+}WplyIo1z zAcvbijOq8BW{y#6Q&<br_!+y@qUrfoi@E>)g(}^cqsYZXfUK>)ZLg@wn8-Qkv7pEG zn#6KlPtEhk?>h*&Yu<LG5Ei+7VyJ4H%eZtnUOWn%!2G-LLu24qto)SED{k40FE764 zv-{-}zICA@`trT+tA5gV?E<S|ZJ#5bZ+Yx@#{$lv#vNBpzDh=Y`Sz)ThH=_=jeQ^1 z?*tggvjR4#h02@0%$#$~{X#w&Xgy%LyxiKS4QelVzeJ)$;gs<;NNvOVi95wR-=hJg zlR0_C>A>n(zQ!U?bmvHq<RfDhp)Qe}ir@~T?G>Q`e&(v2s1+Szb-Zt#O_UhE&8;>r zKe`;=(X;pJ*$(ehIrC5_$8DLvOVGY__<1bwmh8lYqCVr;raHFZ>kP?3u@9EpY8m8j zmJq?3X#b<g@wN=GiLVfepkwUn5!QV3{&RdOv#B{Zjs-(Y%!rR0VVBC!go9!4-;+7# zc5rT(HK<j{BhjEJe)c;|$tm1Ewm%{@NQ!Ohn5>+}@~!<XF+^>Z>tr}7xt`Sa)ipEq zShAt$=S5-d+$45{=iK&N=BsxsZqk}p=9pDY(05g7LN9bo*58U+KEd}=3Wa_2KFRuS z>e9VgwlW0%JS|GF%@;V!qI;p;^&*@0a%~pP>|0r!fcEJiKk1E;*IQ)6sAt?wMqfkt z&%0u)${0zb1YS#cN61hwPl*K)^)y)}bq7v*XFdDmv%3z4r9RkYe1t^T==<iUq@%#H zm&J+s^9BCa>hhPaasDz3*I)>H0B!p>@g{kk^KXVZ%uKr}2g4kt;->nmImeU3T@IAG zj1S~*YteV!&Tf8uC$Hh(I(sx(;<EI!6(b+C_gyG~U8QQI3I(KXP@XuKNlEzeR8g8} ztSgnzY$&&|KkbWldxrfprldx9vB_flWv>BK`EO4NC{Zm^+w{!TOIvEUJ(ixhP0X8~ zwPrjaS1|aqbb$BBaxKTWsp_%8%lDt2wV9>k6kVSM-^_mqF_sRB;5fQnYB^b@i4pJ9 zWd0~TTj{?2T!W-G%I$3Y3fWHn$9vq5?^QXPmHPN9?8d@H5|0(W<v=>CqByrlTZ@dg zk$pqr<1~G*C+CzG#j1Tqhxu?IA7!@lI|fd64)QPOxAhL#h{c=i6?&T8Donf5Vr>NE z#ROuzK|g)kel__ea!#h3QYzq1d2CX6mqaw_*&g%CNWW*`dtz%OyKz@t^P&6BU)zlC z?IdlWY|nX}umS{G_#ugpUcB#H5GClHl_^>^d|vS%@6^JrX0zQ1%23vbUOe2J@=R{$ z@j@xCaVML9k&5}p^>-u(m<VF-Mf?cq?~H)kzRDBj7h*Fw292XjK5l4|_z}-;hJ)qi zb-g!}u??<Bewev6U1QU!8aceT@o|28Niz6g%fE`XE<vW4>}PQ~UGPqv{>zT)sxOV% z#9N2!+R|bDZdH64Rp0GakDaMJ85`r?mx<YveBRWaw)#TK`qW-@T7OTukPaF`q7*a5 z@p8T?SOdwMUb2H^`db7Ajq}o{w!#@f)S#rkZ+sZR^0<!a^AAcq9(8*xmT4t594uox z>`YC|DdW&oJ)|pL%zSm0j=XoRuGUReFZ;8*=F#E<c4{3I1$@6oO;sIzO0DAPS7!2G z-|U%ME558_I(XTvrp!rG<=x01l%~IrGQ`X5t?ncLJJ!<)2`a#1LKR_rBs0$=yxXn0 z9QLJ4gl}u#)Rc1XflLtdr-qWkpT*NjO45{lLyqZ^o)5#hH#}cACM=9*#Bxj&)CfLy zs$p22CTsF&7MW^$Z0F~V)?|o;)SRU=vn(?GWly=7E+GW06f^zq^dlda%JX1Lsw(8< zTSHvx*_6caLGB@M<t696q$xrArv=Xyiyk<kd3UXNRD8XC*&H77@TU#%G@fF{DR|{d zq+E5GNi)=RJnqFf{u#F-okg*;7s@74aaC3)jrPQfCkd4jF^b*=d!mOLCf9sZNhy4U zPU<DxIyElwpQG8*TJ4kZiwd_ygm>S{T=Jb<lM#@VY*MHxIm_f^Q*w~M+xSHL%}{Du zXeKaaCH~b*6_X8elTjbH>C;4aD%syJ^$1GHj-o5MTsZb%CywH1Y&r4Dz@g`daaL?f zvXlp3hol__K+{PtLo|NcSZgpDr}z4}m232`2`xD8pgT6WYwF7CeW6GW6><x`jkOI} zh~7$!O7L}8r<fMHc6C}?Q{*(d$!hnuEn+05$?|XI9~a9W68|1j8vY>3>yXgQ*1dv) z+0Oe9nktfsbPM~4q4ctX9Q)qU164EBPORt}=5*3O!ZxoPV9EPK8q)UHDG!fErta#S z+DN4}lWnMAZ>$gSXxMt6f1W02P+Wh%-EoDKJE}v@`k?7*ozmEObvm?I1djx(ByH#L zQ=P5v6Z=c37L!aMaw8A9!=Vcre>(_l(X`oL=@_Uu&9+-eo5Juyd5KmIRe4D8t=P{m zRu_6qrJ^r1L-I~*SnC5HckujtyuXl|7|cH3bVTSAq9lVcArw)kcj(G9i-wZaQFYuM zawAHcC90fE(C*q_$&o#3d?OU8>TVmO-L0n|yD3La&T7hTFgQ0rc=MQ!E%t)u%2`|t z8z)s!-df?xhp|b19)bh@GM!Mk_(~+=z4EaPixX#k02PZvyVCdM)=|@M(b37T25yMW zJhpZZTXbumP3xC?Jx|lE9miaeD3X~Mu5mFLBHWk?EmFi~Uq4KmMvwdRP$fVn)n_hs zls@V?!>jmms+WUuV6xEXy~h=`=?n>N317X`Y#32~9*9_WyX_)T{;hBR`zZhJ_uaSh zU%xt*hHNk5C@6G(U{6iPT0FwS5GeX&AUO-uVtx}p^|s%ZfhFD))*|rCHjLUQCvz|{ zF0OULD2GZjwSDczy=QV$wBkmA6S<Y(qvD?UOm(ua;%KS<%|XIzIf)bnA+q|j@jq@B z&xKXr6|I}jn4=`wfgD~}NVn;yU8nLx)7W<=nbS>VU-at9Jtif3OVPwihkd2Z1*~yf zI`O1+9v8c<D%R&*TUI7<tQQ=t(I%qXOhef0+A85h72;VM!?r{dHifR9x6gxb#&Wp7 z<*7XG!NSsd9ITQ@be`5fwp!%A`q$aV?Z~lB*2z&Yxny>)%bVn?nRKI8)51NZ;hH?^ zQ<hX?!Yh`PZWcbQm#U!9n5)NyLEJpB##6abBHaw8uWDO_kCRG*o|&IojEy;z!`?9U zGmSJtKR+%Z8}WT+-pq5Jx8xOSPp_jKE7tqGkU%nOk0Eojw?^TR?2iBI!LRZ0DdgKO z*M`0CBn6R2iHng3)|9*sHv_mYMcS9cw+fLH)DD>E-nn?czapk3B1%g3k7AT(2*tdT z2PsEe95~Jt{aQx`o2Cx^Rei4a;Wj$*!o0cj&)ICu<k75oyg5x@+a%qW@g0Mj!J5r) ztR$b^s12rU3=C3JBkt6^9-uzlordL+de<i>L!(mVn6ufY6?j;oNu22NqZ}W#R?%Zy zKYjmtap2;_Tr8Fm_=V<4m)Q6DyNTimv+p(ijLfv`$}wuDIva83iFo;sU%bB!NI<5{ zHUBOY(X<ja=9vFwZllwqPs_IDqGqpF|LxKVZ?S9Y=jf2ZD*A%xFEf9#td>#h(;%Z2 zs8q}gd)sMe?NW{|b-zA_j@xWSbz?2;Sucd-#ErOjo3x7RUN1{aKTY{lvc<aXsH4iO z7NH}0>%I|Bak;!onlQ^X`D8<1RYnb27Y{ofR<uQu{yXf@EO8|>cS3Pi!8#FAQI1N^ z+`6}|eUe8Zd8OSiO<qz@Y^^hs^g1NXON@DvEkKE9*SmaXE1PoN_2#9L8dw)^Ev>b< zpQelYW3GC~J7p;(T4pi!X;o3<ryI#cF+a~H{qUUD<7oHDwSLkYvrnsuf}d`@Cdvf& zm+ys-`e@>d<KP!%5_N&6eDMa;cuO-kYo9t9d`p?^jWjLW;@^g;k7%n!&y0!Aw>7$~ zhnxBrVFYN5*o<Ojysk=fEzKmZ^m6h=v;xU~J)2g{&g{jWrOu=Lba$p2iedhu2;)j~ z#AEbrD$zh1o9}t#_1nfEMO<+kDdsu$w_2jwx*O?4HH{MNYU4MYFZxq09Mek5m;|>= zR8*DK#AeP**b>g-$hJ$0c_A4o4X+sK88;~&4K1fyd;d*5*x>nd;kJ=Qmg4cm)UMjS zWdxIHhb~DwG{`65iX8h^>spQRE5-DnNCO{#Op53yY1;gp+S%WY<LVB^Q|>eI&+n{D z@EL>ONYLgr^G&=YtGD=|7eQguPqEoLFwCHY#}@z=5q<*Ox9o@k`Or^N1PqGA@)gAr zDr(T-j=O|lDqs2*p(e1*QaFH>2>2pm7mHKcaKt&8pa1o|(8VH3NO63HLd^)JVDCSi z{`hK0xRrdK_;c!0W=Fy2gCgJf9>)^Oa!F8TcGL=RpRX6Gb7Kl9z2Tb(dG){=l>jFR zeFvmb6T}x>hN?O!LeHNFef8U_A3y%dwSv*|$+hW8yg68U=Wh(pbjZ!F!Jt(dVaTgf zn<zTQKZf-&QXj4}o`}6l1)gjC2smb!Q9`aiyfe!8{&PW>lMu<vsPag56jN6zxt{vN z{?Lxc6~iYHMS=5-l$KYWc3a$>=bF+{W_0^hLpDl#{BoIu?XRZnn5B7VLOqpSU{+}L z&*)9=!6E6BW9WPshbIMTtU<W{J#^j-;a22*UB*bvMh@Ug9zsAw((0Gxd|%D*A0;x6 zahU26K!1*FHcQHeOU;eOZ$zJZ4<jF_)M`loeq?`2pN^($q#Xb${CnHPoctU4C6DKC z5=`gt0y0p{6N~wb)qu+3pzu%RB0<;+O_taA;u@=K3f4BYr^#L+9kFyn%AMQ4@y|~; zmc~MFRxJk4H<Av@e~sVd=Xd?aFPT09`4N0<AP>Fzvyb~wx_a^X(eK*Z-zQfWI7?6e z-gPID|NZrRS*q6J&#duKPLlMW(~Zge)sR0OeH%4AQk_BU0T#Ev&$pjwZw^?5JUY3n zjoB#L7op90@fU;kiuc#Q`i+vH;Q#qh6hmD*du$%S`r7%^oAA=}@d*m@nPKxhb$VfU ze}T<oKySiFFF+5^*7fl4hG&CC0NO|wUeDeGaSbQp;MWTDCKAGevb;j_iVFOE3Ic)x ze7u4pd~$+(g1n+&c@af<em*Js|G5azmxi6Y13=XA3k!&dAo!;L`Hi1U-vac^Zv9sM z@FH253XzyVsXJI;^#UW6jl_ZgnIExv;Hsy>%v$=(Vo5owXo4>zZQ50;m|6EB9i65z z@0!RzG~YD|`pjrkj)^d{AhG&<tei<kOPZCi5@p^GKDzrs7P$I8aPsPS@-FX0^m63~ zJMiyHxRjZ>lv!0(_1Rgz+w88Iy0QD05oT=;KXVW>S0tou9@5l{ZOC}3<X-N{UCGJ4 zcsH)pM$`MN7I=ugX+kZL(CAU}douTkaYz$n3Hq#7@wjAJXkCAS#m^Yj>knx%%~>Y1 z>YT=FTS)SMyD)6rwgkz6)<yb2{I;zHz8A_K7cMJVF@i^Y#s)x#5#I)ugHo5#*J&3x zTTDQ{p>&6tF6kz$5)Ux8tq*PX@OrG;)FCcW$^}Npai$Lgaj4TfSPeiD=tJAI!-^wX zA646iAf>%eJ&ljwnx@@6gmH7fbzfpKc<c%lYTKA<^8ST6*%Qzv*5=oX<Ec|^eq41* zWSZfU7RcC%Y_P30+(p*hCn(x<_=33;Pk3u$w2Q=7#`rjK8OI8}9x_;P(8h}q(54KT zj6&N>6F@h60yXn&cykaR9Qe2st!2A;RFZ5ZyaOT#`PLigY2jYJ%(#x?&*o=%T*yni zm*J8TU)~=tl_C!Ev!I~*sgXF?v9WFAU_NY?+QIoM+@IM`9^gaK&k{`akDGb1Pqjci z<Q=8{n*;VWt)?5{Ikc_p<=2~~5QT4cri1Jbou<cGrsc`s2jd}?c?sdXWt$}8-C7{@ z$2=t$XVz4Qra_=`+D$RL&IP$9I*#pnIWwVdqr|oL&k)m?M30pCq7rC(U{H=J2^4Qo z@W#Js*|&{KZd|Hc9@Lx^4bQ1EbzK!Kw5O{{jqfS@@O)fqg`WIzC&%Z*O-%@c+*g|U z!_AIu4SussXm)T=4NSEx{&-06=66UN!HyzOO`5G-wBzTeRzTt+x0d7q>WxDf^lyc# z7l)EYoffKvfI>XZ6&LSSo78I(T`ta2AtqZB*gz9bZEle3APG<XYUATZUh@LYiKu1L zzuYT-I!(ccs#dPQ72BRd&NAv|Gq)#(X~+k|%+dwceFk<0EiF<3freD6(0v$cXk$=3 z?9`^!W^aYb#7X`&!3z8N_O`~3Sqzlnla^>|fWgD(vDanG!EKRpW_%$gph3~m;^M)R z(E*VY^6!IZH;}?zwkj>!P_|25_ZsbnB)>6H8DA(D_~tipTMMKEnD(D6(<D<BwT2|} zoGxF%6c-}ri!%d=9fU!7T<T5<^!*DxFzb`8B6o)E4Ng|+r>+;H(iR&?%CpsCZK!J7 z))!h>V+E$wveo*ANG@B{bM3y^^Sxqiz{|4MUo6o3$yO^FVr2)<5mvr8Zp8xMykj(+ z_q8H*yqNQCbL*`tSTx8VR-}0H<?ub<BR9f9DyNG%a>$u(T}pQFuk>YmtHT0&izd1K zxbcdZjq0*?o1z6a*C>{@H*D7AzCG@3Y4?gouH3$G8(eDvO7uR6!dNRX)ga;Xj#;Y( z(tAxS`iG`*-D_I)=)I;9c)mR)fo0$zDYs32G-@NLWnP_Zl*^$;@{2Z~=m`)-J`Q5- zd@!J?j%zgT(@km~F$Q7Dn-K2h^n5naKYL}ofH%LTA(2}XHNPGWRO*K7T4I>E1*Sl9 zy1+#4Bvf>G?9uLoLoc%T=+Wyyj>Cu?NZ?i;rbmxkTQDRE>bF+CjMV17F4@ZCr*fQf ziX@RH{`gXx0^fVAX?Wo2hGPD(Xs!1O`5?Mvs+Z;dtIVX_0EXR<GXVw^C}(Pk=3+Lp z)=)9Sl!RwQe=)Lq_#?xgVs*YyjBCixluVUA)RqrgU}49+#{<!8$jAolge=Cn+J zmAX5~wvv4rF(UQefgV^z!hpyVi_@wYo?;8j>QJ$dg=I{<s>N;|h9=MSR@G{PqCPV$ z<IO=BN~n4%7Z}Lp+Cj@$O%ROjYOJT)tPWUT7D1I5<HyNgX9AurU}k?~Xe#{?=SlA9 z8}m71VysuPV38)zSd0hjGTh$J-+8~2P2xfJxAnKBKO#;EfI{UN6F+(x?+Z<0naDJV zhctROV<iEl|2XculIA@aKmI*E6QJ*p4er=fR^NSOCDV|kY?Dtmh~s#1=6Lwq<7_AU z+gWkxj}l%X(}tRi(E*b|EtiWqNZV#F1@CxwyAnu97~Q0yraD!e<CPrnJ)4p}bS5!s zsENkQhB6S0cT<YR0_p|7(PL$W`Lv-%$!3Tkrb6(>8GIqT&OLSbetJPCPaOEl7S~<k zoP^t3Bn&3bNId{*3a)Ynp=JjQI@8wsKZK{<CcjC*H_o3Wn0`^i(@xdjM8KDyRK{WW zOpqj}tNI&uL4)jXvXv1dB=6|7_`k)6mUWAMdE93*P>k<eL~Q9MoS8%!vTd**QxnEk zXq72ToGnk`OLmmG#9)d~wN=#P9F<<H1EQ=1^h#*VEOQA|8Nm&qfh<LtSml^1-CHg# z_jukF#~4#tkU57?z5a17T%|0ZPaa&WZ6RzI2(?pZ0Tb8_*A}2=wI;x&Y%9jasHo!p zt8c3qH`}lx?`mS&ut<oOju^stiI%hFB6MnkUCjYuz8cQ=xX5WEHzE48xjOa4p1KpG z#SMD?*ji%)gnXmH=o6!g-0D$PQ!M2f(5W#|5gs5#7%weu91m#bT0Lx}{#3~yt$H+z z3#SHp<f%DfYvhkGU(~nQJW!hCjHj!;2>bQj#2@rY*1TH%IIH$SE~I5E54)pa;n1fT zxPh==pIc51{V|S5-+C09_~RdsWffp2Md7a%!m!?*BGf8N8~ZHHf0`A-lGYn+<vJxG zO033UF6Fxeg<+L?BGhU^t&kvxEV5!zS(6RA)XNrTPbXMNV%<XG@pj=b;Q)M7VN~k* zRO?qJLb5c?U~^DyND`Cg@Wy`Y{#FG2SGs+A1fN;aLa7hLK3&dS<w%`sOM?yVm*EV% zI@PuY8?;h8liMxB1o$A-#k`&3VNc`aj4L`an@2=T*`|74+grTL@KV!hW%zukF21Fq zjYerabEw_~Q7~&|0kV7`49?dkKn^a1Z@~cA!r!Wb&~to&;mo+V*+Ag7%&7+U<16wv z9;b`aTgZe94mpswUjXDq<QV}KW42-QWD_`oH@Xe5r^OK=@Wzz4VU(m_qkwX)Fj6Dg z8W2!76$1K60yk$fPNK?%5mFY|uymYh7@%{FBT&bU4+A;*nK)fAlEG+;G@Pz}K;bMh zaJr}w*33)FEOtDhr<-LrsNGYK0@}{t;A0qTmhiZIyAls)yq7>lf8u*BK_AJ+=$NPv zCpB3#ulP2sozyy3{<AP#z{B<#m~j)uh>%NDR^}!ZuIgS4FQ~PspvpWR8&DuDof}cd z-?lDV-~>LBZxBA6D8Q=C5R0aUShZ+3@JOZ#?32ss0@H!QR6k5H0flO|G_Ik^#r762 z7#(JKz?i_a#DU@rC8n+y=X4}F!6!AD{vSVCRHUjG=uLdGP=On^i8k#*z_Mj`Ew*V} z0q&#Y#m<{;Kg{_^dyhn;Zn$mh61Bf_UT2v)9OoPJAlDCv-w4U^<aE5S-xYykZjJzT zMYXH|JydBB79V2oS07MvM%)|kU637LIc%3<5Gtkx2R1xYvMR16L<kJNR^&hf?_c!- zjwI0ZbCNhf9f7_Q<p2XG(;z&g!xnu^0E|WiyNZw&3227o9YNm;GSC^jUZJV~LvWxM zST*es6)58PT6ditXk?m6=UAX%F{fBnEef!_IfANEKOuNPe=H*(h|M32uT-j@0}3hA zP_B7>1sJ)4#aWiyKQ30{ju(xp(tp+bX~2PBOY%e64<C%@H5-q9Ag~9@3ToW}K4rFK z)$?<}shm1=N=OamI7A-L`yz71+G_$dQf;wKhjS8U|3rLYs{?uo)S+=b2h{Rjz=xjQ z-`Zq9E6SEUvP}KJ^9pz7&<P_as59vBmHiVF+3gc-8+ve{vBx&t;0eM751ir$K<SUK zlfH3~)oeT=&$&J20R~#EephCS4BXj!eL|EG4s_bSB@QJ8hLH%mihwU*BaX*ar>Eq- z0IMYe+Kt?9=+y*@P;%uH0xS4L+<9vj?wrgfQeNS$`vQ|vPWXdsg$r+A>8{<A6%YnT zEQrex^Y1n@#7E5E0Ga@Agf&#L6$czB)*ourih)Q~Tk*kxNsJ12MW+uOFKCrx|Ddfi zOdU!l5?mq7ULZBY`EC?<!D1j6^AERPn|q<EmlzOWeLIubPr~g_o^vyXDp3HnKylko za5m9^7UQk25QeXdm2v}N_bwIW;cDn|k>?nTuzM@SxP&=WkySv;K0lP9I&9-BHg9v1 z06lcMpjH1C)WC~cv=~^~ea@%B00Qp)N|)w(XytrC`@SX!@GXrSE)9dX@v%LC{$H}Z zJYNRBX~eg67XI-0;8<R<9iadNst(@1#HIs^)Xj{>aM4C0gcC9;G@!xKbbM7w420l8 z)Qx(dBifCApF_|Mlp&TR)&&XOWKUQ(<cpLq1_u2}tw~jvX}E0to%#f8>|UrL)ei$c zgEQ6-fEk2OUHS?L;egM_^v}pVCZ{Z-bPbt1^7zW;#*>haT5ND&D5gI`5ktsb&It!o z1p`0C3tn;e`ZJEN(8(ob#wC0{yk+=#uZBRzcm*&{I=NLgS74ZQ$S=(n(6YOvQR@MV z2ycrCh~*qF?%v4EW8nisNx}jnH1O_C!57RVL<UE67qBX!8rs|NCA_hTh<gpZ_I!no zSPyVB9WP#rJXUI(471OVWwd@-OA5Y;VzdUqH4rWw=bj=vUSO$@ESsz|PaP8LJGCKH zkhO9K0vN@DMT8JFFWd0MuyorTTU_Q|zyvg!HRvKQ5cDbBKL3=^0d5+zgChpLfY1)O z<tTBf;Ew~oK~31D#W|6wBf<4)%s3!hiM)X{W&|<?J;2{~<i2+~r;R~*L_F6DiC-X> z&^p=4EmN6K17kxIoyh`NJI8<qnvZ0mdeu4c#d>UMM6>~>@guN-T7rDv8+JA=#gDIi zhiJ&>X7Tzx1%>O13RqRE8=`MRbkelo{!4rjNtBCKt|<vK58Qp>%JmYpVs=dv5Z|fq z)vPs|ID9jP`Q9=fw#b)B<_>j(*bkY;c#7+dWzl#EM+w%-Pe8={%vy<^x4Fu_=A+mv zQX60sO*jXIvhW*#%L%wJ)ttR>7pC6_P`is!Xe$WovIhv|<`vhGMA*nT+UX@wW8l?y zp+N8rucoztth`;x1_3nA({v*4@jQnF(!h$dV?)t!E@@uGEJUBAO`!Lqktk=}vXfP( zOb*P>4|HeJc@-c!cD#Ha#W}|Mk1gzvK_;lYhM;_w2HP<H9cwR}+L{qjyHEFF93Tu- zE2Ydrv>tgO3?C?p7Gd|GQ}{UYZ*n1pXA~O*zckyXegl4HD>u1d5<=1J2i`34bOO8n zcoZxi?r5&q%S{}SN&#PSK!Cy(jjr+W*b!XOr1ruxaNvq2MPc)mDF_I;cv-TNH(jO< zBl$+an5z-?bgxudN-7r};>JS);(@EIGA*r!NyiIW<tCW<o9RP=?BJ<$ZUexa-b>|4 z_TZaW_H^D_ua^K%1fD6Xs)aw{c<~764aQ`^{U4cs|0A<SvtrQ!d{gk_)->wO78uOH z(&JacGl!9h{cQkuq5{-Zfh}>pqWOFnsZZOs@Q@K)yogcUBZQrB4D|I1J>E<^>(O{O zHS{aJ-W)=R`&J%{5R6$%%I<Rti~H|$7)v(bf?%B0JQ6TKQD;5SXGw%W!aN%Q7Y4ia zDqMgOL0$!?nZT#JO>sk1XrDiQI5sFn^#U>N#RZ2|EJ0wd7QQ5tGhbgJ?j~+53Ikk1 z@nR+oZ@srzF??F}C`uRU+VEEF%43WufkuEX7JC?O<Pfv2kCfLB{RIDfx)0O%ZZz&Q zpAJ^8WZ#!$x4C$EUwz)T{u-i$XbB_26>wPKZKlfUKLJvpx@*Lw6v-e8&^T&-0>HR9 zU)T``U3BvbsWkAIFgR=ioJ(Bb;_sD`{4NCTqFlbX&`8lQ4ACE6yjM%kE!RW+I{$-^ z?uA2|(58MAsgALgH1z_u_`%8QdWViEJ8cl~0`=yn@TlDsJVFLnP8hSb(7kpNHXyW< z@u#akJh~u!A;bueE;14p8$CH)QyW}A`C_)nH^EA^FQRMFeTR*(?P_rR<f`Bq*}P~z zkVJw-Un@!Qu&A7E4K`JwDo7z1Fp9oo&<Y-$%a7)51izTqr51R|i@JeG5Mx{JGkFvc zuftqu7XgDf#YK)R#p)Vf41^^@>wF@hT?w8gKsQ;pVY_yKG3;>?-3?eoXeN-(_WFkl ziOwt4pRI0;PmURl*gnCw>EjuNPHl4Al=F;1r;>1NK2`(QHh^BnKXZgN77f!P2$nXb zlmvuJN=?{subGs5(d_-{nelE?fEn~16%})^K{%uuJByLMCY~k}ws{HX%K$^BufBNO z8>sC%TV}{@SKJ7XG3IoAYfcHh$J$h~aE&CQS>a{A^_HJ%fUenqIM94p)Y3L5if26? zhN2|2^_y~KSdmT;bG28zZLb)3vQ@|YU&p#dap`pbk2;JdteG-zVT`^)a0XM9+_WA+ zVeUq#`@%WQR4+9C4*6DEp<%_yIZPmMHw7Cuc@n#3#G~Jbff<&I0J~DFIWZ$eWhK#O z45S^36dsN8@C+VODx>A=GM>8edm1w%c5&g=3&-U65gWk&%-(|eIoQD2717;qi@3d# zwFaPU5d@DJ&ti_?F^gW_^O%ksf{4XZE~L016X75qH$w23a(jp{5ENz3A%RxD%_ZLe z_?@2mpzKzK1#CA+wg~YHQH<Sf@bewO=9#8>Rnh;@_s0T_wdp4ZAXrT5EPlY`X>%FP zrVWmC5}C(PK`2>&=q?~RiKfc!KzUJ&;3=HR6irACVBwM}hoNZiysgD?2VUuChoDzP z=h^rX{0c1HxeN#e!8d7hx;p^F;&{RSzVws4m4x;mx(*f^u)uvdNXh4gU^KPx?e7^) zqc*#HlLrXa2$p4k?h}G#ftio@11w9+x@q0wNigW_!I^_QoMkB|6hN>nv$0tSiwC5D zzgY=4R9gs=h0&UYwK6IJk{Fv+312KPg-^Co0Np$>P_1FyO4>Z))UJWBc}}oTfU|j+ zJj;}I(3`8x>F_qAjYUH?7nU^1f7A=Clvj6t8wbFHiSFKHA&j1ufE@^~SEA!-ZA{DX zxP8_RgpL1ER&>`p3#V7!({SQ7$jjUxHGA9i=O-9(^GBUFM;Jo498@!%Nb|xr2u?sR z?Zr6ZD^`>>fr;V(BwB!*`E{!(>ps+rj}~Enh5Lcc;aB?0mRGsmT!0`7dWF=%u`3}( z40xHrniD+?UWj0i9G9$vQc-J6F;Wmmp592b{81J~8G(U02<&Z0(R-NI@NTppAXhv_ z+nUov+2GW(smZ89!0|^j(Nqun52v)tnK)*OPIMpT+otBs*BSRR8qSBKxM=%`Mav&# zA+&0usX#;JyC~qDT-j&C)yh=k9mCN4sS=1~4t?FkpLMr*PD7<_;V_+fz&`XmkeSxg zJ^3vnxXYGKMUX4oA!R^tr$}??o{;5&P^<>;kwb#&7+gpOD2o#Apfvm$*259*v2T0x zs~HDyP)sqM0H4w|6^8+!Evqwd7~rfWX^Z8h$|p}aZ`lL^-PsD^*kBw0&jb^wd-Q9H zes?%;5zbnQmZN1MSeA)*%nb;dWq^yW;{*Q1m?-N+C4yz);~Si!iRgpy@l_Mjh69~a z*esZ=RhY)M10h`^uzMEUvI4|cRE0XU9FZ0;JKSHxBRb&lo(52@?BJ-1;ATT32om@v zc7*>HP%c17kC|lVRIdiujJk7`4`j`N^T20RW`R}n4*~8`CK>9K0OTdm5{#@QAIA$2 zG&1%9`qJ@&FxBoF&@gz5GY)Ulzt+?%G)!hu%mPX#0~dnvOy1sdsDp1{FZpg&em{T< z(+;ia%s_OP@AW+;5inz9t8SAmKX-quj=o+faDd>o?)zUYWRXKyWb<hZGWumYUkhNB z-BX%bsKLjkMnq`9DjGi%^Ho0^j2pkZ&QJ3XOAhih6D_;8DTPF(34v_V1oT15DpEhI zsf*j|1R;sFPBvmnbv6fETrRT#3{6RH$qkj7?}y%KJz8ROFv^+0_E}u87gaxNG)~-~ zssl{g#(tx=Uy@s@mwR?uB;UA{KKJf2I9R@7amaT#%P832LbPmg$a$OEYIYuAM=G@@ z2)|(bO}7C=*$J-fZs0J%MiXMMV?kL#J$q==u`LINGcc|-FvdzA;7uD&7j?G~mZ_ic z^8|4=2jpLN&{23Vt{0N|aw@w((MlswRLSZf_+~+;jX*aCVCiWxz3QeinK*`kJXO)% zko^Y06Y({km|i63;uu19*w%Qre{c0toyG3`(NyPaAOQSR1bctDfA5f1*O&jp?&010 zqfop=>|$-<t)h&&_c~jRu=EU%WW7YFOg%*3c>i8GS+e?i3GB;FHTe1Z8NTO0_(rHn zzQ@%q0fIt+_vZz(wyCj@LU(G;=)mrHRR*>9sYA4*10}Tvz^B!|U6jFqGcHxO_yH&3 zgv|MZZ~V>-&`5SfR=jGHDo_Y~<Hy$qr53z-WB(V#(t-|rD6@yF16yReAP(0}co2_& zE7K54Ze0Zr0D)8!9{<6w;o;w3P=7lR{l#4`1qv&)BJ3X&(*;h0PP9F1NARGcE$4G( z3DRb0CR;F*(iW_iULn!<5#CW}Th2iG6LF3wx+}MjILLzwK=jum)<$6Osswl|0}t=n zQ2ht{_lk;5-*wN2)|cB{0?~wMxx~ItFN&x3M2aMhydNgs*g$2c5`0??ibzhh@&H^G zEsq%>{PQ#g^;0s7Be8DFRRX7Z+OE4@AINUVwxxi5bz@H#ewrt$oSBH=LwEOP&VauP z1&xZfdv_uZ8JcT06Hc*B)4e?R{JC9YTp)OOG>Ah6m}=o>X)VeOgaw*N-uuvY+ce<> zL5WWMf+Zr38Jubp%X>k<Ia`m|y&=T?a)zKpjePyQaZY-IfzTyUxfkP9d!oK$6LG5N zHD1h!2>d3HiZ=l#b1w^sbCdz@<r9u5=W$|3FGZ{Y1jOOnUp7EbrtEieVj}3bOs0gi zGIHhL$Ow=AG$-T7?@sRYUSgQqowTyUT^FUpJ@^)D>gr!!iyQ}8zD%$SQocWQ81zHf zLsM66Eki7-ZR<!x1PE$oM);U@+)nVbR|nm_Jp%U_XTZ`A-5bLNnt7;rq5ee5+s%6y zQ-cO!3<Z$9O-Y61Qem?ZiTB1Z)!UTpIJ^szaY2(Abz}Jfc0f-<4h7DI5CX!{v_BEy zkw6}YWOr@CYS9u$6$P5Gl6s!EIhN_KV~McuGQLl2fFHtwvbSFG!hM%5#3>#qo9SNP zIP(%ydlydQ0T1<F-5AyYzNL0!?Bu2pM}wxWjc;Lo%la@0p>e>uFZ>)&lvqz0;9Fj& z3taj3^FmwCAuOwj2!(^q)+8cAK+*DNG#Jp9wPu*h0~+A4!P8(uIf3Q|db!pOds>wU z&@KLK4$$Q~gWs6#+m*@Ua%4&CFJYvRA@}vC{w%wC?-}nM&AIQ6MBPya5S=j~2J~kn zZ*nE*hWf!TA$5zwCp<zoPyWOc;rF}hBm7LS+QhWlhojqE#bVBIt}Jwq5tf+S+XP6C zkLKzCO#|QHa|1V{((ki$xR+70Z)5lhUEz%9-xb{o8wAsGVp9~$n^(E`p`~bV0TKDF zn&^1nQ=TW>F5+;*D0p+pPy#rdQ-`ZD$wJsvvJIhha&d67<@SbP2Eli(DmM%rpP-E2 z1%q$I){)>P*R1#OfS#mKTL5(f-(2z`_1CrlTY?lz7-XFfC^3Xe0O%Xg#+wIfaN`(C zw-E=)4==jAu!vJ_hkKr$cpxTbX<t#=f)A8Sy2Ly_SRfYW&_9L}FVL#x#7!d)JW<5x zaUTuK;hk%TY3)Vic;dMC(X`@Ru1QIR#hhZcuk%TSm!Cc~@4;y`U7pEL<Zc?Rn(i0m zgVn6#c0&CMRLLX)dU&}hKA@p=SoV{rS<5Dnk$A{HBTowq$0NhE4Tq4aIEQ~Bi}ef_ zBOmq+&m(vAlf~fDJ_Km_0^ry2%`&+-*N|`)a>_6w^6aoXGG7!ZchpaFV3g+`WK=gi zxAa0m(o<i1WeaMdeKH0(<Cd4?iO9Iz)EJ{iB3N;qo|F}~>s(WV$Zi1i2DCmP4}VMs zLgC{g=tKVZfW@WV-@8(>CA~u3p-6~BQYZ6oU=nE6966jT`6DvcJ&-VK`&6M4u|fIS zVz3QST&!p+V{o;xsH})xqd69kml(V~1=z2CC&e+}xP(fsR8TrwVjM;ptH{!PmPY~0 z5d%M)sKvPGm0G~ZSfi(o=<`I)E<{W0<rBeUU1Nep%zC0v$Z<CIh>GBouRS&mSFhz} zf0XUlYeLN9N&0o2(lmx@3dw0$h76J%gX}Fwz8q!ZNd@?ltr(Z<ND@)XQ@Ba%SQ1c& zQ)=^%>i%f=%O!&$KPpgiEzc0WVS2vrL3(g8_JI&zyPrVuq0WDS))VD90>#!P1P&?B zP3bS7H?D`!K9l!e1HqA30RsW<+d6^@818EbTteU%1WqIH69R`2*b7JbcPDpL&*V#0 zM|l3|9g^`qB#g}Q)Wao=H1U8Vl{*}lT;Z7Gg2;E)!<`NfbkxI5fr>i-_>lnX;r}&+ zi9ZLbgxvs*v;QHWc}SzF7P3EN-LhvHi??iF>>P_14Hy3lR8&NA`!FZVu&2q2>V2d% z#5u5(bPZEmz|64}(CZ;vz+SQx*OSLR49nHVVXuf(!o>1sWwuBpPygNWSIgD-|8Zd> z#ytPCDvA!v$m^a<-@RR^k{~G{ZeL?rj#%=<IPR5f#m8S`kce>ifB0mLT_SS#6xqC& z(;wGkjk^<tXs=1Oi)l(7`CkI|DwWtU3v+QFA77rT+TB^6zhvBAX{`CbfvOnvf&_E1 zz0%14FL-uqZoT*IP1>KGy9I9RJ?3cO^1lV3kGMVNaC4&nKY*T;My@oMY@KK-kHGTh z`@`(Qxn7J|58PEJ4`3Tr{wvV#kIS-x%INP|Lh=3wP_b0}WuO<TIBxJcNHN8rXvgFA z>$i&w#lt!i*wdBCqu6gNsa4eO20RAcQ~tZ|5JLd^+=utcW(|G(?_i*|hM*6drZV|s z-1i!`KXGaRj24z`{gomyc_PmVZj_VaOlyz>bN;NC<KVQdlOy9Ksgrxi*<X7P7@Rwi zr1ge6ztgSPTckL`QPm0`jus++`Dkp2aZpGk)MF3qO$C&`GTfhKi4_89nV8jy>y%46 z<vwywO0**h$&tDOJOqk31KKZD-2iDJKk~z9$y)M@o)D1-80!So(Tr0Mxjjh|d!CCR zv96QAq6Iw3j0<rmdeB-iGuQY{!{1Ng&98|qhvBKnqn{^32TMfe`e_H+oH|XA#0qiT zd%0V2{nkLskvFFgXnPs=qK8gV^LoAfk$Bbx0fQog(Z|HAf&5RXyzYA^U8xO+>ppC0 zYNBE0k!;*LI-Mzl)4^g$9~i75+DDaYJE^g?XJ?oaLmKeLG5XmH01gU~C}rD#48!1< zbYH_~F{IvxviC3tG31U(e{T3F2KTU*ACGerfP9Q5YW*=Q0D7#@XsXp-(}aSX)2L(E z1K(7{us;W2-{Z|)w5rFO@6lN9Z@xtDJHN?}X19Lx_`d>0w3iIke;qx1;FYKU0%-52 z1<XwXs6j1Q6lo<!0s3y4!|%S7940Q|fvIS!`Z_w4x>z=`&o6Zg5-L%Hy!<Pm55AOE zD0;n03#d7T*v-8{3wVOHD86#sB?Wljfq55V0aVrkN}v_pVGN2V0r2}f5oB&p<V0Dc z*VMP;3rXDCxZ|EAT0M_MaH^)zch@9L!{R-$Kz*dG*hikY)qS{oVPIQ&oB%c%R=8RD zkKM<+&&D5la-E&}$?K<~(!K{wuxM)U9yfnfo;Bvqi1}0Wm0t0JSR@`n8A6m}6e(@= zM!te;6m02&Qxs>Zf*q7m$%177EWI&42g$Tyy!sKAjbCx~-@#8Ak~^c<u!BU+;txpg zs0x~p@>9MvvW(p3oUs`_Odfdf9}ot?2QC#KQezYg0UbuWhoPdYSpGkOOaS_xWf&eD zP|?#|EuXyJ+Oc-1@DCHisPLEJ#;C9jQ$xqJ4U+*tCguJT$df_OL+W~%{P6+SKOyWp zKJW~wWqk8r<(r_>chWR-AF`NQ@cQ+2c0VpLUD=D|QTv70sJzZ}U@S>++RkE0c0$h5 zuW;hXDtrA;5E9Tx9R<Jrw~(%pLtFOJJ{zxW-|~OM*N<AnePBKfstu>OH)XL-k&>EZ zv$lNy2{2||;>B+bY|59GAB7MfMm_b!JO0RcX|jrzCmj0dI5H>v1}f*X^jrkRU1WvK z4{sG&d<_#8c94wnBCG7fe!S}W4$q+d)E1ao>*>b71LE~YCnvF$$nRxu-Lt=!JqykL zS*Ggo-@;dK0W*pIPMVi)7grvdL57!~2k!Vi1+I-gNV@)D?CSZAwnF@Y%jm!WXFfRh zPnd_)^}EewV+)J3TiD6y|LX2Lz?y2(wiW5U_ogUFFH#i}5djearArH;H>pyjmjsX^ zQWT_!G(l-mdJmxqC`dJQ0s<m6)Ib9HgYWLXyZip%?tbn1zwf_ht~>WUGnveRbLPy< zdG0yE3iGcA13SF<txhddn(<U<6TKAN(GVkD+AWSWHIlN38hTpNwTo6o3_mYwr2sRN z*tV116O#Zg(}+2tx~VqwNg}8J6y8A;qS@|8?ik5=M>T^6l6p=(xC1z!r2?0m&kBKy z!Zl%2ZBNsI#KGr-ryEbW+|SKb!;PHor0@kXnRhYHXW7EZ;VZDIkWY;#Syf*t&&F*; zcX7*cUI%K1ZSN*F1x7aJ{y1){+vc21{oYe-GveN^@&@a{3nyG<dMFO%7`AOjtM(f| zh9s<90Owh<P1>LQ0qV?mae~XfKa|s-KDm-bS4m=foo^8*sC8N(fabj?wEV)$ieu$Z z@VdOS8IbEJC|&t}_x*LfE4v8-%TFDwj8;0RZV}-8!p)T6V|<v)8|Gcq`kR-#sFgPX zyQqaTn6Z|4WdePo{tB3O`9heYyo?3+sJ~Un%Ai_v$??EQckm4ib#u3!Y-Pf3pW+|k zu6!8RXYlTWa4xN#+}1dSHY&P{f_3iq|N4MzGQuuYOK<hO$gRs<X0*OJ?+6+T6$Wke zSdD!*-5^7cJrX0G9Pc14fy{g*zM{1QIu$Xw(020vprhhvZNSna7|;7W(tAarDxeu- zD&ebsgOx3DY=6@UO0m_+sZnu5{g5v%cN{JjJ!{ueBq^u2;#}e9mX)}Paj=N=?5`(6 zC4*mjP_ZS@l5fRRLl&W{ZQ{Wal=PddmhcgT-bU$^;?3$0(N0Y-FSp@FJ{V1l<1$(s zH_l6yImKW2YA~-lbil2sSKUG!%Jir*uZKZsS|F`VQuz$BFQt7xF)YQVmFe{!|9r!1 z1B>s6;!o!~sY>i~%^Ig%d~+KcdI-2^O(2h4d_le`xJ4inzJPEq`-1g5Pq8Qb3Y%+u zDEu(DKm#PAb$Ymlo->5$k<1)dH|mjK(>~AKE5(kM=sh{sjT+2%HGHd=cg*}=@)q=` zK?&e5(CSGoECCQ&UJze>LukoabEek_6(mlhsv9M7w>MSmW3Q@%0%F*)tv9rGrtp`o zeljRWds06rXx+vKBwro@a_IfWsZhsx_a)Md21Q28ZhiR^xUoOEI_ie>FX<@@{QUke zU>s4KIc8kdcdb;pDo&>KDgn5bLUS%(!y7d>yv;JgOxUQjPIbr4t7U|D^4zBSN>ayv z!GE4t8M^X3s>j{<`{wmlc2m%ie!anuh~>Jk0>z>Z&bBY*{{rj|Pr)zG!1%_X%gVzI zWo@piYH0!(+f|KQR9%1a($GQ6eq7{{yzy1epqEw-tM-2c3cHs}U&>f>#}=ygWV9s- zP}=2a>sXBuJNle5NB|e~Lvet1V3mJ(p@Wvo%R+~89!Fuvm);HpKsc<W+MxzDp7656 z>i5Td?}xvpb&9FydpKRPPH7>7>{|>v-fxuzZE+p!uh!35Ovg%WUS+Gx3?lZbYp*Y` znAVdb@k*`ND2Y*lQPIKyibOH+EUeAr7LU+xSTp~Yt+a1gL_o-OcMEof;`pYat`mxl z2US6Aa!n5(>`LoXJhBMCw#~WlHrXpiOF`77w&4o}WKt)xiqmWSvSMkwgWOD+mZx#) z7nhoc<?`l+mR~B<ZW0yUCtbRK-ql*XENUNiUIZ-Q7Ww5qiMh3?ThzvVntwL3pzN7f z%no--)YRG;eAZLZP1uU)t=Emg`Y^}R_VK7MD>r8{$39N9<YpG=^z*y({+!kOV%FSn zN!W7t8)1_lFS4PMH?<yCR0LAL;W#~FFr{E%Q01+V8*VUbVuY=`#qyyMZx(jNjj{WS z$ztncFM+mtZN8KJPL=bEg5h4@+Ukq=d=Kbd>A(kWWL%qv*Y;Hm7uZzyLpKfP7R7^H z;7$8wF(pTYE4>&+oeed1it_Q~m4K_)6Q`pnEuen&q~B1ak8g6yJcn|B&pVg%l|%u> zIvst(lWns-B;Xt!is9F&=lA~DHQ<5=iicU#iLe#woj1&VZ@5LQY099!FkX4MLrJ7K zjHR~SFV@dl>#jDiv%d$HdRK4y+hFx5lRr^{IbNxAuTuxRKnmK_)@Q3@kH^Mz(R3`( zg1zEDeA{LXoG<dpBktq=XojMOu&~_7tTYD~OSy%)Sl@tLFff&X_UN-;^)f#8q(#id z<$aCuq<_Ej?OEaDZ!Z*YMw^cb&vWfXJop+z_4*qL3HdI+yDDhnLP&@$KcQ#zgX@++ znMYMsWN!+{5?<m<6J#y99(Ce*juvrIky`T&huQp9?x;miB3*>AB8}s`SoJNg?5JJO z^Ad<F_0%TwBGnyo^|XIlDWXNDrH%8_J%r?p^3;>j!96RYc~WkDs4qDQ><5Wp<fzk_ zJzm(4iAa`?1v=Tqc0h}=s?-#MlHKhsLN+R4)RdBWRGt(S=Uihq{RVCQYceBOwudjE z^sA|yY+q!J|1_ubR9bbQ8RBujug6hp*e<y3-YS;5qw*@P@>5~(k>FC0f-tB->nKpC z@6b+PO*;Eu__vW?AuI>pUoXhf`MbIO_A}S_kVF`Tyc&yJL^+J6w&O2<smJQqh0F0p zNY-VUR$$r=&D%7Oqr%{>t4mF{gh3Q{k52FRnMCThil*(1<uNxkG7r`;U#m@%TrKP_ zkQqGjCBDvoLFsBh^$aKmw||b8;zdHarHk_Hon*qk<=suG!@Erx7%4Gr>HWLX_`BuC za5JS#-<e<9(7aqAd1<yEX3}djrcp8Z9t{)BOBvgr-#32r^}VH~iW~nQM)<0@xqoY3 zcD5vjVzh`B{l6?5As*FV@JI1Z$7J2l_SYMW5wn3{e5?70Dp)qaPZ1;eC*+>xPL2jc zysgYn+X8R)8XrNbV<zs_mvTQZh&75c{nEP;5dv>&=kUp4`q2pBy(+OYuB2D7MrF<f z5Y>%YvmmPQ(Y08it{Yf&%`up~E;Q*o0A9-`{-)GW?(?GFee^;BdIwd_FwR-~WYi&H zmdNi)fhE0=&E_q0j*z2szt0b^1<?N097BpqjB`P~3ZDPadPofRV}|t$QM^OMUkvQD zDSwr6Vl|be63Zm{tx%UsNd%9zzNxIRSSB;84rRO`R6P}O2`#CQy;SpOu#xR7FWg%n z?2e8pxQ%pzXp%lms8Dz-ge%%E;09}4^Tuf%Bc9)O*3@!ITj?*Uxm&bkU)1GjZ>k1i zyPW}qOhqx}_l0P!h7{xXUkt>FbQoV!=FNU<6kQcn<Xq%a(<cS-j5b~^D+ju>yPgLy ztZ^T9=frYhx^tY%4Y4`$dZwm&rp<b$K)w3B9f<D;gsGOo^@yTao9X2PrVkn)VVlK? z>IUuk@2rOmVNN2ZvMgeml&m@=@oyvlJIsC&wV-AahiLU{9r>@oL!V(z4yFk$qvzwV zTR$KZ`x&n80-DZAV+|Ft%e%-b*O?EZ7*kZ(@Rv|x@Hd{J8~`5YNFUxv{^3t6jjApJ zHDFmPLC#pdAa5GC7#~9a5)r@a>t#M%Pq)h91oiVY2h81dD~WG<)hGbUF+V;cwNbO2 z=8<!c`S~)oqENm*Wpe(mOVnCEO+~zXbr+eqSIljX)j&rza~z$2;N!|tQiVDf&o1AU zd<W3zdVFTcgDOdvgD&3wG1DGF>*W25<Ab;>K*Mt;y>zY->EC1a>3NQ2gj)!c$}ok? zMZjZxH|V7`A0nfM0r70CaaAn?wiyAlnjr(%2cAPX?9)RUeln12kFk;qjM>5g`%z=x zVj2tgLR_1dC}5{pPZBXQpy{U&*mJBWkC-Iz@wud7I*$2!#}~<PcYvlPVe_|++Z#_V zYz@&FXYnaM3x&y^SSw*r`ufKnC&tZ^Q$uu;?e9-JT&?$yP~xV!p;C<?m7~(36HaZ@ z0_@n2P`O4>;-<-;>5)%pIkCxHYd1%CeBqvE;6hPc=`!#n70s6Wxl#jH%7Az2Y~w`# z>$LmbJrUs(Cc^X7?aCHn6t8P%TeM>t1D;d&g9gr3>_;Nzn<rFm0n|YyubU?!SOh%f zLI;MTjTZNfZSU}2DVm#oMi!@Cn%D8+n9jsNpqkU_t%j2v_r1igE|{0@k)EQy-nE>( zMY;!KA6-mDQ-)i^*d<vsiZr5*EXrAKiuX5|#h00B_|zDi)vPbMl#9EVBzC_aGL_>j z^$UA3Z=54jaec$wceeiLJ)g1O#rI5uMz*j<A>otwu*<XG8VYOF#nl?ks1nTNAJ-Uj z)O=oXDc^T_I51{*JXSG0=aRkgbx!1@oN@a7Zh?_dL8)$vG0n<P0nfWloQ~=WDZ_2e zj9aclYin%p7Mxhy%|1>YS7+tf)v3EEaP_*2j=3)<&#>mshzT@_>o;+z`<WN|RmH5= z>TftuPCSyE{zCb2YN7syZen1{aPHCI!p!^BVGvFL{f(C#KNdn?QEF^9gQ{`Knc<-= z9bcS5mAcf-^0>ce-I_t=xlGLP47?l1&7jg<lIM6N-dRvL#aH15Pg(-Bff}W#aO9Uh z*i=eIRs^`t*HU2$;og7Z?f{*6iJTFmY$_LO;$ZTdBl3gH_=i(~4^^yHkQ>!+vQXA_ zK2e*BRL!r`PFKRN&StM!`zKXFwhv_2)lfg2kuiv#5f~jbs2I#gIjGwKVAjnMlWCf} zQiSii)qK-l{}_1Ei|Kz(&BBFl(^CJ@?05CES<;oFHg8eyZWjXI*t>69J-M1E<xn%C z2JYb$x(-IT6vrR}$8_nSsP{R%lv!ij3ci!d%oT6J5oXh4e7J@H1+|4@s&{$Y3N<5( zUJ`c29BIYKl(U$Td=|SG%RcEQ#i*5}&ZD<U5_g*yq?f`lQ2{K#zKVvFwA1n2I4Keo ziy0k?{-<G>a<HnuYJCLbbU;8j0TjccmmIR0qlX;oy~i&Xg<<(RMN<W?ZHxw(x?j)Z zrYq19N=v9RSpRqy@BNC4Uil^Gl;0U-mz+hnQiH|flwo}NHLKI>?4qwng>^^Yq1j6p zy!W?G&6KaKi~5ebXz3r*(RNK}5n2Ok;|z0_Iv5iErmBChfZzmNSbw|NqT~)bTDRdi zd4W79PMbgYjltW>(Vw-2kC(~N`q90&U&<sG-Ln&Bdf4~3)TaokS!{v1Bb}&Q9=%v{ z@gYs_1GSHwoB7dpa?0u*^Se&^$4y~?*>60wE(^k_9p^IRj;WFQvgm?huZM{dUyVyq zv(Cq6iA=V|)1|1<)%6fLoRVe6LmCrZM$5!&Yjp!-3&f3zjcshj%cWfo$5COd%ULhz z{W7xn?@5*Nmr2&$Vz+XSfi;vxNYzbKfSq3vIR<a+!&^VLFk~3l_Ha0RsZ<AFob_f? z%yROd{5GKQaYpOTjk-?<25^CoC)A$NZXP6|&o@@WsqC;M^C!qq3PnII=sX~4V`Kg^ ztmTUE$%+BG^)v5OjzaB?D(AKf)T~om=gqqg$l&)roG`%dyM<9FFiqtWHFX}Wz%PF| zxdPL03!|ZCz%Ha=9rTYSLEYF^oxb;{4Q<DWai0+Vm$+MyY%MHeeB?Ridu@eewp5}j z$X4I@w5@x0`bR-G?><Ltt5mlveF!+lng19;JaTgnx?dFWgQ}w+;{o=0!h@LpcmXjy z{2Gg?tr&FL%hBx{KgmVE^kQ|A4K6faxi;MhC_qI`U+4Qie#Bo#D1w3iLjJmem?qy4 zjRHxHsME8O0yB+6o)HOaME<EC6X`D9OZnIWWD6UbyLys1{11V1<-swRTw{TTf11(H z5^d@NLxo0R;VC6Pk6uY%S>4E0k5OdO@LWk?!uy^QFrVCdL3GF{EQ#~rK?lGEsY!$V zdn4z{NKfj=W4@$ABj}J6#t=FL+m~G^053atYIYz-Vw0l1iW&H5nsfyKoPs$T!Lnsa zi5Mq#Z%*_O47De$SH#NKlA5+L$tv{yiq=FI6x09I(mwdvMrXYYPBMhkkfS19_duj$ zZCKdfUeV(ERs}VvUn*@nBaP<?gXGdUgB%#fPMa8$^3k@9i4M|RXt3L-tu^sZJejJa z+f$mFYLHB8Vq$9{LQ`v^v>U@OUUp*P=H#c8*MPjH;Ma8lwY8!)zU<lR<C~`xyl^0B ze*|REL$|y71k67vaA0H24EZ@_F&){IyC}TbcYjg;_H{%)BOiVZvu34#uyU$_d^NH9 z_(8@N9t;6HE_-VRYU&>d;KAP)I)Y4q(|1c}L%#l;`CbMH5fjD^DWKCZ^+4SBU=n^F z32$)!OWnRxq-2+YMdRHV@vJ1$5%dGSVCoZPVeC`BPJ?OmyJZdi1MM*2=XAvWr<kWI z>MVF6AZG*S^H;f~*D6{QgSg=D7D}sL7mI|b>kzL*#7ZYqKI-|PnfbyG*t1`6mw3ON zV*=f(f01^A13fLiYSlJKjZIW-8)U$SMC7#*Sv>f8h%#z3JBX1^(N;SFXBm!8O5!am zhe2iYmG~gE3FdMGWR!37j>Lui7@?HAhcQek#|JU^WCE-uzdwlimaJ!o?Ld7Zt3E-w zez)BTy)lw|x9_wG^i;vy^*QJMkHhvbp!6P-T3gZ#c2S?H>tIB+jm{Rk*b4~SGU*TX zT{EdWgOX6b+Cyw?#oV0(?D5UEhz*mm(|D~3x~7FMiG)2a4@zAK&?D3g__T4@?iv=1 zaD|=JmxLnd_1G6E)Re)oLeyx;#n)1uOwj=dvTCMd+goAx=)qwRMDV*FJ*CX%J6re( zO#ez7(@*I<UZ&^}1Wb?pfT9BcMha15Z(G=1TmO3_1e_~%X1pXZHYRAl*v94Yj*<zr zVb>{y80wAHgCwOg<dPo>3IG^h>u3aD%Fax{+{RqvKtJ`gmswy!b)6NAAQbGBE1}Yw z_!f3!R>3VJcmV+J6iUEA7;>c+m^6YBv3l(2rx-ig;KX1VGd6b(dwO0C7Wx5o*NeC~ z3zzp)>G}1O7{aMj4vb|hxz~3((H7T+P`FBhVl^bJ6^xRjsH>@T;RA*1{=)?4>`wy& zh%Ha9pSptfZCEZeTsVNT>*>Ow{Oy4mu#1JV>(pg2_ihAVBH2PKXHUw`-Tv><wIZHJ z18n46!4a@_HX5!;c_DkejiYiGN#hc1oIHw0@Jg!~a=t&3<`I~Z*~2hf`*cjN6R&u# z_PzLeghi_>l>z^^?MVdXCz7^WsdL_AmEvw;3)d|&PCC<lIu?2e)&LM2ZW1xjvsnjy zsz-`w6e6pbs)ZU1JS|jy823o{X8plq)qwr!h@kCrh?SlV4cF$`Hz8cg#G3E{>e}!R zoQCD9YBD9mQGJT_OcsXRWyAsiCq*(_i~7fyKyZ`?t2`#uM$H`g69Ux@ScYin)-OPe z?pgQ;XQx#j8K9XLc6_@?=M3GP;^}^d1k5dW1cCJ3*b4_#5!_{W`pi$)Fdlu1PDnBu z>>DtjVN!c{VRMO2*v5G?F2f|%efED0321|}Lb9+ZN~w}_zd;?mj*0Yz&DSC<A!n}( zqN>iZmk4dweDfx%f{iYkERF{B>?BcDIW<jTuV;WguYDURb1w=NXqQ1sGa{oTA=*a( zt`z$*GvjjmB1_};rTb0ZlBK5~c`X2>A}wXZ{na1tvG#*!88>CY6O6M`UX{I`sT5fD zeM{pxdjj;^Gj)BuBpDNRUr)c)U)C?a@Z}4y2Gj1kp}c-UsQpJ%<C3Lq8vVK@Pb$jN zoZ~{=^htoshD6NLmxe;zU3qVGX+Nx)qU5u;TP_30IDF}z{_CT|#a<HgO6C4;4<&Ag zO~IwZ)2IMhYPTOAuhP;JH)T{Ld+1Ahyy;3aw&S(JwLfEJ=4p0Yi4+mdAgW;N*-Ela z$t}@{m42)ae03>=W!wKr8%up-^Birn#q76pWa)=DB0T!B%$}}KKy=DxvkF9xFAtl- z`TB!M#kLO5PrW!K3!mr<+7#JJI;Z#IP#mtcbRs>UyK_qHsq-X^GN7m#c!67gwvGst zcDNGG)rX~mUsyW1G9SEiO8Mi}(u&s6ZZx~xfzZ}e#A+{g4gT|c2$_`PlQuHiqw7x+ z%<8caUpl?qK~(=@5x_&YF9>gnV*y+ThcdY<fbDHP0WlGY?MK|Ta-=Ih8DkK0D)ZDs zx)Xaz;0h!OXMYHEgv^|NT*;+E^qf*2rc303DuZdOGCh5zLvuHJR-{53=+HZ85wrmt z(GmB!A_~g1AA4v&u>+WmdeDyzcyb`N<#FEN<)J@+?a^yI*ZY3KCH%nL(};cdEk3wG z0BIK(|KcZmUceko<kIKC(Y*#`VSH~o+6lt~ZP$IIKdZpppcwzbIrjzDM_d2Ypay+2 zWAp0lN^N2Aw%PX|^Ht&}!79S|y{cq`vBBD<-Hk%r3fm<|HUN+epqmSdJPr+|c`#Q; z4;1|Bl6uOe`LtULnmc+e^}(j2*3lep5nU3IF>0T>C-bgfuw|%_CUY;);zH)+f>B)R zP=KB(9MTql@zrQlYM`e+-OhU_JKZ70cPFO$vbvm78qA5QlSwDH7cWC~7}=r-H7{gd zuFxWSZTMYlL*d<U>ZFH$gOZ-CE+b7FA+uw^KHqB?zLV^fT?pJ{NKA$FUd#8=U-5!E zWsg2d)d)^uJo#SemGWB1clPqCR~(^OuU5G{$LTHbLY1&Eer$qWE=PewP>uP9^8o72 z(5IRF<SXinc1RlMs9q_KOVPbB*8CAIg^5xyfN%%tb$Qoo_P$q7DpSns;1nRrunEx_ zSJG*w$}0Po8O%9hr#}9jsZX%9`fV*cqsZ$*n{Gmr8ol%n@BM7<b-I|6dD-JN!GdDA zJ(_x$vID|ve(;b?-FX4zQn#X$gGmVEH%yYLd|v0k$owuZwe4QzoljdV=F@o;l)BT< zk~~G`<}j&y&WA(0P4FK_*Lp$=VARZP@9@<kvr#??Mxaz9&`7$}2t|4h>@|fR=UZtI zLPyZe0TH%LI~^%8f6-P6Y4_*&y-q+URA|@^j2vZEZy*Ds_Rb;dR~aCdBevwJZ;R>2 z?+sog#a@BX7*rc&NVY&>7C%3T`>kmcWxr@miwMQ)pSMVB#SG1{&1!*0f5hhpzas`{ zfl9tp`4>u7qoG2>=@;l}Z#_s`7(K)mp*0|TQ1xN9V=RJwH9j*89J8lh)CQqo1cy?r z3EagoMr*n^nc9xFvL{M{U2M(Y+FV=zoOY6N>4mU4aOq32P10*YmKuDyct+gDH5Y>q zUt;)!6QA9z=cu_Ez|IrpDRJqYB+BHrJ_u11Ti8n9k$$43J|Wpn8*Rie6bwGM2Yud3 zKg{;xC`DIfye)pEE41Wu`ihqN*uW>@2{yUod<_HX^~%(^av(=itG38MPLicmsKHuF zoC;nO5+`GSxj5l_T5`5bih+iA-yL0!USR<xf^qMNxuZmQw>|A7=VP0}fq&nrE=S_K z4Xv(ZywGe^cX7g4TGsvX$H(U_39C%Z>kz^d6<E>)37Fp2x|n()O*LC4)_~Njk6)Lg zMmR*N2>Nz!DeYP2aJqq+(_N76YRNm%H|=ll85w|wnSoj~u7dj+lxl)T8I)XSuzRHg z!17W%(_JLtrR<C$Qq;Neos`k=V*_we;p*F4u9@z4M|7aUvNLIKv-Bs0brgys4G1>p zVuB@7S6x+Z#_&OL6X5v#LJzSbcZk@9Rt-MU@T{Sp8hFQ##lU%sy$_5SmXK*;i#UMs zd5`=g^9X?<P4%NsF+U18L%sv{9y|f;a37bL@hQ=S7?vdApn&%TSH0s;8b20!t$Fvn z_+Zq>0q59BLX?SrV$tMMB*#c1krVXqYx=jCTb14^D)C(KqBbQBA;`>7%#bh1*->i} zJ!6)%@0z&v{gnzgy}wT{eQI!(!380ZLZ{bB9C3FV`an(ANm6bO2dX#-;m(7shj?ha z;$&slg9#naigs^9Vg8zjSDEvSh#S;%ha%_=CAmqdCu!qqrSf!SK;NSq9n@=!<_)kx zN~#><*FpT*-nYok{D#iozzorbHviSrn1J0RlCN+1n&8GE)vA29=6~hf2<Ka0v^D2s zR7o`~43l`@b$NZ!z?$Yjx^|W~B$&bt4rnF4l}nwQ3p?MmDCwcZ(XBRX`>_XP<sy?1 zvoPb<{aq!>GRF}2DmOL|vXnlaL0uqOF3oXZWo9dLucf-%&h&|MVz1QpFlQ=wiUnW_ zes1*AP+5gh^1Wr*v7b(~0P7R;tc}d+RKw=e6?7V`E3RQvUmyL2?ozQ#>W6(xt*#`T zWHMp2#kr`=(KJc;C1gy%{D+yiFCkfmxX#T_EGuXb-!rd=bT42O7<%Y~`&wS^TcCtu zh#v<B)aQXIsWj!}7Y--?`U6Ogo|ecvcJ^3&yEs8m!+x+Xp_FDweS!*@C+EHpts?f= zFP&RQB((N2FO7di{X-AT1Ix&-yIq9~9@Je16*udh)x#idM(p?PQ{q6`&x)D($s|## z`V4I$Gduvf@`S9rR##Yn+zA%wuk!mQ`Q?a~UZ?74$JC3?G{u68!!C|y8y=-0u4BFB zr1`#&^rc&wCFxmpqbuaPtc9kN5%R*gBzA$CzM5`g`aFs^V+G~XRP3GOYS#D66OBai z1;$axzWtK1uQi;F<4o3YGaZ@o;6yXqw<w2Emq4c_@Ms{dB3ljTx^bv_Ice<}e=X;L z@vf2Ujf`ru$|&K2nhVTt<SuA5kHKp>4~!S5T_{~Ph_1M{kTgTgYRp8*^2UD%$hm}^ zBfLHfE>QB~y1B3In!(qo^1+BDlTylOB|Wi$3BTZW&Ck@hwnHJCbsf9%%7_c5Yvxi} zH9y_!GLR}ZnOxFa&(b1<{X46bZZQbB4_ex;X);@PB9m@A0W}aWdI_3vd`+7VIxMk0 zRzCq*&QQeu!Cc_3v`w8xnoXyB;?=I$8BPj?5~QpEAbq=M;#JuMySUP=I|7;RoqIr= zRz5Fk_6b^ACILBmUeJw;*)0eW*ARVlP?)gQmD}tGR)M~^_chH@;<`rAP619s?RV;p zpgD#g`dgb=l2W>28xy~$#DyIRBvbhdFDiQj-(kKDxd>2Rx9QYOz+~@yR<E%Va_tLK zc%4t_gI>y->dl-Pa`6#Sbd+3KU&?ODu1fbg@E))lnCMpuQevw+g#Ajpf0-y(YLY9K zT-jU7HqIJJ_i1#~P5-j`QOQ!ixPSTaM7Bhh!S}Pouurr*A%`RVx12OTLPB`sEPL|I zQhoMC=M};iyk3vk`)K$N{21UEP?F0fBp&!!%4?bs3P^Mo^)IK{oK=HXqRb*><y|La zW%!_w>N!5Bks>o6)IiZyA5<@)9O9{V`j`FZ51IMj8@(!fck0S8yqbNGRWPEop`cmp zGwGrGWo2*Ng57;1!qW5HLA$Wx1$3GeDv&tI5=b*8{2Gv(AriuMU<Gb4T&|Qdd%tah z6m3ZEuj2@VVvPnss3*RIAk^c1I0)r2wpqD<+PGPHH_R6!I$ce;02W1OuV%L_Bq9b0 z#G-kD1kogF#n0U&uZnqWq}ptCb;a_d;64^CSj%D~P^ac*N7Jd%eNe>j*T&14B6k$V ziBHFl)oF&WjMa(5SAR~~!VP{-sr6<qVi$VXD_WNh_cmVGeVLF<ww2x&_bB$D>dmAw z5$HKxHUBo%)^b4)W&Ck@I6fc^s+&j#P{)Wp^f{621P!Lj0hgn;RdUz&iZ4I(*^<<B z`T;<bVXKuM?qYfb9A(cEw~2D=BSZ3I^_t-Th7KWG>s+TrrnySJ82;(j^{wJ<%*VD| z#6<sTC?&9xiC)5Lbnj^<0Q%5G6k?TMo!Fb1p87$2g&$W(=r-J;mk@`d)OEL5!Bt}< zvU@xagX1E8cnt|ZW=Xj#<l5T6R>^%VFt1lu4uHmSn1#r^%|)7q1kx7bR<A&sK~c1r zy>YHCm8ZO?VLUUgWju$0-_Qw?L64@qxO>nu&o*jQUdy$1dIiUOcm*diRbn{jQWRUc z^$o9<T!@Ui85uXM!WemhglAdDh<GphKGg7Of$@g^L-=PZk(^8CIgPSa$@f|GlO3E* zC9Oq10PzZ-@)o~?gGv0Bhw=K##IEuX0u;d9>WnnL5?0RQXf8hO@(AnF(kj2+O{ral zI1tV9o@Tz$%;xtHS{cG2j+@D);k)Z5`k}nDmT@ZO+g-Q*2ZTgy?WM^$C(-<0#GOp( z(Ngt`5o2BRfvFbw<Nkjw7;F3g7S<*`mRiT6ox7TfJ`@#OCa|6^S4NLKj~bu46GV$( zE}`P*DtD{?IArCQ4OTZn_Oh^=LB$OTUKkL212A^XlDz4Iyc+Tz%edpjHD5`wZ<N4D z!kP<_#glT28r4Ui%#d#cEgm7W4nCzr&l}xB&JuoL07wf&EIOh5b06A$r(MmvQ5duN zoVPLAKfuGNdb<P93b+w|1<4?e8xErw+<*|%YEa=991%X!$WUJoW^vrlt>_hmC6?5- zfyDm@>vW#EXN-G0PvhSu0wl9Dp~hz!HGV(*rcf&VrPIkb9&2uX<!Mm!|4utYNUW@W z%_&y%e@#2{<oe^oA75t*I)X0F4z?c)`6toNsQj{>yzK}oE`ZMAv;t7_rVUEIKbA*P zEuOKp_X%84<s24Hr{b$P0&5Z#+ozmrMQ}<1heqkHg^*fx%Qnl#7fqL5-<zuHa3(&` z)Onh@BfVtX*OM0h&ezj`ZDo|PewFlj>8b{O#i}4|`H={~pnvAAjeO1UBN11F`02M` z^T{eF)SMf2nBt7V)b!gj-7dFAuG=0z`5jOsN4<`sCU8E<7)h$8Cb9iYC>w`yqSDN} zF4qxe;*db%+fM?i3qu0A#SF7vhr?3bmhdV|ZIp9LZbk)ufdXcjs5#m}D2@GPy$;%s zu*>Vl)!U2E?S})!5M4fXD*V2Bz(8$LIZA!!hVR12_A-~BzY_W(61fC-K;evM*Ftyr z5RMNslx8M0c2VQEsqiLhzP;z_inb6RC4hUMl?JnS{|ed%xYs}b4!(fYyjQMag8J7y z=&m_uPIxOYRdASJOP~C!GQXGp#k2-=BNYd9qaF`f#9jmEG|)SKyy0_^kf{2~?saj% z&VTt<Ho<s#kdWQyAkoQj?OLrv;b(cmp<r(*-u||f@R7s5s^#YBXBH_RuYp_j&1+x8 zVvZ%;#HrRkBVJd*&WXG6Qk8ZSv@hgS9ke%*9JRz?1Ef;@Iq*eO!p>$Kh}RWD^tA!d zeXAsXF(xWtWoZzr%x1aua%9ev-HZko$5~~E1(n@p>C~EsNOmEMDwxn_P%Gh)><3dV zn?pJ^r`cH2o@Y=^@QfK!`#@Kg9hbO0ZA>22ix5Ky3|WtaQRga>n#{Y&BK`Q4*+P@& z^EAJ~10@&HFB5vqWq3V$1Ddb=O`>4?WouPgzuTvxt+F3793HDpo(HHbvlsS}v%~(Z zb{r*jc9aB$a;&mgYbqVG-ojH>c5O=d?7kEP7a*^AB2!_H*A)vriE&b?OrDI2nUEGU z2FN2bQYl>oZFvp7ydw?&dcPSNSbLn5aG6_Vr@|OqnPLa+t|3F^@@y75g`Nd41~m*8 zsN$lwSImOtCTJ0IANpNvo{ZhD7xb1>VyAJRqrsyeD$+2@d!;bND0($A#i&qlP0*@G zjR0vu$v2UaepfiNw>o^ls^-W5KOm>Y2^Q4=V-|N)P94xf`Z#beU3OETD(3RbREdH0 zCcM@{f;0v%yNMS#ZeqXitSE~S`_S)tDkkN(?*plGeFuDsZ}>O*I9~V9_HjL57wEhT zgNwSYQ<l~tbSq$GqHdj(r5_0gC(DT&?cLVtcrP8JLPyojeV|;%;?uYbyXPhZVX<ja zy|kQ_-(En5;)1ByJPQbw<qX~rLMc6YHT7Hpf0eWO_|<lHRW2csUenML;1iK`1KS{K zzZttCk=Q^#V9DvTn%yM3ERm>W?vvh~-Q1vUtNUZRNZQeNV2bcj?6^6c5z~QwDedSw zFrHohgq^pK@IfeCyX^L5BC|^F%#I5>h;2E~5R1dzk_|YCM>QA?&11vll+D7=iy^L? z(s9k}APL)73I=e=cie!H%tC+p2+<-bnyeMpBU-k3f4Nab!-&Z)MyoxClj{@Qsm^?< z4pEB1=Y;0f6e+-^lg^4498m&_WGg5l3yAi%v_-VuJi-0U)sx2^u7hEAZ+F~QnvRyV zek6;D$IEjcu>V={6HJjbFa1k{*BV)g;tHT8><bt`Q8_OMt9<7Tvum>;DFxG%kt}Hc zCqn-`PFEJwA0~_=m&ZJ^d=hp9#q$EvqV#F+DqUTA^It_Sw=zfX(8k^rCMqINyL3P9 zpOW@aMw-)u*Phm*Ph%@JV3fuk1T_|wRJi&t{X;Va7fKvS?9t&6KvoNH`sH_rJbwfH zn_y)&Dg?$y3#WfM&)?}u&d9Dx8G|C{hT3iexMS$%iG#`iEM5Ubo;d^}`alJtZ^XDk zmQSj1sHBd9B$P}r5y9>4mqyYZQS3<th#Ex6C!nbQ<T6FJP2UR9+-84$wju~>|F%t| z9OHo^%uGz^vn#*zA8eH%zefIBG2qpS{Q*r)Li&Wlgp8HLTv}zotB?yF3-$*(H1X*Z zAcwG5AxyLjOV)UOSxgrnH2s4BC$0~RO6Fz{q38Pd$1GoZ$^M9^w&;)C?B1*d`pS_& zGtAHE1G^7TDbPD4^rSwFHvh30#Xx8|jSivZ3QFRH!}(D|IGo+#-;9YSu>`x}MfpEO zzc!<3*xcWSuQSBhru=r`3|Fh4r7UKsbo&l1r;^k6H_1^Ne@D;~Uq7iXTE1b3k3RWt z2%FI-4r;QPZ!sMaTDJv=63JyReT}{O?<8OD64Qq4livRKoxHR+>BB@hapOP=$>EC4 z@}vUQ{S`!vnrUPdeaFQ+*2KaD8P=Hw3+u@Z2xr>9m`#vza1Ov9V#o<w`2O<u3#Lv- zG1U{9{1S?KG6A6G+Z@5Pbzo``oaZm{-Yd$HztmUPFqExO59=^l%t;#y?Yirk7>lKu zRLN5mnP*1pqExc<=4I4>l>9uj=36KGQ1Z0$pNCf!QJ5EDg?Q{$?%sD!+qq#^lo=z; zh+P;;)ZeiFmyp#8^*5okj1Q_nzlBPq-n3m-Gf%sSDGk8`S`2<J5_4^6o-Vz^L`)+J z2;k*?6s`akXeP;;e}tsog0lv&{nA_AuohbXO~4xjqdVw0&yHZ^hOpDB5((TvNpVLM zcv8>CEN-9A4yQw1{!Pq_(DbAo==i0Qvn4pxT8GGDdfPoEa^VEGT7`MRV9L7rYZz|# z4))gY-<^-O1Bm}5<7Ek^nS=XaSbtOVsuFukDzHUZ5PLIxQs@5@VIxS8$rgP6jj%h9 zbCJdH0r{-j`#?mFK+2@sfBxcMYWPo+73K6OoCqwp>OU8@9FA|tD>_fq=?FScd~48o z?9LQ2Q)mz3lOKxF*#k3$AaDOGG(cx^K6t4zJ#5DWK{dG)cBGfzWrV*Pe3fYO<I`HV zeDN%&e!>4JEr06gnm?22R3|w3*HlZCsGR(Vw@^8`Q=m{_Js~;S{8Zi}|4WwBt{{Pq zyX4noI+Y8WmHvTNU-}vst{XTU7v6maug`!rXgKcXS(Q#7gf{LHYb?7Y@c#2Vq2H}o z_-m)_V!SX8HI?5b9@9}^3FA6|TLsYl5_0~x_9W3B^Gd-~zq#weTXjF(5wa^}k{PDp zScN1!zNK;fqCn2`<bTy{#wSpoG-O9c-U0cp<=HA=HjODpk!-}V(rwZtA#-7sH)Jwl zmFfflf<Zy{vS84fEdj8O1fX*wfWR5VoB`+ze9oZmtlaKj0Doqiawfo*b0N(&LVZ(b zmGa3E-~j;$H7`04a{10G^*Dnl$3o~?IfFC!#k{T!*K;^eC&;>Ma4HBSW+iujxwGg{ z_`7*Hm!>i5L}h3pNL_K|8{or#=V0bc-N4sjk0Gvr8`Yn!s82)mP^`hExgC$#JJ>wQ z{_)sSHTZe+C4g^}f2R6PZ`SNK265gwR=@`lGv)n$QNCHs(RLoW-KFPGZweB<`u~Q! zA<qyYdK(x1?vnNU-|6J@Y2p>v{H}hyWblMdHRcB$Lg0Yqyn#C0kU`3b_}>3KO43GX z*(0P0)4egg{(hU`iKG!;`#(cF*i6)5Z2+@oypIP#tdJGPDSmpyhU$=mv9em9i-*w? zBzXZ$@(6Pn#ccGKZCbYofAE=bh@eMC{H8K#Cc|0-xx+7twX4RW=r2n}GShZ2C=z5t zA&RtoaKiJCKPygxiT^A`21NI7QxK%&zr@J(6uAg-3^gETN-A1%o^~1<<jKbiSHm#! zw*MxS3?>0}C~R}LLfPoE+ag~a9;D+XFqTidz;&6to0m*UY=#)-{-*}%84`45L09f| zHtv}uR(#<0_|uz0L^<S-FMa)cqFP7(xDpj4ap2jd`KRF|imk4r{8l`@yX!+b!n`Mo zz7v?h+J-krnLkPx2evTsLJx3)<k~h0YNqBbzt3Db#7_~GF&?lTz3{MuLqx&M(8884 zYN!ung8vbN8k%)N<8l1Tfs$tawX{hG>T9Q;@zhBNnrop?bOIjpn;l}?7<g$4e8YA| zP(%9F04pwD9*85o#$?Q@DPfF4ZXVcivn73-(yHSye;;__I2Swa$YrwqE!2ku=<i4J zq$x5C=12mxuxgj&F>MFpYglmF1>Q*s{vEuY<|n2g+h)4Y2b_F_GbSQk-Y<4h?RhvB z-V<8+#EotXb2f*wj-5enKo);Z;|`Rc=|!Lh7O#1-;_l92xU*xZJQ*Y+dSe#*t+Re2 znJ3X_U0{3m2egjV)8Jq#z=aXX?z;An%*C^FiR92BVXNap068d9+QPO?<whuxUc_r@ z72Ck>y@XYck!x=q?+s?08G0p*pPeL$tpN06{V&c!1K1WU|41-P)eGYEOSjUf9!T77 z_*)`iL;0dC67xSToF+PT+??3HqZj<YKeSys{ZYz-E*SF&VE%nT&-!a;o^3%lNS!rP zGfftX2T8PrFh-J2fe9P({J$9&-3+d|bc)-e2QmDw2`bOzv$3afb?C}AH2!>Ez0U9- fU-#wn80`HxfbfQUN(EUdIcX)zD_7L@G${WMoh3Za literal 0 HcmV?d00001 diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/.gitignore b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/.gitignore new file mode 100755 index 0000000..2cb7ec1 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/.gitignore @@ -0,0 +1,3 @@ +/dvs128_simple +/davis_simple +/*.exe \ No newline at end of file diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/README b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/README new file mode 100755 index 0000000..94d4b77 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/README @@ -0,0 +1,7 @@ +DVS128 example: +C: gcc -std=c11 -pedantic -Wall -Wextra -O2 -o dvs128_simple dvs128_simple.c -D_POSIX_C_SOURCE=1 -D_BSD_SOURCE=1 -lcaer +C++: g++ -std=c++11 -pedantic -Wall -Wextra -O2 -o dvs128_simple dvs128_simple.cpp -D_POSIX_C_SOURCE=1 -D_BSD_SOURCE=1 -lcaer + +DAVIS example: +C: gcc -std=c11 -pedantic -Wall -Wextra -O2 -o davis_simple davis_simple.c -D_POSIX_C_SOURCE=1 -D_BSD_SOURCE=1 -lcaer +C++: g++ -std=c++11 -pedantic -Wall -Wextra -O2 -o davis_simple davis_simple.cpp -D_POSIX_C_SOURCE=1 -D_BSD_SOURCE=1 -lcaer diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/davis_simple.c b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/davis_simple.c new file mode 100755 index 0000000..780951b --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/davis_simple.c @@ -0,0 +1,140 @@ +#include <libcaer/libcaer.h> +#include <libcaer/devices/davis.h> +#include <stdio.h> +#include <signal.h> +#include <stdatomic.h> + +static atomic_bool globalShutdown = ATOMIC_VAR_INIT(false); + +static void globalShutdownSignalHandler(int signal) { + // Simply set the running flag to false on SIGTERM and SIGINT (CTRL+C) for global shutdown. + if (signal == SIGTERM || signal == SIGINT) { + atomic_store(&globalShutdown, true); + } +} + +int main(void) { + // Install signal handler for global shutdown. +#ifdef _WIN32 + signal(SIGTERM, globalShutdownSignalHandler); + signal(SIGINT, globalShutdownSignalHandler); +#else + struct sigaction shutdownAction; + + shutdownAction.sa_handler = &globalShutdownSignalHandler; + shutdownAction.sa_flags = 0; + sigemptyset(&shutdownAction.sa_mask); + sigaddset(&shutdownAction.sa_mask, SIGTERM); + sigaddset(&shutdownAction.sa_mask, SIGINT); + + if (sigaction(SIGTERM, &shutdownAction, NULL) == -1) { + caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGTERM. Error: %d.", errno); + return (EXIT_FAILURE); + } + + if (sigaction(SIGINT, &shutdownAction, NULL) == -1) { + caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGINT. Error: %d.", errno); + return (EXIT_FAILURE); + } +#endif + + // Open a DAVIS, give it a device ID of 1, and don't care about USB bus or SN restrictions. + caerDeviceHandle davis_handle = caerDeviceOpen(1, CAER_DEVICE_DAVIS_FX2, 0, 0, NULL); + if (davis_handle == NULL) { + return (EXIT_FAILURE); + } + + // Let's take a look at the information we have on the device. + struct caer_davis_info davis_info = caerDavisInfoGet(davis_handle); + + printf("%s --- ID: %d, Master: %d, DVS X: %d, DVS Y: %d, Logic: %d.\n", davis_info.deviceString, + davis_info.deviceID, davis_info.deviceIsMaster, davis_info.dvsSizeX, davis_info.dvsSizeY, + davis_info.logicVersion); + + // Send the default configuration before using the device. + // No configuration is sent automatically! + caerDeviceSendDefaultConfig(davis_handle); + + // Tweak some biases, to increase bandwidth in this case. + struct caer_bias_coarsefine coarseFineBias; + + coarseFineBias.coarseValue = 2; + coarseFineBias.fineValue = 116; + coarseFineBias.enabled = true; + coarseFineBias.sexN = false; + coarseFineBias.typeNormal = true; + coarseFineBias.currentLevelNormal = true; + caerDeviceConfigSet(davis_handle, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_PRBP, + caerBiasCoarseFineGenerate(coarseFineBias)); + + coarseFineBias.coarseValue = 1; + coarseFineBias.fineValue = 33; + coarseFineBias.enabled = true; + coarseFineBias.sexN = false; + coarseFineBias.typeNormal = true; + coarseFineBias.currentLevelNormal = true; + caerDeviceConfigSet(davis_handle, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_PRSFBP, + caerBiasCoarseFineGenerate(coarseFineBias)); + + // Let's verify they really changed! + uint32_t prBias, prsfBias; + caerDeviceConfigGet(davis_handle, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_PRBP, &prBias); + caerDeviceConfigGet(davis_handle, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_PRSFBP, &prsfBias); + + printf("New bias values --- PR-coarse: %d, PR-fine: %d, PRSF-coarse: %d, PRSF-fine: %d.\n", + caerBiasCoarseFineParse(prBias).coarseValue, caerBiasCoarseFineParse(prBias).fineValue, + caerBiasCoarseFineParse(prsfBias).coarseValue, caerBiasCoarseFineParse(prsfBias).fineValue); + + // Now let's get start getting some data from the device. We just loop, no notification needed. + caerDeviceDataStart(davis_handle, NULL, NULL, NULL, NULL, NULL); + + // Let's turn on blocking data-get mode to avoid wasting resources. + caerDeviceConfigSet(davis_handle, CAER_HOST_CONFIG_DATAEXCHANGE, CAER_HOST_CONFIG_DATAEXCHANGE_BLOCKING, true); + + while (!atomic_load_explicit(&globalShutdown, memory_order_relaxed)) { + caerEventPacketContainer packetContainer = caerDeviceDataGet(davis_handle); + if (packetContainer == NULL) { + continue; // Skip if nothing there. + } + + int32_t packetNum = caerEventPacketContainerGetEventPacketsNumber(packetContainer); + + printf("\nGot event container with %d packets (allocated).\n", packetNum); + + for (int32_t i = 0; i < packetNum; i++) { + caerEventPacketHeader packetHeader = caerEventPacketContainerGetEventPacket(packetContainer, i); + if (packetHeader == NULL) { + printf("Packet %d is empty (not present).\n", i); + continue; // Skip if nothing there. + } + + printf("Packet %d of type %d -> size is %d.\n", i, caerEventPacketHeaderGetEventType(packetHeader), + caerEventPacketHeaderGetEventNumber(packetHeader)); + + // Packet 0 is always the special events packet for DVS128, while packet is the polarity events packet. + if (i == POLARITY_EVENT) { + caerPolarityEventPacket polarity = (caerPolarityEventPacket) packetHeader; + + // Get full timestamp and addresses of first event. + caerPolarityEvent firstEvent = caerPolarityEventPacketGetEvent(polarity, 0); + + int32_t ts = caerPolarityEventGetTimestamp(firstEvent); + uint16_t x = caerPolarityEventGetX(firstEvent); + uint16_t y = caerPolarityEventGetY(firstEvent); + bool pol = caerPolarityEventGetPolarity(firstEvent); + + printf("First polarity event - ts: %d, x: %d, y: %d, pol: %d.\n", ts, x, y, pol); + } + } + + caerEventPacketContainerFree(packetContainer); + } + + caerDeviceDataStop(davis_handle); + + caerDeviceClose(&davis_handle); + + printf("Shutdown successful.\n"); + + return (EXIT_SUCCESS); +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/davis_simple.cpp b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/davis_simple.cpp new file mode 100755 index 0000000..11fdc72 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/davis_simple.cpp @@ -0,0 +1,142 @@ +#include <libcaer/libcaer.h> +#include <libcaer/devices/davis.h> +#include <cstdio> +#include <csignal> +#include <atomic> + +using namespace std; + +static atomic_bool globalShutdown(false); + +static void globalShutdownSignalHandler(int signal) { + // Simply set the running flag to false on SIGTERM and SIGINT (CTRL+C) for global shutdown. + if (signal == SIGTERM || signal == SIGINT) { + globalShutdown.store(true); + } +} + +int main(void) { +#ifdef _WIN32 + signal(SIGTERM, globalShutdownSignalHandler); + signal(SIGINT, globalShutdownSignalHandler); +#else + // Install signal handler for global shutdown. + struct sigaction shutdownAction; + + shutdownAction.sa_handler = &globalShutdownSignalHandler; + shutdownAction.sa_flags = 0; + sigemptyset(&shutdownAction.sa_mask); + sigaddset(&shutdownAction.sa_mask, SIGTERM); + sigaddset(&shutdownAction.sa_mask, SIGINT); + + if (sigaction(SIGTERM, &shutdownAction, NULL) == -1) { + caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGTERM. Error: %d.", errno); + return (EXIT_FAILURE); + } + + if (sigaction(SIGINT, &shutdownAction, NULL) == -1) { + caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGINT. Error: %d.", errno); + return (EXIT_FAILURE); + } +#endif + + // Open a DAVIS, give it a device ID of 1, and don't care about USB bus or SN restrictions. + caerDeviceHandle davis_handle = caerDeviceOpen(1, CAER_DEVICE_DAVIS_FX2, 0, 0, NULL); + if (davis_handle == NULL) { + return (EXIT_FAILURE); + } + + // Let's take a look at the information we have on the device. + struct caer_davis_info davis_info = caerDavisInfoGet(davis_handle); + + printf("%s --- ID: %d, Master: %d, DVS X: %d, DVS Y: %d, Logic: %d.\n", davis_info.deviceString, + davis_info.deviceID, davis_info.deviceIsMaster, davis_info.dvsSizeX, davis_info.dvsSizeY, + davis_info.logicVersion); + + // Send the default configuration before using the device. + // No configuration is sent automatically! + caerDeviceSendDefaultConfig(davis_handle); + + // Tweak some biases, to increase bandwidth in this case. + struct caer_bias_coarsefine coarseFineBias; + + coarseFineBias.coarseValue = 2; + coarseFineBias.fineValue = 116; + coarseFineBias.enabled = true; + coarseFineBias.sexN = false; + coarseFineBias.typeNormal = true; + coarseFineBias.currentLevelNormal = true; + caerDeviceConfigSet(davis_handle, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_PRBP, + caerBiasCoarseFineGenerate(coarseFineBias)); + + coarseFineBias.coarseValue = 1; + coarseFineBias.fineValue = 33; + coarseFineBias.enabled = true; + coarseFineBias.sexN = false; + coarseFineBias.typeNormal = true; + coarseFineBias.currentLevelNormal = true; + caerDeviceConfigSet(davis_handle, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_PRSFBP, + caerBiasCoarseFineGenerate(coarseFineBias)); + + // Let's verify they really changed! + uint32_t prBias, prsfBias; + caerDeviceConfigGet(davis_handle, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_PRBP, &prBias); + caerDeviceConfigGet(davis_handle, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_PRSFBP, &prsfBias); + + printf("New bias values --- PR-coarse: %d, PR-fine: %d, PRSF-coarse: %d, PRSF-fine: %d.\n", + caerBiasCoarseFineParse(prBias).coarseValue, caerBiasCoarseFineParse(prBias).fineValue, + caerBiasCoarseFineParse(prsfBias).coarseValue, caerBiasCoarseFineParse(prsfBias).fineValue); + + // Now let's get start getting some data from the device. We just loop, no notification needed. + caerDeviceDataStart(davis_handle, NULL, NULL, NULL, NULL, NULL); + + // Let's turn on blocking data-get mode to avoid wasting resources. + caerDeviceConfigSet(davis_handle, CAER_HOST_CONFIG_DATAEXCHANGE, CAER_HOST_CONFIG_DATAEXCHANGE_BLOCKING, true); + + while (!globalShutdown.load(memory_order_relaxed)) { + caerEventPacketContainer packetContainer = caerDeviceDataGet(davis_handle); + if (packetContainer == NULL) { + continue; // Skip if nothing there. + } + + int32_t packetNum = caerEventPacketContainerGetEventPacketsNumber(packetContainer); + + printf("\nGot event container with %d packets (allocated).\n", packetNum); + + for (int32_t i = 0; i < packetNum; i++) { + caerEventPacketHeader packetHeader = caerEventPacketContainerGetEventPacket(packetContainer, i); + if (packetHeader == NULL) { + printf("Packet %d is empty (not present).\n", i); + continue; // Skip if nothing there. + } + + printf("Packet %d of type %d -> size is %d.\n", i, caerEventPacketHeaderGetEventType(packetHeader), + caerEventPacketHeaderGetEventNumber(packetHeader)); + + // Packet 0 is always the special events packet for DVS128, while packet is the polarity events packet. + if (i == POLARITY_EVENT) { + caerPolarityEventPacket polarity = (caerPolarityEventPacket) packetHeader; + + // Get full timestamp and addresses of first event. + caerPolarityEvent firstEvent = caerPolarityEventPacketGetEvent(polarity, 0); + + int32_t ts = caerPolarityEventGetTimestamp(firstEvent); + uint16_t x = caerPolarityEventGetX(firstEvent); + uint16_t y = caerPolarityEventGetY(firstEvent); + bool pol = caerPolarityEventGetPolarity(firstEvent); + + printf("First polarity event - ts: %d, x: %d, y: %d, pol: %d.\n", ts, x, y, pol); + } + } + + caerEventPacketContainerFree(packetContainer); + } + + caerDeviceDataStop(davis_handle); + + caerDeviceClose(&davis_handle); + + printf("Shutdown successful.\n"); + + return (EXIT_SUCCESS); +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/dvs128_simple.c b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/dvs128_simple.c new file mode 100755 index 0000000..9d21433 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/dvs128_simple.c @@ -0,0 +1,116 @@ +#include <libcaer/libcaer.h> +#include <libcaer/devices/dvs128.h> +#include <stdio.h> +#include <signal.h> +#include <stdatomic.h> + +static atomic_bool globalShutdown = ATOMIC_VAR_INIT(false); + +static void globalShutdownSignalHandler(int signal) { + // Simply set the running flag to false on SIGTERM and SIGINT (CTRL+C) for global shutdown. + if (signal == SIGTERM || signal == SIGINT) { + atomic_store(&globalShutdown, true); + } +} + +int main(void) { + // Install signal handler for global shutdown. + struct sigaction shutdownAction; + + shutdownAction.sa_handler = &globalShutdownSignalHandler; + shutdownAction.sa_flags = 0; + sigemptyset(&shutdownAction.sa_mask); + sigaddset(&shutdownAction.sa_mask, SIGTERM); + sigaddset(&shutdownAction.sa_mask, SIGINT); + + if (sigaction(SIGTERM, &shutdownAction, NULL) == -1) { + caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGTERM. Error: %d.", errno); + return (EXIT_FAILURE); + } + + if (sigaction(SIGINT, &shutdownAction, NULL) == -1) { + caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGINT. Error: %d.", errno); + return (EXIT_FAILURE); + } + + // Open a DVS128, give it a device ID of 1, and don't care about USB bus or SN restrictions. + caerDeviceHandle dvs128_handle = caerDeviceOpen(1, CAER_DEVICE_DVS128, 0, 0, NULL); + if (dvs128_handle == NULL) { + return (EXIT_FAILURE); + } + + // Let's take a look at the information we have on the device. + struct caer_dvs128_info dvs128_info = caerDVS128InfoGet(dvs128_handle); + + printf("%s --- ID: %d, Master: %d, DVS X: %d, DVS Y: %d, Logic: %d.\n", dvs128_info.deviceString, + dvs128_info.deviceID, dvs128_info.deviceIsMaster, dvs128_info.dvsSizeX, dvs128_info.dvsSizeY, + dvs128_info.logicVersion); + + // Send the default configuration before using the device. + // No configuration is sent automatically! + caerDeviceSendDefaultConfig(dvs128_handle); + + // Tweak some biases, to increase bandwidth in this case. + caerDeviceConfigSet(dvs128_handle, DVS128_CONFIG_BIAS, DVS128_CONFIG_BIAS_PR, 695); + caerDeviceConfigSet(dvs128_handle, DVS128_CONFIG_BIAS, DVS128_CONFIG_BIAS_FOLL, 867); + + // Let's verify they really changed! + uint32_t prBias, follBias; + caerDeviceConfigGet(dvs128_handle, DVS128_CONFIG_BIAS, DVS128_CONFIG_BIAS_PR, &prBias); + caerDeviceConfigGet(dvs128_handle, DVS128_CONFIG_BIAS, DVS128_CONFIG_BIAS_FOLL, &follBias); + + printf("New bias values --- PR: %d, FOLL: %d.\n", prBias, follBias); + + // Now let's get start getting some data from the device. We just loop, no notification needed. + caerDeviceDataStart(dvs128_handle, NULL, NULL, NULL, NULL, NULL); + + // Let's turn on blocking data-get mode to avoid wasting resources. + caerDeviceConfigSet(dvs128_handle, CAER_HOST_CONFIG_DATAEXCHANGE, CAER_HOST_CONFIG_DATAEXCHANGE_BLOCKING, true); + + while (!atomic_load_explicit(&globalShutdown, memory_order_relaxed)) { + caerEventPacketContainer packetContainer = caerDeviceDataGet(dvs128_handle); + if (packetContainer == NULL) { + continue; // Skip if nothing there. + } + + int32_t packetNum = caerEventPacketContainerGetEventPacketsNumber(packetContainer); + + printf("\nGot event container with %d packets (allocated).\n", packetNum); + + for (int32_t i = 0; i < packetNum; i++) { + caerEventPacketHeader packetHeader = caerEventPacketContainerGetEventPacket(packetContainer, i); + if (packetHeader == NULL) { + printf("Packet %d is empty (not present).\n", i); + continue; // Skip if nothing there. + } + + printf("Packet %d of type %d -> size is %d.\n", i, caerEventPacketHeaderGetEventType(packetHeader), + caerEventPacketHeaderGetEventNumber(packetHeader)); + + // Packet 0 is always the special events packet for DVS128, while packet is the polarity events packet. + if (i == POLARITY_EVENT) { + caerPolarityEventPacket polarity = (caerPolarityEventPacket) packetHeader; + + // Get full timestamp and addresses of first event. + caerPolarityEvent firstEvent = caerPolarityEventPacketGetEvent(polarity, 0); + + int32_t ts = caerPolarityEventGetTimestamp(firstEvent); + uint16_t x = caerPolarityEventGetX(firstEvent); + uint16_t y = caerPolarityEventGetY(firstEvent); + bool pol = caerPolarityEventGetPolarity(firstEvent); + + printf("First polarity event - ts: %d, x: %d, y: %d, pol: %d.\n", ts, x, y, pol); + } + } + + caerEventPacketContainerFree(packetContainer); + } + + caerDeviceDataStop(dvs128_handle); + + caerDeviceClose(&dvs128_handle); + + printf("Shutdown successful.\n"); + + return (EXIT_SUCCESS); +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/dvs128_simple.cpp b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/dvs128_simple.cpp new file mode 100755 index 0000000..874a922 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/examples/dvs128_simple.cpp @@ -0,0 +1,118 @@ +#include <libcaer/libcaer.h> +#include <libcaer/devices/dvs128.h> +#include <cstdio> +#include <csignal> +#include <atomic> + +using namespace std; + +static atomic_bool globalShutdown(false); + +static void globalShutdownSignalHandler(int signal) { + // Simply set the running flag to false on SIGTERM and SIGINT (CTRL+C) for global shutdown. + if (signal == SIGTERM || signal == SIGINT) { + globalShutdown.store(true); + } +} + +int main(void) { + // Install signal handler for global shutdown. + struct sigaction shutdownAction; + + shutdownAction.sa_handler = &globalShutdownSignalHandler; + shutdownAction.sa_flags = 0; + sigemptyset(&shutdownAction.sa_mask); + sigaddset(&shutdownAction.sa_mask, SIGTERM); + sigaddset(&shutdownAction.sa_mask, SIGINT); + + if (sigaction(SIGTERM, &shutdownAction, NULL) == -1) { + caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGTERM. Error: %d.", errno); + return (EXIT_FAILURE); + } + + if (sigaction(SIGINT, &shutdownAction, NULL) == -1) { + caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGINT. Error: %d.", errno); + return (EXIT_FAILURE); + } + + // Open a DVS128, give it a device ID of 1, and don't care about USB bus or SN restrictions. + caerDeviceHandle dvs128_handle = caerDeviceOpen(1, CAER_DEVICE_DVS128, 0, 0, NULL); + if (dvs128_handle == NULL) { + return (EXIT_FAILURE); + } + + // Let's take a look at the information we have on the device. + struct caer_dvs128_info dvs128_info = caerDVS128InfoGet(dvs128_handle); + + printf("%s --- ID: %d, Master: %d, DVS X: %d, DVS Y: %d, Logic: %d.\n", dvs128_info.deviceString, + dvs128_info.deviceID, dvs128_info.deviceIsMaster, dvs128_info.dvsSizeX, dvs128_info.dvsSizeY, + dvs128_info.logicVersion); + + // Send the default configuration before using the device. + // No configuration is sent automatically! + caerDeviceSendDefaultConfig(dvs128_handle); + + // Tweak some biases, to increase bandwidth in this case. + caerDeviceConfigSet(dvs128_handle, DVS128_CONFIG_BIAS, DVS128_CONFIG_BIAS_PR, 695); + caerDeviceConfigSet(dvs128_handle, DVS128_CONFIG_BIAS, DVS128_CONFIG_BIAS_FOLL, 867); + + // Let's verify they really changed! + uint32_t prBias, follBias; + caerDeviceConfigGet(dvs128_handle, DVS128_CONFIG_BIAS, DVS128_CONFIG_BIAS_PR, &prBias); + caerDeviceConfigGet(dvs128_handle, DVS128_CONFIG_BIAS, DVS128_CONFIG_BIAS_FOLL, &follBias); + + printf("New bias values --- PR: %d, FOLL: %d.\n", prBias, follBias); + + // Now let's get start getting some data from the device. We just loop, no notification needed. + caerDeviceDataStart(dvs128_handle, NULL, NULL, NULL, NULL, NULL); + + // Let's turn on blocking data-get mode to avoid wasting resources. + caerDeviceConfigSet(dvs128_handle, CAER_HOST_CONFIG_DATAEXCHANGE, CAER_HOST_CONFIG_DATAEXCHANGE_BLOCKING, true); + + while (!globalShutdown.load(memory_order_relaxed)) { + caerEventPacketContainer packetContainer = caerDeviceDataGet(dvs128_handle); + if (packetContainer == NULL) { + continue; // Skip if nothing there. + } + + int32_t packetNum = caerEventPacketContainerGetEventPacketsNumber(packetContainer); + + printf("\nGot event container with %d packets (allocated).\n", packetNum); + + for (int32_t i = 0; i < packetNum; i++) { + caerEventPacketHeader packetHeader = caerEventPacketContainerGetEventPacket(packetContainer, i); + if (packetHeader == NULL) { + printf("Packet %d is empty (not present).\n", i); + continue; // Skip if nothing there. + } + + printf("Packet %d of type %d -> size is %d.\n", i, caerEventPacketHeaderGetEventType(packetHeader), + caerEventPacketHeaderGetEventNumber(packetHeader)); + + // Packet 0 is always the special events packet for DVS128, while packet is the polarity events packet. + if (i == POLARITY_EVENT) { + caerPolarityEventPacket polarity = (caerPolarityEventPacket) packetHeader; + + // Get full timestamp and addresses of first event. + caerPolarityEvent firstEvent = caerPolarityEventPacketGetEvent(polarity, 0); + + int32_t ts = caerPolarityEventGetTimestamp(firstEvent); + uint16_t x = caerPolarityEventGetX(firstEvent); + uint16_t y = caerPolarityEventGetY(firstEvent); + bool pol = caerPolarityEventGetPolarity(firstEvent); + + printf("First polarity event - ts: %d, x: %d, y: %d, pol: %d.\n", ts, x, y, pol); + } + } + + caerEventPacketContainerFree(packetContainer); + } + + caerDeviceDataStop(dvs128_handle); + + caerDeviceClose(&dvs128_handle); + + printf("Shutdown successful.\n"); + + return (EXIT_SUCCESS); +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/.gitignore b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/.gitignore new file mode 100755 index 0000000..6c7aec8 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/.gitignore @@ -0,0 +1 @@ +/libcaer.h diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/CMakeLists.txt b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/CMakeLists.txt new file mode 100755 index 0000000..fdefea8 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/CMakeLists.txt @@ -0,0 +1,10 @@ +CONFIGURE_FILE(libcaer_in.h ${CMAKE_CURRENT_SOURCE_DIR}/libcaer.h @ONLY) + +SET(INC_INSTALL_DIR ${CMAKE_INSTALL_INCLUDEDIR}/${CMAKE_PROJECT_NAME}) +INSTALL(FILES libcaer.h log.h portable_endian.h frame_utils.h DESTINATION ${INC_INSTALL_DIR}) +INSTALL(DIRECTORY events DESTINATION ${INC_INSTALL_DIR}) +INSTALL(DIRECTORY devices DESTINATION ${INC_INSTALL_DIR}) + +IF (ENABLE_OPENCV) + INSTALL(FILES frame_utils_opencv.h DESTINATION ${INC_INSTALL_DIR}) +ENDIF() diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/devices/davis.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/devices/davis.h new file mode 100755 index 0000000..89a8d39 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/devices/davis.h @@ -0,0 +1,1823 @@ +/** + * @file davis.h + * + * DAVIS specific configuration defines and information structures. + */ + +#ifndef LIBCAER_DEVICES_DAVIS_H_ +#define LIBCAER_DEVICES_DAVIS_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usb.h" +#include "../events/polarity.h" +#include "../events/special.h" +#include "../events/frame.h" +#include "../events/imu6.h" + +/** + * Device type definition for iniLabs DAVIS FX2-based boards, like DAVIS240a/b/c. + */ +#define CAER_DEVICE_DAVIS_FX2 1 +/** + * Device type definition for iniLabs DAVIS FX3-based boards, like DAVIS640. + */ +#define CAER_DEVICE_DAVIS_FX3 2 + +/** + * DAVIS240A chip identifier. + * 240x180, no color, no global shutter. + */ +#define DAVIS_CHIP_DAVIS240A 0 +/** + * DAVIS240B chip identifier. + * 240x180, no color, 50 test columns left-side. + */ +#define DAVIS_CHIP_DAVIS240B 1 +/** + * DAVIS240C chip identifier. + * 240x180, no color. + */ +#define DAVIS_CHIP_DAVIS240C 2 +/** + * DAVIS128 chip identifier. + * 128x128, color possible, internal ADC. + */ +#define DAVIS_CHIP_DAVIS128 3 +/** + * DAVIS346A chip identifier. + * 346x260, color possible, internal ADC. + */ +#define DAVIS_CHIP_DAVIS346A 4 +/** + * DAVIS346B chip identifier. + * 346x260, color possible, internal ADC. + */ +#define DAVIS_CHIP_DAVIS346B 5 +/** + * DAVIS640 chip identifier. + * 640x480, color possible, internal ADC. + */ +#define DAVIS_CHIP_DAVIS640 6 +/** + * DAVISRGB chip identifier. + * 640x480 APS, 320x240 DVS, color possible, internal ADC. + */ +#define DAVIS_CHIP_DAVISRGB 7 +/** + * DAVIS208 chip identifier. + * 208x192, special sensitive test pixels, color possible, internal ADC. + */ +#define DAVIS_CHIP_DAVIS208 8 +/** + * DAVIS346C chip identifier. + * 346x260, BSI, color possible, internal ADC. + */ +#define DAVIS_CHIP_DAVIS346C 9 + +//@{ +/** + * Macros to check a chip identifier integer against the known chip types. + * Returns true if a chip identifier matches, false otherwise. + */ +#define IS_DAVIS128(chipID) ((chipID) == DAVIS_CHIP_DAVIS128) +#define IS_DAVIS208(chipID) ((chipID) == DAVIS_CHIP_DAVIS208) +#define IS_DAVIS240A(chipID) ((chipID) == DAVIS_CHIP_DAVIS240A) +#define IS_DAVIS240B(chipID) ((chipID) == DAVIS_CHIP_DAVIS240B) +#define IS_DAVIS240C(chipID) ((chipID) == DAVIS_CHIP_DAVIS240C) +#define IS_DAVIS240(chipID) (IS_DAVIS240A(chipID) || IS_DAVIS240B(chipID) || IS_DAVIS240C(chipID)) +#define IS_DAVIS346A(chipID) ((chipID) == DAVIS_CHIP_DAVIS346A) +#define IS_DAVIS346B(chipID) ((chipID) == DAVIS_CHIP_DAVIS346B) +#define IS_DAVIS346C(chipID) ((chipID) == DAVIS_CHIP_DAVIS346C) +#define IS_DAVIS346(chipID) (IS_DAVIS346A(chipID) || IS_DAVIS346B(chipID) || IS_DAVIS346C(chipID)) +#define IS_DAVIS640(chipID) ((chipID) == DAVIS_CHIP_DAVIS640) +#define IS_DAVISRGB(chipID) ((chipID) == DAVIS_CHIP_DAVISRGB) +//@} + +/** + * Module address: device-side Multiplexer configuration. + * The Multiplexer is responsible for mixing, timestamping and outputting + * (via USB) the various event types generated by the device. It is also + * responsible for timestamp generation and synchronization. + */ +#define DAVIS_CONFIG_MUX 0 +/** + * Module address: device-side DVS configuration. + * The DVS state machine handshakes with the chip's AER bus and gets the + * polarity events from it. It supports various configurable delays, as + * well as advanced filtering capabilities on the polarity events. + */ +#define DAVIS_CONFIG_DVS 1 +/** + * Module address: device-side APS (Frame) configuration. + * The APS (Active-Pixel-Sensor) is responsible for getting the normal, + * synchronous frame from the camera chip. It supports various options + * for very precise timing control, as well as Region of Interest imaging. + */ +#define DAVIS_CONFIG_APS 2 +/** + * Module address: device-side IMU (Inertial Measurement Unit) configuration. + * The IMU module connects to the external IMU chip and sends data on the + * device's movement in space. It can configure various options on the external + * chip, such as accelerometer range or gyroscope refresh rate. + */ +#define DAVIS_CONFIG_IMU 3 +/** + * Module address: device-side External Input (signal detector/generator) configuration. + * The External Input module is used to detect external signals on the external input + * jack and inject an event into the event stream when this happens. It can detect pulses + * of a specific length or rising and falling edges. + * On some systems, a signal generator module is also present, which can generate + * PWM-like pulsed signals with configurable timing. + */ +#define DAVIS_CONFIG_EXTINPUT 4 +/** + * Module address: device-side chip bias configuration. + * Shared with DAVIS_CONFIG_CHIP. + * This state machine is responsible for configuring the chip's bias generator. + */ +#define DAVIS_CONFIG_BIAS 5 +/** + * Module address: device-side chip control configuration. + * Shared with DAVIS_CONFIG_BIAS. + * This state machine is responsible for configuring the chip's internal + * control shift registers, to set special options. + */ +#define DAVIS_CONFIG_CHIP 5 +/** + * Module address: device-side system information. + * The system information module provides various details on the device, such + * as currently installed logic revision or clock speeds. + * All its parameters are read-only. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation for more details on what information is available. + */ +#define DAVIS_CONFIG_SYSINFO 6 +/** + * Module address: device-side USB output configuration. + * The USB output module forwards the data from the device and the FPGA/CPLD to + * the USB chip, usually a Cypress FX2 or FX3. + */ +#define DAVIS_CONFIG_USB 9 + +/** + * Parameter address for module DAVIS_CONFIG_MUX: + * run the Multiplexer state machine, which is responsible for + * mixing the various event types at the device level, timestamping + * them and outputting them via USB or other connectors. + */ +#define DAVIS_CONFIG_MUX_RUN 0 +/** + * Parameter address for module DAVIS_CONFIG_MUX: + * run the Timestamp Generator inside the Multiplexer state machine, + * which will provide microsecond accurate timestamps to the + * events passing through. + */ +#define DAVIS_CONFIG_MUX_TIMESTAMP_RUN 1 +/** + * Parameter address for module DAVIS_CONFIG_MUX: + * reset the Timestamp Generator to zero. This also sends a reset + * pulse to all connected slave devices, resetting their timestamp too. + */ +#define DAVIS_CONFIG_MUX_TIMESTAMP_RESET 2 +/** + * Parameter address for module DAVIS_CONFIG_MUX: + * under normal circumstances, the chip's bias generator is only powered + * up when either the DVS or the APS state machines are running, to save + * power. This flag forces the bias generator to be powered up all the time, + * which may be useful when one wants to shut-down both APS and DVS + * temporarily, but still have a quick and well-defined resume behavior. + */ +#define DAVIS_CONFIG_MUX_FORCE_CHIP_BIAS_ENABLE 3 +/** + * Parameter address for module DAVIS_CONFIG_MUX: + * drop DVS events if the USB output FIFO is full, instead of having + * them pile up at the input FIFOs. + */ +#define DAVIS_CONFIG_MUX_DROP_DVS_ON_TRANSFER_STALL 4 +/** + * Parameter address for module DAVIS_CONFIG_MUX: + * drop APS events if the USB output FIFO is full, instead of having + * them pile up at the input FIFOs. + * This normally should not be enabled to guarantee complete, coherent + * frame events, though small timing differences may cause a reduction + * in observed image quality. + */ +#define DAVIS_CONFIG_MUX_DROP_APS_ON_TRANSFER_STALL 5 +/** + * Parameter address for module DAVIS_CONFIG_MUX: + * drop IMU events if the USB output FIFO is full, instead of having + * them pile up at the input FIFOs. + * This normally should not be enabled to guarantee complete, coherent + * IMU events, and not get incomplete or wrong IMU information. + */ +#define DAVIS_CONFIG_MUX_DROP_IMU_ON_TRANSFER_STALL 6 +/** + * Parameter address for module DAVIS_CONFIG_MUX: + * drop External Input events if the USB output FIFO is full, instead of having + * them pile up at the input FIFOs. + */ +#define DAVIS_CONFIG_MUX_DROP_EXTINPUT_ON_TRANSFER_STALL 7 + +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * read-only parameter, contains the X axis resolution of the + * DVS events returned by the camera. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get proper size information that already + * considers the rotation and orientation settings. + */ +#define DAVIS_CONFIG_DVS_SIZE_COLUMNS 0 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * read-only parameter, contains the Y axis resolution of the + * DVS events returned by the camera. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get proper size information that already + * considers the rotation and orientation settings. + */ +#define DAVIS_CONFIG_DVS_SIZE_ROWS 1 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * read-only parameter, contains information on the orientation + * of the X/Y axes, whether they should be inverted or not on + * the host when parsing incoming events. + * Bit 0: dvsInvertXY + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get proper size information that already + * considers the rotation and orientation settings. + */ +#define DAVIS_CONFIG_DVS_ORIENTATION_INFO 2 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * run the DVS state machine and get polarity events from the chip by + * handshaking with its AER bus. + */ +#define DAVIS_CONFIG_DVS_RUN 3 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * delay capturing the data and acknowledging it on the AER bus for + * the row events (serial AER protocol) by this many LogicClock cycles. + */ +#define DAVIS_CONFIG_DVS_ACK_DELAY_ROW 4 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * delay capturing the data and acknowledging it on the AER bus for + * the column events (serial AER protocol) by this many LogicClock cycles. + */ +#define DAVIS_CONFIG_DVS_ACK_DELAY_COLUMN 5 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * extend the length of the acknowledge on the AER bus for + * the row events (serial AER protocol) by this many LogicClock cycles. + */ +#define DAVIS_CONFIG_DVS_ACK_EXTENSION_ROW 6 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * extend the length of the acknowledge on the AER bus for + * the column events (serial AER protocol) by this many LogicClock cycles. + */ +#define DAVIS_CONFIG_DVS_ACK_EXTENSION_COLUMN 7 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * if the output FIFO for this module is full, stall the AER handshake with + * the chip and wait until it's free again, instead of just continuing + * the handshake and dropping the resulting events. + */ +#define DAVIS_CONFIG_DVS_WAIT_ON_TRANSFER_STALL 8 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * enable row-only event filter, to eliminate spurious row events with no + * following columns events. This can happen on DAVIS240 chips, or + * following the various pixel and background-activity filtering stages, + * which drop column events to achieve their effect. + * This should always be enabled! + */ +#define DAVIS_CONFIG_DVS_FILTER_ROW_ONLY_EVENTS 9 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * enable external AER control. This ensures the chip and the DVS pixel + * array are running, but doesn't do the handshake and leaves the ACK + * pin in high-impedance, to allow for an external system to take + * over the AER communication with the chip. + * DAVIS_CONFIG_DVS_RUN has to be turned off for this to work. + */ +#define DAVIS_CONFIG_DVS_EXTERNAL_AER_CONTROL 10 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * read-only parameter, information about the presence of the + * pixel filter feature. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get this information. + */ +#define DAVIS_CONFIG_DVS_HAS_PIXEL_FILTER 11 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 0, Y axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_0_ROW 12 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 0, X axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_0_COLUMN 13 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 1, Y axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_1_ROW 14 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 1, X axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_1_COLUMN 15 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 2, Y axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_2_ROW 16 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 2, X axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_2_COLUMN 17 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 3, Y axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_3_ROW 18 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 3, X axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_3_COLUMN 19 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 4, Y axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_4_ROW 20 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 4, X axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_4_COLUMN 21 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 5, Y axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_5_ROW 22 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 5, X axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_5_COLUMN 23 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 6, Y axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_6_ROW 24 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 6, X axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_6_COLUMN 25 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 7, Y axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_7_ROW 26 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * the pixel filter completely suppresses up to eight pixels in the + * DVS array, filtering out all events produced by them. + * This is the pixel 7, X axis setting. + */ +#define DAVIS_CONFIG_DVS_FILTER_PIXEL_7_COLUMN 27 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * read-only parameter, information about the presence of the + * background-activity filter feature. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get this information. + */ +#define DAVIS_CONFIG_DVS_HAS_BACKGROUND_ACTIVITY_FILTER 28 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * enable the background-activity filter, which tries to remove events + * caused by transistor leakage, by rejecting uncorrelated events. + */ +#define DAVIS_CONFIG_DVS_FILTER_BACKGROUND_ACTIVITY 29 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * specify the time difference constant for the background-activity + * filter in microseconds. Events that do correlated within this + * time-frame are let through, while others are filtered out. + */ +#define DAVIS_CONFIG_DVS_FILTER_BACKGROUND_ACTIVITY_DELTAT 30 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * read-only parameter, information about the presence of the + * test event generator feature. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get this information. + */ +#define DAVIS_CONFIG_DVS_HAS_TEST_EVENT_GENERATOR 31 +/** + * Parameter address for module DAVIS_CONFIG_DVS: + * enable the test event generator for debugging purposes. + * This generates fake events that appear to originate from all rows + * sequentially, and for each row going through all its columns, + * first with an ON polarity and then with an OFF polarity. + * Both DAVIS_CONFIG_DVS_RUN and DAVIS_CONFIG_DVS_EXTERNAL_AER_CONTROL + * have to be turned off for this to work. + */ +#define DAVIS_CONFIG_DVS_TEST_EVENT_GENERATOR_ENABLE 32 + +/** + * Parameter address for module DAVIS_CONFIG_APS: + * read-only parameter, contains the X axis resolution of the + * APS frames returned by the camera. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get proper size information that already + * considers the rotation and orientation settings. + */ +#define DAVIS_CONFIG_APS_SIZE_COLUMNS 0 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * read-only parameter, contains the Y axis resolution of the + * APS frames returned by the camera. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get proper size information that already + * considers the rotation and orientation settings. + */ +#define DAVIS_CONFIG_APS_SIZE_ROWS 1 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * read-only parameter, contains information on the orientation + * of the X/Y axes, whether they should be inverted or not on + * the host when parsing incoming pixels, as well as if the X + * or Y axes need to be flipped when reading the pixels. + * Bit 2: apsInvertXY + * Bit 1: apsFlipX + * Bit 0: apsFlipY + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get proper size information that already + * considers the rotation and orientation settings. + */ +#define DAVIS_CONFIG_APS_ORIENTATION_INFO 2 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * read-only parameter, contains information on the type of + * color filter present on the device. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get proper color filter information. + */ +#define DAVIS_CONFIG_APS_COLOR_FILTER 3 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * enable the APS module and take intensity images of the scene. + * While this parameter is enabled, frames will be taken continuously. + * To slow down the frame-rate, see DAVIS_CONFIG_APS_FRAME_DELAY. + * To only take snapshots, see DAVIS_CONFIG_APS_SNAPSHOT. + */ +#define DAVIS_CONFIG_APS_RUN 4 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * enable the reset read phase in addition to the signal read, + * to allow for correlated double sampling schemes. This heavily + * improves image quality and should always be turned on. In special + * cases, especially when the camera is perfectly stationary, this + * can be turned off for longer periods of time to achieve a higher + * frame-rate and significantly faster frame capture. + */ +#define DAVIS_CONFIG_APS_RESET_READ 5 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * if the output FIFO for this module is full, stall the APS state machine + * and wait until it's free again, instead of just dropping the pixels as + * they are being read out. This guarantees a complete frame readout, at the + * possible cost of slight timing differences between pixels. If disabled, + * incomplete frames may be transmitted and will then be dropped on the host, + * resulting in lower frame-rates, especially during high DVS traffic. + */ +#define DAVIS_CONFIG_APS_WAIT_ON_TRANSFER_STALL 6 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * read-only parameter, information about the presence of the + * global shutter feature. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get this information. + */ +#define DAVIS_CONFIG_APS_HAS_GLOBAL_SHUTTER 7 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * enable Global Shutter mode instead of Rolling Shutter. + * The Global Shutter eliminates motion artifacts, but + * is noisier than the Rolling Shutter (worse quality). + */ +#define DAVIS_CONFIG_APS_GLOBAL_SHUTTER 8 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * start position on the X axis for Region of Interest 0. + * Must be between 0 and APS_SIZE_X-1, and be smaller + * or equal to DAVIS_CONFIG_APS_END_COLUMN_0 for the ROI + * region to be enabled. Setting it to APS_SIZE_X itself + * deactivates this ROI region completely. + */ +#define DAVIS_CONFIG_APS_START_COLUMN_0 9 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * start position on the Y axis for Region of Interest 0. + * Must be between 0 and APS_SIZE_Y-1, and be smaller + * or equal to DAVIS_CONFIG_APS_END_ROW_0. + */ +#define DAVIS_CONFIG_APS_START_ROW_0 10 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * end position on the X axis for Region of Interest 0. + * Must be between 0 and APS_SIZE_X-1, and be greater + * or equal to DAVIS_CONFIG_APS_START_COLUMN_0. + */ +#define DAVIS_CONFIG_APS_END_COLUMN_0 11 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * end position on the Y axis for Region of Interest 0. + * Must be between 0 and APS_SIZE_Y-1, and be greater + * or equal to DAVIS_CONFIG_APS_START_ROW_0. + */ +#define DAVIS_CONFIG_APS_END_ROW_0 12 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * frame exposure time in microseconds, up to about + * one second maximum. + * Very precise for Global Shutter, slightly less exact for + * Rolling Shutter due to column-based timing constraints. + */ +#define DAVIS_CONFIG_APS_EXPOSURE 13 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * delay between consecutive frames in microseconds, + * up to about one second maximum. + * This can be used to achieve slower frame-rates, down + * to about 1 Hertz. + */ +#define DAVIS_CONFIG_APS_FRAME_DELAY 14 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * column reset settle time in ADCClock cycles. + */ +#define DAVIS_CONFIG_APS_RESET_SETTLE 15 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * column settle time in ADCClock cycles. + */ +#define DAVIS_CONFIG_APS_COLUMN_SETTLE 16 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * row settle time in ADCClock cycles. + */ +#define DAVIS_CONFIG_APS_ROW_SETTLE 17 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * null (between states) settle time in ADCClock cycles. + */ +#define DAVIS_CONFIG_APS_NULL_SETTLE 18 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * read-only parameter, information about the presence of the + * Quadruple Region of Interest feature. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get this information. + */ +#define DAVIS_CONFIG_APS_HAS_QUAD_ROI 19 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * start position on the X axis for Region of Interest 1. + * Must be between 0 and APS_SIZE_X-1, and be smaller + * or equal to DAVIS_CONFIG_APS_END_COLUMN_1 for the ROI + * region to be enabled. Setting it to APS_SIZE_X itself + * deactivates this ROI region completely. + */ +#define DAVIS_CONFIG_APS_START_COLUMN_1 20 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * start position on the Y axis for Region of Interest 1. + * Must be between 0 and APS_SIZE_Y-1, and be smaller + * or equal to DAVIS_CONFIG_APS_END_ROW_1. + */ +#define DAVIS_CONFIG_APS_START_ROW_1 21 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * end position on the X axis for Region of Interest 1. + * Must be between 0 and APS_SIZE_X-1, and be greater + * or equal to DAVIS_CONFIG_APS_START_COLUMN_1. + */ +#define DAVIS_CONFIG_APS_END_COLUMN_1 22 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * end position on the Y axis for Region of Interest 1. + * Must be between 0 and APS_SIZE_Y-1, and be greater + * or equal to DAVIS_CONFIG_APS_START_ROW_1. + */ +#define DAVIS_CONFIG_APS_END_ROW_1 23 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * start position on the X axis for Region of Interest 2. + * Must be between 0 and APS_SIZE_X-1, and be smaller + * or equal to DAVIS_CONFIG_APS_END_COLUMN_2 for the ROI + * region to be enabled. Setting it to APS_SIZE_X itself + * deactivates this ROI region completely. + */ +#define DAVIS_CONFIG_APS_START_COLUMN_2 24 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * start position on the Y axis for Region of Interest 2. + * Must be between 0 and APS_SIZE_Y-1, and be smaller + * or equal to DAVIS_CONFIG_APS_END_ROW_2. + */ +#define DAVIS_CONFIG_APS_START_ROW_2 25 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * end position on the X axis for Region of Interest 2. + * Must be between 0 and APS_SIZE_X-1, and be greater + * or equal to DAVIS_CONFIG_APS_START_COLUMN_2. + */ +#define DAVIS_CONFIG_APS_END_COLUMN_2 26 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * end position on the Y axis for Region of Interest 2. + * Must be between 0 and APS_SIZE_Y-1, and be greater + * or equal to DAVIS_CONFIG_APS_START_ROW_2. + */ +#define DAVIS_CONFIG_APS_END_ROW_2 27 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * start position on the X axis for Region of Interest 3. + * Must be between 0 and APS_SIZE_X-1, and be smaller + * or equal to DAVIS_CONFIG_APS_END_COLUMN_3 for the ROI + * region to be enabled. Setting it to APS_SIZE_X itself + * deactivates this ROI region completely. + */ +#define DAVIS_CONFIG_APS_START_COLUMN_3 28 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * start position on the Y axis for Region of Interest 3. + * Must be between 0 and APS_SIZE_Y-1, and be smaller + * or equal to DAVIS_CONFIG_APS_END_ROW_3. + */ +#define DAVIS_CONFIG_APS_START_ROW_3 29 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * end position on the X axis for Region of Interest 3. + * Must be between 0 and APS_SIZE_X-1, and be greater + * or equal to DAVIS_CONFIG_APS_START_COLUMN_3. + */ +#define DAVIS_CONFIG_APS_END_COLUMN_3 30 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * end position on the Y axis for Region of Interest 3. + * Must be between 0 and APS_SIZE_Y-1, and be greater + * or equal to DAVIS_CONFIG_APS_START_ROW_3. + */ +#define DAVIS_CONFIG_APS_END_ROW_3 31 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * read-only parameter, information about the presence of an + * external ADC to read the pixel values. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get this information. + */ +#define DAVIS_CONFIG_APS_HAS_EXTERNAL_ADC 32 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * read-only parameter, information about the presence of an + * internal, on-chip ADC to read the pixel values. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get this information. + */ +#define DAVIS_CONFIG_APS_HAS_INTERNAL_ADC 33 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * use the internal, on-chip ADC instead of the external one. + * This enables a much faster and more power-efficient readout + * for the frames, and should as such always be preferred. + */ +#define DAVIS_CONFIG_APS_USE_INTERNAL_ADC 34 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * enable sampling of pixel voltage by the internal ADC circuitry. + * Must always be enabled to get proper frame values. + */ +#define DAVIS_CONFIG_APS_SAMPLE_ENABLE 35 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * sample settle time in ADCClock cycles. + */ +#define DAVIS_CONFIG_APS_SAMPLE_SETTLE 36 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * ramp reset time in ADCClock cycles. + */ +#define DAVIS_CONFIG_APS_RAMP_RESET 37 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * only perform a short ramp (half length) during reset reads, given that + * the voltage should always be close to the top of the range. + * This increases the frame-rate, but may have impacts on image quality, + * especially in very bright regions. + */ +#define DAVIS_CONFIG_APS_RAMP_SHORT_RESET 38 +/** + * Parameter address for module DAVIS_CONFIG_APS: + * put all APS pixels into reset, while keeping everything else running. + * This is only useful for testing and characterizing the internal + * ADC, to minimize noise. + */ +#define DAVIS_CONFIG_APS_ADC_TEST_MODE 39 + +// Extra timing settings for DAVISRGB APS module. +/** + * Parameter address for module DAVIS_CONFIG_APS (only for DAVIS RGB chip): + * charge transfer time in ADCClock cycles. + */ +#define DAVISRGB_CONFIG_APS_TRANSFER 50 +/** + * Parameter address for module DAVIS_CONFIG_APS (only for DAVIS RGB chip): + * Rolling Shutter FD settle time in ADCClock cycles. + */ +#define DAVISRGB_CONFIG_APS_RSFDSETTLE 51 +/** + * Parameter address for module DAVIS_CONFIG_APS (only for DAVIS RGB chip): + * Global Shutter PD reset time in ADCClock cycles. + */ +#define DAVISRGB_CONFIG_APS_GSPDRESET 52 +/** + * Parameter address for module DAVIS_CONFIG_APS (only for DAVIS RGB chip): + * Global Shutter Reset Fall time in ADCClock cycles. + */ +#define DAVISRGB_CONFIG_APS_GSRESETFALL 53 +/** + * Parameter address for module DAVIS_CONFIG_APS (only for DAVIS RGB chip): + * Global Shutter Transfer Fall time in ADCClock cycles. + */ +#define DAVISRGB_CONFIG_APS_GSTXFALL 54 +/** + * Parameter address for module DAVIS_CONFIG_APS (only for DAVIS RGB chip): + * Global Shutter FD reset time in ADCClock cycles. + */ +#define DAVISRGB_CONFIG_APS_GSFDRESET 55 + +/** + * Parameter address for module DAVIS_CONFIG_APS: + * takes a snapshot (one frame), like a photo-camera. + * More efficient implementation that just toggling + * the DAVIS_CONFIG_APS_RUN parameter. + * The APS module should not be running prior to calling this, + * as it only makes sense if frames are not being generated + * at the time. Also, DAVIS_CONFIG_APS_FRAME_DELAY should + * be set to zero if only doing snapshots, to ensure a + * quicker readiness for the next one, since the delay is + * always observed after taking a frame. + */ +#define DAVIS_CONFIG_APS_SNAPSHOT 80 + +/** + * Parameter address for module DAVIS_CONFIG_IMU: + * run the IMU state machine to get information about the + * movement and position of the device. This takes the + * IMU chip out of sleep. + */ +#define DAVIS_CONFIG_IMU_RUN 0 +/** + * Parameter address for module DAVIS_CONFIG_IMU: + * put the temperature sensor in standby, disabling it. + */ +#define DAVIS_CONFIG_IMU_TEMP_STANDBY 1 +/** + * Parameter address for module DAVIS_CONFIG_IMU: + * put the accelerometer sensor in standby, disabling it. + */ +#define DAVIS_CONFIG_IMU_ACCEL_STANDBY 2 +/** + * Parameter address for module DAVIS_CONFIG_IMU: + * put the gyroscope sensor in standby, disabling it. + */ +#define DAVIS_CONFIG_IMU_GYRO_STANDBY 3 +/** + * Parameter address for module DAVIS_CONFIG_IMU: + * put the IMU into Cycle Mode. In Cycle Mode, the device + * cycles between sleep mode and waking up to take a single + * sample of data from the accelerometer at a rate determined + * by DAVIS_CONFIG_IMU_LP_WAKEUP. + */ +#define DAVIS_CONFIG_IMU_LP_CYCLE 4 +/** + * Parameter address for module DAVIS_CONFIG_IMU: + * rate at which the IMU takes an accelerometer sample while + * in Cycle Mode (see DAVIS_CONFIG_IMU_LP_CYCLE). + * Valid values are: + * 0 - 1.25 Hz wake-up frequency + * 1 - 5 Hz wake-up frequency + * 2 - 20 Hz wake-up frequency + * 3 - 40 Hz wake-up frequency + */ +#define DAVIS_CONFIG_IMU_LP_WAKEUP 5 +/** + * Parameter address for module DAVIS_CONFIG_IMU: + * this specifies the divider from the Gyroscope Output Rate used + * to generate the Sample Rate for the IMU. + * Valid values are from 0 to 255. + * The Sample Rate is generated like this: + * Sample Rate = Gyroscope Output Rate / (1 + DAVIS_CONFIG_IMU_SAMPLE_RATE_DIVIDER) + * where Gyroscope Output Rate = 8 kHz when DAVIS_CONFIG_IMU_DIGITAL_LOW_PASS_FILTER + * is disabled (set to 0 or 7), and 1 kHz when enabled. + * Note: the accelerometer output rate is 1 kHz. This means that for a Sample Rate + * greater than 1 kHz, the same accelerometer sample may be output multiple times. + */ +#define DAVIS_CONFIG_IMU_SAMPLE_RATE_DIVIDER 6 +/** + * Parameter address for module DAVIS_CONFIG_IMU: + * this configures the digital low-pass filter for both the + * accelerometer and the gyroscope. + * Valid values are from 0 to 7 and have the following meaning: + * 0 - Accel: BW=260Hz, Delay=0ms, FS=1kHz - Gyro: BW=256Hz, Delay=0.98ms, FS=8kHz + * 1 - Accel: BW=184Hz, Delay=2.0ms, FS=1kHz - Gyro: BW=188Hz, Delay=1.9ms, FS=1kHz + * 2 - Accel: BW=94Hz, Delay=3.0ms, FS=1kHz - Gyro: BW=98Hz, Delay=2.8ms, FS=1kHz + * 3 - Accel: BW=44Hz, Delay=4.9ms, FS=1kHz - Gyro: BW=42Hz, Delay=4.8ms, FS=1kHz + * 4 - Accel: BW=21Hz, Delay=8.5ms, FS=1kHz - Gyro: BW=20Hz, Delay=8.3ms, FS=1kHz + * 5 - Accel: BW=10Hz, Delay=13.8ms, FS=1kHz - Gyro: BW=10Hz, Delay=13.4ms, FS=1kHz + * 6 - Accel: BW=5Hz, Delay=19.0ms, FS=1kHz - Gyro: BW=5Hz, Delay=18.6ms, FS=1kHz + * 7 - Accel: RESERVED, FS=1kHz - Gyro: RESERVED, FS=8kHz + */ +#define DAVIS_CONFIG_IMU_DIGITAL_LOW_PASS_FILTER 7 +/** + * Parameter address for module DAVIS_CONFIG_IMU: + * select the full scale range of the accelerometer outputs. + * Valid values are: + * 0 - +- 2 g + * 1 - +- 4 g + * 2 - +- 8 g + * 3 - +- 16 g + */ +#define DAVIS_CONFIG_IMU_ACCEL_FULL_SCALE 8 +/** + * Parameter address for module DAVIS_CONFIG_IMU: + * select the full scale range of the gyroscope outputs. + * Valid values are: + * 0 - +- 250 °/s + * 1 - +- 500 °/s + * 2 - +- 1000 °/s + * 3 - +- 2000 °/s + */ +#define DAVIS_CONFIG_IMU_GYRO_FULL_SCALE 9 + +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * enable the signal detector module. It generates events + * when it sees certain types of signals, such as edges or + * pulses of a defined length, on the IN JACK signal. + * This can be useful to inject events into the event + * stream in response to external stimuli or controls, + * such as turning on a LED lamp. + */ +#define DAVIS_CONFIG_EXTINPUT_RUN_DETECTOR 0 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * send a special EXTERNAL_INPUT_RISING_EDGE event when a + * rising edge is detected (transition from low voltage to high). + */ +#define DAVIS_CONFIG_EXTINPUT_DETECT_RISING_EDGES 1 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * send a special EXTERNAL_INPUT_FALLING_EDGE event when a + * falling edge is detected (transition from high voltage to low). + */ +#define DAVIS_CONFIG_EXTINPUT_DETECT_FALLING_EDGES 2 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * send a special EXTERNAL_INPUT_PULSE event when a pulse, of + * a specified, configurable polarity and length, is detected. + * See DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_POLARITY and + * DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_LENGTH for more details. + */ +#define DAVIS_CONFIG_EXTINPUT_DETECT_PULSES 3 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * the polarity the pulse must exhibit to be detected as such. + * '1' means active high; a pulse will start when the signal + * goes from low to high and will continue to be seen as the + * same pulse as long as it stays high. + * '0' means active low; a pulse will start when the signal + * goes from high to low and will continue to be seen as the + * same pulse as long as it stays low. + */ +#define DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_POLARITY 4 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * the minimal length that a pulse must have to trigger the + * sending of a special event. This is measured in cycles + * at LogicClock frequency (see 'struct caer_davis_info' for + * details on how to get the frequency). + */ +#define DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_LENGTH 5 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * read-only parameter, information about the presence of the + * signal generator feature. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get this information. + */ +#define DAVIS_CONFIG_EXTINPUT_HAS_GENERATOR 6 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * enable the signal generator module. It generates a + * PWM-like signal based on configurable parameters and + * outputs it on the OUT JACK signal. + */ +#define DAVIS_CONFIG_EXTINPUT_RUN_GENERATOR 7 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * instead of generating a PWM-like signal by using the + * configured parameters, use a signal on the FPGA/CPLD + * that's passed as an input to the External Input module. + * By default this is disabled and tied to ground, but + * it can be useful for customized logic designs. + */ +#define DAVIS_CONFIG_EXTINPUT_GENERATE_USE_CUSTOM_SIGNAL 8 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * polarity of the PWM-like signal to be generated. + * '1' means active high, '0' means active low. + */ +#define DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_POLARITY 9 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * the interval between the start of two consecutive pulses, + * expressed in cycles at LogicClock frequency (see + * 'struct caer_davis_info' for details on how to get the frequency). + * This must be bigger or equal to DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_LENGTH. + * To generate a signal with 50% duty cycle, this would + * have to be exactly double of DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_LENGTH. + */ +#define DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_INTERVAL 10 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * the length a pulse stays active, expressed in cycles at + * LogicClock frequency (see 'struct caer_davis_info' for + * details on how to get the frequency). This must be + * smaller or equal to DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_INTERVAL. + * To generate a signal with 50% duty cycle, this would + * have to be exactly half of DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_INTERVAL. + */ +#define DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_LENGTH 11 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * enables event injection when a rising edge occurs in the + * generated signal; a special event EXTERNAL_GENERATOR_RISING_EDGE + * is emitted into the event stream. + */ +#define DAVIS_CONFIG_EXTINPUT_GENERATE_INJECT_ON_RISING_EDGE 12 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * enables event injection when a falling edge occurs in the + * generated signal; a special event EXTERNAL_GENERATOR_FALLING_EDGE + * is emitted into the event stream. + */ +#define DAVIS_CONFIG_EXTINPUT_GENERATE_INJECT_ON_FALLING_EDGE 13 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * read-only parameter, information about the presence of the + * extra detectors feature. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get this information. + */ +#define DAVIS_CONFIG_EXTINPUT_HAS_EXTRA_DETECTORS 14 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * enable the signal detector module. It generates events + * when it sees certain types of signals, such as edges or + * pulses of a defined length, on the B1P20 input pin. + * This can be useful to inject events into the event + * stream in response to external stimuli or controls, + * such as turning on a LED lamp. + */ +#define DAVIS_CONFIG_EXTINPUT_RUN_DETECTOR1 15 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * send a special EXTERNAL_INPUT1_RISING_EDGE event when a + * rising edge is detected (transition from low voltage to high). + */ +#define DAVIS_CONFIG_EXTINPUT_DETECT_RISING_EDGES1 16 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * send a special EXTERNAL_INPUT1_FALLING_EDGE event when a + * falling edge is detected (transition from high voltage to low). + */ +#define DAVIS_CONFIG_EXTINPUT_DETECT_FALLING_EDGES1 17 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * send a special EXTERNAL_INPUT1_PULSE event when a pulse, of + * a specified, configurable polarity and length, is detected. + * See DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_POLARITY1 and + * DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_LENGTH1 for more details. + */ +#define DAVIS_CONFIG_EXTINPUT_DETECT_PULSES1 18 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * the polarity the pulse must exhibit to be detected as such. + * '1' means active high; a pulse will start when the signal + * goes from low to high and will continue to be seen as the + * same pulse as long as it stays high. + * '0' means active low; a pulse will start when the signal + * goes from high to low and will continue to be seen as the + * same pulse as long as it stays low. + */ +#define DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_POLARITY1 19 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * the minimal length that a pulse must have to trigger the + * sending of a special event. This is measured in cycles + * at LogicClock frequency (see 'struct caer_davis_info' for + * details on how to get the frequency). + */ +#define DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_LENGTH1 20 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * enable the signal detector module. It generates events + * when it sees certain types of signals, such as edges or + * pulses of a defined length, on the B1P21 input pin. + * This can be useful to inject events into the event + * stream in response to external stimuli or controls, + * such as turning on a LED lamp. + */ +#define DAVIS_CONFIG_EXTINPUT_RUN_DETECTOR2 21 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * send a special EXTERNAL_INPUT2_RISING_EDGE event when a + * rising edge is detected (transition from low voltage to high). + */ +#define DAVIS_CONFIG_EXTINPUT_DETECT_RISING_EDGES2 22 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * send a special EXTERNAL_INPUT2_FALLING_EDGE event when a + * falling edge is detected (transition from high voltage to low). + */ +#define DAVIS_CONFIG_EXTINPUT_DETECT_FALLING_EDGES2 23 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * send a special EXTERNAL_INPUT2_PULSE event when a pulse, of + * a specified, configurable polarity and length, is detected. + * See DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_POLARITY2 and + * DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_LENGTH2 for more details. + */ +#define DAVIS_CONFIG_EXTINPUT_DETECT_PULSES2 24 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * the polarity the pulse must exhibit to be detected as such. + * '1' means active high; a pulse will start when the signal + * goes from low to high and will continue to be seen as the + * same pulse as long as it stays high. + * '0' means active low; a pulse will start when the signal + * goes from high to low and will continue to be seen as the + * same pulse as long as it stays low. + */ +#define DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_POLARITY2 25 +/** + * Parameter address for module DAVIS_CONFIG_EXTINPUT: + * the minimal length that a pulse must have to trigger the + * sending of a special event. This is measured in cycles + * at LogicClock frequency (see 'struct caer_davis_info' for + * details on how to get the frequency). + */ +#define DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_LENGTH2 26 + +/** + * Parameter address for module DAVIS_CONFIG_SYSINFO: + * read-only parameter, the version of the logic currently + * running on the device's FPGA/CPLD. It usually represents + * a specific SVN revision, at which the logic code was + * synthesized. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get this information. + */ +#define DAVIS_CONFIG_SYSINFO_LOGIC_VERSION 0 +/** + * Parameter address for module DAVIS_CONFIG_SYSINFO: + * read-only parameter, an integer used to identify the different + * types of sensor chips used on the device. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get this information. + */ +#define DAVIS_CONFIG_SYSINFO_CHIP_IDENTIFIER 1 +/** + * Parameter address for module DAVIS_CONFIG_SYSINFO: + * read-only parameter, whether the device is currently a timestamp + * master or slave when synchronizing multiple devices together. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get this information. + */ +#define DAVIS_CONFIG_SYSINFO_DEVICE_IS_MASTER 2 +/** + * Parameter address for module DAVIS_CONFIG_SYSINFO: + * read-only parameter, the frequency in MHz at which the main + * FPGA/CPLD logic is running. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get this information. + */ +#define DAVIS_CONFIG_SYSINFO_LOGIC_CLOCK 3 +/** + * Parameter address for module DAVIS_CONFIG_SYSINFO: + * read-only parameter, the frequency in MHz at which the FPGA/CPLD + * logic related to APS frame grabbing is running. + * This is reserved for internal use and should not be used by + * anything other than libcaer. Please see the 'struct caer_davis_info' + * documentation to get this information. + */ +#define DAVIS_CONFIG_SYSINFO_ADC_CLOCK 4 + +/** + * Parameter address for module DAVIS_CONFIG_USB: + * enable the USB FIFO module, which transfers the data from the + * FPGA/CPLD to the USB chip, to be then sent to the host. + * Turning this off will suppress any USB data communication! + */ +#define DAVIS_CONFIG_USB_RUN 0 +/** + * Parameter address for module DAVIS_CONFIG_USB: + * the time delay after which a packet of data is committed to + * USB, even if it is not full yet (short USB packet). + * The value is in 125µs time-slices, corresponding to how + * USB schedules its operations (a value of 4 for example + * would mean waiting at most 0.5ms until sending a short + * USB packet to the host). + */ +#define DAVIS_CONFIG_USB_EARLY_PACKET_DELAY 1 + +//@{ +/** + * Parameter address for module DAVIS128_CONFIG_BIAS: + * DAVIS128 chip biases. + * Bias configuration values must be generated using the proper + * functions, which are: + * - caerBiasVDACGenerate() for VDAC (voltage) biases. + * - caerBiasCoarseFineGenerate() for coarse-fine (current) biases. + * - caerBiasShiftedSourceGenerate() for shifted-source biases. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DAVIS128_CONFIG_BIAS_APSOVERFLOWLEVEL 0 +#define DAVIS128_CONFIG_BIAS_APSCAS 1 +#define DAVIS128_CONFIG_BIAS_ADCREFHIGH 2 +#define DAVIS128_CONFIG_BIAS_ADCREFLOW 3 +#define DAVIS128_CONFIG_BIAS_LOCALBUFBN 8 +#define DAVIS128_CONFIG_BIAS_PADFOLLBN 9 +#define DAVIS128_CONFIG_BIAS_DIFFBN 10 +#define DAVIS128_CONFIG_BIAS_ONBN 11 +#define DAVIS128_CONFIG_BIAS_OFFBN 12 +#define DAVIS128_CONFIG_BIAS_PIXINVBN 13 +#define DAVIS128_CONFIG_BIAS_PRBP 14 +#define DAVIS128_CONFIG_BIAS_PRSFBP 15 +#define DAVIS128_CONFIG_BIAS_REFRBP 16 +#define DAVIS128_CONFIG_BIAS_READOUTBUFBP 17 +#define DAVIS128_CONFIG_BIAS_APSROSFBN 18 +#define DAVIS128_CONFIG_BIAS_ADCCOMPBP 19 +#define DAVIS128_CONFIG_BIAS_COLSELLOWBN 20 +#define DAVIS128_CONFIG_BIAS_DACBUFBP 21 +#define DAVIS128_CONFIG_BIAS_LCOLTIMEOUTBN 22 +#define DAVIS128_CONFIG_BIAS_AEPDBN 23 +#define DAVIS128_CONFIG_BIAS_AEPUXBP 24 +#define DAVIS128_CONFIG_BIAS_AEPUYBP 25 +#define DAVIS128_CONFIG_BIAS_IFREFRBN 26 +#define DAVIS128_CONFIG_BIAS_IFTHRBN 27 +#define DAVIS128_CONFIG_BIAS_BIASBUFFER 34 +#define DAVIS128_CONFIG_BIAS_SSP 35 +#define DAVIS128_CONFIG_BIAS_SSN 36 +//@} + +//@{ +/** + * Parameter address for module DAVIS128_CONFIG_CHIP: + * DAVIS128 chip configuration. + * These are for expert control and should never be used + * or changed unless for advanced debugging purposes. + * To change the Global Shutter configuration, please use + * DAVIS_CONFIG_APS_GLOBAL_SHUTTER instead. + */ +#define DAVIS128_CONFIG_CHIP_DIGITALMUX0 128 +#define DAVIS128_CONFIG_CHIP_DIGITALMUX1 129 +#define DAVIS128_CONFIG_CHIP_DIGITALMUX2 130 +#define DAVIS128_CONFIG_CHIP_DIGITALMUX3 131 +#define DAVIS128_CONFIG_CHIP_ANALOGMUX0 132 +#define DAVIS128_CONFIG_CHIP_ANALOGMUX1 133 +#define DAVIS128_CONFIG_CHIP_ANALOGMUX2 134 +#define DAVIS128_CONFIG_CHIP_BIASMUX0 135 +#define DAVIS128_CONFIG_CHIP_RESETCALIBNEURON 136 +#define DAVIS128_CONFIG_CHIP_TYPENCALIBNEURON 137 +#define DAVIS128_CONFIG_CHIP_RESETTESTPIXEL 138 +#define DAVIS128_CONFIG_CHIP_AERNAROW 140 +#define DAVIS128_CONFIG_CHIP_USEAOUT 141 +#define DAVIS128_CONFIG_CHIP_GLOBAL_SHUTTER 142 +#define DAVIS128_CONFIG_CHIP_SELECTGRAYCOUNTER 143 +//@} + +//@{ +/** + * Parameter address for module DAVIS208_CONFIG_BIAS: + * DAVIS208 chip biases. + * Bias configuration values must be generated using the proper + * functions, which are: + * - caerBiasVDACGenerate() for VDAC (voltage) biases. + * - caerBiasCoarseFineGenerate() for coarse-fine (current) biases. + * - caerBiasShiftedSourceGenerate() for shifted-source biases. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DAVIS208_CONFIG_BIAS_APSOVERFLOWLEVEL 0 +#define DAVIS208_CONFIG_BIAS_APSCAS 1 +#define DAVIS208_CONFIG_BIAS_ADCREFHIGH 2 +#define DAVIS208_CONFIG_BIAS_ADCREFLOW 3 +#define DAVIS208_CONFIG_BIAS_RESETHIGHPASS 6 +#define DAVIS208_CONFIG_BIAS_REFSS 7 +#define DAVIS208_CONFIG_BIAS_LOCALBUFBN 8 +#define DAVIS208_CONFIG_BIAS_PADFOLLBN 9 +#define DAVIS208_CONFIG_BIAS_DIFFBN 10 +#define DAVIS208_CONFIG_BIAS_ONBN 11 +#define DAVIS208_CONFIG_BIAS_OFFBN 12 +#define DAVIS208_CONFIG_BIAS_PIXINVBN 13 +#define DAVIS208_CONFIG_BIAS_PRBP 14 +#define DAVIS208_CONFIG_BIAS_PRSFBP 15 +#define DAVIS208_CONFIG_BIAS_REFRBP 16 +#define DAVIS208_CONFIG_BIAS_READOUTBUFBP 17 +#define DAVIS208_CONFIG_BIAS_APSROSFBN 18 +#define DAVIS208_CONFIG_BIAS_ADCCOMPBP 19 +#define DAVIS208_CONFIG_BIAS_COLSELLOWBN 20 +#define DAVIS208_CONFIG_BIAS_DACBUFBP 21 +#define DAVIS208_CONFIG_BIAS_LCOLTIMEOUTBN 22 +#define DAVIS208_CONFIG_BIAS_AEPDBN 23 +#define DAVIS208_CONFIG_BIAS_AEPUXBP 24 +#define DAVIS208_CONFIG_BIAS_AEPUYBP 25 +#define DAVIS208_CONFIG_BIAS_IFREFRBN 26 +#define DAVIS208_CONFIG_BIAS_IFTHRBN 27 +#define DAVIS208_CONFIG_BIAS_REGBIASBP 28 +#define DAVIS208_CONFIG_BIAS_REFSSBN 30 +#define DAVIS208_CONFIG_BIAS_BIASBUFFER 34 +#define DAVIS208_CONFIG_BIAS_SSP 35 +#define DAVIS208_CONFIG_BIAS_SSN 36 +//@} + +//@{ +/** + * Parameter address for module DAVIS208_CONFIG_CHIP: + * DAVIS208 chip configuration. + * These are for expert control and should never be used + * or changed unless for advanced debugging purposes. + * To change the Global Shutter configuration, please use + * DAVIS_CONFIG_APS_GLOBAL_SHUTTER instead. + */ +#define DAVIS208_CONFIG_CHIP_DIGITALMUX0 128 +#define DAVIS208_CONFIG_CHIP_DIGITALMUX1 129 +#define DAVIS208_CONFIG_CHIP_DIGITALMUX2 130 +#define DAVIS208_CONFIG_CHIP_DIGITALMUX3 131 +#define DAVIS208_CONFIG_CHIP_ANALOGMUX0 132 +#define DAVIS208_CONFIG_CHIP_ANALOGMUX1 133 +#define DAVIS208_CONFIG_CHIP_ANALOGMUX2 134 +#define DAVIS208_CONFIG_CHIP_BIASMUX0 135 +#define DAVIS208_CONFIG_CHIP_RESETCALIBNEURON 136 +#define DAVIS208_CONFIG_CHIP_TYPENCALIBNEURON 137 +#define DAVIS208_CONFIG_CHIP_RESETTESTPIXEL 138 +#define DAVIS208_CONFIG_CHIP_AERNAROW 140 +#define DAVIS208_CONFIG_CHIP_USEAOUT 141 +#define DAVIS208_CONFIG_CHIP_GLOBAL_SHUTTER 142 +#define DAVIS208_CONFIG_CHIP_SELECTGRAYCOUNTER 143 +#define DAVIS208_CONFIG_CHIP_SELECTPREAMPAVG 145 +#define DAVIS208_CONFIG_CHIP_SELECTBIASREFSS 146 +#define DAVIS208_CONFIG_CHIP_SELECTSENSE 147 +#define DAVIS208_CONFIG_CHIP_SELECTPOSFB 148 +#define DAVIS208_CONFIG_CHIP_SELECTHIGHPASS 149 +//@} + +//@{ +/** + * Parameter address for module DAVIS240_CONFIG_BIAS: + * DAVIS240chip biases. + * Bias configuration values must be generated using the proper + * functions, which are: + * - caerBiasCoarseFineGenerate() for coarse-fine (current) biases. + * - caerBiasShiftedSourceGenerate() for shifted-source biases. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DAVIS240_CONFIG_BIAS_DIFFBN 0 +#define DAVIS240_CONFIG_BIAS_ONBN 1 +#define DAVIS240_CONFIG_BIAS_OFFBN 2 +#define DAVIS240_CONFIG_BIAS_APSCASEPC 3 +#define DAVIS240_CONFIG_BIAS_DIFFCASBNC 4 +#define DAVIS240_CONFIG_BIAS_APSROSFBN 5 +#define DAVIS240_CONFIG_BIAS_LOCALBUFBN 6 +#define DAVIS240_CONFIG_BIAS_PIXINVBN 7 +#define DAVIS240_CONFIG_BIAS_PRBP 8 +#define DAVIS240_CONFIG_BIAS_PRSFBP 9 +#define DAVIS240_CONFIG_BIAS_REFRBP 10 +#define DAVIS240_CONFIG_BIAS_AEPDBN 11 +#define DAVIS240_CONFIG_BIAS_LCOLTIMEOUTBN 12 +#define DAVIS240_CONFIG_BIAS_AEPUXBP 13 +#define DAVIS240_CONFIG_BIAS_AEPUYBP 14 +#define DAVIS240_CONFIG_BIAS_IFTHRBN 15 +#define DAVIS240_CONFIG_BIAS_IFREFRBN 16 +#define DAVIS240_CONFIG_BIAS_PADFOLLBN 17 +#define DAVIS240_CONFIG_BIAS_APSOVERFLOWLEVELBN 18 +#define DAVIS240_CONFIG_BIAS_BIASBUFFER 19 +#define DAVIS240_CONFIG_BIAS_SSP 20 +#define DAVIS240_CONFIG_BIAS_SSN 21 +//@} + +//@{ +/** + * Parameter address for module DAVIS240_CONFIG_CHIP: + * DAVIS240 chip configuration. + * These are for expert control and should never be used + * or changed unless for advanced debugging purposes. + * To change the Global Shutter configuration, please use + * DAVIS_CONFIG_APS_GLOBAL_SHUTTER instead. + * On DAVIS240B cameras, DAVIS240_CONFIG_CHIP_SPECIALPIXELCONTROL + * can be used to enable the test pixel array. + */ +#define DAVIS240_CONFIG_CHIP_DIGITALMUX0 128 +#define DAVIS240_CONFIG_CHIP_DIGITALMUX1 129 +#define DAVIS240_CONFIG_CHIP_DIGITALMUX2 130 +#define DAVIS240_CONFIG_CHIP_DIGITALMUX3 131 +#define DAVIS240_CONFIG_CHIP_ANALOGMUX0 132 +#define DAVIS240_CONFIG_CHIP_ANALOGMUX1 133 +#define DAVIS240_CONFIG_CHIP_ANALOGMUX2 134 +#define DAVIS240_CONFIG_CHIP_BIASMUX0 135 +#define DAVIS240_CONFIG_CHIP_RESETCALIBNEURON 136 +#define DAVIS240_CONFIG_CHIP_TYPENCALIBNEURON 137 +#define DAVIS240_CONFIG_CHIP_RESETTESTPIXEL 138 +#define DAVIS240_CONFIG_CHIP_SPECIALPIXELCONTROL 139 +#define DAVIS240_CONFIG_CHIP_AERNAROW 140 +#define DAVIS240_CONFIG_CHIP_USEAOUT 141 +#define DAVIS240_CONFIG_CHIP_GLOBAL_SHUTTER 142 +//@} + +//@{ +/** + * Parameter address for module DAVIS346_CONFIG_BIAS: + * DAVIS346 chip biases. + * Bias configuration values must be generated using the proper + * functions, which are: + * - caerBiasVDACGenerate() for VDAC (voltage) biases. + * - caerBiasCoarseFineGenerate() for coarse-fine (current) biases. + * - caerBiasShiftedSourceGenerate() for shifted-source biases. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DAVIS346_CONFIG_BIAS_APSOVERFLOWLEVEL 0 +#define DAVIS346_CONFIG_BIAS_APSCAS 1 +#define DAVIS346_CONFIG_BIAS_ADCREFHIGH 2 +#define DAVIS346_CONFIG_BIAS_ADCREFLOW 3 +#define DAVIS346_CONFIG_BIAS_ADCTESTVOLTAGE 4 +#define DAVIS346_CONFIG_BIAS_LOCALBUFBN 8 +#define DAVIS346_CONFIG_BIAS_PADFOLLBN 9 +#define DAVIS346_CONFIG_BIAS_DIFFBN 10 +#define DAVIS346_CONFIG_BIAS_ONBN 11 +#define DAVIS346_CONFIG_BIAS_OFFBN 12 +#define DAVIS346_CONFIG_BIAS_PIXINVBN 13 +#define DAVIS346_CONFIG_BIAS_PRBP 14 +#define DAVIS346_CONFIG_BIAS_PRSFBP 15 +#define DAVIS346_CONFIG_BIAS_REFRBP 16 +#define DAVIS346_CONFIG_BIAS_READOUTBUFBP 17 +#define DAVIS346_CONFIG_BIAS_APSROSFBN 18 +#define DAVIS346_CONFIG_BIAS_ADCCOMPBP 19 +#define DAVIS346_CONFIG_BIAS_COLSELLOWBN 20 +#define DAVIS346_CONFIG_BIAS_DACBUFBP 21 +#define DAVIS346_CONFIG_BIAS_LCOLTIMEOUTBN 22 +#define DAVIS346_CONFIG_BIAS_AEPDBN 23 +#define DAVIS346_CONFIG_BIAS_AEPUXBP 24 +#define DAVIS346_CONFIG_BIAS_AEPUYBP 25 +#define DAVIS346_CONFIG_BIAS_IFREFRBN 26 +#define DAVIS346_CONFIG_BIAS_IFTHRBN 27 +#define DAVIS346_CONFIG_BIAS_BIASBUFFER 34 +#define DAVIS346_CONFIG_BIAS_SSP 35 +#define DAVIS346_CONFIG_BIAS_SSN 36 +//@} + +//@{ +/** + * Parameter address for module DAVIS346_CONFIG_CHIP: + * DAVIS346 chip configuration. + * These are for expert control and should never be used + * or changed unless for advanced debugging purposes. + * To change the Global Shutter configuration, please use + * DAVIS_CONFIG_APS_GLOBAL_SHUTTER instead. + */ +#define DAVIS346_CONFIG_CHIP_DIGITALMUX0 128 +#define DAVIS346_CONFIG_CHIP_DIGITALMUX1 129 +#define DAVIS346_CONFIG_CHIP_DIGITALMUX2 130 +#define DAVIS346_CONFIG_CHIP_DIGITALMUX3 131 +#define DAVIS346_CONFIG_CHIP_ANALOGMUX0 132 +#define DAVIS346_CONFIG_CHIP_ANALOGMUX1 133 +#define DAVIS346_CONFIG_CHIP_ANALOGMUX2 134 +#define DAVIS346_CONFIG_CHIP_BIASMUX0 135 +#define DAVIS346_CONFIG_CHIP_RESETCALIBNEURON 136 +#define DAVIS346_CONFIG_CHIP_TYPENCALIBNEURON 137 +#define DAVIS346_CONFIG_CHIP_RESETTESTPIXEL 138 +#define DAVIS346_CONFIG_CHIP_AERNAROW 140 +#define DAVIS346_CONFIG_CHIP_USEAOUT 141 +#define DAVIS346_CONFIG_CHIP_GLOBAL_SHUTTER 142 +#define DAVIS346_CONFIG_CHIP_SELECTGRAYCOUNTER 143 +#define DAVIS346_CONFIG_CHIP_TESTADC 144 +//@} + +//@{ +/** + * Parameter address for module DAVIS640_CONFIG_BIAS: + * DAVIS640 chip biases. + * Bias configuration values must be generated using the proper + * functions, which are: + * - caerBiasVDACGenerate() for VDAC (voltage) biases. + * - caerBiasCoarseFineGenerate() for coarse-fine (current) biases. + * - caerBiasShiftedSourceGenerate() for shifted-source biases. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DAVIS640_CONFIG_BIAS_APSOVERFLOWLEVEL 0 +#define DAVIS640_CONFIG_BIAS_APSCAS 1 +#define DAVIS640_CONFIG_BIAS_ADCREFHIGH 2 +#define DAVIS640_CONFIG_BIAS_ADCREFLOW 3 +#define DAVIS640_CONFIG_BIAS_ADCTESTVOLTAGE 4 +#define DAVIS640_CONFIG_BIAS_LOCALBUFBN 8 +#define DAVIS640_CONFIG_BIAS_PADFOLLBN 9 +#define DAVIS640_CONFIG_BIAS_DIFFBN 10 +#define DAVIS640_CONFIG_BIAS_ONBN 11 +#define DAVIS640_CONFIG_BIAS_OFFBN 12 +#define DAVIS640_CONFIG_BIAS_PIXINVBN 13 +#define DAVIS640_CONFIG_BIAS_PRBP 14 +#define DAVIS640_CONFIG_BIAS_PRSFBP 15 +#define DAVIS640_CONFIG_BIAS_REFRBP 16 +#define DAVIS640_CONFIG_BIAS_READOUTBUFBP 17 +#define DAVIS640_CONFIG_BIAS_APSROSFBN 18 +#define DAVIS640_CONFIG_BIAS_ADCCOMPBP 19 +#define DAVIS640_CONFIG_BIAS_COLSELLOWBN 20 +#define DAVIS640_CONFIG_BIAS_DACBUFBP 21 +#define DAVIS640_CONFIG_BIAS_LCOLTIMEOUTBN 22 +#define DAVIS640_CONFIG_BIAS_AEPDBN 23 +#define DAVIS640_CONFIG_BIAS_AEPUXBP 24 +#define DAVIS640_CONFIG_BIAS_AEPUYBP 25 +#define DAVIS640_CONFIG_BIAS_IFREFRBN 26 +#define DAVIS640_CONFIG_BIAS_IFTHRBN 27 +#define DAVIS640_CONFIG_BIAS_BIASBUFFER 34 +#define DAVIS640_CONFIG_BIAS_SSP 35 +#define DAVIS640_CONFIG_BIAS_SSN 36 +//@} + +//@{ +/** + * Parameter address for module DAVIS640_CONFIG_CHIP: + * DAVIS640 chip configuration. + * These are for expert control and should never be used + * or changed unless for advanced debugging purposes. + * To change the Global Shutter configuration, please use + * DAVIS_CONFIG_APS_GLOBAL_SHUTTER instead. + */ +#define DAVIS640_CONFIG_CHIP_DIGITALMUX0 128 +#define DAVIS640_CONFIG_CHIP_DIGITALMUX1 129 +#define DAVIS640_CONFIG_CHIP_DIGITALMUX2 130 +#define DAVIS640_CONFIG_CHIP_DIGITALMUX3 131 +#define DAVIS640_CONFIG_CHIP_ANALOGMUX0 132 +#define DAVIS640_CONFIG_CHIP_ANALOGMUX1 133 +#define DAVIS640_CONFIG_CHIP_ANALOGMUX2 134 +#define DAVIS640_CONFIG_CHIP_BIASMUX0 135 +#define DAVIS640_CONFIG_CHIP_RESETCALIBNEURON 136 +#define DAVIS640_CONFIG_CHIP_TYPENCALIBNEURON 137 +#define DAVIS640_CONFIG_CHIP_RESETTESTPIXEL 138 +#define DAVIS640_CONFIG_CHIP_AERNAROW 140 +#define DAVIS640_CONFIG_CHIP_USEAOUT 141 +#define DAVIS640_CONFIG_CHIP_GLOBAL_SHUTTER 142 +#define DAVIS640_CONFIG_CHIP_SELECTGRAYCOUNTER 143 +#define DAVIS640_CONFIG_CHIP_TESTADC 144 +//@} + +//@{ +/** + * Parameter address for module DAVISRGB_CONFIG_BIAS: + * DAVISRGB chip biases. + * Bias configuration values must be generated using the proper + * functions, which are: + * - caerBiasVDACGenerate() for VDAC (voltage) biases. + * - caerBiasCoarseFineGenerate() for coarse-fine (current) biases. + * - caerBiasShiftedSourceGenerate() for shifted-source biases. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DAVISRGB_CONFIG_BIAS_APSCAS 0 +#define DAVISRGB_CONFIG_BIAS_OVG1LO 1 +#define DAVISRGB_CONFIG_BIAS_OVG2LO 2 +#define DAVISRGB_CONFIG_BIAS_TX2OVG2HI 3 +#define DAVISRGB_CONFIG_BIAS_GND07 4 +#define DAVISRGB_CONFIG_BIAS_ADCTESTVOLTAGE 5 +#define DAVISRGB_CONFIG_BIAS_ADCREFHIGH 6 +#define DAVISRGB_CONFIG_BIAS_ADCREFLOW 7 +#define DAVISRGB_CONFIG_BIAS_IFREFRBN 8 +#define DAVISRGB_CONFIG_BIAS_IFTHRBN 9 +#define DAVISRGB_CONFIG_BIAS_LOCALBUFBN 10 +#define DAVISRGB_CONFIG_BIAS_PADFOLLBN 11 +#define DAVISRGB_CONFIG_BIAS_PIXINVBN 13 +#define DAVISRGB_CONFIG_BIAS_DIFFBN 14 +#define DAVISRGB_CONFIG_BIAS_ONBN 15 +#define DAVISRGB_CONFIG_BIAS_OFFBN 16 +#define DAVISRGB_CONFIG_BIAS_PRBP 17 +#define DAVISRGB_CONFIG_BIAS_PRSFBP 18 +#define DAVISRGB_CONFIG_BIAS_REFRBP 19 +#define DAVISRGB_CONFIG_BIAS_ARRAYBIASBUFFERBN 20 +#define DAVISRGB_CONFIG_BIAS_ARRAYLOGICBUFFERBN 22 +#define DAVISRGB_CONFIG_BIAS_FALLTIMEBN 23 +#define DAVISRGB_CONFIG_BIAS_RISETIMEBP 24 +#define DAVISRGB_CONFIG_BIAS_READOUTBUFBP 25 +#define DAVISRGB_CONFIG_BIAS_APSROSFBN 26 +#define DAVISRGB_CONFIG_BIAS_ADCCOMPBP 27 +#define DAVISRGB_CONFIG_BIAS_DACBUFBP 28 +#define DAVISRGB_CONFIG_BIAS_LCOLTIMEOUTBN 30 +#define DAVISRGB_CONFIG_BIAS_AEPDBN 31 +#define DAVISRGB_CONFIG_BIAS_AEPUXBP 32 +#define DAVISRGB_CONFIG_BIAS_AEPUYBP 33 +#define DAVISRGB_CONFIG_BIAS_BIASBUFFER 34 +#define DAVISRGB_CONFIG_BIAS_SSP 35 +#define DAVISRGB_CONFIG_BIAS_SSN 36 +//@} + +//@{ +/** + * Parameter address for module DAVISRGB_CONFIG_CHIP: + * DAVISRGB chip configuration. + * These are for expert control and should never be used + * or changed unless for advanced debugging purposes. + * To change the Global Shutter configuration, please use + * DAVIS_CONFIG_APS_GLOBAL_SHUTTER instead. + */ +#define DAVISRGB_CONFIG_CHIP_DIGITALMUX0 128 +#define DAVISRGB_CONFIG_CHIP_DIGITALMUX1 129 +#define DAVISRGB_CONFIG_CHIP_DIGITALMUX2 130 +#define DAVISRGB_CONFIG_CHIP_DIGITALMUX3 131 +#define DAVISRGB_CONFIG_CHIP_ANALOGMUX0 132 +#define DAVISRGB_CONFIG_CHIP_ANALOGMUX1 133 +#define DAVISRGB_CONFIG_CHIP_ANALOGMUX2 134 +#define DAVISRGB_CONFIG_CHIP_BIASMUX0 135 +#define DAVISRGB_CONFIG_CHIP_RESETCALIBNEURON 136 +#define DAVISRGB_CONFIG_CHIP_TYPENCALIBNEURON 137 +#define DAVISRGB_CONFIG_CHIP_RESETTESTPIXEL 138 +#define DAVISRGB_CONFIG_CHIP_AERNAROW 140 +#define DAVISRGB_CONFIG_CHIP_USEAOUT 141 +#define DAVISRGB_CONFIG_CHIP_SELECTGRAYCOUNTER 143 +#define DAVISRGB_CONFIG_CHIP_TESTADC 144 +#define DAVISRGB_CONFIG_CHIP_ADJUSTOVG1LO 145 +#define DAVISRGB_CONFIG_CHIP_ADJUSTOVG2LO 146 +#define DAVISRGB_CONFIG_CHIP_ADJUSTTX2OVG2HI 147 +//@} + +/** + * DAVIS device-related information. + */ +struct caer_davis_info { + /// Unique device identifier. Also 'source' for events. + int16_t deviceID; + /// Device serial number. + char deviceSerialNumber[8 + 1]; + /// Device USB bus number. + uint8_t deviceUSBBusNumber; + /// Device USB device address. + uint8_t deviceUSBDeviceAddress; + /// Device information string, for logging purposes. + char *deviceString; + /// Logic (FPGA/CPLD) version. + int16_t logicVersion; + /// Whether the device is a time-stamp master or slave. + bool deviceIsMaster; + /// Clock in MHz for main logic (FPGA/CPLD). + int16_t logicClock; + /// Clock in MHz for ADC/APS logic (FPGA/CPLD). + int16_t adcClock; + /// Chip identifier/type. + int16_t chipID; + /// DVS X axis resolution. + int16_t dvsSizeX; + /// DVS Y axis resolution. + int16_t dvsSizeY; + /// Feature test: DVS pixel-level filtering. + bool dvsHasPixelFilter; + /// Feature test: DVS Background Activity filter. + bool dvsHasBackgroundActivityFilter; + /// Feature test: fake event generator (testing/debug). + bool dvsHasTestEventGenerator; + /// APS X axis resolution. + int16_t apsSizeX; + /// APS Y axis resolution. + int16_t apsSizeY; + /// APS color filter type. + enum caer_frame_event_color_filter apsColorFilter; + /// Feature test: APS supports Global Shutter. + bool apsHasGlobalShutter; + /// Feature test: APS supports Quadruple Region-of-Interest readout. + bool apsHasQuadROI; + /// Feature test: APS supports External ADC for getting the image. + bool apsHasExternalADC; + /// Feature test: APS supports Internal (on-chip) ADC for getting the image. + bool apsHasInternalADC; + /// Feature test: External Input module supports Signal-Generation. + bool extInputHasGenerator; + /// Feature test: External Input module supports extra detectors (1 & 2). + bool extInputHasExtraDetectors; +}; + +/** + * Return basic information on the device, such as its ID, its + * resolution, the logic version, and so on. See the 'struct + * caer_davis_info' documentation for more details. + * + * @param handle a valid device handle. + * + * @return a copy of the device information structure if successful, + * an empty structure (all zeros) on failure. + */ +struct caer_davis_info caerDavisInfoGet(caerDeviceHandle handle); + +/** + * On-chip voltage digital-to-analog converter configuration. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +struct caer_bias_vdac { + /// Voltage, between 0 and 63, as a fraction of 1/64th of VDD=3.3V. + uint8_t voltageValue; + /// Current, between 0 and 7, that drives the voltage. + uint8_t currentValue; +}; + +/** + * Transform VDAC bias structure into internal integer representation, + * suited for sending directly to the device via caerDeviceConfigSet(). + * + * @param vdacBias VDAC bias structure. + * + * @return internal integer representation for device configuration. + */ +uint16_t caerBiasVDACGenerate(struct caer_bias_vdac vdacBias); +/** + * Transform internal integer representation, as received by calls to + * caerDeviceConfigGet(), into a VDAC bias structure, for easier + * handling and understanding of the various parameters. + * + * @param vdacBias internal integer representation from device. + * + * @return VDAC bias structure. + */ +struct caer_bias_vdac caerBiasVDACParse(uint16_t vdacBias); + +/** + * On-chip coarse-fine bias current configuration. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +struct caer_bias_coarsefine { + /// Coarse current, from 0 to 7, creates big variations in output current. + uint8_t coarseValue; + /// Fine current, from 0 to 255, creates small variations in output current. + uint8_t fineValue; + /// Whether this bias is enabled or not. + bool enabled; + /// Bias sex: true for 'N' type, false for 'P' type. + bool sexN; + /// Bias type: true for 'Normal', false for 'Cascode'. + bool typeNormal; + /// Bias current level: true for 'Normal, false for 'Low'. + bool currentLevelNormal; +}; + +/** + * Transform coarse-fine bias structure into internal integer representation, + * suited for sending directly to the device via caerDeviceConfigSet(). + * + * @param coarseFineBias coarse-fine bias structure. + * + * @return internal integer representation for device configuration. + */ +uint16_t caerBiasCoarseFineGenerate(struct caer_bias_coarsefine coarseFineBias); +/** + * Transform internal integer representation, as received by calls to + * caerDeviceConfigGet(), into a coarse-fine bias structure, for easier + * handling and understanding of the various parameters. + * + * @param coarseFineBias internal integer representation from device. + * + * @return coarse-fine bias structure. + */ +struct caer_bias_coarsefine caerBiasCoarseFineParse(uint16_t coarseFineBias); + +/** + * Shifted-source bias operating mode. + */ +enum caer_bias_shiftedsource_operating_mode { + /// Standard mode. + SHIFTED_SOURCE = 0, + /// High impedance (driven from outside). + HI_Z = 1, + /// Tied to ground (SSN) or VDD (SSP). + TIED_TO_RAIL = 2, +}; + +/** + * Shifted-source bias voltage level. + */ +enum caer_bias_shiftedsource_voltage_level { + /// Standard mode (200-400mV). + SPLIT_GATE = 0, + /// Higher shifted-source voltage (one cascode). + SINGLE_DIODE = 1, + /// Even higher shifted-source voltage (two cascodes). + DOUBLE_DIODE = 2, +}; + +/** + * On-chip shifted-source bias current configuration. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +struct caer_bias_shiftedsource { + /// Shifted-source bias level, from 0 to 63. + uint8_t refValue; + /// Shifted-source bias current for buffer amplifier, from 0 to 63. + uint8_t regValue; + /// Shifted-source operating mode (see 'enum caer_bias_shiftedsource_operating_mode'). + enum caer_bias_shiftedsource_operating_mode operatingMode; + /// Shifted-source voltage level (see 'enum caer_bias_shiftedsource_voltage_level'). + enum caer_bias_shiftedsource_voltage_level voltageLevel; +}; + +/** + * Transform shifted-source bias structure into internal integer representation, + * suited for sending directly to the device via caerDeviceConfigSet(). + * + * @param shiftedSourceBias shifted-source bias structure. + * + * @return internal integer representation for device configuration. + */ +uint16_t caerBiasShiftedSourceGenerate(struct caer_bias_shiftedsource shiftedSourceBias); +/** + * Transform internal integer representation, as received by calls to + * caerDeviceConfigGet(), into a shifted-source bias structure, for easier + * handling and understanding of the various parameters. + * + * @param shiftedSourceBias internal integer representation from device. + * + * @return shifted-source bias structure. + */ +struct caer_bias_shiftedsource caerBiasShiftedSourceParse(uint16_t shiftedSourceBias); + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_DEVICES_DAVIS_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/devices/dvs128.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/devices/dvs128.h new file mode 100755 index 0000000..acf21ba --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/devices/dvs128.h @@ -0,0 +1,169 @@ +/** + * @file dvs128.h + * + * DVS128 specific configuration defines and information structures. + */ + +#ifndef LIBCAER_DEVICES_DVS128_H_ +#define LIBCAER_DEVICES_DVS128_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usb.h" +#include "../events/polarity.h" +#include "../events/special.h" + +/** + * Device type definition for iniLabs DVS128. + */ +#define CAER_DEVICE_DVS128 0 + +/** + * Module address: device-side DVS configuration. + */ +#define DVS128_CONFIG_DVS 0 +/** + * Module address: device-side chip bias generator configuration. + */ +#define DVS128_CONFIG_BIAS 1 + +/** + * Parameter address for module DVS128_CONFIG_DVS: + * run the DVS chip and generate polarity event data. + */ +#define DVS128_CONFIG_DVS_RUN 0 +/** + * Parameter address for module DVS128_CONFIG_DVS: + * reset the time-stamp counter of the device. This is a temporary + * configuration switch and will reset itself right away. + */ +#define DVS128_CONFIG_DVS_TIMESTAMP_RESET 1 +/** + * Parameter address for module DVS128_CONFIG_DVS: + * reset the whole DVS pixel array. This is a temporary + * configuration switch and will reset itself right away. + */ +#define DVS128_CONFIG_DVS_ARRAY_RESET 2 +/** + * Parameter address for module DVS128_CONFIG_DVS: + * control if this DVS is a timestamp master device. + * Default is enabled. + */ +#define DVS128_CONFIG_DVS_TS_MASTER 3 + +/** + * Parameter address for module DVS128_CONFIG_BIAS: + * First stage amplifier cascode bias. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DVS128_CONFIG_BIAS_CAS 0 +/** + * Parameter address for module DVS128_CONFIG_BIAS: + * Injected ground bias. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DVS128_CONFIG_BIAS_INJGND 1 +/** + * Parameter address for module DVS128_CONFIG_BIAS: + * Pull down on chip request (AER). + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DVS128_CONFIG_BIAS_REQPD 2 +/** + * Parameter address for module DVS128_CONFIG_BIAS: + * Pull up on request from X arbiter (AER). + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DVS128_CONFIG_BIAS_PUX 3 +/** + * Parameter address for module DVS128_CONFIG_BIAS: + * Off events threshold bias. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DVS128_CONFIG_BIAS_DIFFOFF 4 +/** + * Parameter address for module DVS128_CONFIG_BIAS: + * Pull down for passive load inverters in digital AER pixel circuitry. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DVS128_CONFIG_BIAS_REQ 5 +/** + * Parameter address for module DVS128_CONFIG_BIAS: + * Refractory period bias. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DVS128_CONFIG_BIAS_REFR 6 +/** + * Parameter address for module DVS128_CONFIG_BIAS: + * Pull up on request from Y arbiter (AER). + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DVS128_CONFIG_BIAS_PUY 7 +/** + * Parameter address for module DVS128_CONFIG_BIAS: + * On events threshold bias. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DVS128_CONFIG_BIAS_DIFFON 8 +/** + * Parameter address for module DVS128_CONFIG_BIAS: + * Differential (second stage amplifier) bias. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DVS128_CONFIG_BIAS_DIFF 9 +/** + * Parameter address for module DVS128_CONFIG_BIAS: + * Source follower bias. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DVS128_CONFIG_BIAS_FOLL 10 +/** + * Parameter address for module DVS128_CONFIG_BIAS: + * Photoreceptor bias. + * See 'http://inilabs.com/support/biasing/' for more details. + */ +#define DVS128_CONFIG_BIAS_PR 11 + +/** + * DVS128 device-related information. + */ +struct caer_dvs128_info { + /// Unique device identifier. Also 'source' for events. + int16_t deviceID; + /// Device serial number. + char deviceSerialNumber[8 + 1]; + /// Device USB bus number. + uint8_t deviceUSBBusNumber; + /// Device USB device address. + uint8_t deviceUSBDeviceAddress; + /// Device information string, for logging purposes. + char *deviceString; + /// Logic (FPGA/CPLD) version. + int16_t logicVersion; + /// Whether the device is a time-stamp master or slave. + bool deviceIsMaster; + /// DVS X axis resolution. + int16_t dvsSizeX; + /// DVS Y axis resolution. + int16_t dvsSizeY; +}; + +/** + * Return basic information on the device, such as its ID, its + * resolution, the logic version, and so on. See the 'struct + * caer_dvs128_info' documentation for more details. + * + * @param handle a valid device handle. + * + * @return a copy of the device information structure if successful, + * an empty structure (all zeros) on failure. + */ +struct caer_dvs128_info caerDVS128InfoGet(caerDeviceHandle handle); + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_DEVICES_DVS128_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/devices/usb.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/devices/usb.h new file mode 100755 index 0000000..1d2c05c --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/devices/usb.h @@ -0,0 +1,242 @@ +/** + * @file usb.h + * + * Common functions to access, configure and exchange data with + * supported USB devices. Also contains defines for host/USB + * related configuration options. + */ + +#ifndef LIBCAER_DEVICES_USB_H_ +#define LIBCAER_DEVICES_USB_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "../libcaer.h" +#include "../events/packetContainer.h" + +/** + * Reference to an open device on which to operate. + */ +typedef struct caer_device_handle *caerDeviceHandle; + +/** + * Module address: host-side USB configuration. + */ +#define CAER_HOST_CONFIG_USB -1 +/** + * Module address: host-side data exchange (ring-buffer) configuration. + */ +#define CAER_HOST_CONFIG_DATAEXCHANGE -2 +/** + * Module address: host-side event packets generation configuration. + */ +#define CAER_HOST_CONFIG_PACKETS -3 + +/** + * Parameter address for module CAER_HOST_CONFIG_USB: + * set number of buffers used by libusb for asynchronous data transfers + * with the USB device. The default values are usually fine, only change + * them if you're running into I/O limits. + */ +#define CAER_HOST_CONFIG_USB_BUFFER_NUMBER 0 +/** + * Parameter address for module CAER_HOST_CONFIG_USB: + * set size of each buffer used by libusb for asynchronous data transfers + * with the USB device. The default values are usually fine, only change + * them if you're running into I/O limits. + */ +#define CAER_HOST_CONFIG_USB_BUFFER_SIZE 1 + +/** + * Parameter address for module CAER_HOST_CONFIG_DATAEXCHANGE: + * set size of elements that can be held by the thread-safe FIFO + * buffer between the USB data transfer thread and the main thread. + * The default values are usually fine, only change them if you're + * running into lots of dropped/missing packets; you can turn on + * the INFO log level to see when this is the case. + */ +#define CAER_HOST_CONFIG_DATAEXCHANGE_BUFFER_SIZE 0 +/** + * Parameter address for module CAER_HOST_CONFIG_DATAEXCHANGE: + * when calling caerDeviceDataGet(), the function can either be + * blocking, meaning it waits until it has a valid + * EventPacketContainer to return, or not, meaning it returns + * right away. This behavior can be set with this flag. + * Please see the caerDeviceDataGet() documentation for more + * information on its return values. + */ +#define CAER_HOST_CONFIG_DATAEXCHANGE_BLOCKING 1 +/** + * Parameter address for module CAER_HOST_CONFIG_DATAEXCHANGE: + * whether to start all the data producer modules on the device + * (DVS, APS, Mux, ...) automatically when starting the USB + * data transfer thread with caerDeviceDataStart() or not. + * If disabled, be aware you will have to start the right modules + * manually, which can be useful if you need precise control + * over which ones are running at any time. + */ + #define CAER_HOST_CONFIG_DATAEXCHANGE_START_PRODUCERS 2 +/** + * Parameter address for module CAER_HOST_CONFIG_DATAEXCHANGE: + * whether to stop all the data producer modules on the device + * (DVS, APS, Mux, ...) automatically when stopping the USB + * data transfer thread with caerDeviceDataStop() or not. + * If disabled, be aware you will have to stop the right modules + * manually, to halt the data flow, which can be useful if you + * need precise control over which ones are running at any time. + */ + #define CAER_HOST_CONFIG_DATAEXCHANGE_STOP_PRODUCERS 3 + +/** + * Parameter address for module CAER_HOST_CONFIG_PACKETS: + * set the maximum number of events any of a packet container's + * packets may hold before it's made available to the user. + * This is checked for each number of events held in each typed + * EventPacket that is a part of the EventPacketContainer. + */ +#define CAER_HOST_CONFIG_PACKETS_MAX_CONTAINER_PACKET_SIZE 0 +/** + * Parameter address for module CAER_HOST_CONFIG_PACKETS: + * set the time interval between subsequent packet containers. + * The value is in microseconds, and is checked across all + * types of events contained in the EventPacketContainer. + */ +#define CAER_HOST_CONFIG_PACKETS_MAX_CONTAINER_INTERVAL 1 + +/** + * Open a specified USB device, assign an ID to it and return a handle for further usage. + * Various means can be employed to limit the selection of the device. + * + * @param deviceID a unique ID to identify the device from others. Will be used as the + * source for EventPackets being generate from its data. + * @param deviceType type of the device to open. Currently supported are: + * CAER_DEVICE_DVS128, CAER_DEVICE_DAVIS_FX2, CAER_DEVICE_DAVIS_FX3 + * @param busNumberRestrict restrict the search for viable devices to only this USB bus number. + * @param devAddressRestrict restrict the search for viable devices to only this USB device address. + * @param serialNumberRestrict restrict the search for viable devices to only devices which do + * possess the given Serial Number in their USB SerialNumber descriptor. + * + * @return a valid device handle that can be used with the other libcaer functions, + * or NULL on error. Always check for this! + */ +caerDeviceHandle caerDeviceOpen(uint16_t deviceID, uint16_t deviceType, uint8_t busNumberRestrict, + uint8_t devAddressRestrict, const char *serialNumberRestrict); +/** + * Close a previously opened USB device and invalidate its handle. + * + * @param handle pointer to a valid device handle. Will set handle to NULL if closing is + * successful, to prevent further usage of this handle for other operations. + * + * @return true if closing was successful, false on errors. + */ +bool caerDeviceClose(caerDeviceHandle *handle); + +/** + * Send a set of good default configuration settings to the device. + * This avoids users having to set every configuration option each time, + * especially when wanting to get going quickly or just needing to change + * a few settings to get to the desired operating mode. + * + * @param handle a valid device handle. + * + * @return true if sending the configuration was successful, false on errors. + */ +bool caerDeviceSendDefaultConfig(caerDeviceHandle handle); + +/** + * Set a configuration parameter to a given value. + * + * @param handle a valid device handle. + * @param modAddr a module address, used to specify which configuration module + * one wants to update. Negative addresses are used for host-side + * configuration, while positive addresses (including zero) are + * used for device-side configuration. + * @param paramAddr a parameter address, to select a specific parameter to update + * from this particular configuration module. Only positive numbers + * (including zero) are allowed. + * @param param a configuration parameter's new value. + * + * @return true if sending the configuration was successful, false on errors. + */ +bool caerDeviceConfigSet(caerDeviceHandle handle, int8_t modAddr, uint8_t paramAddr, uint32_t param); + +/** + * Get the value of a configuration parameter. + * + * @param handle a valid device handle. + * @param modAddr a module address, used to specify which configuration module + * one wants to query. Negative addresses are used for host-side + * configuration, while positive addresses (including zero) are + * used for device-side configuration. + * @param paramAddr a parameter address, to select a specific parameter to query + * from this particular configuration module. Only positive numbers + * (including zero) are allowed. + * @param param a pointer to an integer, in which to store the configuration + * parameter's current value. The integer will always be either set + * to zero (on failure), or to the current value (on success). + * + * @return true if sending the configuration was successful, false on errors. + */ +bool caerDeviceConfigGet(caerDeviceHandle handle, int8_t modAddr, uint8_t paramAddr, uint32_t *param); + +/** + * Start getting data from the device, setting up the USB data transfer thread + * and starting the data producers (see CAER_HOST_CONFIG_DATAEXCHANGE_START_PRODUCERS). + * Supports notification of new data and shutdown events via user-defined call-backs. + * + * @param handle a valid device handle. + * @param dataNotifyIncrease function pointer, called every time a new piece of data + * available and has been put in the FIFO buffer for consumption. + * dataNotifyUserPtr will be passed as parameter to the function. + * @param dataNotifyDecrease function pointer, called every time a new piece of data + * has been consumed from the FIFO buffer inside caerDeviceDataGet(). + * dataNotifyUserPtr will be passed as parameter to the function. + * @param dataNotifyUserPtr pointer that will be passed to the dataNotifyIncrease and + * dataNotifyDecrease functions. Can be NULL. + * @param dataShutdownNotify function pointer, called on shut-down of the USB data transfer + * thread. This can be used to detect exceptional shut-downs that + * do not come from calling caerDeviceDataStop(), such as when the + * device is disconnected or all USB transfers fail. + * @param dataShutdownUserPtr pointer that will be passed to the dataShutdownNotify + * function. Can be NULL. + * + * @return true if starting the data transfer was successful, false on errors. + */ +bool caerDeviceDataStart(caerDeviceHandle handle, void (*dataNotifyIncrease)(void *ptr), + void (*dataNotifyDecrease)(void *ptr), void *dataNotifyUserPtr, void (*dataShutdownNotify)(void *ptr), + void *dataShutdownUserPtr); + +/** + * Stop getting data from the device, shutting down the USB data transfer thread + * and stopping the data producers (see CAER_HOST_CONFIG_DATAEXCHANGE_STOP_PRODUCERS). + * This normal shut-down will also generate a notification (see caerDeviceDataStart()). + * + * @param handle a valid device handle. + * + * @return true if stopping the data transfer was successful, false on errors. + */ +bool caerDeviceDataStop(caerDeviceHandle handle); + +/** + * Get an event packet container, which contains events of various types generated by + * the device, from the USB data transfer thread for further processing. + * The returned data structures are allocated in memory and will need to be freed. + * The caerEventPacketContainerFree() function can be used to correctly free the full + * container memory. For single caerEventPackets, just use free(). + * This function can be made blocking with the CAER_HOST_CONFIG_DATAEXCHANGE_BLOCKING + * configuration parameter. By default it is non-blocking. + * + * @param handle a valid device handle. + * + * @return a valid event packet container. NULL will be returned on errors, or when + * there is no container available in non-blocking mode. Always check for this! + */ +caerEventPacketContainer caerDeviceDataGet(caerDeviceHandle handle); + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_DEVICES_USB_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/common.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/common.h new file mode 100755 index 0000000..39470da --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/common.h @@ -0,0 +1,780 @@ +/** + * @file common.h + * + * Common EventPacket header format definition and handling functions. + * Every EventPacket, of any type, has as a first member a common header, + * which describes various properties of the contained events. This allows + * easy parsing of events. See the 'struct caer_event_packet_header' + * documentation for more details. + */ + +#ifndef LIBCAER_EVENTS_COMMON_H_ +#define LIBCAER_EVENTS_COMMON_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "../libcaer.h" + +/** + * Generic validity mark: + * this bit is used to mark whether an event is still + * valid or not, and can be used to efficiently filter + * out events from a packet. + * The caerXXXEventValidate() and caerXXXEventInvalidate() + * functions should be used to toggle this! + * 0 in the 0th bit of the first byte means invalid, 1 means valid. + * This way zeroing-out an event packet sets all its events to invalid. + * Care must be taken to put the field containing the validity + * mark always as the first member of an event. + */ +//@{ +#define VALID_MARK_SHIFT 0 +#define VALID_MARK_MASK 0x00000001 +//@} + +/** + * 64bit timestamp support: + * since timestamps wrap around after some time, being only 31 bit (32 bit signed int), + * another timestamp at the packet level provides another 31 bit (32 bit signed int), + * to enable the generation of a 62 bit (64 bit signed int) microsecond timestamp which + * is guaranteed to never wrap around (in the next 146'138 years at least). + * The TSOverflow needs to be shifted by 31 thus when constructing such a timestamp. + */ +#define TS_OVERFLOW_SHIFT 31 + +/** + * List of supported event types. + * Each event type has its own integer representation. + * All event types below 100 are reserved for use + * by libcaer and cAER. + * DO NOT USE THEM FOR YOUR OWN EVENT TYPES! + */ +enum caer_default_event_types { + SPECIAL_EVENT = 0, //!< Special events. + POLARITY_EVENT = 1, //!< Polarity (change, DVS) events. + FRAME_EVENT = 2, //!< Frame (intensity, APS) events. + IMU6_EVENT = 3, //!< 6 axes IMU events. + IMU9_EVENT = 4, //!< 9 axes IMU events. + SAMPLE_EVENT = 5, //!< ADC sample events. + EAR_EVENT = 6, //!< Ear (cochlea) events. + CONFIG_EVENT = 7, //!< Device configuration events. + POINT1D_EVENT = 8, //!< 1D measurement events. + POINT2D_EVENT = 9, //!< 2D measurement events. + POINT3D_EVENT = 10, //!< 3D measurement events. + POINT4D_EVENT = 11, //!< 4D measurement events. +}; + +/** + * Size of the EventPacket header. + * This is constant across all supported systems. + */ +#define CAER_EVENT_PACKET_HEADER_SIZE 28 + +/** + * EventPacket header data structure definition. + * The size, also defined in CAER_EVENT_PACKET_HEADER_SIZE, + * must always be constant. The header is common to all + * types of event packets and is always the very first + * member of an event packet data structure. + * Signed integers are used for compatibility with languages that + * do not have unsigned ones, such as Java. + */ +struct caer_event_packet_header { + /// Numerical type ID, unique to each event type (see 'enum caer_default_event_types'). + int16_t eventType; + /// Numerical source ID, unique inside a process, identifies who generated the events. + int16_t eventSource; + /// Size of one event in bytes. + int32_t eventSize; + /// Offset from the start of an event, in bytes, at which the main 32 bit time-stamp can be found. + int32_t eventTSOffset; + /// Overflow counter for the standard 32bit event time-stamp. Used to generate the 64 bit time-stamp. + int32_t eventTSOverflow; + /// Maximum number of events this packet can store. + int32_t eventCapacity; + /// Total number of events present in this packet (valid + invalid). + int32_t eventNumber; + /// Total number of valid events present in this packet. + int32_t eventValid; +}__attribute__((__packed__)); + +/** + * Type for pointer to EventPacket header data structure. + */ +typedef struct caer_event_packet_header *caerEventPacketHeader; + +/** + * Return the numerical event type ID, representing the event type this + * EventPacket is containing. + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * + * @return the numerical event type (see 'enum caer_default_event_types'). + */ +static inline int16_t caerEventPacketHeaderGetEventType(caerEventPacketHeader header) { + return (le16toh(header->eventType)); +} + +/** + * Set the numerical event type ID, representing the event type this + * EventPacket will contain. + * All event types below 100 are reserved for use by libcaer and cAER. + * DO NOT USE THEM FOR YOUR OWN EVENT TYPES! + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * @param eventType the numerical event type (see 'enum caer_default_event_types'). + */ +static inline void caerEventPacketHeaderSetEventType(caerEventPacketHeader header, int16_t eventType) { + if (eventType < 0) { + // Negative numbers (bit 31 set) are not allowed! + caerLog(CAER_LOG_CRITICAL, "EventPacket Header", + "Called caerEventPacketHeaderSetEventType() with negative value!"); + return; + } + + header->eventType = htole16(eventType); +} + +/** + * Get the numerical event source ID, representing the event source + * that generated all the events present in this packet. + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * + * @return the numerical event source ID. + */ +static inline int16_t caerEventPacketHeaderGetEventSource(caerEventPacketHeader header) { + return (le16toh(header->eventSource)); +} + +/** + * Set the numerical event source ID, representing the event source + * that generated all the events present in this packet. + * This ID should be unique at least within a process, if not within + * the whole system, to guarantee correct identification of who + * generated an event later on. + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * @param eventSource the numerical event source ID. + */ +static inline void caerEventPacketHeaderSetEventSource(caerEventPacketHeader header, int16_t eventSource) { + if (eventSource < 0) { + // Negative numbers (bit 31 set) are not allowed! + caerLog(CAER_LOG_CRITICAL, "EventPacket Header", + "Called caerEventPacketHeaderSetEventSource() with negative value!"); + return; + } + + header->eventSource = htole16(eventSource); +} + +/** + * Get the size of a single event, in bytes. + * All events inside an event packet always have the same size. + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * + * @return the event size in bytes. + */ +static inline int32_t caerEventPacketHeaderGetEventSize(caerEventPacketHeader header) { + return (le32toh(header->eventSize)); +} + +/** + * Set the size of a single event, in bytes. + * All events inside an event packet always have the same size. + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * @param eventSize the event size in bytes. + */ +static inline void caerEventPacketHeaderSetEventSize(caerEventPacketHeader header, int32_t eventSize) { + if (eventSize < 0) { + // Negative numbers (bit 31 set) are not allowed! + caerLog(CAER_LOG_CRITICAL, "EventPacket Header", + "Called caerEventPacketHeaderSetEventSize() with negative value!"); + return; + } + + header->eventSize = htole32(eventSize); +} + +/** + * Get the offset, in bytes, to where the field with the main + * 32 bit timestamp is stored. This is useful for generic access + * to the timestamp field, given that different event types might + * have it at different offsets or might even have multiple + * timestamps, in which case this offset references the 'main' + * timestamp, the most representative one. + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * + * @return the event timestamp offset in bytes. + */ +static inline int32_t caerEventPacketHeaderGetEventTSOffset(caerEventPacketHeader header) { + return (le32toh(header->eventTSOffset)); +} + +/** + * Set the offset, in bytes, to where the field with the main + * 32 bit timestamp is stored. This is useful for generic access + * to the timestamp field, given that different event types might + * have it at different offsets or might even have multiple + * timestamps, in which case this offset references the 'main' + * timestamp, the most representative one. + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * @param eventTSOffset the event timestamp offset in bytes. + */ +static inline void caerEventPacketHeaderSetEventTSOffset(caerEventPacketHeader header, int32_t eventTSOffset) { + if (eventTSOffset < 0) { + // Negative numbers (bit 31 set) are not allowed! + caerLog(CAER_LOG_CRITICAL, "EventPacket Header", + "Called caerEventPacketHeaderSetEventTSOffset() with negative value!"); + return; + } + + header->eventTSOffset = htole32(eventTSOffset); +} + +/** + * Get the 32 bit timestamp overflow counter (in microseconds). This is per-packet + * and is used to generate a 64 bit timestamp that never wraps around. + * Since timestamps wrap around after some time, being only 31 bit (32 bit signed int), + * another timestamp at the packet level provides another 31 bit (32 bit signed int), + * to enable the generation of a 62 bit (64 bit signed int) microsecond timestamp which + * is guaranteed to never wrap around (in the next 146'138 years at least). + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * + * @return the packet-level timestamp overflow counter, in microseconds. + */ +static inline int32_t caerEventPacketHeaderGetEventTSOverflow(caerEventPacketHeader header) { + return (le32toh(header->eventTSOverflow)); +} + +/** + * Set the 32 bit timestamp overflow counter (in microseconds). This is per-packet + * and is used to generate a 64 bit timestamp that never wraps around. + * Since timestamps wrap around after some time, being only 31 bit (32 bit signed int), + * another timestamp at the packet level provides another 31 bit (32 bit signed int), + * to enable the generation of a 62 bit (64 bit signed int) microsecond timestamp which + * is guaranteed to never wrap around (in the next 146'138 years at least). + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * @param eventTSOverflow the packet-level timestamp overflow counter, in microseconds. + */ +static inline void caerEventPacketHeaderSetEventTSOverflow(caerEventPacketHeader header, int32_t eventTSOverflow) { + if (eventTSOverflow < 0) { + // Negative numbers (bit 31 set) are not allowed! + caerLog(CAER_LOG_CRITICAL, "EventPacket Header", + "Called caerEventPacketHeaderSetEventTSOverflow() with negative value!"); + return; + } + + header->eventTSOverflow = htole32(eventTSOverflow); +} + +/** + * Get the maximum number of events this packet can store. + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * + * @return the number of events this packet can hold. + */ +static inline int32_t caerEventPacketHeaderGetEventCapacity(caerEventPacketHeader header) { + return (le32toh(header->eventCapacity)); +} + +/** + * Set the maximum number of events this packet can store. + * This is determined at packet allocation time and should + * not be changed during the life-time of the packet. + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * @param eventsCapacity the number of events this packet can hold. + */ +static inline void caerEventPacketHeaderSetEventCapacity(caerEventPacketHeader header, int32_t eventsCapacity) { + if (eventsCapacity < 0) { + // Negative numbers (bit 31 set) are not allowed! + caerLog(CAER_LOG_CRITICAL, "EventPacket Header", + "Called caerEventPacketHeaderSetEventCapacity() with negative value!"); + return; + } + + header->eventCapacity = htole32(eventsCapacity); +} + +/** + * Get the number of events currently stored in this packet, + * considering both valid and invalid events. + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * + * @return the number of events in this packet. + */ +static inline int32_t caerEventPacketHeaderGetEventNumber(caerEventPacketHeader header) { + return (le32toh(header->eventNumber)); +} + +/** + * Set the number of events currently stored in this packet, + * considering both valid and invalid events. + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * @param eventsNumber the number of events in this packet. + */ +static inline void caerEventPacketHeaderSetEventNumber(caerEventPacketHeader header, int32_t eventsNumber) { + if (eventsNumber < 0) { + // Negative numbers (bit 31 set) are not allowed! + caerLog(CAER_LOG_CRITICAL, "EventPacket Header", + "Called caerEventPacketHeaderSetEventNumber() with negative value!"); + return; + } + + header->eventNumber = htole32(eventsNumber); +} + +/** + * Get the number of valid events in this packet, disregarding + * invalid ones (where the invalid mark is set). + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * + * @return the number of valid events in this packet. + */ +static inline int32_t caerEventPacketHeaderGetEventValid(caerEventPacketHeader header) { + return (le32toh(header->eventValid)); +} + +/** + * Set the number of valid events in this packet, disregarding + * invalid ones (where the invalid mark is set). + * + * @param header a valid EventPacket header pointer. Cannot be NULL. + * @param eventsValid the number of valid events in this packet. + */ +static inline void caerEventPacketHeaderSetEventValid(caerEventPacketHeader header, int32_t eventsValid) { + if (eventsValid < 0) { + // Negative numbers (bit 31 set) are not allowed! + caerLog(CAER_LOG_CRITICAL, "EventPacket Header", + "Called caerEventPacketHeaderSetEventValid() with negative value!"); + return; + } + + header->eventValid = htole32(eventsValid); +} + +/** + * Grows an event packet. + * Use free() to reclaim this memory afterwards. + * + * @param packet the current events packet. + * @param eventCapacity the new maximum number of events this packet will hold. + * + * @return a valid event packet handle or NULL on error. + * On success, the old packet handle is to be considered invalid and not to be + * used anymore. On failure, the old packet handle is not touched in any way. + */ +static inline caerEventPacketHeader caerGenericEventPacketGrow(caerEventPacketHeader packet, int32_t newEventCapacity) { + if (packet == NULL || newEventCapacity == 0) { + return (NULL); + } + + int32_t oldEventCapacity = caerEventPacketHeaderGetEventCapacity(packet); + + if (newEventCapacity <= oldEventCapacity) { + caerLog(CAER_LOG_CRITICAL, "Generic Event Packet", + "Called caerGenericEventPacketGrow() with a new capacity value (%" PRIi32 ") that is equal or smaller than the old one (%" PRIi32 "). " + "Only strictly growing an event packet is supported!", newEventCapacity, oldEventCapacity); + return (NULL); + } + + int32_t eventSize = caerEventPacketHeaderGetEventSize(packet); + size_t newEventPacketSize = CAER_EVENT_PACKET_HEADER_SIZE + (size_t) (newEventCapacity * eventSize); + + // Grow memory used to hold events. + packet = (caerEventPacketHeader) realloc(packet, newEventPacketSize); + if (packet == NULL) { + caerLog(CAER_LOG_CRITICAL, "Generic Event Packet", + "Failed to reallocate %zu bytes of memory for growing Event Packet of capacity %" + PRIi32 " to new capacity of %" PRIi32 ". Error: %d.", newEventPacketSize, oldEventCapacity, + newEventCapacity, errno); + return (NULL); + } + + // Zero out new event memory (all events invalid). + memset(((uint8_t *) packet) + CAER_EVENT_PACKET_HEADER_SIZE + (oldEventCapacity * eventSize), 0, + (size_t) ((newEventCapacity - oldEventCapacity) * eventSize)); + + // Update header fields. + caerEventPacketHeaderSetEventCapacity(packet, newEventCapacity); + + return (packet); +} + +/** + * Appends an event packet to another. + * This is a simple append operation, no timestamp reordering is done. + * Please ensure time is monotonically increasing over the two packets! + * Use free() to reclaim this memory afterwards. + * + * @param packet the main events packet. + * @param appendPacket the events packet to append on the main one. + * + * @return a valid event packet handle or NULL on error. + * On success, the old packet handle is to be considered invalid and not to be + * used anymore. On failure, the old packet handle is not touched in any way. + * The appendPacket handle is never touched in any way. + */ +static inline caerEventPacketHeader caerGenericEventPacketAppend(caerEventPacketHeader packet, + caerEventPacketHeader appendPacket) { + if (packet == NULL) { + return (NULL); + } + + // Support appending nothing, the result is the unmodified input. + if (appendPacket == NULL) { + return (packet); + } + + // Check that the two packets are of the same type and size, and have the same TSOverflow epoch. + if ((caerEventPacketHeaderGetEventType(packet) != caerEventPacketHeaderGetEventType(appendPacket)) + || (caerEventPacketHeaderGetEventSize(packet) != caerEventPacketHeaderGetEventSize(appendPacket)) + || (caerEventPacketHeaderGetEventTSOverflow(packet) != caerEventPacketHeaderGetEventTSOverflow(appendPacket))) { + return (NULL); + } + + int32_t packetEventValid = caerEventPacketHeaderGetEventValid(packet); + int32_t packetEventNumber = caerEventPacketHeaderGetEventNumber(packet); + int32_t packetEventCapacity = caerEventPacketHeaderGetEventCapacity(packet); + + int32_t appendPacketEventValid = caerEventPacketHeaderGetEventValid(appendPacket); + int32_t appendPacketEventNumber = caerEventPacketHeaderGetEventNumber(appendPacket); + int32_t appendPacketEventCapacity = caerEventPacketHeaderGetEventCapacity(appendPacket); + + int32_t eventSize = caerEventPacketHeaderGetEventSize(packet); // Is the same! Checked above. + size_t newEventPacketSize = CAER_EVENT_PACKET_HEADER_SIZE + + (size_t) ((packetEventCapacity + appendPacketEventCapacity) * eventSize); + + // Grow memory used to hold events. + packet = (caerEventPacketHeader) realloc(packet, newEventPacketSize); + if (packet == NULL) { + caerLog(CAER_LOG_CRITICAL, "Generic Event Packet", + "Failed to reallocate %zu bytes of memory for appending Event Packet of capacity %" + PRIi32 " to Event Packet of capacity %" PRIi32 ". Error: %d.", newEventPacketSize, + appendPacketEventCapacity, packetEventCapacity, errno); + return (NULL); + } + + // Copy appendPacket event memory at start of free space in packet. + memcpy(((uint8_t *) packet) + CAER_EVENT_PACKET_HEADER_SIZE + (packetEventNumber * eventSize), + ((uint8_t *) appendPacket) + CAER_EVENT_PACKET_HEADER_SIZE, (size_t) (appendPacketEventNumber * eventSize)); + + // Zero out remaining event memory (all events invalid). + memset( + ((uint8_t *) packet) + CAER_EVENT_PACKET_HEADER_SIZE + + ((packetEventNumber + appendPacketEventNumber) * eventSize), 0, + (size_t) (((packetEventCapacity + appendPacketEventCapacity) - (packetEventNumber + appendPacketEventNumber)) + * eventSize)); + + // Update header fields. + caerEventPacketHeaderSetEventValid(packet, (packetEventValid + appendPacketEventValid)); + caerEventPacketHeaderSetEventNumber(packet, (packetEventNumber + appendPacketEventNumber)); + caerEventPacketHeaderSetEventCapacity(packet, (packetEventCapacity + appendPacketEventCapacity)); + + return (packet); +} + +/** + * Get a generic pointer to an event, without having to know what event + * type the packet is containing. + * + * @param headerPtr a valid EventPacket header pointer. Cannot be NULL. + * @param n the index of the returned event. Must be within [0,eventCapacity[ bounds. + * + * @return a generic pointer to the requested event. NULL on error. + */ +static inline void *caerGenericEventGetEvent(caerEventPacketHeader headerPtr, int32_t n) { + // Check that we're not out of bounds. + if (n < 0 || n >= caerEventPacketHeaderGetEventCapacity(headerPtr)) { + caerLog(CAER_LOG_CRITICAL, "Generic Event", + "Called caerGenericEventGetEvent() with invalid event offset %" PRIi32 ", while maximum allowed value is %" PRIi32 ". Negative values are not allowed!", + n, caerEventPacketHeaderGetEventCapacity(headerPtr) - 1); + return (NULL); + } + + // Return a pointer to the specified event. + return (((uint8_t *) headerPtr) + + (CAER_EVENT_PACKET_HEADER_SIZE + U64T(n * caerEventPacketHeaderGetEventSize(headerPtr)))); +} + +/** + * Get the main 32 bit timestamp for a generic event, without having to + * know what event type the packet is containing. + * + * @param eventPtr a generic pointer to an event. Cannot be NULL. + * @param headerPtr a valid EventPacket header pointer. Cannot be NULL. + * + * @return the main 32 bit timestamp of this event. + */ +static inline int32_t caerGenericEventGetTimestamp(void *eventPtr, caerEventPacketHeader headerPtr) { + return (le32toh(*((int32_t *) (((uint8_t *) eventPtr) + U64T(caerEventPacketHeaderGetEventTSOffset(headerPtr)))))); +} + +/** + * Get the main 64 bit timestamp for a generic event, without having to + * know what event type the packet is containing. This takes the + * per-packet timestamp into account too, generating a timestamp + * that doesn't suffer from overflow problems. + * + * @param eventPtr a generic pointer to an event. Cannot be NULL. + * @param headerPtr a valid EventPacket header pointer. Cannot be NULL. + * + * @return the main 64 bit timestamp of this event. + */ +static inline int64_t caerGenericEventGetTimestamp64(void *eventPtr, caerEventPacketHeader headerPtr) { + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(headerPtr)) << TS_OVERFLOW_SHIFT) | U64T(caerGenericEventGetTimestamp(eventPtr, headerPtr)))); +} + +/** + * Check if the given generic event is valid or not. + * + * @param eventPtr a generic pointer to an event. Cannot be NULL. + * + * @return true if the event is valid, false otherwise. + */ +static inline bool caerGenericEventIsValid(void *eventPtr) { + // Look at first byte of event memory's lowest bit. + // This should always work since first event member must contain the valid mark + // and memory is little-endian, so lowest bit must be in first byte of memory. + return (*((uint8_t *) eventPtr) & VALID_MARK_MASK); +} + +/** + * Generic iterator over all events in a packet. + * Returns the current index in the 'caerIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerIteratorElement' variable + * of type EVENT_TYPE. + * + * PACKET_HEADER: a valid EventPacket header pointer. Cannot be NULL. + * EVENT_TYPE: the event pointer type for this EventPacket (ie. caerPolarityEvent or caerFrameEvent). + */ +#define CAER_ITERATOR_ALL_START(PACKET_HEADER, EVENT_TYPE) \ + for (int32_t caerIteratorCounter = 0; \ + caerIteratorCounter < caerEventPacketHeaderGetEventNumber(PACKET_HEADER); \ + caerIteratorCounter++) { \ + EVENT_TYPE caerIteratorElement = (EVENT_TYPE) caerGenericEventGetEvent(PACKET_HEADER, caerIteratorCounter); + +/** + * Generic iterator close statement. + */ +#define CAER_ITERATOR_ALL_END } + +/** + * Generic iterator over only the valid events in a packet. + * Returns the current index in the 'caerIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerIteratorElement' variable + * of type EVENT_TYPE. + * + * PACKET_HEADER: a valid EventPacket header pointer. Cannot be NULL. + * EVENT_TYPE: the event pointer type for this EventPacket (ie. caerPolarityEvent or caerFrameEvent). + */ +#define CAER_ITERATOR_VALID_START(PACKET_HEADER, EVENT_TYPE) \ + for (int32_t caerIteratorCounter = 0; \ + caerIteratorCounter < caerEventPacketHeaderGetEventNumber(PACKET_HEADER); \ + caerIteratorCounter++) { \ + EVENT_TYPE caerIteratorElement = (EVENT_TYPE) caerGenericEventGetEvent(PACKET_HEADER, caerIteratorCounter); \ + if (!caerGenericEventIsValid(caerIteratorElement)) { continue; } // Skip invalid events. + +/** + * Generic iterator close statement. + */ +#define CAER_ITERATOR_VALID_END } + +// Functions for event packet copying. + +/** + * Make a full copy of an event packet (up to eventCapacity). + * + * @param eventPacket an event packet to copy. + * + * @return a full copy of an event packet. + */ +static inline void *caerCopyEventPacket(void *eventPacket) { + // Handle empty event packets. + if (eventPacket == NULL) { + return (NULL); + } + + // Calculate needed memory for new event packet. + caerEventPacketHeader header = (caerEventPacketHeader) eventPacket; + int32_t eventSize = caerEventPacketHeaderGetEventSize(header); + int32_t eventNumber = caerEventPacketHeaderGetEventNumber(header); + int32_t eventCapacity = caerEventPacketHeaderGetEventCapacity(header); + size_t packetMem = CAER_EVENT_PACKET_HEADER_SIZE + (size_t) (eventSize * eventCapacity); + size_t dataMem = CAER_EVENT_PACKET_HEADER_SIZE + (size_t) (eventSize * eventNumber); + + // Allocate memory for new event packet. + caerEventPacketHeader eventPacketCopy = (caerEventPacketHeader) malloc(packetMem); + if (eventPacketCopy == NULL) { + // Failed to allocate memory. + return (NULL); + } + + // Copy the data over. + memcpy(eventPacketCopy, eventPacket, dataMem); + + // Zero out the rest of the packet. + memset(((uint8_t *) eventPacketCopy) + dataMem, 0, packetMem - dataMem); + + return (eventPacketCopy); +} + +/** + * Make a copy of an event packet, sized down to only include the + * currently present events (eventNumber, valid+invalid), and not + * including the possible extra unused events (up to eventCapacity). + * + * @param eventPacket an event packet to copy. + * + * @return a sized down copy of an event packet. + */ +static inline void *caerCopyEventPacketOnlyEvents(void *eventPacket) { + // Handle empty event packets. + if (eventPacket == NULL) { + return (NULL); + } + + // Calculate needed memory for new event packet. + caerEventPacketHeader header = (caerEventPacketHeader) eventPacket; + int32_t eventSize = caerEventPacketHeaderGetEventSize(header); + int32_t eventNumber = caerEventPacketHeaderGetEventNumber(header); + + if (eventNumber == 0) { + // No copy possible if result is empty (capacity=0). + return (NULL); + } + + size_t packetMem = CAER_EVENT_PACKET_HEADER_SIZE + (size_t) (eventSize * eventNumber); + + // Allocate memory for new event packet. + caerEventPacketHeader eventPacketCopy = (caerEventPacketHeader) malloc(packetMem); + if (eventPacketCopy == NULL) { + // Failed to allocate memory. + return (NULL); + } + + // Copy the data over. + memcpy(eventPacketCopy, eventPacket, packetMem); + + // Set the event capacity to the event number, since we only allocated + // memory for that many events. + caerEventPacketHeaderSetEventCapacity(eventPacketCopy, eventNumber); + + return (eventPacketCopy); +} + +/** + * Make a copy of an event packet, sized down to only include the + * currently valid events (eventValid), and discarding everything else. + * + * @param eventPacket an event packet to copy. + * + * @return a copy of an event packet, containing only valid events. + */ +static inline void *caerCopyEventPacketOnlyValidEvents(void *eventPacket) { + // Handle empty event packets. + if (eventPacket == NULL) { + return (NULL); + } + + // Calculate needed memory for new event packet. + caerEventPacketHeader header = (caerEventPacketHeader) eventPacket; + int32_t eventSize = caerEventPacketHeaderGetEventSize(header); + int32_t eventValid = caerEventPacketHeaderGetEventValid(header); + + if (eventValid == 0) { + // No copy possible if result is empty (capacity=0). + return (NULL); + } + + size_t packetMem = CAER_EVENT_PACKET_HEADER_SIZE + (size_t) (eventSize * eventValid); + + // Allocate memory for new event packet. + caerEventPacketHeader eventPacketCopy = (caerEventPacketHeader) malloc(packetMem); + if (eventPacketCopy == NULL) { + // Failed to allocate memory. + return (NULL); + } + + // First copy over the header. + memcpy(eventPacketCopy, eventPacket, CAER_EVENT_PACKET_HEADER_SIZE); + + // Copy the data over. Must check every event for validity! + size_t offset = CAER_EVENT_PACKET_HEADER_SIZE; + + CAER_ITERATOR_VALID_START(header, void *) + memcpy(((uint8_t *) eventPacketCopy) + offset, caerIteratorElement, (size_t) eventSize); + offset += (size_t) eventSize; + } + + // Set the event capacity and the event number to the number of + // valid events, since we only copied those. + caerEventPacketHeaderSetEventCapacity(eventPacketCopy, eventValid); + caerEventPacketHeaderSetEventNumber(eventPacketCopy, eventValid); + + return (eventPacketCopy); +} + +/** + * Cleanup a packet by removing all invalid events, so that + * the total number of events is the number of valid events. + * The packet's capacity doesn't change. + * + * @param eventPacket an event packet to clean. + */ +static inline void caerCleanEventPacket(void *eventPacket) { + // Handle empty event packets. + if (eventPacket == NULL) { + return; + } + + // Calculate needed memory for new event packet. + caerEventPacketHeader header = (caerEventPacketHeader) eventPacket; + int32_t eventSize = caerEventPacketHeaderGetEventSize(header); + int32_t eventValid = caerEventPacketHeaderGetEventValid(header); + int32_t eventNumber = caerEventPacketHeaderGetEventNumber(header); + int32_t eventCapacity = caerEventPacketHeaderGetEventCapacity(header); + + // If we have no invalid events, we're already done. + if (eventValid == eventNumber) { + return; + } + + // Move all valid events close together. Must check every event for validity! + size_t offset = CAER_EVENT_PACKET_HEADER_SIZE; + + CAER_ITERATOR_VALID_START(header, void *) + void *dest = ((uint8_t *) header) + offset; + + if (dest != caerIteratorElement) { + memcpy(dest, caerIteratorElement, (size_t) eventSize); + offset += (size_t) eventSize; + } + } + + // Reset remaining memory, up to capacity, to zero (all events invalid). + memset(((uint8_t *) header) + offset, 0, (size_t) ((eventCapacity - eventValid) * eventSize)); + + // Event capacity remains unchanged, event number shrunk to event valid number. + caerEventPacketHeaderSetEventNumber(header, eventValid); +} + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_EVENTS_COMMON_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/config.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/config.h new file mode 100755 index 0000000..c66c07a --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/config.h @@ -0,0 +1,332 @@ +/** + * @file config.h + * + * Configuration Events format definition and handling functions. + * This event contains information about the current configuration of + * the device. By having configuration as a standardized event format, + * it becomes host-software agnostic, and it also becomes part of the + * event stream, enabling easy tracking of changes through time, by + * putting them into the event stream at the moment they happen. + * While the resolution of the timestamps for these events is in + * microseconds for compatibility with all other event types, the + * precision is in the order of ~1-20 milliseconds, given that these + * events are generated and injected on the host-side. + */ + +#ifndef LIBCAER_EVENTS_CONFIG_H_ +#define LIBCAER_EVENTS_CONFIG_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "common.h" + +/** + * Shift and mask values for the module address. + * Module address is only 7 bits, since the eighth bit + * is used device-side to differentiate reads from writes. + * Here we can just re-use it for the validity mark. + */ +//@{ +#define MODULE_ADDR_SHIFT 1 +#define MODULE_ADDR_MASK 0x0000007F +//@} + +/** + * Configuration event data structure definition. + * This contains the actual configuration module address, the + * parameter address and the actual parameter content, as + * well as the 32 bit event timestamp. + * Signed integers are used for fields that are to be interpreted + * directly, for compatibility with languages that do not have + * unsigned integer types, such as Java. + */ +struct caer_configuration_event { + /// Configuration module address. First (also) because of valid mark. + uint8_t moduleAddress; + /// Configuration parameter address. + uint8_t parameterAddress; + /// Configuration parameter content (4 bytes). + uint32_t parameter; + /// Event timestamp. + int32_t timestamp; +}__attribute__((__packed__)); + +/** + * Type for pointer to configuration event data structure. + */ +typedef struct caer_configuration_event *caerConfigurationEvent; + +/** + * Configuration event packet data structure definition. + * EventPackets are always made up of the common packet header, + * followed by 'eventCapacity' events. Everything has to + * be in one contiguous memory block. + */ +struct caer_configuration_event_packet { + /// The common event packet header. + struct caer_event_packet_header packetHeader; + /// The events array. + struct caer_configuration_event events[]; +}__attribute__((__packed__)); + +/** + * Type for pointer to configuration event packet data structure. + */ +typedef struct caer_configuration_event_packet *caerConfigurationEventPacket; + +/** + * Allocate a new configuration events packet. + * Use free() to reclaim this memory. + * + * @param eventCapacity the maximum number of events this packet will hold. + * @param eventSource the unique ID representing the source/generator of this packet. + * @param tsOverflow the current timestamp overflow counter value for this packet. + * + * @return a valid ConfigurationEventPacket handle or NULL on error. + */ +caerConfigurationEventPacket caerConfigurationEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, + int32_t tsOverflow); + +/** + * Get the configuration event at the given index from the event packet. + * + * @param packet a valid ConfigurationEventPacket pointer. Cannot be NULL. + * @param n the index of the returned event. Must be within [0,eventCapacity[ bounds. + * + * @return the requested configuration event. NULL on error. + */ +static inline caerConfigurationEvent caerConfigurationEventPacketGetEvent(caerConfigurationEventPacket packet, + int32_t n) { + // Check that we're not out of bounds. + if (n < 0 || n >= caerEventPacketHeaderGetEventCapacity(&packet->packetHeader)) { + caerLog(CAER_LOG_CRITICAL, "Configuration Event", + "Called caerConfigurationEventPacketGetEvent() with invalid event offset %" PRIi32 ", while maximum allowed value is %" PRIi32 ".", + n, caerEventPacketHeaderGetEventCapacity(&packet->packetHeader) - 1); + return (NULL); + } + + // Return a pointer to the specified event. + return (packet->events + n); +} + +/** + * Get the 32bit event timestamp, in microseconds. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid ConfigurationEvent pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond timestamp. + */ +static inline int32_t caerConfigurationEventGetTimestamp(caerConfigurationEvent event) { + return (le32toh(event->timestamp)); +} + +/** + * Get the 64bit event timestamp, in microseconds. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid ConfigurationEvent pointer. Cannot be NULL. + * @param packet the ConfigurationEventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond timestamp. + */ +static inline int64_t caerConfigurationEventGetTimestamp64(caerConfigurationEvent event, + caerConfigurationEventPacket packet) { + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(&packet->packetHeader)) << TS_OVERFLOW_SHIFT) | U64T(caerConfigurationEventGetTimestamp(event)))); +} + +/** + * Set the 32bit event timestamp, the value has to be in microseconds. + * + * @param event a valid ConfigurationEvent pointer. Cannot be NULL. + * @param timestamp a positive 32bit microsecond timestamp. + */ +static inline void caerConfigurationEventSetTimestamp(caerConfigurationEvent event, int32_t timestamp) { + if (timestamp < 0) { + // Negative means using the 31st bit! + caerLog(CAER_LOG_CRITICAL, "Configuration Event", + "Called caerConfigurationEventSetTimestamp() with negative value!"); + return; + } + + event->timestamp = htole32(timestamp); +} + +/** + * Check if this configuration event is valid. + * + * @param event a valid ConfigurationEvent pointer. Cannot be NULL. + * + * @return true if valid, false if not. + */ +static inline bool caerConfigurationEventIsValid(caerConfigurationEvent event) { + return (GET_NUMBITS8(event->moduleAddress, VALID_MARK_SHIFT, VALID_MARK_MASK)); +} + +/** + * Validate the current event by setting its valid bit to true + * and increasing the event packet's event count and valid + * event count. Only works on events that are invalid. + * DO NOT CALL THIS AFTER HAVING PREVIOUSLY ALREADY + * INVALIDATED THIS EVENT, the total count will be incorrect. + * + * @param event a valid ConfigurationEvent pointer. Cannot be NULL. + * @param packet the ConfigurationEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerConfigurationEventValidate(caerConfigurationEvent event, caerConfigurationEventPacket packet) { + if (!caerConfigurationEventIsValid(event)) { + SET_NUMBITS8(event->moduleAddress, VALID_MARK_SHIFT, VALID_MARK_MASK, 1); + + // Also increase number of events and valid events. + // Only call this on (still) invalid events! + caerEventPacketHeaderSetEventNumber(&packet->packetHeader, + caerEventPacketHeaderGetEventNumber(&packet->packetHeader) + 1); + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) + 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Configuration Event", + "Called caerConfigurationEventValidate() on already valid event."); + } +} + +/** + * Invalidate the current event by setting its valid bit + * to false and decreasing the number of valid events held + * in the packet. Only works with events that are already + * valid! + * + * @param event a valid ConfigurationEvent pointer. Cannot be NULL. + * @param packet the ConfigurationEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerConfigurationEventInvalidate(caerConfigurationEvent event, caerConfigurationEventPacket packet) { + if (caerConfigurationEventIsValid(event)) { + CLEAR_NUMBITS8(event->moduleAddress, VALID_MARK_SHIFT, VALID_MARK_MASK); + + // Also decrease number of valid events. Number of total events doesn't change. + // Only call this on valid events! + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) - 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Configuration Event", + "Called caerConfigurationEventInvalidate() on already invalid event."); + } +} + +/** + * Get the configuration event's module address. + * + * @param event a valid ConfigurationEvent pointer. Cannot be NULL. + * + * @return configuration module address. + */ +static inline uint8_t caerConfigurationEventGetModuleAddress(caerConfigurationEvent event) { + return U8T(GET_NUMBITS8(event->moduleAddress, MODULE_ADDR_SHIFT, MODULE_ADDR_MASK)); +} + +/** + * Set the configuration event's module address. + * + * @param event a valid ConfigurationEvent pointer. Cannot be NULL. + * @param moduleAddress configuration module address. + */ +static inline void caerConfigurationEventSetModuleAddress(caerConfigurationEvent event, uint8_t moduleAddress) { + CLEAR_NUMBITS8(event->moduleAddress, MODULE_ADDR_SHIFT, MODULE_ADDR_MASK); + SET_NUMBITS8(event->moduleAddress, MODULE_ADDR_SHIFT, MODULE_ADDR_MASK, moduleAddress); +} + +/** + * Get the configuration event's parameter address. + * + * @param event a valid ConfigurationEvent pointer. Cannot be NULL. + * + * @return configuration parameter address. + */ +static inline uint8_t caerConfigurationEventGetParameterAddress(caerConfigurationEvent event) { + return (event->parameterAddress); +} + +/** + * Set the configuration event's parameter address. + * + * @param event a valid ConfigurationEvent pointer. Cannot be NULL. + * @param parameterAddress configuration parameter address. + */ +static inline void caerConfigurationEventSetParameterAddress(caerConfigurationEvent event, uint8_t parameterAddress) { + event->parameterAddress = parameterAddress; +} + +/** + * Get the configuration event's parameter. + * + * @param event a valid ConfigurationEvent pointer. Cannot be NULL. + * + * @return configuration parameter. + */ +static inline uint32_t caerConfigurationEventGetParameter(caerConfigurationEvent event) { + return (le32toh(event->parameter)); +} + +/** + * Set the configuration event's parameter. + * + * @param event a valid ConfigurationEvent pointer. Cannot be NULL. + * @param parameter configuration parameter. + */ +static inline void caerConfigurationEventSetParameter(caerConfigurationEvent event, uint32_t parameter) { + event->parameter = htole32(parameter); +} + +/** + * Iterator over all configuration events in a packet. + * Returns the current index in the 'caerConfigurationIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerConfigurationIteratorElement' variable + * of type caerConfigurationEvent. + * + * CONFIGURATION_PACKET: a valid ConfigurationEventPacket pointer. Cannot be NULL. + */ +#define CAER_CONFIGURATION_ITERATOR_ALL_START(CONFIGURATION_PACKET) \ + for (int32_t caerConfigurationIteratorCounter = 0; \ + caerConfigurationIteratorCounter < caerEventPacketHeaderGetEventNumber(&(CONFIGURATION_PACKET)->packetHeader); \ + caerConfigurationIteratorCounter++) { \ + caerConfigurationEvent caerConfigurationIteratorElement = caerConfigurationEventPacketGetEvent(CONFIGURATION_PACKET, caerConfigurationIteratorCounter); + +/** + * Iterator close statement. + */ +#define CAER_CONFIGURATION_ITERATOR_ALL_END } + +/** + * Iterator over only the valid configuration events in a packet. + * Returns the current index in the 'caerConfigurationIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerConfigurationIteratorElement' variable + * of type caerConfigurationEvent. + * + * CONFIGURATION_PACKET: a valid ConfigurationEventPacket pointer. Cannot be NULL. + */ +#define CAER_CONFIGURATION_ITERATOR_VALID_START(CONFIGURATION_PACKET) \ + for (int32_t caerConfigurationIteratorCounter = 0; \ + caerConfigurationIteratorCounter < caerEventPacketHeaderGetEventNumber(&(CONFIGURATION_PACKET)->packetHeader); \ + caerConfigurationIteratorCounter++) { \ + caerConfigurationEvent caerConfigurationIteratorElement = caerConfigurationEventPacketGetEvent(CONFIGURATION_PACKET, caerConfigurationIteratorCounter); \ + if (!caerConfigurationEventIsValid(caerConfigurationIteratorElement)) { continue; } // Skip invalid configuration events. + +/** + * Iterator close statement. + */ +#define CAER_CONFIGURATION_ITERATOR_VALID_END } + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_EVENTS_CONFIG_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/ear.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/ear.h new file mode 100755 index 0000000..1556f8b --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/ear.h @@ -0,0 +1,334 @@ +/** + * @file ear.h + * + * Ear (Cochlea) Events format definition and handling functions. + * This encodes events from a silicon cochlea chip, containing + * information about which ear (microphone) generated the event, + * as well as which channel was involved and additional information + * on filters and neurons. + */ + +#ifndef LIBCAER_EVENTS_EAR_H_ +#define LIBCAER_EVENTS_EAR_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "common.h" + +/** + * Shift and mask values for the ear event values coming from + * a cochlea: the ear position (up to 16), the channel number + * (up to 2048), the ganglion (up to 256) and the filter (up to 256). + * Bit 0 is the valid mark, see 'common.h' for more details. + */ +//@{ +#define EAR_SHIFT 1 +#define EAR_MASK 0x0000000F +#define CHANNEL_SHIFT 5 +#define CHANNEL_MASK 0x000007FF +#define NEURON_SHIFT 16 +#define NEURON_MASK 0x000000FF +#define FILTER_SHIFT 24 +#define FILTER_MASK 0x000000FF +//@} + +/** + * Ear (cochlea) event data structure definition. + * Contains information on events gotten from a cochlea chip: + * ears, channels, neurons and filters are stored. + * Signed integers are used for fields that are to be interpreted + * directly, for compatibility with languages that do not have + * unsigned integer types, such as Java. + */ +struct caer_ear_event { + /// Event data. First because of valid mark. + uint32_t data; + /// Event timestamp. + int32_t timestamp; +}__attribute__((__packed__)); + +/** + * Type for pointer to ear (cochlea) event data structure. + */ +typedef struct caer_ear_event *caerEarEvent; + +/** + * Ear (cochlea) event packet data structure definition. + * EventPackets are always made up of the common packet header, + * followed by 'eventCapacity' events. Everything has to + * be in one contiguous memory block. + */ +struct caer_ear_event_packet { + /// The common event packet header. + struct caer_event_packet_header packetHeader; + /// The events array. + struct caer_ear_event events[]; +}__attribute__((__packed__)); + +/** + * Type for pointer to ear (cochlea) event packet data structure. + */ +typedef struct caer_ear_event_packet *caerEarEventPacket; + +/** + * Allocate a new ear (cochlea) events packet. + * Use free() to reclaim this memory. + * + * @param eventCapacity the maximum number of events this packet will hold. + * @param eventSource the unique ID representing the source/generator of this packet. + * @param tsOverflow the current timestamp overflow counter value for this packet. + * + * @return a valid EarEventPacket handle or NULL on error. + */ +caerEarEventPacket caerEarEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow); + +/** + * Get the ear (cochlea) event at the given index from the event packet. + * + * @param packet a valid EarEventPacket pointer. Cannot be NULL. + * @param n the index of the returned event. Must be within [0,eventCapacity[ bounds. + * + * @return the requested ear (cochlea) event. NULL on error. + */ +static inline caerEarEvent caerEarEventPacketGetEvent(caerEarEventPacket packet, int32_t n) { + // Check that we're not out of bounds. + if (n < 0 || n >= caerEventPacketHeaderGetEventCapacity(&packet->packetHeader)) { + caerLog(CAER_LOG_CRITICAL, "Ear Event", + "Called caerEarEventPacketGetEvent() with invalid event offset %" PRIi32 ", while maximum allowed value is %" PRIi32 ".", + n, caerEventPacketHeaderGetEventCapacity(&packet->packetHeader) - 1); + return (NULL); + } + + // Return a pointer to the specified event. + return (packet->events + n); +} + +/** + * Get the 32bit event timestamp, in microseconds. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid EarEvent pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond timestamp. + */ +static inline int32_t caerEarEventGetTimestamp(caerEarEvent event) { + return (le32toh(event->timestamp)); +} + +/** + * Get the 64bit event timestamp, in microseconds. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid EarEvent pointer. Cannot be NULL. + * @param packet the EarEventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond timestamp. + */ +static inline int64_t caerEarEventGetTimestamp64(caerEarEvent event, caerEarEventPacket packet) { + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(&packet->packetHeader)) << TS_OVERFLOW_SHIFT) | U64T(caerEarEventGetTimestamp(event)))); +} + +/** + * Set the 32bit event timestamp, the value has to be in microseconds. + * + * @param event a valid EarEvent pointer. Cannot be NULL. + * @param timestamp a positive 32bit microsecond timestamp. + */ +static inline void caerEarEventSetTimestamp(caerEarEvent event, int32_t timestamp) { + if (timestamp < 0) { + // Negative means using the 31st bit! + caerLog(CAER_LOG_CRITICAL, "Ear Event", "Called caerEarEventSetTimestamp() with negative value!"); + return; + } + + event->timestamp = htole32(timestamp); +} + +/** + * Check if this ear (cochlea) event is valid. + * + * @param event a valid EarEvent pointer. Cannot be NULL. + * + * @return true if valid, false if not. + */ +static inline bool caerEarEventIsValid(caerEarEvent event) { + return (GET_NUMBITS32(event->data, VALID_MARK_SHIFT, VALID_MARK_MASK)); +} + +/** + * Validate the current event by setting its valid bit to true + * and increasing the event packet's event count and valid + * event count. Only works on events that are invalid. + * DO NOT CALL THIS AFTER HAVING PREVIOUSLY ALREADY + * INVALIDATED THIS EVENT, the total count will be incorrect. + * + * @param event a valid EarEvent pointer. Cannot be NULL. + * @param packet the EarEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerEarEventValidate(caerEarEvent event, caerEarEventPacket packet) { + if (!caerEarEventIsValid(event)) { + SET_NUMBITS32(event->data, VALID_MARK_SHIFT, VALID_MARK_MASK, 1); + + // Also increase number of events and valid events. + // Only call this on (still) invalid events! + caerEventPacketHeaderSetEventNumber(&packet->packetHeader, + caerEventPacketHeaderGetEventNumber(&packet->packetHeader) + 1); + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) + 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Ear Event", "Called caerEarEventValidate() on already valid event."); + } +} + +/** + * Invalidate the current event by setting its valid bit + * to false and decreasing the number of valid events held + * in the packet. Only works with events that are already + * valid! + * + * @param event a valid EarEvent pointer. Cannot be NULL. + * @param packet the EarEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerEarEventInvalidate(caerEarEvent event, caerEarEventPacket packet) { + if (caerEarEventIsValid(event)) { + CLEAR_NUMBITS32(event->data, VALID_MARK_SHIFT, VALID_MARK_MASK); + + // Also decrease number of valid events. Number of total events doesn't change. + // Only call this on valid events! + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) - 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Ear Event", "Called caerEarEventInvalidate() on already invalid event."); + } +} + +/** + * Get the numerical ID of the ear (microphone). + * Usually, 0 is left, 1 is right for 2 ear cochleas. + * For 4 ear cochleas, 0 is front left, 1 is front right, + * 2 is back left and 3 is back right. + * + * @param event a valid EarEvent pointer. Cannot be NULL. + * + * @return the ear (microphone) ID. + */ +static inline uint8_t caerEarEventGetEar(caerEarEvent event) { + return U8T(GET_NUMBITS32(event->data, EAR_SHIFT, EAR_MASK)); +} + +/** + * Set the numerical ID of the ear (microphone). + * Usually, 0 is left, 1 is right for 2 ear cochleas. + * For 4 ear cochleas, 0 is front left, 1 is front right, + * 2 is back left and 3 is back right. + * + * @param event a valid EarEvent pointer. Cannot be NULL. + * @param ear the ear (microphone) ID. + */ +static inline void caerEarEventSetEar(caerEarEvent event, uint8_t ear) { + CLEAR_NUMBITS32(event->data, EAR_SHIFT, EAR_MASK); + SET_NUMBITS32(event->data, EAR_SHIFT, EAR_MASK, ear); +} + +/** + * Get the channel (frequency band) ID. + * The channels count from 0 upward, where 0 is the highest + * frequency channel, while higher numbers are progressively + * lower frequency channels. This is derived from how the actual + * human ear works. + * + * @param event a valid EarEvent pointer. Cannot be NULL. + * + * @return the channel (frequency band) ID. + */ +static inline uint16_t caerEarEventGetChannel(caerEarEvent event) { + return U16T(GET_NUMBITS32(event->data, CHANNEL_SHIFT, CHANNEL_MASK)); +} + +/** + * Set the channel (frequency band) ID. + * The channels count from 0 upward, where 0 is the highest + * frequency channel, while higher numbers are progressively + * lower frequency channels. This is derived from how the actual + * human ear works. + * + * @param event a valid EarEvent pointer. Cannot be NULL. + * @param channel the channel (frequency band) ID. + */ +static inline void caerEarEventSetChannel(caerEarEvent event, uint16_t channel) { + CLEAR_NUMBITS32(event->data, CHANNEL_SHIFT, CHANNEL_MASK); + SET_NUMBITS32(event->data, CHANNEL_SHIFT, CHANNEL_MASK, channel); +} + +static inline uint8_t caerEarEventGetNeuron(caerEarEvent event) { + return U8T(GET_NUMBITS32(event->data, NEURON_SHIFT, NEURON_MASK)); +} + +static inline void caerEarEventSetNeuron(caerEarEvent event, uint8_t neuron) { + CLEAR_NUMBITS32(event->data, NEURON_SHIFT, NEURON_MASK); + SET_NUMBITS32(event->data, NEURON_SHIFT, NEURON_MASK, neuron); +} + +static inline uint8_t caerEarEventGetFilter(caerEarEvent event) { + return U8T(GET_NUMBITS32(event->data, FILTER_SHIFT, FILTER_MASK)); +} + +static inline void caerEarEventSetFilter(caerEarEvent event, uint8_t filter) { + CLEAR_NUMBITS32(event->data, FILTER_SHIFT, FILTER_MASK); + SET_NUMBITS32(event->data, FILTER_SHIFT, FILTER_MASK, filter); +} + +/** + * Iterator over all ear events in a packet. + * Returns the current index in the 'caerEarIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerEarIteratorElement' variable + * of type caerEarEvent. + * + * EAR_PACKET: a valid EarEventPacket pointer. Cannot be NULL. + */ +#define CAER_EAR_ITERATOR_ALL_START(EAR_PACKET) \ + for (int32_t caerEarIteratorCounter = 0; \ + caerEarIteratorCounter < caerEventPacketHeaderGetEventNumber(&(EAR_PACKET)->packetHeader); \ + caerEarIteratorCounter++) { \ + caerEarEvent caerEarIteratorElement = caerEarEventPacketGetEvent(EAR_PACKET, caerEarIteratorCounter); + +/** + * Iterator close statement. + */ +#define CAER_EAR_ITERATOR_ALL_END } + +/** + * Iterator over only the valid ear events in a packet. + * Returns the current index in the 'caerEarIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerEarIteratorElement' variable + * of type caerEarEvent. + * + * EAR_PACKET: a valid EarEventPacket pointer. Cannot be NULL. + */ +#define CAER_EAR_ITERATOR_VALID_START(EAR_PACKET) \ + for (int32_t caerEarIteratorCounter = 0; \ + caerEarIteratorCounter < caerEventPacketHeaderGetEventNumber(&(EAR_PACKET)->packetHeader); \ + caerEarIteratorCounter++) { \ + caerEarEvent caerEarIteratorElement = caerEarEventPacketGetEvent(EAR_PACKET, caerEarIteratorCounter); \ + if (!caerEarEventIsValid(caerEarIteratorElement)) { continue; } // Skip invalid ear events. + +/** + * Iterator close statement. + */ +#define CAER_EAR_ITERATOR_VALID_END } + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_EVENTS_EAR_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/frame.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/frame.h new file mode 100755 index 0000000..ed15e6d --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/frame.h @@ -0,0 +1,1019 @@ +/** + * @file frame.h + * + * Frame Events format definition and handling functions. + * This event type encodes intensity frames, like you would + * get from a normal APS camera. It supports multiple channels + * for color, color filter information, as well as multiple + * Regions of Interest (ROI). + * The (0, 0) pixel is in the upper left corner of the screen, + * like in OpenCV/computer graphics. The pixel array is laid out row by row + * (increasing X axis), going from top to bottom (increasing Y axis). + */ + +#ifndef LIBCAER_EVENTS_FRAME_H_ +#define LIBCAER_EVENTS_FRAME_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "common.h" + +/** + * Shift and mask values for the color channels number, the color + * filter arrangement and the ROI identifier contained in the + * 'info' field of the frame event. + * Multiple channels (RGB for example) are possible, see the + * 'enum caer_frame_event_color_channels'. To understand the original + * color filter arrangement to interpolate color images, see + * the 'enum caer_frame_event_color_filter'. + * Also, up to 128 different Regions of Interest (ROI) can be tracked. + * Bit 0 is the valid mark, see 'common.h' for more details. + */ +//@{ +#define COLOR_CHANNELS_SHIFT 1 +#define COLOR_CHANNELS_MASK 0x00000007 +#define COLOR_FILTER_SHIFT 4 +#define COLOR_FILTER_MASK 0x0000000F +#define ROI_IDENTIFIER_SHIFT 8 +#define ROI_IDENTIFIER_MASK 0x0000007F +//@} + +/** + * List of all frame event color channel identifiers. + * Used to interpret the frame event color channel field. + */ +enum caer_frame_event_color_channels { + GRAYSCALE = 1, //!< Grayscale, one channel only. + RGB = 3, //!< Red Green Blue, 3 color channels. + RGBA = 4, //!< Red Green Blue Alpha, 3 color channels plus transparency. +}; + +/** + * List of all frame event color filter identifiers. + * Used to interpret the frame event color filter field. + */ +enum caer_frame_event_color_filter { + MONO = 0, //!< No color filter present, all light passes. + RGBG = 1, //!< Standard Bayer color filter, 1 red 2 green 1 blue. Variation 1. + GRGB = 2, //!< Standard Bayer color filter, 1 red 2 green 1 blue. Variation 2. + GBGR = 3, //!< Standard Bayer color filter, 1 red 2 green 1 blue. Variation 3. + BGRG = 4, //!< Standard Bayer color filter, 1 red 2 green 1 blue. Variation 4. + RGBW = 5, //!< Modified Bayer color filter, with white (pass all light) instead of extra green. Variation 1. + GRWB = 6, //!< Modified Bayer color filter, with white (pass all light) instead of extra green. Variation 2. + WBGR = 7, //!< Modified Bayer color filter, with white (pass all light) instead of extra green. Variation 3. + BWRG = 8, //!< Modified Bayer color filter, with white (pass all light) instead of extra green. Variation 4. +}; + +/** + * Frame event data structure definition. + * This contains the actual information on the frame (ROI, color channels, + * color filter), several timestamps to signal start and end of capture and + * of exposure, as well as the actual pixels, in a 16 bit normalized format. + * The (0, 0) address is in the upper left corner, like in OpenCV/computer graphics. + * The pixel array is laid out row by row (increasing X axis), going from + * top to bottom (increasing Y axis). + * Signed integers are used for fields that are to be interpreted + * directly, for compatibility with languages that do not have + * unsigned integer types, such as Java. + */ +struct caer_frame_event { + /// Event information (ROI region, color channels, color filter). First because of valid mark. + uint32_t info; + /// Start of Frame (SOF) timestamp. + int32_t ts_startframe; + /// End of Frame (EOF) timestamp. + int32_t ts_endframe; + /// Start of Exposure (SOE) timestamp. + int32_t ts_startexposure; + /// End of Exposure (EOE) timestamp. + int32_t ts_endexposure; + /// X axis length in pixels. + int32_t lengthX; + /// Y axis length in pixels. + int32_t lengthY; + /// X axis position (upper left offset) in pixels. + int32_t positionX; + /// Y axis position (upper left offset) in pixels. + int32_t positionY; + /// Pixel array, 16 bit unsigned integers, normalized to 16 bit depth. + /// The pixel array is laid out row by row (increasing X axis), going + /// from top to bottom (increasing Y axis). + uint16_t pixels[]; +}__attribute__((__packed__)); + +/** + * Type for pointer to frame event data structure. + */ +typedef struct caer_frame_event *caerFrameEvent; + +/** + * Frame event packet data structure definition. + * EventPackets are always made up of the common packet header, + * followed by 'eventCapacity' events. Everything has to + * be in one contiguous memory block. Direct access to the events + * array is not possible for Frame events. To calculate position + * offsets, use the 'eventSize' field in the packet header. + */ +struct caer_frame_event_packet { + /// The common event packet header. + struct caer_event_packet_header packetHeader; +/// All events follow here. Direct access to the events +/// array is not possible. To calculate position, use the +/// 'eventSize' field in the packetHeader. +}__attribute__((__packed__)); + +/** + * Type for pointer to frame event packet data structure. + */ +typedef struct caer_frame_event_packet *caerFrameEventPacket; + +/** + * Allocate a new frame events packet. + * Use free() to reclaim this memory. + * The frame events allocate memory for a maximum sized pixels array, depending + * on the parameters passed to this function, so that every event occupies the + * same amount of memory (constant size). The actual frames inside of it + * might be smaller than that, for example when using ROI, and their actual size + * is stored inside the frame event and should always be queried from there. + * The unused part of a pixels array is guaranteed to be zeros. + * + * @param eventCapacity the maximum number of events this packet will hold. + * @param eventSource the unique ID representing the source/generator of this packet. + * @param tsOverflow the current timestamp overflow counter value for this packet. + * @param maxLengthX the maximum expected X axis size for frames in this packet. + * @param maxLengthY the maximum expected Y axis size for frames in this packet. + * @param maxChannelNumber the maximum expected number of channels for frames in this packet. + * + * @return a valid FrameEventPacket handle or NULL on error. + */ +caerFrameEventPacket caerFrameEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow, + int32_t maxLengthX, int32_t maxLengthY, int16_t maxChannelNumber); + +/** + * Get the frame event at the given index from the event packet. + * + * @param packet a valid FrameEventPacket pointer. Cannot be NULL. + * @param n the index of the returned event. Must be within [0,eventCapacity[ bounds. + * + * @return the requested frame event. NULL on error. + */ +static inline caerFrameEvent caerFrameEventPacketGetEvent(caerFrameEventPacket packet, int32_t n) { + // Check that we're not out of bounds. + if (n < 0 || n >= caerEventPacketHeaderGetEventCapacity(&packet->packetHeader)) { + caerLog(CAER_LOG_CRITICAL, "Frame Event", + "Called caerFrameEventPacketGetEvent() with invalid event offset %" PRIi32 ", while maximum allowed value is %" PRIi32 ".", + n, caerEventPacketHeaderGetEventCapacity(&packet->packetHeader) - 1); + return (NULL); + } + + // Return a pointer to the specified event. + return ((caerFrameEvent) (((uint8_t *) &packet->packetHeader) + + (CAER_EVENT_PACKET_HEADER_SIZE + U64T(n * caerEventPacketHeaderGetEventSize(&packet->packetHeader))))); +} + +/** + * Get the 32bit start of frame capture timestamp, in microseconds. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond start of frame timestamp. + */ +static inline int32_t caerFrameEventGetTSStartOfFrame(caerFrameEvent event) { + return (le32toh(event->ts_startframe)); +} + +/** + * Get the 64bit start of frame capture timestamp, in microseconds. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param packet the FrameEventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond start of frame timestamp. + */ +static inline int64_t caerFrameEventGetTSStartOfFrame64(caerFrameEvent event, caerFrameEventPacket packet) { + // Even if frames have multiple time-stamps, it's not possible for later time-stamps to + // be in a different TSOverflow period, since in those rare cases the event is dropped. + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(&packet->packetHeader)) << TS_OVERFLOW_SHIFT) | U64T(caerFrameEventGetTSStartOfFrame(event)))); +} + +/** + * Set the 32bit start of frame capture timestamp, the value has to be in microseconds. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param startFrame a positive 32bit microsecond timestamp. + */ +static inline void caerFrameEventSetTSStartOfFrame(caerFrameEvent event, int32_t startFrame) { + if (startFrame < 0) { + // Negative means using the 31st bit! + caerLog(CAER_LOG_CRITICAL, "Frame Event", "Called caerFrameEventSetTSStartOfFrame() with negative value!"); + return; + } + + event->ts_startframe = htole32(startFrame); +} + +/** + * Get the 32bit end of frame capture timestamp, in microseconds. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond end of frame timestamp. + */ +static inline int32_t caerFrameEventGetTSEndOfFrame(caerFrameEvent event) { + return (le32toh(event->ts_endframe)); +} + +/** + * Get the 64bit end of frame capture timestamp, in microseconds. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param packet the FrameEventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond end of frame timestamp. + */ +static inline int64_t caerFrameEventGetTSEndOfFrame64(caerFrameEvent event, caerFrameEventPacket packet) { + // Even if frames have multiple time-stamps, it's not possible for later time-stamps to + // be in a different TSOverflow period, since in those rare cases the event is dropped. + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(&packet->packetHeader)) << TS_OVERFLOW_SHIFT) | U64T(caerFrameEventGetTSEndOfFrame(event)))); +} + +/** + * Set the 32bit end of frame capture timestamp, the value has to be in microseconds. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param endFrame a positive 32bit microsecond timestamp. + */ +static inline void caerFrameEventSetTSEndOfFrame(caerFrameEvent event, int32_t endFrame) { + if (endFrame < 0) { + // Negative means using the 31st bit! + caerLog(CAER_LOG_CRITICAL, "Frame Event", "Called caerFrameEventSetTSEndOfFrame() with negative value!"); + return; + } + + event->ts_endframe = htole32(endFrame); +} + +/** + * Get the 32bit start of exposure timestamp, in microseconds. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond start of exposure timestamp. + */ +static inline int32_t caerFrameEventGetTSStartOfExposure(caerFrameEvent event) { + return (le32toh(event->ts_startexposure)); +} + +/** + * Get the 64bit start of exposure timestamp, in microseconds. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param packet the FrameEventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond start of exposure timestamp. + */ +static inline int64_t caerFrameEventGetTSStartOfExposure64(caerFrameEvent event, caerFrameEventPacket packet) { + // Even if frames have multiple time-stamps, it's not possible for later time-stamps to + // be in a different TSOverflow period, since in those rare cases the event is dropped. + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(&packet->packetHeader)) << TS_OVERFLOW_SHIFT) | U64T(caerFrameEventGetTSStartOfExposure(event)))); +} + +/** + * Set the 32bit start of exposure timestamp, the value has to be in microseconds. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param startExposure a positive 32bit microsecond timestamp. + */ +static inline void caerFrameEventSetTSStartOfExposure(caerFrameEvent event, int32_t startExposure) { + if (startExposure < 0) { + // Negative means using the 31st bit! + caerLog(CAER_LOG_CRITICAL, "Frame Event", "Called caerFrameEventSetTSStartOfExposure() with negative value!"); + return; + } + + event->ts_startexposure = htole32(startExposure); +} + +/** + * Get the 32bit end of exposure timestamp, in microseconds. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond end of exposure timestamp. + */ +static inline int32_t caerFrameEventGetTSEndOfExposure(caerFrameEvent event) { + return (le32toh(event->ts_endexposure)); +} + +/** + * Get the 64bit end of exposure timestamp, in microseconds. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param packet the FrameEventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond end of exposure timestamp. + */ +static inline int64_t caerFrameEventGetTSEndOfExposure64(caerFrameEvent event, caerFrameEventPacket packet) { + // Even if frames have multiple time-stamps, it's not possible for later time-stamps to + // be in a different TSOverflow period, since in those rare cases the event is dropped. + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(&packet->packetHeader)) << TS_OVERFLOW_SHIFT) | U64T(caerFrameEventGetTSEndOfExposure(event)))); +} + +/** + * Set the 32bit end of exposure timestamp, the value has to be in microseconds. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param endExposure a positive 32bit microsecond timestamp. + */ +static inline void caerFrameEventSetTSEndOfExposure(caerFrameEvent event, int32_t endExposure) { + if (endExposure < 0) { + // Negative means using the 31st bit! + caerLog(CAER_LOG_CRITICAL, "Frame Event", "Called caerFrameEventSetTSEndOfExposure() with negative value!"); + return; + } + + event->ts_endexposure = htole32(endExposure); +} + +/** + * The total length, in microseconds, of the frame exposure time. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return the exposure time in microseconds. + */ +static inline int32_t caerFrameEventGetExposureLength(caerFrameEvent event) { + return (caerFrameEventGetTSEndOfExposure(event) - caerFrameEventGetTSStartOfExposure(event)); +} + +/** + * Get the 32bit event timestamp, in microseconds. + * This is a median of the exposure timestamps. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond timestamp. + */ +static inline int32_t caerFrameEventGetTimestamp(caerFrameEvent event) { + return (caerFrameEventGetTSStartOfExposure(event) + (caerFrameEventGetExposureLength(event) / 2)); +} + +/** + * Get the 64bit event timestamp, in microseconds. + * This is a median of the exposure timestamps. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param packet the FrameEventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond timestamp. + */ +static inline int64_t caerFrameEventGetTimestamp64(caerFrameEvent event, caerFrameEventPacket packet) { + // Even if frames have multiple time-stamps, it's not possible for later time-stamps to + // be in a different TSOverflow period, since in those rare cases the event is dropped. + return (caerFrameEventGetTSStartOfExposure64(event, packet) + (caerFrameEventGetExposureLength(event) / 2)); +} + +/** + * Check if this frame event is valid. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return true if valid, false if not. + */ +static inline bool caerFrameEventIsValid(caerFrameEvent event) { + return (GET_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK)); +} + +/** + * Validate the current event by setting its valid bit to true + * and increasing the event packet's event count and valid + * event count. Only works on events that are invalid. + * DO NOT CALL THIS AFTER HAVING PREVIOUSLY ALREADY + * INVALIDATED THIS EVENT, the total count will be incorrect. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param packet the FrameEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerFrameEventValidate(caerFrameEvent event, caerFrameEventPacket packet) { + if (!caerFrameEventIsValid(event)) { + SET_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK, 1); + + // Also increase number of events and valid events. + // Only call this on (still) invalid events! + caerEventPacketHeaderSetEventNumber(&packet->packetHeader, + caerEventPacketHeaderGetEventNumber(&packet->packetHeader) + 1); + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) + 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Frame Event", "Called caerFrameEventValidate() on already valid event."); + } +} + +/** + * Invalidate the current event by setting its valid bit + * to false and decreasing the number of valid events held + * in the packet. Only works with events that are already + * valid! + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param packet the FrameEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerFrameEventInvalidate(caerFrameEvent event, caerFrameEventPacket packet) { + if (caerFrameEventIsValid(event)) { + CLEAR_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK); + + // Also decrease number of valid events. Number of total events doesn't change. + // Only call this on valid events! + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) - 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Frame Event", "Called caerFrameEventInvalidate() on already invalid event."); + } +} + +/** + * Get the maximum size of the pixels array in bytes, based upon how + * much memory was allocated to it by 'caerFrameEventPacketAllocate()'. + * + * @param packet a valid FrameEventPacket pointer. Cannot be NULL. + * + * @return maximum pixels array size in bytes. + */ +static inline size_t caerFrameEventPacketGetPixelsSize(caerFrameEventPacket packet) { + return ((size_t) caerEventPacketHeaderGetEventSize(&packet->packetHeader) - sizeof(struct caer_frame_event)); +} + +/** + * Get the maximum index into the pixels array, based upon how + * much memory was allocated to it by 'caerFrameEventPacketAllocate()'. + * + * @param packet a valid FrameEventPacket pointer. Cannot be NULL. + * + * @return maximum pixels array index. + */ +static inline size_t caerFrameEventPacketGetPixelsMaxIndex(caerFrameEventPacket packet) { + return (caerFrameEventPacketGetPixelsSize(packet) / sizeof(uint16_t)); +} + +/** + * Get the numerical identifier for the Region of Interest + * (ROI) region, to distinguish between multiple of them. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return numerical ROI identifier. + */ +static inline uint8_t caerFrameEventGetROIIdentifier(caerFrameEvent event) { + return U8T(GET_NUMBITS32(event->info, ROI_IDENTIFIER_SHIFT, ROI_IDENTIFIER_MASK)); +} + +/** + * Set the numerical identifier for the Region of Interest + * (ROI) region, to distinguish between multiple of them. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param roiIdentifier numerical ROI identifier. + */ +static inline void caerFrameEventSetROIIdentifier(caerFrameEvent event, uint8_t roiIdentifier) { + CLEAR_NUMBITS32(event->info, ROI_IDENTIFIER_SHIFT, ROI_IDENTIFIER_MASK); + SET_NUMBITS32(event->info, ROI_IDENTIFIER_SHIFT, ROI_IDENTIFIER_MASK, roiIdentifier); +} + +/** + * Get the identifier for the color filter used by the sensor. + * Useful for interpolating color images. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return color filter identifier. + */ +static inline enum caer_frame_event_color_filter caerFrameEventGetColorFilter(caerFrameEvent event) { + return ((enum caer_frame_event_color_filter) U8T(GET_NUMBITS32(event->info, COLOR_FILTER_SHIFT, COLOR_FILTER_MASK))); +} + +/** + * Set the identifier for the color filter used by the sensor. + * Useful for interpolating color images. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param colorFilter color filter identifier. + */ +static inline void caerFrameEventSetColorFilter(caerFrameEvent event, enum caer_frame_event_color_filter colorFilter) { + CLEAR_NUMBITS32(event->info, COLOR_FILTER_SHIFT, COLOR_FILTER_MASK); + SET_NUMBITS32(event->info, COLOR_FILTER_SHIFT, COLOR_FILTER_MASK, colorFilter); +} + +/** + * Get the actual X axis length for the current frame. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return frame X axis length. + */ +static inline int32_t caerFrameEventGetLengthX(caerFrameEvent event) { + return (le32toh(event->lengthX)); +} + +/** + * Get the actual Y axis length for the current frame. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return frame Y axis length. + */ +static inline int32_t caerFrameEventGetLengthY(caerFrameEvent event) { + return (le32toh(event->lengthY)); +} + +/** + * Get the actual color channels number for the current frame. + * This can be used to store RGB frames for example. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return frame color channels number. + */ +static inline enum caer_frame_event_color_channels caerFrameEventGetChannelNumber(caerFrameEvent event) { + return ((enum caer_frame_event_color_channels) U8T( + GET_NUMBITS32(event->info, COLOR_CHANNELS_SHIFT, COLOR_CHANNELS_MASK))); +} + +/** + * Set the X and Y axes length and the color channels number for a frame, + * while taking into account the maximum amount of memory available + * for the pixel array, as allocated in 'caerFrameEventPacketAllocate()'. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param lengthX the frame's X axis length. + * @param lengthY the frame's Y axis length. + * @param channelNumber the number of color channels for this frame. + * @param packet the FrameEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerFrameEventSetLengthXLengthYChannelNumber(caerFrameEvent event, int32_t lengthX, int32_t lengthY, + enum caer_frame_event_color_channels channelNumber, caerFrameEventPacket packet) { + // Verify lengths and color channels number don't exceed allocated space. + size_t neededMemory = (sizeof(uint16_t) * (size_t) lengthX * (size_t) lengthY * channelNumber); + + if (neededMemory > caerFrameEventPacketGetPixelsSize(packet)) { + caerLog(CAER_LOG_CRITICAL, "Frame Event", + "Called caerFrameEventSetLengthXLengthYChannelNumber() with values that result in requiring %zu bytes, which exceeds the maximum allocated event size of %zu bytes.", + neededMemory, (size_t) caerEventPacketHeaderGetEventSize(&packet->packetHeader)); + return; + } + + event->lengthX = htole32(lengthX); + event->lengthY = htole32(lengthY); + CLEAR_NUMBITS32(event->info, COLOR_CHANNELS_SHIFT, COLOR_CHANNELS_MASK); + SET_NUMBITS32(event->info, COLOR_CHANNELS_SHIFT, COLOR_CHANNELS_MASK, channelNumber); +} + +/** + * Get the maximum valid index into the pixel array, at which + * you can still get valid pixels. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return maximum valid pixels array index. + */ +static inline size_t caerFrameEventGetPixelsMaxIndex(caerFrameEvent event) { + enum caer_frame_event_color_channels channels = caerFrameEventGetChannelNumber(event); + return ((size_t) (caerFrameEventGetLengthX(event) * caerFrameEventGetLengthY(event) * I32T(channels))); +} + +/** + * Get the maximum size of the pixels array in bytes, in which + * you can still get valid pixels. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return maximum valid pixels array size in bytes. + */ +static inline size_t caerFrameEventGetPixelsSize(caerFrameEvent event) { + return (caerFrameEventGetPixelsMaxIndex(event) * sizeof(uint16_t)); +} + +/** + * Get the X axis position offset. + * This is used to place partial frames, like the ones gotten from + * ROI readouts, in the visual space. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return X axis position offset. + */ +static inline int32_t caerFrameEventGetPositionX(caerFrameEvent event) { + return (le32toh(event->positionX)); +} + +/** + * Set the X axis position offset. + * This is used to place partial frames, like the ones gotten from + * ROI readouts, in the visual space. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param positionX X axis position offset. + */ +static inline void caerFrameEventSetPositionX(caerFrameEvent event, int32_t positionX) { + event->positionX = htole32(positionX); +} + +/** + * Get the Y axis position offset. + * This is used to place partial frames, like the ones gotten from + * ROI readouts, in the visual space. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return Y axis position offset. + */ +static inline int32_t caerFrameEventGetPositionY(caerFrameEvent event) { + return (le32toh(event->positionY)); +} + +/** + * Set the Y axis position offset. + * This is used to place partial frames, like the ones gotten from + * ROI readouts, in the visual space. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param positionY Y axis position offset. + */ +static inline void caerFrameEventSetPositionY(caerFrameEvent event, int32_t positionY) { + event->positionY = htole32(positionY); +} + +/** + * Get the pixel value at the specified (X, Y) address. + * (X, Y) are checked against the actual possible values for this frame. + * Different channels are not taken into account! + * The (0, 0) pixel is in the upper left corner, like in OpenCV/computer graphics. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param xAddress X address value (checked). + * @param yAddress Y address value (checked). + * + * @return pixel value (normalized to 16 bit depth). + */ +static inline uint16_t caerFrameEventGetPixel(caerFrameEvent event, int32_t xAddress, int32_t yAddress) { + // Check frame bounds first. + if (yAddress < 0 || yAddress >= caerFrameEventGetLengthY(event)) { + caerLog(CAER_LOG_CRITICAL, "Frame Event", + "Called caerFrameEventGetPixel() with invalid Y address of %" PRIi32 ", should be between 0 and %" PRIi32 ".", + yAddress, caerFrameEventGetLengthY(event) - 1); + return (0); + } + + int32_t xLength = caerFrameEventGetLengthX(event); + + if (xAddress < 0 || xAddress >= xLength) { + caerLog(CAER_LOG_CRITICAL, "Frame Event", + "Called caerFrameEventGetPixel() with invalid X address of %" PRIi32 ", should be between 0 and %" PRIi32".", + xAddress, xLength - 1); + return (0); + } + + // Get pixel value at specified position. + return (le16toh(event->pixels[(yAddress * xLength) + xAddress])); +} + +/** + * Set the pixel value at the specified (X, Y) address. + * (X, Y) are checked against the actual possible values for this frame. + * Different channels are not taken into account! + * The (0, 0) pixel is in the upper left corner, like in OpenCV/computer graphics. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param xAddress X address value (checked). + * @param yAddress Y address value (checked). + * @param pixelValue pixel value (normalized to 16 bit depth). + */ +static inline void caerFrameEventSetPixel(caerFrameEvent event, int32_t xAddress, int32_t yAddress, uint16_t pixelValue) { + // Check frame bounds first. + if (yAddress < 0 || yAddress >= caerFrameEventGetLengthY(event)) { + caerLog(CAER_LOG_CRITICAL, "Frame Event", + "Called caerFrameEventSetPixel() with invalid Y address of %" PRIi32 ", should be between 0 and %" PRIi32 ".", + yAddress, caerFrameEventGetLengthY(event) - 1); + return; + } + + int32_t xLength = caerFrameEventGetLengthX(event); + + if (xAddress < 0 || xAddress >= xLength) { + caerLog(CAER_LOG_CRITICAL, "Frame Event", + "Called caerFrameEventSetPixel() with invalid X address of %" PRIi32 ", should be between 0 and %" PRIi32 ".", + xAddress, xLength - 1); + return; + } + + // Set pixel value at specified position. + event->pixels[(yAddress * xLength) + xAddress] = htole16(pixelValue); +} + +/** + * Get the pixel value at the specified (X, Y) address, taking into + * account the specified channel. + * (X, Y) and the channel number are checked against the actual + * possible values for this frame. + * The (0, 0) pixel is in the upper left corner, like in OpenCV/computer graphics. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param xAddress X address value (checked). + * @param yAddress Y address value (checked). + * @param channel the channel number (checked). + * + * @return pixel value (normalized to 16 bit depth). + */ +static inline uint16_t caerFrameEventGetPixelForChannel(caerFrameEvent event, int32_t xAddress, int32_t yAddress, + uint8_t channel) { + // Check frame bounds first. + if (yAddress < 0 || yAddress >= caerFrameEventGetLengthY(event)) { + caerLog(CAER_LOG_CRITICAL, "Frame Event", + "Called caerFrameEventGetPixelForChannel() with invalid Y address of %" PRIi32 ", should be between 0 and %" PRIi32 ".", + yAddress, caerFrameEventGetLengthY(event) - 1); + return (0); + } + + int32_t xLength = caerFrameEventGetLengthX(event); + + if (xAddress < 0 || xAddress >= xLength) { + caerLog(CAER_LOG_CRITICAL, "Frame Event", + "Called caerFrameEventGetPixelForChannel() with invalid X address of %" PRIi32 ", should be between 0 and %" PRIi32 ".", + xAddress, xLength - 1); + return (0); + } + + uint8_t channelNumber = caerFrameEventGetChannelNumber(event); + + if (channel >= channelNumber) { + caerLog(CAER_LOG_CRITICAL, "Frame Event", + "Called caerFrameEventGetPixelForChannel() with invalid channel number of %" PRIu8 ", should be between 0 and %" PRIu8 ".", + channel, (uint8_t) (channelNumber - 1)); + return (0); + } + + // Get pixel value at specified position. + return (le16toh(event->pixels[(((yAddress * xLength) + xAddress) * channelNumber) + channel])); +} + +/** + * Set the pixel value at the specified (X, Y) address, taking into + * account the specified channel. + * (X, Y) and the channel number are checked against the actual + * possible values for this frame. + * The (0, 0) pixel is in the upper left corner, like in OpenCV/computer graphics. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param xAddress X address value (checked). + * @param yAddress Y address value (checked). + * @param channel the channel number (checked). + * @param pixelValue pixel value (normalized to 16 bit depth). + */ +static inline void caerFrameEventSetPixelForChannel(caerFrameEvent event, int32_t xAddress, int32_t yAddress, + uint8_t channel, uint16_t pixelValue) { + // Check frame bounds first. + if (yAddress < 0 || yAddress >= caerFrameEventGetLengthY(event)) { + caerLog(CAER_LOG_CRITICAL, "Frame Event", + "Called caerFrameEventSetPixelForChannel() with invalid Y address of %" PRIi32 ", should be between 0 and %" PRIi32 ".", + yAddress, caerFrameEventGetLengthY(event) - 1); + return; + } + + int32_t xLength = caerFrameEventGetLengthX(event); + + if (xAddress < 0 || xAddress >= xLength) { + caerLog(CAER_LOG_CRITICAL, "Frame Event", + "Called caerFrameEventSetPixelForChannel() with invalid X address of %" PRIi32 ", should be between 0 and %" PRIi32 ".", + xAddress, xLength - 1); + return; + } + + uint8_t channelNumber = caerFrameEventGetChannelNumber(event); + + if (channel >= channelNumber) { + caerLog(CAER_LOG_CRITICAL, "Frame Event", + "Called caerFrameEventSetPixelForChannel() with invalid channel number of %" PRIu8 ", should be between 0 and %" PRIu8 ".", + channel, (uint8_t) (channelNumber - 1)); + return; + } + + // Set pixel value at specified position. + event->pixels[(((yAddress * xLength) + xAddress) * channelNumber) + channel] = htole16(pixelValue); +} + +/** + * Get the pixel value at the specified (X, Y) address. + * No checks on (X, Y) are performed! + * The (0, 0) pixel is in the upper left corner, like in OpenCV/computer graphics. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param xAddress X address value (unchecked). + * @param yAddress Y address value (unchecked). + * + * @return pixel value (normalized to 16 bit depth). + */ +static inline uint16_t caerFrameEventGetPixelUnsafe(caerFrameEvent event, int32_t xAddress, int32_t yAddress) { + // Get pixel value at specified position. + return (le16toh(event->pixels[(yAddress * caerFrameEventGetLengthX(event)) + xAddress])); +} + +/** + * Set the pixel value at the specified (X, Y) address. + * No checks on (X, Y) are performed! + * The (0, 0) pixel is in the upper left corner, like in OpenCV/computer graphics. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param xAddress X address value (unchecked). + * @param yAddress Y address value (unchecked). + * @param pixelValue pixel value (normalized to 16 bit depth). + */ +static inline void caerFrameEventSetPixelUnsafe(caerFrameEvent event, int32_t xAddress, int32_t yAddress, + uint16_t pixelValue) { + // Set pixel value at specified position. + event->pixels[(yAddress * caerFrameEventGetLengthX(event)) + xAddress] = htole16(pixelValue); +} + +/** + * Get the pixel value at the specified (X, Y) address, taking into + * account the specified channel. + * No checks on (X, Y) and the channel number are performed! + * The (0, 0) pixel is in the upper left corner, like in OpenCV/computer graphics. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param xAddress X address value (unchecked). + * @param yAddress Y address value (unchecked). + * @param channel the channel number (unchecked). + * + * @return pixel value (normalized to 16 bit depth). + */ +static inline uint16_t caerFrameEventGetPixelForChannelUnsafe(caerFrameEvent event, int32_t xAddress, int32_t yAddress, + uint8_t channel) { + enum caer_frame_event_color_channels channels = caerFrameEventGetChannelNumber(event); + // Get pixel value at specified position. + return (le16toh( + event->pixels[(((yAddress * caerFrameEventGetLengthX(event)) + xAddress) * I32T(channels))+ channel])); +} + +/** + * Set the pixel value at the specified (X, Y) address, taking into + * account the specified channel. + * No checks on (X, Y) and the channel number are performed! + * The (0, 0) pixel is in the upper left corner, like in OpenCV/computer graphics. + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * @param xAddress X address value (unchecked). + * @param yAddress Y address value (unchecked). + * @param channel the channel number (unchecked). + * @param pixelValue pixel value (normalized to 16 bit depth). + */ +static inline void caerFrameEventSetPixelForChannelUnsafe(caerFrameEvent event, int32_t xAddress, int32_t yAddress, + uint8_t channel, uint16_t pixelValue) { + enum caer_frame_event_color_channels channels = caerFrameEventGetChannelNumber(event); + // Set pixel value at specified position. + event->pixels[(((yAddress * caerFrameEventGetLengthX(event)) + xAddress) * I32T(channels)) + channel] = htole16( + pixelValue); +} + +/** + * Get a direct reference to the underlying pixels array. + * This can be used to both get and set values. + * No checks at all are performed at any point, nor any + * conversions, use this at your own risk! + * Remember that the 16 bit pixel values are in little-endian! + * The pixel array is laid out row by row (increasing X axis), + * going from top to bottom (increasing Y axis). + * + * @param event a valid FrameEvent pointer. Cannot be NULL. + * + * @return the pixels array (16 bit integers are little-endian). + */ +static inline uint16_t *caerFrameEventGetPixelArrayUnsafe(caerFrameEvent event) { + // Get pixels array. + return (event->pixels); +} + +/** + * Iterator over all frame events in a packet. + * Returns the current index in the 'caerFrameIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerFrameIteratorElement' variable + * of type caerFrameEvent. + * + * FRAME_PACKET: a valid FrameEventPacket pointer. Cannot be NULL. + */ +#define CAER_FRAME_ITERATOR_ALL_START(FRAME_PACKET) \ + for (int32_t caerFrameIteratorCounter = 0; \ + caerFrameIteratorCounter < caerEventPacketHeaderGetEventNumber(&(FRAME_PACKET)->packetHeader); \ + caerFrameIteratorCounter++) { \ + caerFrameEvent caerFrameIteratorElement = caerFrameEventPacketGetEvent(FRAME_PACKET, caerFrameIteratorCounter); + +/** + * Iterator close statement. + */ +#define CAER_FRAME_ITERATOR_ALL_END } + +/** + * Iterator over only the valid frame events in a packet. + * Returns the current index in the 'caerFrameIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerFrameIteratorElement' variable + * of type caerFrameEvent. + * + * FRAME_PACKET: a valid FrameEventPacket pointer. Cannot be NULL. + */ +#define CAER_FRAME_ITERATOR_VALID_START(FRAME_PACKET) \ + for (int32_t caerFrameIteratorCounter = 0; \ + caerFrameIteratorCounter < caerEventPacketHeaderGetEventNumber(&(FRAME_PACKET)->packetHeader); \ + caerFrameIteratorCounter++) { \ + caerFrameEvent caerFrameIteratorElement = caerFrameEventPacketGetEvent(FRAME_PACKET, caerFrameIteratorCounter); \ + if (!caerFrameEventIsValid(caerFrameIteratorElement)) { continue; } // Skip invalid frame events. + +/** + * Iterator close statement. + */ +#define CAER_FRAME_ITERATOR_VALID_END } + +/** + * Reverse iterator over all frame events in a packet. + * Returns the current index in the 'caerFrameIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerFrameIteratorElement' variable + * of type caerFrameEvent. + * + * FRAME_PACKET: a valid FrameEventPacket pointer. Cannot be NULL. + */ +#define CAER_FRAME_REVERSE_ITERATOR_ALL_START(FRAME_PACKET) \ + for (int32_t caerFrameIteratorCounter = caerEventPacketHeaderGetEventNumber(&(FRAME_PACKET)->packetHeader) - 1; \ + caerFrameIteratorCounter >= 0; \ + caerFrameIteratorCounter--) { \ + caerFrameEvent caerFrameIteratorElement = caerFrameEventPacketGetEvent(FRAME_PACKET, caerFrameIteratorCounter); + +/** + * Reverse iterator close statement. + */ +#define CAER_FRAME_REVERSE_ITERATOR_ALL_END } + +/** + * Reverse iterator over only the valid frame events in a packet. + * Returns the current index in the 'caerFrameIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerFrameIteratorElement' variable + * of type caerFrameEvent. + * + * FRAME_PACKET: a valid FrameEventPacket pointer. Cannot be NULL. + */ +#define CAER_FRAME_REVERSE_ITERATOR_VALID_START(FRAME_PACKET) \ + for (int32_t caerFrameIteratorCounter = caerEventPacketHeaderGetEventNumber(&(FRAME_PACKET)->packetHeader) - 1; \ + caerFrameIteratorCounter >= 0; \ + caerFrameIteratorCounter--) { \ + caerFrameEvent caerFrameIteratorElement = caerFrameEventPacketGetEvent(FRAME_PACKET, caerFrameIteratorCounter); \ + if (!caerFrameEventIsValid(caerFrameIteratorElement)) { continue; } // Skip invalid frame events. + +/** + * Reverse iterator close statement. + */ +#define CAER_FRAME_REVERSE_ITERATOR_VALID_END } + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_EVENTS_FRAME_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/imu6.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/imu6.h new file mode 100755 index 0000000..08d5b80 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/imu6.h @@ -0,0 +1,420 @@ +/** + * @file imu6.h + * + * IMU6 (6 axes) Events format definition and handling functions. + * This contains data coming from the Inertial Measurement Unit + * chip, with the 3-axes accelerometer and 3-axes gyroscope. + * Temperature is also included. + */ + +#ifndef LIBCAER_EVENTS_IMU6_H_ +#define LIBCAER_EVENTS_IMU6_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "common.h" + +/** + * IMU 6-axes event data structure definition. + * This contains accelerometer and gyroscope headings, plus + * temperature. + * The X, Y and Z axes are referred to the camera plane. + * X increases to the right, Y going up and Z towards where + * the lens is pointing. Rotation for the gyroscope is + * counter-clockwise along the increasing axis, for all three axes. + * Floats are in IEEE 754-2008 binary32 format. + * Signed integers are used for fields that are to be interpreted + * directly, for compatibility with languages that do not have + * unsigned integer types, such as Java. + */ +struct caer_imu6_event { + /// Event information. First because of valid mark. + uint32_t info; + /// Event timestamp. + int32_t timestamp; + /// Acceleration in the X axis, measured in g (9.81m/s²). + float accel_x; + /// Acceleration in the Y axis, measured in g (9.81m/s²). + float accel_y; + /// Acceleration in the Z axis, measured in g (9.81m/s²). + float accel_z; + /// Rotation in the X axis, measured in °/s. + float gyro_x; + /// Rotation in the Y axis, measured in °/s. + float gyro_y; + /// Rotation in the Z axis, measured in °/s. + float gyro_z; + /// Temperature, measured in °C. + float temp; +}__attribute__((__packed__)); + +/** + * Type for pointer to IMU 6-axes event data structure. + */ +typedef struct caer_imu6_event *caerIMU6Event; + +/** + * IMU 6-axes event packet data structure definition. + * EventPackets are always made up of the common packet header, + * followed by 'eventCapacity' events. Everything has to + * be in one contiguous memory block. + */ +struct caer_imu6_event_packet { + /// The common event packet header. + struct caer_event_packet_header packetHeader; + /// The events array. + struct caer_imu6_event events[]; +}__attribute__((__packed__)); + +/** + * Type for pointer to IMU 6-axes event packet data structure. + */ +typedef struct caer_imu6_event_packet *caerIMU6EventPacket; + +/** + * Allocate a new IMU 6-axes events packet. + * Use free() to reclaim this memory. + * + * @param eventCapacity the maximum number of events this packet will hold. + * @param eventSource the unique ID representing the source/generator of this packet. + * @param tsOverflow the current timestamp overflow counter value for this packet. + * + * @return a valid IMU6EventPacket handle or NULL on error. + */ +caerIMU6EventPacket caerIMU6EventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow); + +/** + * Get the IMU 6-axes event at the given index from the event packet. + * + * @param packet a valid IMU6EventPacket pointer. Cannot be NULL. + * @param n the index of the returned event. Must be within [0,eventCapacity[ bounds. + * + * @return the requested IMU 6-axes event. NULL on error. + */ +static inline caerIMU6Event caerIMU6EventPacketGetEvent(caerIMU6EventPacket packet, int32_t n) { + // Check that we're not out of bounds. + if (n < 0 || n >= caerEventPacketHeaderGetEventCapacity(&packet->packetHeader)) { + caerLog(CAER_LOG_CRITICAL, "IMU6 Event", + "Called caerIMU6EventPacketGetEvent() with invalid event offset %" PRIi32 ", while maximum allowed value is %" PRIi32 ".", + n, caerEventPacketHeaderGetEventCapacity(&packet->packetHeader) - 1); + return (NULL); + } + + // Return a pointer to the specified event. + return (packet->events + n); +} + +/** + * Get the 32bit event timestamp, in microseconds. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond timestamp. + */ +static inline int32_t caerIMU6EventGetTimestamp(caerIMU6Event event) { + return (le32toh(event->timestamp)); +} + +/** + * Get the 64bit event timestamp, in microseconds. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * @param packet the IMU6EventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond timestamp. + */ +static inline int64_t caerIMU6EventGetTimestamp64(caerIMU6Event event, caerIMU6EventPacket packet) { + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(&packet->packetHeader)) << TS_OVERFLOW_SHIFT) | U64T(caerIMU6EventGetTimestamp(event)))); +} + +/** + * Set the 32bit event timestamp, the value has to be in microseconds. + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * @param timestamp a positive 32bit microsecond timestamp. + */ +static inline void caerIMU6EventSetTimestamp(caerIMU6Event event, int32_t timestamp) { + if (timestamp < 0) { + // Negative means using the 31st bit! + caerLog(CAER_LOG_CRITICAL, "IMU6 Event", "Called caerIMU6EventSetTimestamp() with negative value!"); + return; + } + + event->timestamp = htole32(timestamp); +} + +/** + * Check if this IMU 6-axes event is valid. + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * + * @return true if valid, false if not. + */ +static inline bool caerIMU6EventIsValid(caerIMU6Event event) { + return (GET_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK)); +} + +/** + * Validate the current event by setting its valid bit to true + * and increasing the event packet's event count and valid + * event count. Only works on events that are invalid. + * DO NOT CALL THIS AFTER HAVING PREVIOUSLY ALREADY + * INVALIDATED THIS EVENT, the total count will be incorrect. + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * @param packet the IMU6EventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerIMU6EventValidate(caerIMU6Event event, caerIMU6EventPacket packet) { + if (!caerIMU6EventIsValid(event)) { + SET_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK, 1); + + // Also increase number of events and valid events. + // Only call this on (still) invalid events! + caerEventPacketHeaderSetEventNumber(&packet->packetHeader, + caerEventPacketHeaderGetEventNumber(&packet->packetHeader) + 1); + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) + 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "IMU6 Event", "Called caerIMU6EventValidate() on already valid event."); + } +} + +/** + * Invalidate the current event by setting its valid bit + * to false and decreasing the number of valid events held + * in the packet. Only works with events that are already + * valid! + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * @param packet the IMU6EventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerIMU6EventInvalidate(caerIMU6Event event, caerIMU6EventPacket packet) { + if (caerIMU6EventIsValid(event)) { + CLEAR_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK); + + // Also decrease number of valid events. Number of total events doesn't change. + // Only call this on valid events! + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) - 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "IMU6 Event", "Called caerIMU6EventInvalidate() on already invalid event."); + } +} + +/** + * Get the X axis acceleration reading (from accelerometer). + * This is in g (1 g = 9.81 m/s²). + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * + * @return acceleration on the X axis. + */ +static inline float caerIMU6EventGetAccelX(caerIMU6Event event) { + return (le32toh(event->accel_x)); +} + +/** + * Set the X axis acceleration reading (from accelerometer). + * This is in g (1 g = 9.81 m/s²). + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * @param accelX acceleration on the X axis. + */ +static inline void caerIMU6EventSetAccelX(caerIMU6Event event, float accelX) { + event->accel_x = htole32(accelX); +} + +/** + * Get the Y axis acceleration reading (from accelerometer). + * This is in g (1 g = 9.81 m/s²). + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * + * @return acceleration on the Y axis. + */ +static inline float caerIMU6EventGetAccelY(caerIMU6Event event) { + return (le32toh(event->accel_y)); +} + +/** + * Set the Y axis acceleration reading (from accelerometer). + * This is in g (1 g = 9.81 m/s²). + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * @param accelY acceleration on the Y axis. + */ +static inline void caerIMU6EventSetAccelY(caerIMU6Event event, float accelY) { + event->accel_y = htole32(accelY); +} + +/** + * Get the Z axis acceleration reading (from accelerometer). + * This is in g (1 g = 9.81 m/s²). + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * + * @return acceleration on the Z axis. + */ +static inline float caerIMU6EventGetAccelZ(caerIMU6Event event) { + return (le32toh(event->accel_z)); +} + +/** + * Set the Z axis acceleration reading (from accelerometer). + * This is in g (1 g = 9.81 m/s²). + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * @param accelZ acceleration on the Z axis. + */ +static inline void caerIMU6EventSetAccelZ(caerIMU6Event event, float accelZ) { + event->accel_z = htole32(accelZ); +} + +/** + * Get the X axis (roll) angular velocity reading (from gyroscope). + * This is in °/s (deg/sec). + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * + * @return angular velocity on the X axis (roll). + */ +static inline float caerIMU6EventGetGyroX(caerIMU6Event event) { + return (le32toh(event->gyro_x)); +} + +/** + * Set the X axis (roll) angular velocity reading (from gyroscope). + * This is in °/s (deg/sec). + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * @param gyroX angular velocity on the X axis (roll). + */ +static inline void caerIMU6EventSetGyroX(caerIMU6Event event, float gyroX) { + event->gyro_x = htole32(gyroX); +} + +/** + * Get the Y axis (pitch) angular velocity reading (from gyroscope). + * This is in °/s (deg/sec). + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * + * @return angular velocity on the Y axis (pitch). + */ +static inline float caerIMU6EventGetGyroY(caerIMU6Event event) { + return (le32toh(event->gyro_y)); +} + +/** + * Set the Y axis (pitch) angular velocity reading (from gyroscope). + * This is in °/s (deg/sec). + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * @param gyroY angular velocity on the Y axis (pitch). + */ +static inline void caerIMU6EventSetGyroY(caerIMU6Event event, float gyroY) { + event->gyro_y = htole32(gyroY); +} + +/** + * Get the Z axis (yaw) angular velocity reading (from gyroscope). + * This is in °/s (deg/sec). + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * + * @return angular velocity on the Z axis (yaw). + */ +static inline float caerIMU6EventGetGyroZ(caerIMU6Event event) { + return (le32toh(event->gyro_z)); +} + +/** + * Set the Z axis (yaw) angular velocity reading (from gyroscope). + * This is in °/s (deg/sec). + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * @param gyroZ angular velocity on the Z axis (yaw). + */ +static inline void caerIMU6EventSetGyroZ(caerIMU6Event event, float gyroZ) { + event->gyro_z = htole32(gyroZ); +} + +/** + * Get the temperature reading. + * This is in °C. + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * + * @return temperature in °C. + */ +static inline float caerIMU6EventGetTemp(caerIMU6Event event) { + return (le32toh(event->temp)); +} + +/** + * Set the temperature reading. + * This is in °C. + * + * @param event a valid IMU6Event pointer. Cannot be NULL. + * @param temp temperature in °C. + */ +static inline void caerIMU6EventSetTemp(caerIMU6Event event, float temp) { + event->temp = htole32(temp); +} + +/** + * Iterator over all IMU6 events in a packet. + * Returns the current index in the 'caerIMU6IteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerIMU6IteratorElement' variable + * of type caerIMU6Event. + * + * IMU6_PACKET: a valid IMU6EventPacket pointer. Cannot be NULL. + */ +#define CAER_IMU6_ITERATOR_ALL_START(IMU6_PACKET) \ + for (int32_t caerIMU6IteratorCounter = 0; \ + caerIMU6IteratorCounter < caerEventPacketHeaderGetEventNumber(&(IMU6_PACKET)->packetHeader); \ + caerIMU6IteratorCounter++) { \ + caerIMU6Event caerIMU6IteratorElement = caerIMU6EventPacketGetEvent(IMU6_PACKET, caerIMU6IteratorCounter); + +/** + * Iterator close statement. + */ +#define CAER_IMU6_ITERATOR_ALL_END } + +/** + * Iterator over only the valid IMU6 events in a packet. + * Returns the current index in the 'caerIMU6IteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerIMU6IteratorElement' variable + * of type caerIMU6Event. + * + * IMU6_PACKET: a valid IMU6EventPacket pointer. Cannot be NULL. + */ +#define CAER_IMU6_ITERATOR_VALID_START(IMU6_PACKET) \ + for (int32_t caerIMU6IteratorCounter = 0; \ + caerIMU6IteratorCounter < caerEventPacketHeaderGetEventNumber(&(IMU6_PACKET)->packetHeader); \ + caerIMU6IteratorCounter++) { \ + caerIMU6Event caerIMU6IteratorElement = caerIMU6EventPacketGetEvent(IMU6_PACKET, caerIMU6IteratorCounter); \ + if (!caerIMU6EventIsValid(caerIMU6IteratorElement)) { continue; } // Skip invalid IMU6 events. + +/** + * Iterator close statement. + */ +#define CAER_IMU6_ITERATOR_VALID_END } + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_EVENTS_IMU6_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/imu9.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/imu9.h new file mode 100755 index 0000000..77e8e38 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/imu9.h @@ -0,0 +1,497 @@ +/** + * @file imu9.h + * + * IMU9 (9 axes) Events format definition and handling functions. + * This contains data coming from the Inertial Measurement Unit + * chip, with the 3-axes accelerometer and 3-axes gyroscope. + * Temperature is also included. + * Further, 3-axes from the magnetometer are included, which + * can be used to get a compass-like heading. + */ + +#ifndef LIBCAER_EVENTS_IMU9_H_ +#define LIBCAER_EVENTS_IMU9_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "common.h" + +/** + * IMU 9-axes event data structure definition. + * This contains accelerometer and gyroscope headings, plus + * temperature, and magnetometer readings. + * The X, Y and Z axes are referred to the camera plane. + * X increases to the right, Y going up and Z towards where + * the lens is pointing. Rotation for the gyroscope is + * counter-clockwise along the increasing axis, for all three axes. + * Floats are in IEEE 754-2008 binary32 format. + * Signed integers are used for fields that are to be interpreted + * directly, for compatibility with languages that do not have + * unsigned integer types, such as Java. + */ +struct caer_imu9_event { + /// Event information. First because of valid mark. + uint32_t info; + /// Event timestamp. + int32_t timestamp; + /// Acceleration in the X axis, measured in g (9.81m/s²). + float accel_x; + /// Acceleration in the Y axis, measured in g (9.81m/s²). + float accel_y; + /// Acceleration in the Z axis, measured in g (9.81m/s²). + float accel_z; + /// Rotation in the X axis, measured in °/s. + float gyro_x; + /// Rotation in the Y axis, measured in °/s. + float gyro_y; + /// Rotation in the Z axis, measured in °/s. + float gyro_z; + /// Temperature, measured in °C. + float temp; + /// Magnetometer X axis, measured in µT (magnetic flux density). + float comp_x; + /// Magnetometer Y axis, measured in µT (magnetic flux density). + float comp_y; + /// Magnetometer Z axis, measured in µT (magnetic flux density). + float comp_z; +}__attribute__((__packed__)); + +/** + * Type for pointer to IMU 9-axes event data structure. + */ +typedef struct caer_imu9_event *caerIMU9Event; + +/** + * IMU 9-axes event packet data structure definition. + * EventPackets are always made up of the common packet header, + * followed by 'eventCapacity' events. Everything has to + * be in one contiguous memory block. + */ +struct caer_imu9_event_packet { + /// The common event packet header. + struct caer_event_packet_header packetHeader; + /// The events array. + struct caer_imu9_event events[]; +}__attribute__((__packed__)); + +/** + * Type for pointer to IMU 9-axes event packet data structure. + */ +typedef struct caer_imu9_event_packet *caerIMU9EventPacket; + +/** + * Allocate a new IMU 9-axes events packet. + * Use free() to reclaim this memory. + * + * @param eventCapacity the maximum number of events this packet will hold. + * @param eventSource the unique ID representing the source/generator of this packet. + * @param tsOverflow the current timestamp overflow counter value for this packet. + * + * @return a valid IMU9EventPacket handle or NULL on error. + */ +caerIMU9EventPacket caerIMU9EventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow); + +/** + * Get the IMU 9-axes event at the given index from the event packet. + * + * @param packet a valid IMU9EventPacket pointer. Cannot be NULL. + * @param n the index of the returned event. Must be within [0,eventCapacity[ bounds. + * + * @return the requested IMU 9-axes event. NULL on error. + */ +static inline caerIMU9Event caerIMU9EventPacketGetEvent(caerIMU9EventPacket packet, int32_t n) { + // Check that we're not out of bounds. + if (n < 0 || n >= caerEventPacketHeaderGetEventCapacity(&packet->packetHeader)) { + caerLog(CAER_LOG_CRITICAL, "IMU9 Event", + "Called caerIMU9EventPacketGetEvent() with invalid event offset %" PRIi32 ", while maximum allowed value is %" PRIi32 ".", + n, caerEventPacketHeaderGetEventCapacity(&packet->packetHeader) - 1); + return (NULL); + } + + // Return a pointer to the specified event. + return (packet->events + n); +} + +/** + * Get the 32bit event timestamp, in microseconds. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond timestamp. + */ +static inline int32_t caerIMU9EventGetTimestamp(caerIMU9Event event) { + return (le32toh(event->timestamp)); +} + +/** + * Get the 64bit event timestamp, in microseconds. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * @param packet the IMU9EventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond timestamp. + */ +static inline int64_t caerIMU9EventGetTimestamp64(caerIMU9Event event, caerIMU9EventPacket packet) { + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(&packet->packetHeader)) << TS_OVERFLOW_SHIFT) | U64T(caerIMU9EventGetTimestamp(event)))); +} + +/** + * Set the 32bit event timestamp, the value has to be in microseconds. + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * @param timestamp a positive 32bit microsecond timestamp. + */ +static inline void caerIMU9EventSetTimestamp(caerIMU9Event event, int32_t timestamp) { + if (timestamp < 0) { + // Negative means using the 31st bit! + caerLog(CAER_LOG_CRITICAL, "IMU9 Event", "Called caerIMU9EventSetTimestamp() with negative value!"); + return; + } + + event->timestamp = htole32(timestamp); +} + +/** + * Check if this IMU 9-axes event is valid. + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * + * @return true if valid, false if not. + */ +static inline bool caerIMU9EventIsValid(caerIMU9Event event) { + return (GET_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK)); +} + +/** + * Validate the current event by setting its valid bit to true + * and increasing the event packet's event count and valid + * event count. Only works on events that are invalid. + * DO NOT CALL THIS AFTER HAVING PREVIOUSLY ALREADY + * INVALIDATED THIS EVENT, the total count will be incorrect. + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * @param packet the IMU9EventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerIMU9EventValidate(caerIMU9Event event, caerIMU9EventPacket packet) { + if (!caerIMU9EventIsValid(event)) { + SET_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK, 1); + + // Also increase number of events and valid events. + // Only call this on (still) invalid events! + caerEventPacketHeaderSetEventNumber(&packet->packetHeader, + caerEventPacketHeaderGetEventNumber(&packet->packetHeader) + 1); + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) + 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "IMU9 Event", "Called caerIMU9EventValidate() on already valid event."); + } +} + +/** + * Invalidate the current event by setting its valid bit + * to false and decreasing the number of valid events held + * in the packet. Only works with events that are already + * valid! + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * @param packet the IMU9EventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerIMU9EventInvalidate(caerIMU9Event event, caerIMU9EventPacket packet) { + if (caerIMU9EventIsValid(event)) { + CLEAR_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK); + + // Also decrease number of valid events. Number of total events doesn't change. + // Only call this on valid events! + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) - 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "IMU9 Event", "Called caerIMU9EventInvalidate() on already invalid event."); + } +} + +/** + * Get the X axis acceleration reading (from accelerometer). + * This is in g (1 g = 9.81 m/s²). + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * + * @return acceleration on the X axis. + */ +static inline float caerIMU9EventGetAccelX(caerIMU9Event event) { + return (le32toh(event->accel_x)); +} + +/** + * Set the X axis acceleration reading (from accelerometer). + * This is in g (1 g = 9.81 m/s²). + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * @param accelX acceleration on the X axis. + */ +static inline void caerIMU9EventSetAccelX(caerIMU9Event event, float accelX) { + event->accel_x = htole32(accelX); +} + +/** + * Get the Y axis acceleration reading (from accelerometer). + * This is in g (1 g = 9.81 m/s²). + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * + * @return acceleration on the Y axis. + */ +static inline float caerIMU9EventGetAccelY(caerIMU9Event event) { + return (le32toh(event->accel_y)); +} + +/** + * Set the Y axis acceleration reading (from accelerometer). + * This is in g (1 g = 9.81 m/s²). + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * @param accelY acceleration on the Y axis. + */ +static inline void caerIMU9EventSetAccelY(caerIMU9Event event, float accelY) { + event->accel_y = htole32(accelY); +} + +/** + * Get the Z axis acceleration reading (from accelerometer). + * This is in g (1 g = 9.81 m/s²). + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * + * @return acceleration on the Z axis. + */ +static inline float caerIMU9EventGetAccelZ(caerIMU9Event event) { + return (le32toh(event->accel_z)); +} + +/** + * Set the Z axis acceleration reading (from accelerometer). + * This is in g (1 g = 9.81 m/s²). + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * @param accelZ acceleration on the Z axis. + */ +static inline void caerIMU9EventSetAccelZ(caerIMU9Event event, float accelZ) { + event->accel_z = htole32(accelZ); +} + +/** + * Get the X axis (roll) angular velocity reading (from gyroscope). + * This is in °/s (deg/sec). + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * + * @return angular velocity on the X axis (roll). + */ +static inline float caerIMU9EventGetGyroX(caerIMU9Event event) { + return (le32toh(event->gyro_x)); +} + +/** + * Set the X axis (roll) angular velocity reading (from gyroscope). + * This is in °/s (deg/sec). + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * @param gyroX angular velocity on the X axis (roll). + */ +static inline void caerIMU9EventSetGyroX(caerIMU9Event event, float gyroX) { + event->gyro_x = htole32(gyroX); +} + +/** + * Get the Y axis (pitch) angular velocity reading (from gyroscope). + * This is in °/s (deg/sec). + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * + * @return angular velocity on the Y axis (pitch). + */ +static inline float caerIMU9EventGetGyroY(caerIMU9Event event) { + return (le32toh(event->gyro_y)); +} + +/** + * Set the Y axis (pitch) angular velocity reading (from gyroscope). + * This is in °/s (deg/sec). + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * @param gyroY angular velocity on the Y axis (pitch). + */ +static inline void caerIMU9EventSetGyroY(caerIMU9Event event, float gyroY) { + event->gyro_y = htole32(gyroY); +} + +/** + * Get the Z axis (yaw) angular velocity reading (from gyroscope). + * This is in °/s (deg/sec). + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * + * @return angular velocity on the Z axis (yaw). + */ +static inline float caerIMU9EventGetGyroZ(caerIMU9Event event) { + return (le32toh(event->gyro_z)); +} + +/** + * Set the Z axis (yaw) angular velocity reading (from gyroscope). + * This is in °/s (deg/sec). + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * @param gyroZ angular velocity on the Z axis (yaw). + */ +static inline void caerIMU9EventSetGyroZ(caerIMU9Event event, float gyroZ) { + event->gyro_z = htole32(gyroZ); +} + +/** + * Get the temperature reading. + * This is in °C. + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * + * @return temperature in °C. + */ +static inline float caerIMU9EventGetTemp(caerIMU9Event event) { + return (le32toh(event->temp)); +} + +/** + * Set the temperature reading. + * This is in °C. + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * @param temp temperature in °C. + */ +static inline void caerIMU9EventSetTemp(caerIMU9Event event, float temp) { + event->temp = htole32(temp); +} + +/** + * Get the X axis compass heading (from magnetometer). + * This is in µT. + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * + * @return X axis compass heading. + */ +static inline float caerIMU9EventGetCompX(caerIMU9Event event) { + return (le32toh(event->comp_x)); +} + +/** + * Set the X axis compass heading (from magnetometer). + * This is in µT. + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * @param compX X axis compass heading. + */ +static inline void caerIMU9EventSetCompX(caerIMU9Event event, float compX) { + event->comp_x = htole32(compX); +} + +/** + * Get the Y axis compass heading (from magnetometer). + * This is in µT. + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * + * @return Y axis compass heading. + */ +static inline float caerIMU9EventGetCompY(caerIMU9Event event) { + return (le32toh(event->comp_y)); +} + +/** + * Set the Y axis compass heading (from magnetometer). + * This is in µT. + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * @param compY Y axis compass heading. + */ +static inline void caerIMU9EventSetCompY(caerIMU9Event event, float compY) { + event->comp_y = htole32(compY); +} + +/** + * Get the Z axis compass heading (from magnetometer). + * This is in µT. + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * + * @return Z axis compass heading. + */ +static inline float caerIMU9EventGetCompZ(caerIMU9Event event) { + return (le32toh(event->comp_z)); +} + +/** + * Set the Z axis compass heading (from magnetometer). + * This is in µT. + * + * @param event a valid IMU9Event pointer. Cannot be NULL. + * @param compZ Z axis compass heading. + */ +static inline void caerIMU9EventSetCompZ(caerIMU9Event event, float compZ) { + event->comp_z = htole32(compZ); +} + +/** + * Iterator over all IMU9 events in a packet. + * Returns the current index in the 'caerIMU9IteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerIMU9IteratorElement' variable + * of type caerIMU9Event. + * + * IMU9_PACKET: a valid IMU9EventPacket pointer. Cannot be NULL. + */ +#define CAER_IMU9_ITERATOR_ALL_START(IMU9_PACKET) \ + for (int32_t caerIMU9IteratorCounter = 0; \ + caerIMU9IteratorCounter < caerEventPacketHeaderGetEventNumber(&(IMU9_PACKET)->packetHeader); \ + caerIMU9IteratorCounter++) { \ + caerIMU9Event caerIMU9IteratorElement = caerIMU9EventPacketGetEvent(IMU9_PACKET, caerIMU9IteratorCounter); + +/** + * Iterator close statement. + */ +#define CAER_IMU9_ITERATOR_ALL_END } + +/** + * Iterator over only the valid IMU9 events in a packet. + * Returns the current index in the 'caerIMU9IteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerIMU9IteratorElement' variable + * of type caerIMU9Event. + * + * IMU9_PACKET: a valid IMU9EventPacket pointer. Cannot be NULL. + */ +#define CAER_IMU9_ITERATOR_VALID_START(IMU9_PACKET) \ + for (int32_t caerIMU9IteratorCounter = 0; \ + caerIMU9IteratorCounter < caerEventPacketHeaderGetEventNumber(&(IMU9_PACKET)->packetHeader); \ + caerIMU9IteratorCounter++) { \ + caerIMU9Event caerIMU9IteratorElement = caerIMU9EventPacketGetEvent(IMU9_PACKET, caerIMU9IteratorCounter); \ + if (!caerIMU9EventIsValid(caerIMU9IteratorElement)) { continue; } // Skip invalid IMU9 events. + +/** + * Iterator close statement. + */ +#define CAER_IMU9_ITERATOR_VALID_END } + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_EVENTS_IMU9_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/packetContainer.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/packetContainer.h new file mode 100755 index 0000000..2a458b6 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/packetContainer.h @@ -0,0 +1,374 @@ +/** + * @file packetContainer.h + * + * EventPacketContainer format definition and handling functions. + * An EventPacketContainer is a logical construct that contains packets + * of events (EventPackets) of different event types, with the aim of + * keeping related events of differing types, such as DVS and IMU data, + * together. Such a relation is usually based on time intervals, trying + * to keep groups of event happening in a certain time-slice together. + * This time-order is based on the *main* time-stamp of an event, the one + * whose offset is referenced in the event packet header and that is + * used by the caerGenericEvent*() functions. It's guaranteed that all + * conforming input modules keep to this rule, generating containers + * that include all events from all types within the given time-slice. + * The smallest and largest timestamps are tracked at the packet container + * level as a convenience, to avoid having to examine all packets for + * this often useful piece of information. + * All integers are in their native host format, as this is a purely + * internal, in-memory data structure, never meant for exchange between + * different systems (and different endianness). + */ + +#ifndef LIBCAER_EVENTS_PACKETCONTAINER_H_ +#define LIBCAER_EVENTS_PACKETCONTAINER_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "common.h" + +/** + * EventPacketContainer data structure definition. + * Signed integers are used for compatibility with languages that + * do not have unsigned ones, such as Java. + */ +struct caer_event_packet_container { + /// Smallest event timestamp contained in this packet container. + int64_t lowestEventTimestamp; + /// Largest event timestamp contained in this packet container. + int64_t highestEventTimestamp; + /// Number of events contained within all the packets in this container. + int32_t eventsNumber; + /// Number of valid events contained within all the packets in this container. + int32_t eventsValidNumber; + /// Number of different event packets contained. + int32_t eventPacketsNumber; + /// Array of pointers to the actual event packets. + caerEventPacketHeader eventPackets[]; +}__attribute__((__packed__)); + +/** + * Type for pointer to EventPacketContainer data structure. + */ +typedef struct caer_event_packet_container *caerEventPacketContainer; + +/** + * Allocate a new EventPacketContainer with enough space to + * store up to the given number of EventPacket references. + * All packet references will be NULL initially. + * + * @param eventPacketsNumber the maximum number of EventPacket references + * that can be stored in this container. + * + * @return a valid EventPacketContainer handle or NULL on error. + */ +caerEventPacketContainer caerEventPacketContainerAllocate(int32_t eventPacketsNumber); + +/** + * Free the memory occupied by an EventPacketContainer, as well as + * freeing all of its contained EventPackets and their memory. + * If you don't want the contained EventPackets to be freed, make + * sure that you set their reference to NULL before calling this. + + * @param container the container to be freed. + */ +void caerEventPacketContainerFree(caerEventPacketContainer container); + +/** + * Get the maximum number of EventPacket references that can be stored + * in this particular EventPacketContainer. + * + * @param container a valid EventPacketContainer handle. If NULL, zero is returned. + * + * @return the number of EventPacket references that can be contained. + */ +static inline int32_t caerEventPacketContainerGetEventPacketsNumber(caerEventPacketContainer container) { + // Non-existing (empty) containers have no valid packets in them! + if (container == NULL) { + return (0); + } + + return (container->eventPacketsNumber); +} + +/** + * Set the maximum number of EventPacket references that can be stored + * in this particular EventPacketContainer. This should never be used + * directly, caerEventPacketContainerAllocate() sets this for you. + * + * @param container a valid EventPacketContainer handle. If NULL, nothing happens. + * @param eventPacketsNumber the number of EventPacket references that can be contained. + */ +static inline void caerEventPacketContainerSetEventPacketsNumber(caerEventPacketContainer container, + int32_t eventPacketsNumber) { + // Non-existing (empty) containers have no valid packets in them! + if (container == NULL) { + return; + } + + if (eventPacketsNumber < 0) { + // Negative numbers (bit 31 set) are not allowed! + caerLog(CAER_LOG_CRITICAL, "EventPacket Container", + "Called caerEventPacketContainerSetEventPacketsNumber() with negative value!"); + return; + } + + container->eventPacketsNumber = eventPacketsNumber; +} + +/** + * Get the reference for the EventPacket stored in this container + * at the given index. + * + * @param container a valid EventPacketContainer handle. If NULL, returns NULL too. + * @param n the index of the EventPacket to get. + * + * @return a reference to an EventPacket or NULL on error. + */ +static inline caerEventPacketHeader caerEventPacketContainerGetEventPacket(caerEventPacketContainer container, + int32_t n) { + // Non-existing (empty) containers have no valid packets in them! + if (container == NULL) { + return (NULL); + } + + // Check that we're not out of bounds. + if (n < 0 || n >= caerEventPacketContainerGetEventPacketsNumber(container)) { + caerLog(CAER_LOG_CRITICAL, "EventPacket Container", + "Called caerEventPacketContainerGetEventPacket() with invalid event offset %" PRIi32 ", while maximum allowed value is %" PRIi32 ". Negative values are not allowed!", + n, caerEventPacketContainerGetEventPacketsNumber(container) - 1); + return (NULL); + } + + // Return a pointer to the specified event packet. + return (container->eventPackets[n]); +} + +/** + * Set the reference for the EventPacket stored in this container + * at the given index. + * + * @param container a valid EventPacketContainer handle. If NULL, nothing happens. + * @param n the index of the EventPacket to set. + * @param packetHeader a reference to an EventPacket's header. Can be NULL. + */ +static inline void caerEventPacketContainerSetEventPacket(caerEventPacketContainer container, int32_t n, + caerEventPacketHeader packetHeader) { + // Non-existing (empty) containers have no valid packets in them! + if (container == NULL) { + return; + } + + // Check that we're not out of bounds. + if (n < 0 || n >= caerEventPacketContainerGetEventPacketsNumber(container)) { + caerLog(CAER_LOG_CRITICAL, "EventPacket Container", + "Called caerEventPacketContainerSetEventPacket() with invalid event offset %" PRIi32 ", while maximum allowed value is %" PRIi32 ". Negative values are not allowed!", + n, caerEventPacketContainerGetEventPacketsNumber(container) - 1); + return; + } + + // Store the given event packet. + container->eventPackets[n] = packetHeader; + + // Deleting packets (setting to NULL) will not result in timestamp-tracking updates. + if (packetHeader == NULL) { + return; + } + + // Get timestamps to update lowest/highest tracking. + void *firstEvent = caerGenericEventGetEvent(packetHeader, 0); + int64_t currLowestEventTimestamp = caerGenericEventGetTimestamp64(firstEvent, packetHeader); + + void *lastEvent = caerGenericEventGetEvent(packetHeader, caerEventPacketHeaderGetEventNumber(packetHeader) - 1); + int64_t currHighestEventTimestamp = caerGenericEventGetTimestamp64(lastEvent, packetHeader); + + // Update tracked timestamps (or initialize if needed). + if ((container->lowestEventTimestamp == -1) || (container->lowestEventTimestamp > currLowestEventTimestamp)) { + container->lowestEventTimestamp = currLowestEventTimestamp; + } + + if ((container->highestEventTimestamp == -1) || (container->highestEventTimestamp < currHighestEventTimestamp)) { + container->highestEventTimestamp = currHighestEventTimestamp; + } + + container->eventsNumber += caerEventPacketHeaderGetEventNumber(packetHeader); + container->eventsValidNumber += caerEventPacketHeaderGetEventValid(packetHeader); +} + +/** + * Get the lowest timestamp contained in this event packet container. + * + * @param container a valid EventPacketContainer handle. If NULL, -1 is returned. + * + * @return the lowest timestamp (in µs) or -1 if not initialized. + */ +static inline int64_t caerEventPacketContainerGetLowestEventTimestamp(caerEventPacketContainer container) { + // Non-existing (empty) containers have no valid packets in them! + if (container == NULL) { + return (-1); + } + + return (container->lowestEventTimestamp); +} + +/** + * Get the highest timestamp contained in this event packet container. + * + * @param container a valid EventPacketContainer handle. If NULL, -1 is returned. + * + * @return the highest timestamp (in µs) or -1 if not initialized. + */ +static inline int64_t caerEventPacketContainerGetHighestEventTimestamp(caerEventPacketContainer container) { + // Non-existing (empty) containers have no valid packets in them! + if (container == NULL) { + return (-1); + } + + return (container->highestEventTimestamp); +} + +/** + * Get the number of events contained in this event packet container. + * + * @param container a valid EventPacketContainer handle. If NULL, 0 is returned. + * + * @return the number of events in this container. + */ +static inline int32_t caerEventPacketContainerGetEventsNumber(caerEventPacketContainer container) { + // Non-existing (empty) containers have no valid packets in them! + if (container == NULL) { + return (0); + } + + return (container->eventsNumber); +} + +/** + * Get the number of valid events contained in this event packet container. + * + * @param container a valid EventPacketContainer handle. If NULL, 0 is returned. + * + * @return the number of valid events in this container. + */ +static inline int32_t caerEventPacketContainerGetEventsValidNumber(caerEventPacketContainer container) { + // Non-existing (empty) containers have no valid packets in them! + if (container == NULL) { + return (0); + } + + return (container->eventsValidNumber); +} + +/** + * Iterator over all event packets in an event packet container. + * Returns the current index in the 'caerEventPacketContainerIteratorCounter' variable + * of type 'int32_t' and the current event packet in the 'caerEventPacketContainerIteratorElement' + * variable of type caerEventPacketHeader. The current packet may be NULL, in which case it is + * skipped during iteration. + * + * PACKET_CONTAINER: a valid EventPacketContainer handle. If NULL, no iteration is performed. + */ +#define CAER_EVENT_PACKET_CONTAINER_ITERATOR_START(PACKET_CONTAINER) \ + if ((PACKET_CONTAINER) != NULL) { \ + for (int32_t caerEventPacketContainerIteratorCounter = 0; \ + caerEventPacketContainerIteratorCounter < caerEventPacketContainerGetEventPacketsNumber(PACKET_CONTAINER); \ + caerEventPacketContainerIteratorCounter++) { \ + caerEventPacketHeader caerEventPacketContainerIteratorElement = caerEventPacketContainerGetEventPacket(PACKET_CONTAINER, caerEventPacketContainerIteratorCounter); \ + if (caerEventPacketContainerIteratorElement == NULL) { continue; } + +/** + * Iterator close statement. + */ +#define CAER_EVENT_PACKET_CONTAINER_ITERATOR_END } } + +/** + * Get the reference for an EventPacket stored in this container + * with the given event type. This returns the first found event packet + * with that type ID, or NULL if we get to the end without finding any + * such event packet. + * + * @param container a valid EventPacketContainer handle. If NULL, returns NULL too. + * @param typeID the event type to search for. + * + * @return a reference to an EventPacket with a certain type or NULL if none found. + */ +static inline caerEventPacketHeader caerEventPacketContainerFindEventPacketByType(caerEventPacketContainer container, + int16_t typeID) { + // Non-existing (empty) containers have no valid packets in them! + if (container == NULL) { + return (NULL); + } + + CAER_EVENT_PACKET_CONTAINER_ITERATOR_START(container) + if (caerEventPacketHeaderGetEventType(caerEventPacketContainerIteratorElement) == typeID) { + // Found it, return it. + return (caerEventPacketContainerIteratorElement); + } + CAER_EVENT_PACKET_CONTAINER_ITERATOR_END + + // Found nothing, return nothing. + return (NULL); +} + +/** + * Make a deep copy of an event packet container and all of its + * event packets and their current events. + * + * @param container an event packet container to copy. + * + * @return a deep copy of an event packet container, containing all events. + */ +static inline caerEventPacketContainer caerEventPacketContainerCopyAllEvents(caerEventPacketContainer container) { + if (container == NULL) { + return (NULL); + } + + caerEventPacketContainer newContainer = caerEventPacketContainerAllocate( + caerEventPacketContainerGetEventsNumber(container)); + if (newContainer == NULL) { + return (NULL); + } + + CAER_EVENT_PACKET_CONTAINER_ITERATOR_START(container) + caerEventPacketContainerSetEventPacket(newContainer, caerEventPacketContainerIteratorCounter, + (caerEventPacketHeader) caerCopyEventPacketOnlyEvents((void *) caerEventPacketContainerIteratorElement)); + CAER_EVENT_PACKET_CONTAINER_ITERATOR_END + + return (newContainer); +} + +/** + * Make a deep copy of an event packet container, with its event packets + * sized down to only include the currently valid events (eventValid), + * and discarding everything else. + * + * @param container an event packet container to copy. + * + * @return a deep copy of an event packet container, containing only valid events. + */ +static inline caerEventPacketContainer caerEventPacketContainerCopyValidEvents(caerEventPacketContainer container) { + if (container == NULL) { + return (NULL); + } + + caerEventPacketContainer newContainer = caerEventPacketContainerAllocate( + caerEventPacketContainerGetEventsNumber(container)); + if (newContainer == NULL) { + return (NULL); + } + + CAER_EVENT_PACKET_CONTAINER_ITERATOR_START(container) + caerEventPacketContainerSetEventPacket(newContainer, caerEventPacketContainerIteratorCounter, + (caerEventPacketHeader) caerCopyEventPacketOnlyValidEvents((void *) caerEventPacketContainerIteratorElement)); + CAER_EVENT_PACKET_CONTAINER_ITERATOR_END + + return (newContainer); +} + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_EVENTS_PACKETCONTAINER_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point1d.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point1d.h new file mode 100755 index 0000000..5c797d0 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point1d.h @@ -0,0 +1,335 @@ +/** + * @file point1d.h + * + * THIS EVENT DEFINITIONS IS STILL TO BE CONSIDERED EXPERIMENTAL + * AND IS SUBJECT TO FUTURE CHANGES AND REVISIONS! + * + * Point1D Events format definition and handling functions. + * This contains one dimensional data points as floats, + * together with support for distinguishing type and scale. + */ + +#ifndef LIBCAER_EVENTS_POINT1D_H_ +#define LIBCAER_EVENTS_POINT1D_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "common.h" + +/** + * Shift and mask values for type and scale information + * associated with a Point1D event. + * Up to 128 types are supported. The scale is given as orders + * of magnitude, from 10^-128 to 10^127. + * Bit 0 is the valid mark, see 'common.h' for more details. + */ +//@{ +#define POINT1D_TYPE_SHIFT 1 +#define POINT1D_TYPE_MASK 0x0000007F +#define POINT1D_SCALE_SHIFT 8 +#define POINT1D_SCALE_MASK 0x000000FF +//@} + +/** + * Point1D event data structure definition. + * This contains information about the measurement, such as a type + * and a scale field, together with the usual validity mark. + * The one measurement (x) is stored as a float. + * Floats are in IEEE 754-2008 binary32 format. + * Signed integers are used for fields that are to be interpreted + * directly, for compatibility with languages that do not have + * unsigned integer types, such as Java. + */ +struct caer_point1d_event { + /// Event information. First because of valid mark. + uint32_t info; + /// X axis measurement. + float x; + /// Event timestamp. + int32_t timestamp; +}__attribute__((__packed__)); + +/** + * Type for pointer to Point1D event data structure. + */ +typedef struct caer_point1d_event *caerPoint1DEvent; + +/** + * Point1D event packet data structure definition. + * EventPackets are always made up of the common packet header, + * followed by 'eventCapacity' events. Everything has to + * be in one contiguous memory block. + */ +struct caer_point1d_event_packet { + /// The common event packet header. + struct caer_event_packet_header packetHeader; + /// The events array. + struct caer_point1d_event events[]; +}__attribute__((__packed__)); + +/** + * Type for pointer to Point1D event packet data structure. + */ +typedef struct caer_point1d_event_packet *caerPoint1DEventPacket; + +/** + * Allocate a new Point1D events packet. + * Use free() to reclaim this memory. + * + * @param eventCapacity the maximum number of events this packet will hold. + * @param eventSource the unique ID representing the source/generator of this packet. + * @param tsOverflow the current timestamp overflow counter value for this packet. + * + * @return a valid Point1DEventPacket handle or NULL on error. + */ +caerPoint1DEventPacket caerPoint1DEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow); + +/** + * Get the Point1D event at the given index from the event packet. + * + * @param packet a valid Point1DEventPacket pointer. Cannot be NULL. + * @param n the index of the returned event. Must be within [0,eventCapacity[ bounds. + * + * @return the requested Point1D event. NULL on error. + */ +static inline caerPoint1DEvent caerPoint1DEventPacketGetEvent(caerPoint1DEventPacket packet, int32_t n) { + // Check that we're not out of bounds. + if (n < 0 || n >= caerEventPacketHeaderGetEventCapacity(&packet->packetHeader)) { + caerLog(CAER_LOG_CRITICAL, "Point1D Event", + "Called caerPoint1DEventPacketGetEvent() with invalid event offset %" PRIi32 ", while maximum allowed value is %" PRIi32 ".", + n, caerEventPacketHeaderGetEventCapacity(&packet->packetHeader) - 1); + return (NULL); + } + + // Return a pointer to the specified event. + return (packet->events + n); +} + +/** + * Get the 32bit event timestamp, in microseconds. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid Point1DEvent pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond timestamp. + */ +static inline int32_t caerPoint1DEventGetTimestamp(caerPoint1DEvent event) { + return (le32toh(event->timestamp)); +} + +/** + * Get the 64bit event timestamp, in microseconds. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid Point1DEvent pointer. Cannot be NULL. + * @param packet the Point1DEventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond timestamp. + */ +static inline int64_t caerPoint1DEventGetTimestamp64(caerPoint1DEvent event, caerPoint1DEventPacket packet) { + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(&packet->packetHeader)) << TS_OVERFLOW_SHIFT) | U64T(caerPoint1DEventGetTimestamp(event)))); +} + +/** + * Set the 32bit event timestamp, the value has to be in microseconds. + * + * @param event a valid Point1DEvent pointer. Cannot be NULL. + * @param timestamp a positive 32bit microsecond timestamp. + */ +static inline void caerPoint1DEventSetTimestamp(caerPoint1DEvent event, int32_t timestamp) { + if (timestamp < 0) { + // Negative means using the 31st bit! + caerLog(CAER_LOG_CRITICAL, "Point1D Event", "Called caerPoint1DEventSetTimestamp() with negative value!"); + return; + } + + event->timestamp = htole32(timestamp); +} + +/** + * Check if this Point1D event is valid. + * + * @param event a valid Point1DEvent pointer. Cannot be NULL. + * + * @return true if valid, false if not. + */ +static inline bool caerPoint1DEventIsValid(caerPoint1DEvent event) { + return (GET_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK)); +} + +/** + * Validate the current event by setting its valid bit to true + * and increasing the event packet's event count and valid + * event count. Only works on events that are invalid. + * DO NOT CALL THIS AFTER HAVING PREVIOUSLY ALREADY + * INVALIDATED THIS EVENT, the total count will be incorrect. + * + * @param event a valid Point1DEvent pointer. Cannot be NULL. + * @param packet the Point1DEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerPoint1DEventValidate(caerPoint1DEvent event, caerPoint1DEventPacket packet) { + if (!caerPoint1DEventIsValid(event)) { + SET_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK, 1); + + // Also increase number of events and valid events. + // Only call this on (still) invalid events! + caerEventPacketHeaderSetEventNumber(&packet->packetHeader, + caerEventPacketHeaderGetEventNumber(&packet->packetHeader) + 1); + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) + 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Point1D Event", "Called caerPoint1DEventValidate() on already valid event."); + } +} + +/** + * Invalidate the current event by setting its valid bit + * to false and decreasing the number of valid events held + * in the packet. Only works with events that are already + * valid! + * + * @param event a valid Point1DEvent pointer. Cannot be NULL. + * @param packet the Point1DEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerPoint1DEventInvalidate(caerPoint1DEvent event, caerPoint1DEventPacket packet) { + if (caerPoint1DEventIsValid(event)) { + CLEAR_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK); + + // Also decrease number of valid events. Number of total events doesn't change. + // Only call this on valid events! + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) - 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Point1D Event", "Called caerPoint1DEventInvalidate() on already invalid event."); + } +} + +/** + * Get the measurement event type. This is useful to distinguish + * between different measurements, for example distance or weight. + * + * @param event a valid Point1DEvent pointer. Cannot be NULL. + * + * @return the Point1D measurement type. + */ +static inline uint8_t caerPoint1DEventGetType(caerPoint1DEvent event) { + return U8T(GET_NUMBITS32(event->info, POINT1D_TYPE_SHIFT, POINT1D_TYPE_MASK)); +} + +/** + * Set the measurement event type. This is useful to distinguish + * between different measurements, for example distance or weight. + * + * @param event a valid Point1DEvent pointer. Cannot be NULL. + * @param type the Point1D measurement type. + */ +static inline void caerPoint1DEventSetType(caerPoint1DEvent event, uint8_t type) { + CLEAR_NUMBITS32(event->info, POINT1D_TYPE_SHIFT, POINT1D_TYPE_MASK); + SET_NUMBITS32(event->info, POINT1D_TYPE_SHIFT, POINT1D_TYPE_MASK, type); +} + +/** + * Get the measurement scale. This allows order of magnitude shifts + * on the measured value to be applied automatically, such as having + * measurements of type Distance (meters) and storing the values as + * centimeters (10^-2) for higher precision, but keeping that information + * around to allow easy changes of unit. + * + * @param event a valid Point1DEvent pointer. Cannot be NULL. + * + * @return the Point1D measurement scale. + */ +static inline int8_t caerPoint1DEventGetScale(caerPoint1DEvent event) { + return I8T(GET_NUMBITS32(event->info, POINT1D_SCALE_SHIFT, POINT1D_SCALE_MASK)); +} + +/** + * Set the measurement scale. This allows order of magnitude shifts + * on the measured value to be applied automatically, such as having + * measurements of type Distance (meters) and storing the values as + * centimeters (10^-2) for higher precision, but keeping that information + * around to allow easy changes of unit. + * + * @param event a valid Point1DEvent pointer. Cannot be NULL. + * @param scale the Point1D measurement scale. + */ +static inline void caerPoint1DEventSetScale(caerPoint1DEvent event, int8_t scale) { + CLEAR_NUMBITS32(event->info, POINT1D_SCALE_SHIFT, POINT1D_SCALE_MASK); + SET_NUMBITS32(event->info, POINT1D_SCALE_SHIFT, POINT1D_SCALE_MASK, U8T(scale)); +} + +/** + * Get the X axis measurement. + * + * @param event a valid Point1DEvent pointer. Cannot be NULL. + * + * @return X axis measurement. + */ +static inline float caerPoint1DEventGetX(caerPoint1DEvent event) { + return (le32toh(event->x)); +} + +/** + * Set the X axis measurement. + * + * @param event a valid Point1DEvent pointer. Cannot be NULL. + * @param x X axis measurement. + */ +static inline void caerPoint1DEventSetX(caerPoint1DEvent event, float x) { + event->x = htole32(x); +} + +/** + * Iterator over all Point1D events in a packet. + * Returns the current index in the 'caerPoint1DIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerPoint1DIteratorElement' variable + * of type caerPoint1DEvent. + * + * POINT1D_PACKET: a valid Point1DEventPacket pointer. Cannot be NULL. + */ +#define CAER_POINT1D_ITERATOR_ALL_START(POINT1D_PACKET) \ + for (int32_t caerPoint1DIteratorCounter = 0; \ + caerPoint1DIteratorCounter < caerEventPacketHeaderGetEventNumber(&(POINT1D_PACKET)->packetHeader); \ + caerPoint1DIteratorCounter++) { \ + caerPoint1DEvent caerPoint1DIteratorElement = caerPoint1DEventPacketGetEvent(POINT1D_PACKET, caerPoint1DIteratorCounter); + +/** + * Iterator close statement. + */ +#define CAER_POINT1D_ITERATOR_ALL_END } + +/** + * Iterator over only the valid Point1D events in a packet. + * Returns the current index in the 'caerPoint1DIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerPoint1DIteratorElement' variable + * of type caerPoint1DEvent. + * + * POINT1D_PACKET: a valid Point1DEventPacket pointer. Cannot be NULL. + */ +#define CAER_POINT1D_ITERATOR_VALID_START(POINT1D_PACKET) \ + for (int32_t caerPoint1DIteratorCounter = 0; \ + caerPoint1DIteratorCounter < caerEventPacketHeaderGetEventNumber(&(POINT1D_PACKET)->packetHeader); \ + caerPoint1DIteratorCounter++) { \ + caerPoint1DEvent caerPoint1DIteratorElement = caerPoint1DEventPacketGetEvent(POINT1D_PACKET, caerPoint1DIteratorCounter); \ + if (!caerPoint1DEventIsValid(caerPoint1DIteratorElement)) { continue; } // Skip invalid Point1D events. + +/** + * Iterator close statement. + */ +#define CAER_POINT1D_ITERATOR_VALID_END } + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_EVENTS_POINT1D_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point2d.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point2d.h new file mode 100755 index 0000000..eed4668 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point2d.h @@ -0,0 +1,358 @@ +/** + * @file point2d.h + * + * THIS EVENT DEFINITIONS IS STILL TO BE CONSIDERED EXPERIMENTAL + * AND IS SUBJECT TO FUTURE CHANGES AND REVISIONS! + * + * Point2D Events format definition and handling functions. + * This contains two dimensional data points as floats, + * together with support for distinguishing type and scale. + */ + +#ifndef LIBCAER_EVENTS_POINT2D_H_ +#define LIBCAER_EVENTS_POINT2D_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "common.h" + +/** + * Shift and mask values for type and scale information + * associated with a Point2D event. + * Up to 128 types are supported. The scale is given as orders + * of magnitude, from 10^-128 to 10^127. + * Bit 0 is the valid mark, see 'common.h' for more details. + */ +//@{ +#define POINT2D_TYPE_SHIFT 1 +#define POINT2D_TYPE_MASK 0x0000007F +#define POINT2D_SCALE_SHIFT 8 +#define POINT2D_SCALE_MASK 0x000000FF +//@} + +/** + * Point2D event data structure definition. + * This contains information about the measurement, such as a type + * and a scale field, together with the usual validity mark. + * The two measurements (x, y) are stored as floats. + * Floats are in IEEE 754-2008 binary32 format. + * Signed integers are used for fields that are to be interpreted + * directly, for compatibility with languages that do not have + * unsigned integer types, such as Java. + */ +struct caer_point2d_event { + /// Event information. First because of valid mark. + uint32_t info; + /// X axis measurement. + float x; + /// Y axis measurement. + float y; + /// Event timestamp. + int32_t timestamp; +}__attribute__((__packed__)); + +/** + * Type for pointer to Point2D event data structure. + */ +typedef struct caer_point2d_event *caerPoint2DEvent; + +/** + * Point2D event packet data structure definition. + * EventPackets are always made up of the common packet header, + * followed by 'eventCapacity' events. Everything has to + * be in one contiguous memory block. + */ +struct caer_point2d_event_packet { + /// The common event packet header. + struct caer_event_packet_header packetHeader; + /// The events array. + struct caer_point2d_event events[]; +}__attribute__((__packed__)); + +/** + * Type for pointer to Point2D event packet data structure. + */ +typedef struct caer_point2d_event_packet *caerPoint2DEventPacket; + +/** + * Allocate a new Point2D events packet. + * Use free() to reclaim this memory. + * + * @param eventCapacity the maximum number of events this packet will hold. + * @param eventSource the unique ID representing the source/generator of this packet. + * @param tsOverflow the current timestamp overflow counter value for this packet. + * + * @return a valid Point2DEventPacket handle or NULL on error. + */ +caerPoint2DEventPacket caerPoint2DEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow); + +/** + * Get the Point2D event at the given index from the event packet. + * + * @param packet a valid Point2DEventPacket pointer. Cannot be NULL. + * @param n the index of the returned event. Must be within [0,eventCapacity[ bounds. + * + * @return the requested Point2D event. NULL on error. + */ +static inline caerPoint2DEvent caerPoint2DEventPacketGetEvent(caerPoint2DEventPacket packet, int32_t n) { + // Check that we're not out of bounds. + if (n < 0 || n >= caerEventPacketHeaderGetEventCapacity(&packet->packetHeader)) { + caerLog(CAER_LOG_CRITICAL, "Point2D Event", + "Called caerPoint2DEventPacketGetEvent() with invalid event offset %" PRIi32 ", while maximum allowed value is %" PRIi32 ".", + n, caerEventPacketHeaderGetEventCapacity(&packet->packetHeader) - 1); + return (NULL); + } + + // Return a pointer to the specified event. + return (packet->events + n); +} + +/** + * Get the 32bit event timestamp, in microseconds. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid Point2DEvent pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond timestamp. + */ +static inline int32_t caerPoint2DEventGetTimestamp(caerPoint2DEvent event) { + return (le32toh(event->timestamp)); +} + +/** + * Get the 64bit event timestamp, in microseconds. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid Point2DEvent pointer. Cannot be NULL. + * @param packet the Point2DEventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond timestamp. + */ +static inline int64_t caerPoint2DEventGetTimestamp64(caerPoint2DEvent event, caerPoint2DEventPacket packet) { + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(&packet->packetHeader)) << TS_OVERFLOW_SHIFT) | U64T(caerPoint2DEventGetTimestamp(event)))); +} + +/** + * Set the 32bit event timestamp, the value has to be in microseconds. + * + * @param event a valid Point2DEvent pointer. Cannot be NULL. + * @param timestamp a positive 32bit microsecond timestamp. + */ +static inline void caerPoint2DEventSetTimestamp(caerPoint2DEvent event, int32_t timestamp) { + if (timestamp < 0) { + // Negative means using the 31st bit! + caerLog(CAER_LOG_CRITICAL, "Point2D Event", "Called caerPoint2DEventSetTimestamp() with negative value!"); + return; + } + + event->timestamp = htole32(timestamp); +} + +/** + * Check if this Point2D event is valid. + * + * @param event a valid Point2DEvent pointer. Cannot be NULL. + * + * @return true if valid, false if not. + */ +static inline bool caerPoint2DEventIsValid(caerPoint2DEvent event) { + return (GET_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK)); +} + +/** + * Validate the current event by setting its valid bit to true + * and increasing the event packet's event count and valid + * event count. Only works on events that are invalid. + * DO NOT CALL THIS AFTER HAVING PREVIOUSLY ALREADY + * INVALIDATED THIS EVENT, the total count will be incorrect. + * + * @param event a valid Point2DEvent pointer. Cannot be NULL. + * @param packet the Point2DEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerPoint2DEventValidate(caerPoint2DEvent event, caerPoint2DEventPacket packet) { + if (!caerPoint2DEventIsValid(event)) { + SET_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK, 1); + + // Also increase number of events and valid events. + // Only call this on (still) invalid events! + caerEventPacketHeaderSetEventNumber(&packet->packetHeader, + caerEventPacketHeaderGetEventNumber(&packet->packetHeader) + 1); + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) + 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Point2D Event", "Called caerPoint2DEventValidate() on already valid event."); + } +} + +/** + * Invalidate the current event by setting its valid bit + * to false and decreasing the number of valid events held + * in the packet. Only works with events that are already + * valid! + * + * @param event a valid Point2DEvent pointer. Cannot be NULL. + * @param packet the Point2DEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerPoint2DEventInvalidate(caerPoint2DEvent event, caerPoint2DEventPacket packet) { + if (caerPoint2DEventIsValid(event)) { + CLEAR_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK); + + // Also decrease number of valid events. Number of total events doesn't change. + // Only call this on valid events! + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) - 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Point2D Event", "Called caerPoint2DEventInvalidate() on already invalid event."); + } +} + +/** + * Get the measurement event type. This is useful to distinguish + * between different measurements, for example distance or weight. + * + * @param event a valid Point2DEvent pointer. Cannot be NULL. + * + * @return the Point2D measurement type. + */ +static inline uint8_t caerPoint2DEventGetType(caerPoint2DEvent event) { + return U8T(GET_NUMBITS32(event->info, POINT2D_TYPE_SHIFT, POINT2D_TYPE_MASK)); +} + +/** + * Set the measurement event type. This is useful to distinguish + * between different measurements, for example distance or weight. + * + * @param event a valid Point2DEvent pointer. Cannot be NULL. + * @param type the Point2D measurement type. + */ +static inline void caerPoint2DEventSetType(caerPoint2DEvent event, uint8_t type) { + CLEAR_NUMBITS32(event->info, POINT2D_TYPE_SHIFT, POINT2D_TYPE_MASK); + SET_NUMBITS32(event->info, POINT2D_TYPE_SHIFT, POINT2D_TYPE_MASK, type); +} + +/** + * Get the measurement scale. This allows order of magnitude shifts + * on the measured value to be applied automatically, such as having + * measurements of type Distance (meters) and storing the values as + * centimeters (10^-2) for higher precision, but keeping that information + * around to allow easy changes of unit. + * + * @param event a valid Point2DEvent pointer. Cannot be NULL. + * + * @return the Point2D measurement scale. + */ +static inline int8_t caerPoint2DEventGetScale(caerPoint2DEvent event) { + return I8T(GET_NUMBITS32(event->info, POINT2D_SCALE_SHIFT, POINT2D_SCALE_MASK)); +} + +/** + * Set the measurement scale. This allows order of magnitude shifts + * on the measured value to be applied automatically, such as having + * measurements of type Distance (meters) and storing the values as + * centimeters (10^-2) for higher precision, but keeping that information + * around to allow easy changes of unit. + * + * @param event a valid Point2DEvent pointer. Cannot be NULL. + * @param scale the Point2D measurement scale. + */ +static inline void caerPoint2DEventSetScale(caerPoint2DEvent event, int8_t scale) { + CLEAR_NUMBITS32(event->info, POINT2D_SCALE_SHIFT, POINT2D_SCALE_MASK); + SET_NUMBITS32(event->info, POINT2D_SCALE_SHIFT, POINT2D_SCALE_MASK, U8T(scale)); +} + +/** + * Get the X axis measurement. + * + * @param event a valid Point2DEvent pointer. Cannot be NULL. + * + * @return X axis measurement. + */ +static inline float caerPoint2DEventGetX(caerPoint2DEvent event) { + return (le32toh(event->x)); +} + +/** + * Set the X axis measurement. + * + * @param event a valid Point2DEvent pointer. Cannot be NULL. + * @param x X axis measurement. + */ +static inline void caerPoint2DEventSetX(caerPoint2DEvent event, float x) { + event->x = htole32(x); +} + +/** + * Get the Y axis measurement. + * + * @param event a valid Point2DEvent pointer. Cannot be NULL. + * + * @return Y axis measurement. + */ +static inline float caerPoint2DEventGetY(caerPoint2DEvent event) { + return (le32toh(event->y)); +} + +/** + * Set the Y axis measurement. + * + * @param event a valid Point2DEvent pointer. Cannot be NULL. + * @param y Y axis measurement. + */ +static inline void caerPoint2DEventSetY(caerPoint2DEvent event, float y) { + event->y = htole32(y); +} + +/** + * Iterator over all Point2D events in a packet. + * Returns the current index in the 'caerPoint2DIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerPoint2DIteratorElement' variable + * of type caerPoint2DEvent. + * + * POINT2D_PACKET: a valid Point2DEventPacket pointer. Cannot be NULL. + */ +#define CAER_POINT2D_ITERATOR_ALL_START(POINT2D_PACKET) \ + for (int32_t caerPoint2DIteratorCounter = 0; \ + caerPoint2DIteratorCounter < caerEventPacketHeaderGetEventNumber(&(POINT2D_PACKET)->packetHeader); \ + caerPoint2DIteratorCounter++) { \ + caerPoint2DEvent caerPoint2DIteratorElement = caerPoint2DEventPacketGetEvent(POINT2D_PACKET, caerPoint2DIteratorCounter); + +/** + * Iterator close statement. + */ +#define CAER_POINT2D_ITERATOR_ALL_END } + +/** + * Iterator over only the valid Point2D events in a packet. + * Returns the current index in the 'caerPoint2DIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerPoint2DIteratorElement' variable + * of type caerPoint2DEvent. + * + * POINT2D_PACKET: a valid Point2DEventPacket pointer. Cannot be NULL. + */ +#define CAER_POINT2D_ITERATOR_VALID_START(POINT2D_PACKET) \ + for (int32_t caerPoint2DIteratorCounter = 0; \ + caerPoint2DIteratorCounter < caerEventPacketHeaderGetEventNumber(&(POINT2D_PACKET)->packetHeader); \ + caerPoint2DIteratorCounter++) { \ + caerPoint2DEvent caerPoint2DIteratorElement = caerPoint2DEventPacketGetEvent(POINT2D_PACKET, caerPoint2DIteratorCounter); \ + if (!caerPoint2DEventIsValid(caerPoint2DIteratorElement)) { continue; } // Skip invalid Point2D events. + +/** + * Iterator close statement. + */ +#define CAER_POINT2D_ITERATOR_VALID_END } + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_EVENTS_POINT2D_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point3d.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point3d.h new file mode 100755 index 0000000..a86cc6a --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point3d.h @@ -0,0 +1,381 @@ +/** + * @file point3d.h + * + * THIS EVENT DEFINITIONS IS STILL TO BE CONSIDERED EXPERIMENTAL + * AND IS SUBJECT TO FUTURE CHANGES AND REVISIONS! + * + * Point3D Events format definition and handling functions. + * This contains three dimensional data points as floats, + * together with support for distinguishing type and scale. + */ + +#ifndef LIBCAER_EVENTS_POINT3D_H_ +#define LIBCAER_EVENTS_POINT3D_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "common.h" + +/** + * Shift and mask values for type and scale information + * associated with a Point3D event. + * Up to 128 types are supported. The scale is given as orders + * of magnitude, from 10^-128 to 10^127. + * Bit 0 is the valid mark, see 'common.h' for more details. + */ +//@{ +#define POINT3D_TYPE_SHIFT 1 +#define POINT3D_TYPE_MASK 0x0000007F +#define POINT3D_SCALE_SHIFT 8 +#define POINT3D_SCALE_MASK 0x000000FF +//@} + +/** + * Point3D event data structure definition. + * This contains information about the measurement, such as a type + * and a scale field, together with the usual validity mark. + * The three measurements (x, y, z) are stored as floats. + * Floats are in IEEE 754-2008 binary32 format. + * Signed integers are used for fields that are to be interpreted + * directly, for compatibility with languages that do not have + * unsigned integer types, such as Java. + */ +struct caer_point3d_event { + /// Event information. First because of valid mark. + uint32_t info; + /// X axis measurement. + float x; + /// Y axis measurement. + float y; + /// Z axis measurement. + float z; + /// Event timestamp. + int32_t timestamp; +}__attribute__((__packed__)); + +/** + * Type for pointer to Point3D event data structure. + */ +typedef struct caer_point3d_event *caerPoint3DEvent; + +/** + * Point3D event packet data structure definition. + * EventPackets are always made up of the common packet header, + * followed by 'eventCapacity' events. Everything has to + * be in one contiguous memory block. + */ +struct caer_point3d_event_packet { + /// The common event packet header. + struct caer_event_packet_header packetHeader; + /// The events array. + struct caer_point3d_event events[]; +}__attribute__((__packed__)); + +/** + * Type for pointer to Point3D event packet data structure. + */ +typedef struct caer_point3d_event_packet *caerPoint3DEventPacket; + +/** + * Allocate a new Point3D events packet. + * Use free() to reclaim this memory. + * + * @param eventCapacity the maximum number of events this packet will hold. + * @param eventSource the unique ID representing the source/generator of this packet. + * @param tsOverflow the current timestamp overflow counter value for this packet. + * + * @return a valid Point3DEventPacket handle or NULL on error. + */ +caerPoint3DEventPacket caerPoint3DEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow); + +/** + * Get the Point3D event at the given index from the event packet. + * + * @param packet a valid Point3DEventPacket pointer. Cannot be NULL. + * @param n the index of the returned event. Must be within [0,eventCapacity[ bounds. + * + * @return the requested Point3D event. NULL on error. + */ +static inline caerPoint3DEvent caerPoint3DEventPacketGetEvent(caerPoint3DEventPacket packet, int32_t n) { + // Check that we're not out of bounds. + if (n < 0 || n >= caerEventPacketHeaderGetEventCapacity(&packet->packetHeader)) { + caerLog(CAER_LOG_CRITICAL, "Point3D Event", + "Called caerPoint3DEventPacketGetEvent() with invalid event offset %" PRIi32 ", while maximum allowed value is %" PRIi32 ".", + n, caerEventPacketHeaderGetEventCapacity(&packet->packetHeader) - 1); + return (NULL); + } + + // Return a pointer to the specified event. + return (packet->events + n); +} + +/** + * Get the 32bit event timestamp, in microseconds. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond timestamp. + */ +static inline int32_t caerPoint3DEventGetTimestamp(caerPoint3DEvent event) { + return (le32toh(event->timestamp)); +} + +/** + * Get the 64bit event timestamp, in microseconds. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * @param packet the Point3DEventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond timestamp. + */ +static inline int64_t caerPoint3DEventGetTimestamp64(caerPoint3DEvent event, caerPoint3DEventPacket packet) { + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(&packet->packetHeader)) << TS_OVERFLOW_SHIFT) | U64T(caerPoint3DEventGetTimestamp(event)))); +} + +/** + * Set the 32bit event timestamp, the value has to be in microseconds. + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * @param timestamp a positive 32bit microsecond timestamp. + */ +static inline void caerPoint3DEventSetTimestamp(caerPoint3DEvent event, int32_t timestamp) { + if (timestamp < 0) { + // Negative means using the 31st bit! + caerLog(CAER_LOG_CRITICAL, "Point3D Event", "Called caerPoint3DEventSetTimestamp() with negative value!"); + return; + } + + event->timestamp = htole32(timestamp); +} + +/** + * Check if this Point3D event is valid. + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * + * @return true if valid, false if not. + */ +static inline bool caerPoint3DEventIsValid(caerPoint3DEvent event) { + return (GET_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK)); +} + +/** + * Validate the current event by setting its valid bit to true + * and increasing the event packet's event count and valid + * event count. Only works on events that are invalid. + * DO NOT CALL THIS AFTER HAVING PREVIOUSLY ALREADY + * INVALIDATED THIS EVENT, the total count will be incorrect. + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * @param packet the Point3DEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerPoint3DEventValidate(caerPoint3DEvent event, caerPoint3DEventPacket packet) { + if (!caerPoint3DEventIsValid(event)) { + SET_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK, 1); + + // Also increase number of events and valid events. + // Only call this on (still) invalid events! + caerEventPacketHeaderSetEventNumber(&packet->packetHeader, + caerEventPacketHeaderGetEventNumber(&packet->packetHeader) + 1); + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) + 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Point3D Event", "Called caerPoint3DEventValidate() on already valid event."); + } +} + +/** + * Invalidate the current event by setting its valid bit + * to false and decreasing the number of valid events held + * in the packet. Only works with events that are already + * valid! + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * @param packet the Point3DEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerPoint3DEventInvalidate(caerPoint3DEvent event, caerPoint3DEventPacket packet) { + if (caerPoint3DEventIsValid(event)) { + CLEAR_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK); + + // Also decrease number of valid events. Number of total events doesn't change. + // Only call this on valid events! + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) - 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Point3D Event", "Called caerPoint3DEventInvalidate() on already invalid event."); + } +} + +/** + * Get the measurement event type. This is useful to distinguish + * between different measurements, for example distance or weight. + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * + * @return the Point3D measurement type. + */ +static inline uint8_t caerPoint3DEventGetType(caerPoint3DEvent event) { + return U8T(GET_NUMBITS32(event->info, POINT3D_TYPE_SHIFT, POINT3D_TYPE_MASK)); +} + +/** + * Set the measurement event type. This is useful to distinguish + * between different measurements, for example distance or weight. + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * @param type the Point3D measurement type. + */ +static inline void caerPoint3DEventSetType(caerPoint3DEvent event, uint8_t type) { + CLEAR_NUMBITS32(event->info, POINT3D_TYPE_SHIFT, POINT3D_TYPE_MASK); + SET_NUMBITS32(event->info, POINT3D_TYPE_SHIFT, POINT3D_TYPE_MASK, type); +} + +/** + * Get the measurement scale. This allows order of magnitude shifts + * on the measured value to be applied automatically, such as having + * measurements of type Distance (meters) and storing the values as + * centimeters (10^-2) for higher precision, but keeping that information + * around to allow easy changes of unit. + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * + * @return the Point3D measurement scale. + */ +static inline int8_t caerPoint3DEventGetScale(caerPoint3DEvent event) { + return I8T(GET_NUMBITS32(event->info, POINT3D_SCALE_SHIFT, POINT3D_SCALE_MASK)); +} + +/** + * Set the measurement scale. This allows order of magnitude shifts + * on the measured value to be applied automatically, such as having + * measurements of type Distance (meters) and storing the values as + * centimeters (10^-2) for higher precision, but keeping that information + * around to allow easy changes of unit. + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * @param scale the Point3D measurement scale. + */ +static inline void caerPoint3DEventSetScale(caerPoint3DEvent event, int8_t scale) { + CLEAR_NUMBITS32(event->info, POINT3D_SCALE_SHIFT, POINT3D_SCALE_MASK); + SET_NUMBITS32(event->info, POINT3D_SCALE_SHIFT, POINT3D_SCALE_MASK, U8T(scale)); +} + +/** + * Get the X axis measurement. + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * + * @return X axis measurement. + */ +static inline float caerPoint3DEventGetX(caerPoint3DEvent event) { + return (le32toh(event->x)); +} + +/** + * Set the X axis measurement. + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * @param x X axis measurement. + */ +static inline void caerPoint3DEventSetX(caerPoint3DEvent event, float x) { + event->x = htole32(x); +} + +/** + * Get the Y axis measurement. + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * + * @return Y axis measurement. + */ +static inline float caerPoint3DEventGetY(caerPoint3DEvent event) { + return (le32toh(event->y)); +} + +/** + * Set the Y axis measurement. + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * @param y Y axis measurement. + */ +static inline void caerPoint3DEventSetY(caerPoint3DEvent event, float y) { + event->y = htole32(y); +} + +/** + * Get the Z axis measurement. + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * + * @return Z axis measurement. + */ +static inline float caerPoint3DEventGetZ(caerPoint3DEvent event) { + return (le32toh(event->z)); +} + +/** + * Set the Z axis measurement. + * + * @param event a valid Point3DEvent pointer. Cannot be NULL. + * @param z Z axis measurement. + */ +static inline void caerPoint3DEventSetZ(caerPoint3DEvent event, float z) { + event->z = htole32(z); +} + +/** + * Iterator over all Point3D events in a packet. + * Returns the current index in the 'caerPoint3DIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerPoint3DIteratorElement' variable + * of type caerPoint3DEvent. + * + * POINT3D_PACKET: a valid Point3DEventPacket pointer. Cannot be NULL. + */ +#define CAER_POINT3D_ITERATOR_ALL_START(POINT3D_PACKET) \ + for (int32_t caerPoint3DIteratorCounter = 0; \ + caerPoint3DIteratorCounter < caerEventPacketHeaderGetEventNumber(&(POINT3D_PACKET)->packetHeader); \ + caerPoint3DIteratorCounter++) { \ + caerPoint3DEvent caerPoint3DIteratorElement = caerPoint3DEventPacketGetEvent(POINT3D_PACKET, caerPoint3DIteratorCounter); + +/** + * Iterator close statement. + */ +#define CAER_POINT3D_ITERATOR_ALL_END } + +/** + * Iterator over only the valid Point3D events in a packet. + * Returns the current index in the 'caerPoint3DIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerPoint3DIteratorElement' variable + * of type caerPoint3DEvent. + * + * POINT3D_PACKET: a valid Point3DEventPacket pointer. Cannot be NULL. + */ +#define CAER_POINT3D_ITERATOR_VALID_START(POINT3D_PACKET) \ + for (int32_t caerPoint3DIteratorCounter = 0; \ + caerPoint3DIteratorCounter < caerEventPacketHeaderGetEventNumber(&(POINT3D_PACKET)->packetHeader); \ + caerPoint3DIteratorCounter++) { \ + caerPoint3DEvent caerPoint3DIteratorElement = caerPoint3DEventPacketGetEvent(POINT3D_PACKET, caerPoint3DIteratorCounter); \ + if (!caerPoint3DEventIsValid(caerPoint3DIteratorElement)) { continue; } // Skip invalid Point3D events. + +/** + * Iterator close statement. + */ +#define CAER_POINT3D_ITERATOR_VALID_END } + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_EVENTS_POINT3D_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point4d.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point4d.h new file mode 100755 index 0000000..2c11575 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/point4d.h @@ -0,0 +1,405 @@ +/** + * @file point4d.h + * + * THIS EVENT DEFINITION IS STILL TO BE CONSIDERED EXPERIMENTAL + * AND IS SUBJECT TO FUTURE CHANGES AND REVISIONS! + * + * Point4D Events format definition and handling functions. + * This contains four dimensional data points as floats, + * together with support for distinguishing type and scale. + * Useful for homogeneous coordinates for example. + */ + +#ifndef LIBCAER_EVENTS_POINT4D_H_ +#define LIBCAER_EVENTS_POINT4D_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "common.h" + +/** + * Shift and mask values for type and scale information + * associated with a Point4D event. + * Up to 128 types are supported. The scale is given as orders + * of magnitude, from 10^-128 to 10^127. + * Bit 0 is the valid mark, see 'common.h' for more details. + */ +//@{ +#define POINT4D_TYPE_SHIFT 1 +#define POINT4D_TYPE_MASK 0x0000007F +#define POINT4D_SCALE_SHIFT 8 +#define POINT4D_SCALE_MASK 0x000000FF +//@} + +/** + * Point4D event data structure definition. + * This contains information about the measurement, such as a type + * and a scale field, together with the usual validity mark. + * The four measurements (x, y, z, w) are stored as floats. + * Floats are in IEEE 754-2008 binary32 format. + * Signed integers are used for fields that are to be interpreted + * directly, for compatibility with languages that do not have + * unsigned integer types, such as Java. + */ +struct caer_point4d_event { + /// Event information. First because of valid mark. + uint32_t info; + /// X axis measurement. + float x; + /// Y axis measurement. + float y; + /// Z axis measurement. + float z; + /// W axis measurement. + float w; + /// Event timestamp. + int32_t timestamp; +}__attribute__((__packed__)); + +/** + * Type for pointer to Point4D event data structure. + */ +typedef struct caer_point4d_event *caerPoint4DEvent; + +/** + * Point4D event packet data structure definition. + * EventPackets are always made up of the common packet header, + * followed by 'eventCapacity' events. Everything has to + * be in one contiguous memory block. + */ +struct caer_point4d_event_packet { + /// The common event packet header. + struct caer_event_packet_header packetHeader; + /// The events array. + struct caer_point4d_event events[]; +}__attribute__((__packed__)); + +/** + * Type for pointer to Point4D event packet data structure. + */ +typedef struct caer_point4d_event_packet *caerPoint4DEventPacket; + +/** + * Allocate a new Point4D events packet. + * Use free() to reclaim this memory. + * + * @param eventCapacity the maximum number of events this packet will hold. + * @param eventSource the unique ID representing the source/generator of this packet. + * @param tsOverflow the current timestamp overflow counter value for this packet. + * + * @return a valid Point4DEventPacket handle or NULL on error. + */ +caerPoint4DEventPacket caerPoint4DEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow); + +/** + * Get the Point4D event at the given index from the event packet. + * + * @param packet a valid Point4DEventPacket pointer. Cannot be NULL. + * @param n the index of the returned event. Must be within [0,eventCapacity[ bounds. + * + * @return the requested Point4D event. NULL on error. + */ +static inline caerPoint4DEvent caerPoint4DEventPacketGetEvent(caerPoint4DEventPacket packet, int32_t n) { + // Check that we're not out of bounds. + if (n < 0 || n >= caerEventPacketHeaderGetEventCapacity(&packet->packetHeader)) { + caerLog(CAER_LOG_CRITICAL, "Point4D Event", + "Called caerPoint4DEventPacketGetEvent() with invalid event offset %" PRIi32 ", while maximum allowed value is %" PRIi32 ".", + n, caerEventPacketHeaderGetEventCapacity(&packet->packetHeader) - 1); + return (NULL); + } + + // Return a pointer to the specified event. + return (packet->events + n); +} + +/** + * Get the 32bit event timestamp, in microseconds. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond timestamp. + */ +static inline int32_t caerPoint4DEventGetTimestamp(caerPoint4DEvent event) { + return (le32toh(event->timestamp)); +} + +/** + * Get the 64bit event timestamp, in microseconds. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * @param packet the Point4DEventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond timestamp. + */ +static inline int64_t caerPoint4DEventGetTimestamp64(caerPoint4DEvent event, caerPoint4DEventPacket packet) { + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(&packet->packetHeader)) << TS_OVERFLOW_SHIFT) | U64T(caerPoint4DEventGetTimestamp(event)))); +} + +/** + * Set the 32bit event timestamp, the value has to be in microseconds. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * @param timestamp a positive 32bit microsecond timestamp. + */ +static inline void caerPoint4DEventSetTimestamp(caerPoint4DEvent event, int32_t timestamp) { + if (timestamp < 0) { + // Negative means using the 31st bit! + caerLog(CAER_LOG_CRITICAL, "Point4D Event", "Called caerPoint4DEventSetTimestamp() with negative value!"); + return; + } + + event->timestamp = htole32(timestamp); +} + +/** + * Check if this Point4D event is valid. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * + * @return true if valid, false if not. + */ +static inline bool caerPoint4DEventIsValid(caerPoint4DEvent event) { + return (GET_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK)); +} + +/** + * Validate the current event by setting its valid bit to true + * and increasing the event packet's event count and valid + * event count. Only works on events that are invalid. + * DO NOT CALL THIS AFTER HAVING PREVIOUSLY ALREADY + * INVALIDATED THIS EVENT, the total count will be incorrect. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * @param packet the Point4DEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerPoint4DEventValidate(caerPoint4DEvent event, caerPoint4DEventPacket packet) { + if (!caerPoint4DEventIsValid(event)) { + SET_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK, 1); + + // Also increase number of events and valid events. + // Only call this on (still) invalid events! + caerEventPacketHeaderSetEventNumber(&packet->packetHeader, + caerEventPacketHeaderGetEventNumber(&packet->packetHeader) + 1); + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) + 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Point4D Event", "Called caerPoint4DEventValidate() on already valid event."); + } +} + +/** + * Invalidate the current event by setting its valid bit + * to false and decreasing the number of valid events held + * in the packet. Only works with events that are already + * valid! + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * @param packet the Point4DEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerPoint4DEventInvalidate(caerPoint4DEvent event, caerPoint4DEventPacket packet) { + if (caerPoint4DEventIsValid(event)) { + CLEAR_NUMBITS32(event->info, VALID_MARK_SHIFT, VALID_MARK_MASK); + + // Also decrease number of valid events. Number of total events doesn't change. + // Only call this on valid events! + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) - 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Point4D Event", "Called caerPoint4DEventInvalidate() on already invalid event."); + } +} + +/** + * Get the measurement event type. This is useful to distinguish + * between different measurements, for example distance or weight. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * + * @return the Point4D measurement type. + */ +static inline uint8_t caerPoint4DEventGetType(caerPoint4DEvent event) { + return U8T(GET_NUMBITS32(event->info, POINT4D_TYPE_SHIFT, POINT4D_TYPE_MASK)); +} + +/** + * Set the measurement event type. This is useful to distinguish + * between different measurements, for example distance or weight. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * @param type the Point4D measurement type. + */ +static inline void caerPoint4DEventSetType(caerPoint4DEvent event, uint8_t type) { + CLEAR_NUMBITS32(event->info, POINT4D_TYPE_SHIFT, POINT4D_TYPE_MASK); + SET_NUMBITS32(event->info, POINT4D_TYPE_SHIFT, POINT4D_TYPE_MASK, type); +} + +/** + * Get the measurement scale. This allows order of magnitude shifts + * on the measured value to be applied automatically, such as having + * measurements of type Distance (meters) and storing the values as + * centimeters (10^-2) for higher precision, but keeping that information + * around to allow easy changes of unit. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * + * @return the Point4D measurement scale. + */ +static inline int8_t caerPoint4DEventGetScale(caerPoint4DEvent event) { + return I8T(GET_NUMBITS32(event->info, POINT4D_SCALE_SHIFT, POINT4D_SCALE_MASK)); +} + +/** + * Set the measurement scale. This allows order of magnitude shifts + * on the measured value to be applied automatically, such as having + * measurements of type Distance (meters) and storing the values as + * centimeters (10^-2) for higher precision, but keeping that information + * around to allow easy changes of unit. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * @param scale the Point4D measurement scale. + */ +static inline void caerPoint4DEventSetScale(caerPoint4DEvent event, int8_t scale) { + CLEAR_NUMBITS32(event->info, POINT4D_SCALE_SHIFT, POINT4D_SCALE_MASK); + SET_NUMBITS32(event->info, POINT4D_SCALE_SHIFT, POINT4D_SCALE_MASK, U8T(scale)); +} + +/** + * Get the X axis measurement. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * + * @return X axis measurement. + */ +static inline float caerPoint4DEventGetX(caerPoint4DEvent event) { + return (le32toh(event->x)); +} + +/** + * Set the X axis measurement. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * @param x X axis measurement. + */ +static inline void caerPoint4DEventSetX(caerPoint4DEvent event, float x) { + event->x = htole32(x); +} + +/** + * Get the Y axis measurement. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * + * @return Y axis measurement. + */ +static inline float caerPoint4DEventGetY(caerPoint4DEvent event) { + return (le32toh(event->y)); +} + +/** + * Set the Y axis measurement. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * @param y Y axis measurement. + */ +static inline void caerPoint4DEventSetY(caerPoint4DEvent event, float y) { + event->y = htole32(y); +} + +/** + * Get the Z axis measurement. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * + * @return Z axis measurement. + */ +static inline float caerPoint4DEventGetZ(caerPoint4DEvent event) { + return (le32toh(event->z)); +} + +/** + * Set the Z axis measurement. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * @param z Z axis measurement. + */ +static inline void caerPoint4DEventSetZ(caerPoint4DEvent event, float z) { + event->z = htole32(z); +} + +/** + * Get the W axis measurement. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * + * @return W axis measurement. + */ +static inline float caerPoint4DEventGetW(caerPoint4DEvent event) { + return (le32toh(event->w)); +} + +/** + * Set the W axis measurement. + * + * @param event a valid Point4DEvent pointer. Cannot be NULL. + * @param w W axis measurement. + */ +static inline void caerPoint4DEventSetW(caerPoint4DEvent event, float w) { + event->w = htole32(w); +} + +/** + * Iterator over all Point4D events in a packet. + * Returns the current index in the 'caerPoint4DIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerPoint4DIteratorElement' variable + * of type caerPoint4DEvent. + * + * POINT4D_PACKET: a valid Point4DEventPacket pointer. Cannot be NULL. + */ +#define CAER_POINT4D_ITERATOR_ALL_START(POINT4D_PACKET) \ + for (int32_t caerPoint4DIteratorCounter = 0; \ + caerPoint4DIteratorCounter < caerEventPacketHeaderGetEventNumber(&(POINT4D_PACKET)->packetHeader); \ + caerPoint4DIteratorCounter++) { \ + caerPoint4DEvent caerPoint4DIteratorElement = caerPoint4DEventPacketGetEvent(POINT4D_PACKET, caerPoint4DIteratorCounter); + +/** + * Iterator close statement. + */ +#define CAER_POINT4D_ITERATOR_ALL_END } + +/** + * Iterator over only the valid Point4D events in a packet. + * Returns the current index in the 'caerPoint4DIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerPoint4DIteratorElement' variable + * of type caerPoint4DEvent. + * + * POINT4D_PACKET: a valid Point4DEventPacket pointer. Cannot be NULL. + */ +#define CAER_POINT4D_ITERATOR_VALID_START(POINT4D_PACKET) \ + for (int32_t caerPoint4DIteratorCounter = 0; \ + caerPoint4DIteratorCounter < caerEventPacketHeaderGetEventNumber(&(POINT4D_PACKET)->packetHeader); \ + caerPoint4DIteratorCounter++) { \ + caerPoint4DEvent caerPoint4DIteratorElement = caerPoint4DEventPacketGetEvent(POINT4D_PACKET, caerPoint4DIteratorCounter); \ + if (!caerPoint4DEventIsValid(caerPoint4DIteratorElement)) { continue; } // Skip invalid Point4D events. + +/** + * Iterator close statement. + */ +#define CAER_POINT4D_ITERATOR_VALID_END } + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_EVENTS_POINT4D_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/polarity.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/polarity.h new file mode 100755 index 0000000..392554a --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/polarity.h @@ -0,0 +1,367 @@ +/** + * @file polarity.h + * + * Polarity Events format definition and handling functions. + * This event contains change information, with an X/Y address + * and an ON/OFF polarity. + * The (0, 0) address is in the upper left corner of the screen, + * like in OpenCV/computer graphics. + */ + +#ifndef LIBCAER_EVENTS_POLARITY_H_ +#define LIBCAER_EVENTS_POLARITY_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "common.h" + +/** + * Shift and mask values for the polarity, X and Y addresses + * of a polarity event. + * Addresses up to 14 bit are supported. Polarity is ON(=1) or OFF(=0). + * Bit 0 is the valid mark, see 'common.h' for more details. + */ +//@{ +#define POLARITY_SHIFT 1 +#define POLARITY_MASK 0x00000001 +#define Y_ADDR_SHIFT 2 +#define Y_ADDR_MASK 0x00007FFF +#define X_ADDR_SHIFT 17 +#define X_ADDR_MASK 0x00007FFF +//@} + +/** + * Polarity event data structure definition. + * This contains the actual X/Y addresses, the polarity, + * as well as the 32 bit event timestamp. + * The (0, 0) address is in the upper left corner of the screen, + * like in OpenCV/computer graphics. + * Signed integers are used for fields that are to be interpreted + * directly, for compatibility with languages that do not have + * unsigned integer types, such as Java. + */ +struct caer_polarity_event { + /// Event data. First because of valid mark. + uint32_t data; + /// Event timestamp. + int32_t timestamp; +}__attribute__((__packed__)); + +/** + * Type for pointer to polarity event data structure. + */ +typedef struct caer_polarity_event *caerPolarityEvent; + +/** + * Polarity event packet data structure definition. + * EventPackets are always made up of the common packet header, + * followed by 'eventCapacity' events. Everything has to + * be in one contiguous memory block. + */ +struct caer_polarity_event_packet { + /// The common event packet header. + struct caer_event_packet_header packetHeader; + /// The events array. + struct caer_polarity_event events[]; +}__attribute__((__packed__)); + +/** + * Type for pointer to polarity event packet data structure. + */ +typedef struct caer_polarity_event_packet *caerPolarityEventPacket; + +/** + * Allocate a new polarity events packet. + * Use free() to reclaim this memory. + * + * @param eventCapacity the maximum number of events this packet will hold. + * @param eventSource the unique ID representing the source/generator of this packet. + * @param tsOverflow the current timestamp overflow counter value for this packet. + * + * @return a valid PolarityEventPacket handle or NULL on error. + */ +caerPolarityEventPacket caerPolarityEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow); + +/** + * Get the polarity event at the given index from the event packet. + * + * @param packet a valid PolarityEventPacket pointer. Cannot be NULL. + * @param n the index of the returned event. Must be within [0,eventCapacity[ bounds. + * + * @return the requested polarity event. NULL on error. + */ +static inline caerPolarityEvent caerPolarityEventPacketGetEvent(caerPolarityEventPacket packet, int32_t n) { + // Check that we're not out of bounds. + if (n < 0 || n >= caerEventPacketHeaderGetEventCapacity(&packet->packetHeader)) { + caerLog(CAER_LOG_CRITICAL, "Polarity Event", + "Called caerPolarityEventPacketGetEvent() with invalid event offset %" PRIi32 ", while maximum allowed value is %" PRIi32 ".", + n, caerEventPacketHeaderGetEventCapacity(&packet->packetHeader) - 1); + return (NULL); + } + + // Return a pointer to the specified event. + return (packet->events + n); +} + +/** + * Get the 32bit event timestamp, in microseconds. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid PolarityEvent pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond timestamp. + */ +static inline int32_t caerPolarityEventGetTimestamp(caerPolarityEvent event) { + return (le32toh(event->timestamp)); +} + +/** + * Get the 64bit event timestamp, in microseconds. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid PolarityEvent pointer. Cannot be NULL. + * @param packet the PolarityEventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond timestamp. + */ +static inline int64_t caerPolarityEventGetTimestamp64(caerPolarityEvent event, caerPolarityEventPacket packet) { + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(&packet->packetHeader)) << TS_OVERFLOW_SHIFT) | U64T(caerPolarityEventGetTimestamp(event)))); +} + +/** + * Set the 32bit event timestamp, the value has to be in microseconds. + * + * @param event a valid PolarityEvent pointer. Cannot be NULL. + * @param timestamp a positive 32bit microsecond timestamp. + */ +static inline void caerPolarityEventSetTimestamp(caerPolarityEvent event, int32_t timestamp) { + if (timestamp < 0) { + // Negative means using the 31st bit! + caerLog(CAER_LOG_CRITICAL, "Polarity Event", "Called caerPolarityEventSetTimestamp() with negative value!"); + return; + } + + event->timestamp = htole32(timestamp); +} + +/** + * Check if this polarity event is valid. + * + * @param event a valid PolarityEvent pointer. Cannot be NULL. + * + * @return true if valid, false if not. + */ +static inline bool caerPolarityEventIsValid(caerPolarityEvent event) { + return (GET_NUMBITS32(event->data, VALID_MARK_SHIFT, VALID_MARK_MASK)); +} + +/** + * Validate the current event by setting its valid bit to true + * and increasing the event packet's event count and valid + * event count. Only works on events that are invalid. + * DO NOT CALL THIS AFTER HAVING PREVIOUSLY ALREADY + * INVALIDATED THIS EVENT, the total count will be incorrect. + * + * @param event a valid PolarityEvent pointer. Cannot be NULL. + * @param packet the PolarityEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerPolarityEventValidate(caerPolarityEvent event, caerPolarityEventPacket packet) { + if (!caerPolarityEventIsValid(event)) { + SET_NUMBITS32(event->data, VALID_MARK_SHIFT, VALID_MARK_MASK, 1); + + // Also increase number of events and valid events. + // Only call this on (still) invalid events! + caerEventPacketHeaderSetEventNumber(&packet->packetHeader, + caerEventPacketHeaderGetEventNumber(&packet->packetHeader) + 1); + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) + 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Polarity Event", "Called caerPolarityEventValidate() on already valid event."); + } +} + +/** + * Invalidate the current event by setting its valid bit + * to false and decreasing the number of valid events held + * in the packet. Only works with events that are already + * valid! + * + * @param event a valid PolarityEvent pointer. Cannot be NULL. + * @param packet the PolarityEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerPolarityEventInvalidate(caerPolarityEvent event, caerPolarityEventPacket packet) { + if (caerPolarityEventIsValid(event)) { + CLEAR_NUMBITS32(event->data, VALID_MARK_SHIFT, VALID_MARK_MASK); + + // Also decrease number of valid events. Number of total events doesn't change. + // Only call this on valid events! + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) - 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Polarity Event", "Called caerPolarityEventInvalidate() on already invalid event."); + } +} + +/** + * Get the change event polarity. 1 is ON, 0 is OFF. + * + * @param event a valid PolarityEvent pointer. Cannot be NULL. + * + * @return event polarity value. + */ +static inline bool caerPolarityEventGetPolarity(caerPolarityEvent event) { + return (GET_NUMBITS32(event->data, POLARITY_SHIFT, POLARITY_MASK)); +} + +/** + * Set the change event polarity. 1 is ON, 0 is OFF. + * + * @param event a valid PolarityEvent pointer. Cannot be NULL. + * @param polarity event polarity value. + */ +static inline void caerPolarityEventSetPolarity(caerPolarityEvent event, bool polarity) { + CLEAR_NUMBITS32(event->data, POLARITY_SHIFT, POLARITY_MASK); + SET_NUMBITS32(event->data, POLARITY_SHIFT, POLARITY_MASK, polarity); +} + +/** + * Get the Y (row) address for a change event, in pixels. + * The (0, 0) address is in the upper left corner, like in OpenCV/computer graphics. + * + * @param event a valid PolarityEvent pointer. Cannot be NULL. + * + * @return the event Y address. + */ +static inline uint16_t caerPolarityEventGetY(caerPolarityEvent event) { + return U16T(GET_NUMBITS32(event->data, Y_ADDR_SHIFT, Y_ADDR_MASK)); +} + +/** + * Set the Y (row) address for a change event, in pixels. + * The (0, 0) address is in the upper left corner, like in OpenCV/computer graphics. + * + * @param event a valid PolarityEvent pointer. Cannot be NULL. + * @param yAddress the event Y address. + */ +static inline void caerPolarityEventSetY(caerPolarityEvent event, uint16_t yAddress) { + CLEAR_NUMBITS32(event->data, Y_ADDR_SHIFT, Y_ADDR_MASK); + SET_NUMBITS32(event->data, Y_ADDR_SHIFT, Y_ADDR_MASK, yAddress); +} + +/** + * Get the X (column) address for a change event, in pixels. + * The (0, 0) address is in the upper left corner, like in OpenCV/computer graphics. + * + * @param event a valid PolarityEvent pointer. Cannot be NULL. + * + * @return the event X address. + */ +static inline uint16_t caerPolarityEventGetX(caerPolarityEvent event) { + return U16T(GET_NUMBITS32(event->data, X_ADDR_SHIFT, X_ADDR_MASK)); +} + +/** + * Set the X (column) address for a change event, in pixels. + * The (0, 0) address is in the upper left corner, like in OpenCV/computer graphics. + * + * @param event a valid PolarityEvent pointer. Cannot be NULL. + * @param xAddress the event X address. + */ +static inline void caerPolarityEventSetX(caerPolarityEvent event, uint16_t xAddress) { + CLEAR_NUMBITS32(event->data, X_ADDR_SHIFT, X_ADDR_MASK); + SET_NUMBITS32(event->data, X_ADDR_SHIFT, X_ADDR_MASK, xAddress); +} + +/** + * Iterator over all polarity events in a packet. + * Returns the current index in the 'caerPolarityIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerPolarityIteratorElement' variable + * of type caerPolarityEvent. + * + * POLARITY_PACKET: a valid PolarityEventPacket pointer. Cannot be NULL. + */ +#define CAER_POLARITY_ITERATOR_ALL_START(POLARITY_PACKET) \ + for (int32_t caerPolarityIteratorCounter = 0; \ + caerPolarityIteratorCounter < caerEventPacketHeaderGetEventNumber(&(POLARITY_PACKET)->packetHeader); \ + caerPolarityIteratorCounter++) { \ + caerPolarityEvent caerPolarityIteratorElement = caerPolarityEventPacketGetEvent(POLARITY_PACKET, caerPolarityIteratorCounter); + +/** + * Iterator close statement. + */ +#define CAER_POLARITY_ITERATOR_ALL_END } + +/** + * Iterator over only the valid polarity events in a packet. + * Returns the current index in the 'caerPolarityIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerPolarityIteratorElement' variable + * of type caerPolarityEvent. + * + * POLARITY_PACKET: a valid PolarityEventPacket pointer. Cannot be NULL. + */ +#define CAER_POLARITY_ITERATOR_VALID_START(POLARITY_PACKET) \ + for (int32_t caerPolarityIteratorCounter = 0; \ + caerPolarityIteratorCounter < caerEventPacketHeaderGetEventNumber(&(POLARITY_PACKET)->packetHeader); \ + caerPolarityIteratorCounter++) { \ + caerPolarityEvent caerPolarityIteratorElement = caerPolarityEventPacketGetEvent(POLARITY_PACKET, caerPolarityIteratorCounter); \ + if (!caerPolarityEventIsValid(caerPolarityIteratorElement)) { continue; } // Skip invalid polarity events. + +/** + * Iterator close statement. + */ +#define CAER_POLARITY_ITERATOR_VALID_END } + +/** + * Reverse iterator over all polarity events in a packet. + * Returns the current index in the 'caerPolarityIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerPolarityIteratorElement' variable + * of type caerPolarityEvent. + * + * POLARITY_PACKET: a valid PolarityEventPacket pointer. Cannot be NULL. + */ +#define CAER_POLARITY_REVERSE_ITERATOR_ALL_START(POLARITY_PACKET) \ + for (int32_t caerPolarityIteratorCounter = caerEventPacketHeaderGetEventNumber(&(POLARITY_PACKET)->packetHeader) - 1; \ + caerPolarityIteratorCounter >= 0; \ + caerPolarityIteratorCounter--) { \ + caerPolarityEvent caerPolarityIteratorElement = caerPolarityEventPacketGetEvent(POLARITY_PACKET, caerPolarityIteratorCounter); + +/** + * Reverse iterator close statement. + */ +#define CAER_POLARITY_REVERSE_ITERATOR_ALL_END } + +/** + * Reverse iterator over only the valid polarity events in a packet. + * Returns the current index in the 'caerPolarityIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerPolarityIteratorElement' variable + * of type caerPolarityEvent. + * + * POLARITY_PACKET: a valid PolarityEventPacket pointer. Cannot be NULL. + */ +#define CAER_POLARITY_REVERSE_ITERATOR_VALID_START(POLARITY_PACKET) \ + for (int32_t caerPolarityIteratorCounter = caerEventPacketHeaderGetEventNumber(&(POLARITY_PACKET)->packetHeader) - 1; \ + caerPolarityIteratorCounter >= 0; \ + caerPolarityIteratorCounter--) { \ + caerPolarityEvent caerPolarityIteratorElement = caerPolarityEventPacketGetEvent(POLARITY_PACKET, caerPolarityIteratorCounter); \ + if (!caerPolarityEventIsValid(caerPolarityIteratorElement)) { continue; } // Skip invalid polarity events. + +/** + * Reverse iterator close statement. + */ +#define CAER_POLARITY_REVERSE_ITERATOR_VALID_END } + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_EVENTS_POLARITY_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/sample.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/sample.h new file mode 100755 index 0000000..c0b9837 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/sample.h @@ -0,0 +1,304 @@ +/** + * @file sample.h + * + * Sample (ADC) Events format definition and handling functions. + * Represents different types of ADC readings, up to 24 bits + * of resolution. + */ + +#ifndef LIBCAER_EVENTS_SAMPLE_H_ +#define LIBCAER_EVENTS_SAMPLE_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "common.h" + +/** + * Shift and mask values for the sample type and the actual + * sample value of an ADC sample. + * Up to 128 sample types are supported, with 24 bits of + * data per sample. Higher values mean a higher voltage, + * 0 is ground. + * Bit 0 is the valid mark, see 'common.h' for more details. + */ +//@{ +#define SAMPLE_TYPE_SHIFT 1 +#define SAMPLE_TYPE_MASK 0x0000007F +#define SAMPLE_SHIFT 8 +#define SAMPLE_MASK 0x00FFFFFF +//@} + +/** + * ADC sample event data structure definition. + * Contains a type indication to separate different ADC readouts, + * as well as a value for that readout, up to 24 bits resolution. + * Signed integers are used for fields that are to be interpreted + * directly, for compatibility with languages that do not have + * unsigned integer types, such as Java. + */ +struct caer_sample_event { + /// Event data. First because of valid mark. + uint32_t data; + /// Event timestamp. + int32_t timestamp; +}__attribute__((__packed__)); + +/** + * Type for pointer to ADC sample event data structure. + */ +typedef struct caer_sample_event *caerSampleEvent; + +/** + * ADC sample event packet data structure definition. + * EventPackets are always made up of the common packet header, + * followed by 'eventCapacity' events. Everything has to + * be in one contiguous memory block. + */ +struct caer_sample_event_packet { + /// The common event packet header. + struct caer_event_packet_header packetHeader; + /// The events array. + struct caer_sample_event events[]; +}__attribute__((__packed__)); + +/** + * Type for pointer to ADC sample event packet data structure. + */ +typedef struct caer_sample_event_packet *caerSampleEventPacket; + +/** + * Allocate a new ADC sample events packet. + * Use free() to reclaim this memory. + * + * @param eventCapacity the maximum number of events this packet will hold. + * @param eventSource the unique ID representing the source/generator of this packet. + * @param tsOverflow the current timestamp overflow counter value for this packet. + * + * @return a valid SampleEventPacket handle or NULL on error. + */ +caerSampleEventPacket caerSampleEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow); + +/** + * Get the ADC sample event at the given index from the event packet. + * + * @param packet a valid SampleEventPacket pointer. Cannot be NULL. + * @param n the index of the returned event. Must be within [0,eventCapacity[ bounds. + * + * @return the requested ADC sample event. NULL on error. + */ +static inline caerSampleEvent caerSampleEventPacketGetEvent(caerSampleEventPacket packet, int32_t n) { + // Check that we're not out of bounds. + if (n < 0 || n >= caerEventPacketHeaderGetEventCapacity(&packet->packetHeader)) { + caerLog(CAER_LOG_CRITICAL, "Sample Event", + "Called caerSampleEventPacketGetEvent() with invalid event offset %" PRIi32 ", while maximum allowed value is %" PRIi32 ".", + n, caerEventPacketHeaderGetEventCapacity(&packet->packetHeader) - 1); + return (NULL); + } + + // Return a pointer to the specified event. + return (packet->events + n); +} + +/** + * Get the 32bit event timestamp, in microseconds. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid SampleEvent pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond timestamp. + */ +static inline int32_t caerSampleEventGetTimestamp(caerSampleEvent event) { + return (le32toh(event->timestamp)); +} + +/** + * Get the 64bit event timestamp, in microseconds. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid SampleEvent pointer. Cannot be NULL. + * @param packet the SampleEventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond timestamp. + */ +static inline int64_t caerSampleEventGetTimestamp64(caerSampleEvent event, caerSampleEventPacket packet) { + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(&packet->packetHeader)) << TS_OVERFLOW_SHIFT) | U64T(caerSampleEventGetTimestamp(event)))); +} + +/** + * Set the 32bit event timestamp, the value has to be in microseconds. + * + * @param event a valid SampleEvent pointer. Cannot be NULL. + * @param timestamp a positive 32bit microsecond timestamp. + */ +static inline void caerSampleEventSetTimestamp(caerSampleEvent event, int32_t timestamp) { + if (timestamp < 0) { + // Negative means using the 31st bit! + caerLog(CAER_LOG_CRITICAL, "Sample Event", "Called caerSampleEventSetTimestamp() with negative value!"); + return; + } + + event->timestamp = htole32(timestamp); +} + +/** + * Check if this ADC sample event is valid. + * + * @param event a valid SampleEvent pointer. Cannot be NULL. + * + * @return true if valid, false if not. + */ +static inline bool caerSampleEventIsValid(caerSampleEvent event) { + return (GET_NUMBITS32(event->data, VALID_MARK_SHIFT, VALID_MARK_MASK)); +} + +/** + * Validate the current event by setting its valid bit to true + * and increasing the event packet's event count and valid + * event count. Only works on events that are invalid. + * DO NOT CALL THIS AFTER HAVING PREVIOUSLY ALREADY + * INVALIDATED THIS EVENT, the total count will be incorrect. + * + * @param event a valid SampleEvent pointer. Cannot be NULL. + * @param packet the SampleEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerSampleEventValidate(caerSampleEvent event, caerSampleEventPacket packet) { + if (!caerSampleEventIsValid(event)) { + SET_NUMBITS32(event->data, VALID_MARK_SHIFT, VALID_MARK_MASK, 1); + + // Also increase number of events and valid events. + // Only call this on (still) invalid events! + caerEventPacketHeaderSetEventNumber(&packet->packetHeader, + caerEventPacketHeaderGetEventNumber(&packet->packetHeader) + 1); + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) + 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Sample Event", "Called caerSampleEventValidate() on already valid event."); + } +} + +/** + * Invalidate the current event by setting its valid bit + * to false and decreasing the number of valid events held + * in the packet. Only works with events that are already + * valid! + * + * @param event a valid SampleEvent pointer. Cannot be NULL. + * @param packet the SampleEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerSampleEventInvalidate(caerSampleEvent event, caerSampleEventPacket packet) { + if (caerSampleEventIsValid(event)) { + CLEAR_NUMBITS32(event->data, VALID_MARK_SHIFT, VALID_MARK_MASK); + + // Also decrease number of valid events. Number of total events doesn't change. + // Only call this on valid events! + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) - 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Sample Event", "Called caerSampleEventInvalidate() on already invalid event."); + } +} + +/** + * Get the ADC sample event type. This is useful to distinguish + * between different measurements, for example from two separate + * microphones on a device. + * + * @param event a valid SampleEvent pointer. Cannot be NULL. + * + * @return the ADC sample type. + */ +static inline uint8_t caerSampleEventGetType(caerSampleEvent event) { + return U8T(GET_NUMBITS32(event->data, SAMPLE_TYPE_SHIFT, SAMPLE_TYPE_MASK)); +} + +/** + * Set the ADC sample event type. This is useful to distinguish + * between different measurements, for example from two separate + * microphones on a device. + * + * @param event a valid SampleEvent pointer. Cannot be NULL. + * @param type the ADC sample type. + */ +static inline void caerSampleEventSetType(caerSampleEvent event, uint8_t type) { + CLEAR_NUMBITS32(event->data, SAMPLE_TYPE_SHIFT, SAMPLE_TYPE_MASK); + SET_NUMBITS32(event->data, SAMPLE_TYPE_SHIFT, SAMPLE_TYPE_MASK, type); +} + +/** + * Get the ADC sample value. Up to 24 bits of resolution are possible. + * Higher values mean a higher voltage, 0 is ground. + * + * @param event a valid SampleEvent pointer. Cannot be NULL. + * + * @return the ADC sample value. + */ +static inline uint32_t caerSampleEventGetSample(caerSampleEvent event) { + return U32T(GET_NUMBITS32(event->data, SAMPLE_SHIFT, SAMPLE_MASK)); +} + +/** + * Set the ADC sample value. Up to 24 bits of resolution are possible. + * Higher values mean a higher voltage, 0 is ground. + * + * @param event a valid SampleEvent pointer. Cannot be NULL. + * @param sample the ADC sample value. + */ +static inline void caerSampleEventSetSample(caerSampleEvent event, uint32_t sample) { + CLEAR_NUMBITS32(event->data, SAMPLE_SHIFT, SAMPLE_MASK); + SET_NUMBITS32(event->data, SAMPLE_SHIFT, SAMPLE_MASK, sample); +} + +/** + * Iterator over all sample events in a packet. + * Returns the current index in the 'caerSampleIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerSampleIteratorElement' variable + * of type caerSampleEvent. + * + * SAMPLE_PACKET: a valid SampleEventPacket pointer. Cannot be NULL. + */ +#define CAER_SAMPLE_ITERATOR_ALL_START(SAMPLE_PACKET) \ + for (int32_t caerSampleIteratorCounter = 0; \ + caerSampleIteratorCounter < caerEventPacketHeaderGetEventNumber(&(SAMPLE_PACKET)->packetHeader); \ + caerSampleIteratorCounter++) { \ + caerSampleEvent caerSampleIteratorElement = caerSampleEventPacketGetEvent(SAMPLE_PACKET, caerSampleIteratorCounter); + +/** + * Iterator close statement. + */ +#define CAER_SAMPLE_ITERATOR_ALL_END } + +/** + * Iterator over only the valid sample events in a packet. + * Returns the current index in the 'caerSampleIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerSampleIteratorElement' variable + * of type caerSampleEvent. + * + * SAMPLE_PACKET: a valid SampleEventPacket pointer. Cannot be NULL. + */ +#define CAER_SAMPLE_ITERATOR_VALID_START(SAMPLE_PACKET) \ + for (int32_t caerSampleIteratorCounter = 0; \ + caerSampleIteratorCounter < caerEventPacketHeaderGetEventNumber(&(SAMPLE_PACKET)->packetHeader); \ + caerSampleIteratorCounter++) { \ + caerSampleEvent caerSampleIteratorElement = caerSampleEventPacketGetEvent(SAMPLE_PACKET, caerSampleIteratorCounter); \ + if (!caerSampleEventIsValid(caerSampleIteratorElement)) { continue; } // Skip invalid sample events. + +/** + * Iterator close statement. + */ +#define CAER_SAMPLE_ITERATOR_VALID_END } + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_EVENTS_SAMPLE_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/special.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/special.h new file mode 100755 index 0000000..eca2815 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/events/special.h @@ -0,0 +1,368 @@ +/** + * @file special.h + * + * Special Events format definition and handling functions. + * This event type encodes special occurrences, such as + * timestamp related notifications or external input events. + */ + +#ifndef LIBCAER_EVENTS_SPECIAL_H_ +#define LIBCAER_EVENTS_SPECIAL_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "common.h" + +/** + * Shift and mask values for the type and data portions + * of a special event. + * Up to 128 types, with 24 bits of data each, are possible. + * Bit 0 is the valid mark, see 'common.h' for more details. + */ +//@{ +#define TYPE_SHIFT 1 +#define TYPE_MASK 0x0000007F +#define DATA_SHIFT 8 +#define DATA_MASK 0x00FFFFFF +//@} + +/** + * List of all special event type identifiers. + * Used to interpret the special event type field. + */ +enum caer_special_event_types { + TIMESTAMP_WRAP = 0, //!< A 32 bit timestamp wrap occurred. + TIMESTAMP_RESET = 1, //!< A timestamp reset occurred. + EXTERNAL_INPUT_RISING_EDGE = 2, //!< A rising edge was detected (External Input module on device). + EXTERNAL_INPUT_FALLING_EDGE = 3, //!< A falling edge was detected (External Input module on device). + EXTERNAL_INPUT_PULSE = 4, //!< A pulse was detected (External Input module on device). + DVS_ROW_ONLY = 5, //!< A DVS row-only event was detected (a row address without any following column addresses). + EXTERNAL_INPUT1_RISING_EDGE = 6, //!< A rising edge was detected (External Input 1 module on device). + EXTERNAL_INPUT1_FALLING_EDGE = 7, //!< A falling edge was detected (External Input 1 module on device). + EXTERNAL_INPUT1_PULSE = 8, //!< A pulse was detected (External Input 1 module on device). + EXTERNAL_INPUT2_RISING_EDGE = 9, //!< A rising edge was detected (External Input 2 module on device). + EXTERNAL_INPUT2_FALLING_EDGE = 10, //!< A falling edge was detected (External Input 2 module on device). + EXTERNAL_INPUT2_PULSE = 11, //!< A pulse was detected (External Input 2 module on device). + EXTERNAL_GENERATOR_RISING_EDGE = 12, //!< A rising edge was generated (External Input Generator module on device). + EXTERNAL_GENERATOR_FALLING_EDGE = 13, //!< A falling edge was generated (External Input Generator module on device). + APS_FRAME_START = 14, //!< An APS frame capture has started (Frame Event will follow). + APS_FRAME_END = 15, //!< An APS frame capture has completed (Frame Event is alongside). + APS_EXPOSURE_START = 16, //!< An APS frame exposure has started (Frame Event will follow). + APS_EXPOSURE_END = 17, //!< An APS frame exposure has completed (Frame Event will follow). +}; + +/** + * Special event data structure definition. + * This contains the actual data, as well as the 32 bit event timestamp. + * Signed integers are used for fields that are to be interpreted + * directly, for compatibility with languages that do not have + * unsigned integer types, such as Java. + */ +struct caer_special_event { + /// Event data. First because of valid mark. + uint32_t data; + /// Event timestamp. + int32_t timestamp; +}__attribute__((__packed__)); + +/** + * Type for pointer to special event data structure. + */ +typedef struct caer_special_event *caerSpecialEvent; + +/** + * Special event packet data structure definition. + * EventPackets are always made up of the common packet header, + * followed by 'eventCapacity' events. Everything has to + * be in one contiguous memory block. + */ +struct caer_special_event_packet { + /// The common event packet header. + struct caer_event_packet_header packetHeader; + /// The events array. + struct caer_special_event events[]; +}__attribute__((__packed__)); + +/** + * Type for pointer to special event packet data structure. + */ +typedef struct caer_special_event_packet *caerSpecialEventPacket; + +/** + * Allocate a new special events packet. + * Use free() to reclaim this memory. + * + * @param eventCapacity the maximum number of events this packet will hold. + * @param eventSource the unique ID representing the source/generator of this packet. + * @param tsOverflow the current timestamp overflow counter value for this packet. + * + * @return a valid SpecialEventPacket handle or NULL on error. + */ +caerSpecialEventPacket caerSpecialEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow); + +/** + * Get the special event at the given index from the event packet. + * + * @param packet a valid SpecialEventPacket pointer. Cannot be NULL. + * @param n the index of the returned event. Must be within [0,eventCapacity[ bounds. + * + * @return the requested special event. NULL on error. + */ +static inline caerSpecialEvent caerSpecialEventPacketGetEvent(caerSpecialEventPacket packet, int32_t n) { + // Check that we're not out of bounds. + if (n < 0 || n >= caerEventPacketHeaderGetEventCapacity(&packet->packetHeader)) { + caerLog(CAER_LOG_CRITICAL, "Special Event", + "Called caerSpecialEventPacketGetEvent() with invalid event offset %" PRIi32 ", while maximum allowed value is %" PRIi32 ".", + n, caerEventPacketHeaderGetEventCapacity(&packet->packetHeader) - 1); + return (NULL); + } + + // Return a pointer to the specified event. + return (packet->events + n); +} + +/** + * Get the 32bit event timestamp, in microseconds. + * Be aware that this wraps around! You can either ignore this fact, + * or handle the special 'TIMESTAMP_WRAP' event that is generated when + * this happens, or use the 64bit timestamp which never wraps around. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid SpecialEvent pointer. Cannot be NULL. + * + * @return this event's 32bit microsecond timestamp. + */ +static inline int32_t caerSpecialEventGetTimestamp(caerSpecialEvent event) { + return (le32toh(event->timestamp)); +} + +/** + * Get the 64bit event timestamp, in microseconds. + * See 'caerEventPacketHeaderGetEventTSOverflow()' documentation + * for more details on the 64bit timestamp. + * + * @param event a valid SpecialEvent pointer. Cannot be NULL. + * @param packet the SpecialEventPacket pointer for the packet containing this event. Cannot be NULL. + * + * @return this event's 64bit microsecond timestamp. + */ +static inline int64_t caerSpecialEventGetTimestamp64(caerSpecialEvent event, caerSpecialEventPacket packet) { + return (I64T( + (U64T(caerEventPacketHeaderGetEventTSOverflow(&packet->packetHeader)) << TS_OVERFLOW_SHIFT) | U64T(caerSpecialEventGetTimestamp(event)))); +} + +/** + * Set the 32bit event timestamp, the value has to be in microseconds. + * + * @param event a valid SpecialEvent pointer. Cannot be NULL. + * @param timestamp a positive 32bit microsecond timestamp. + */ +static inline void caerSpecialEventSetTimestamp(caerSpecialEvent event, int32_t timestamp) { + if (timestamp < 0) { + // Negative means using the 31st bit! + caerLog(CAER_LOG_CRITICAL, "Special Event", "Called caerSpecialEventSetTimestamp() with negative value!"); + return; + } + + event->timestamp = htole32(timestamp); +} + +/** + * Check if this special event is valid. + * + * @param event a valid SpecialEvent pointer. Cannot be NULL. + * + * @return true if valid, false if not. + */ +static inline bool caerSpecialEventIsValid(caerSpecialEvent event) { + return (GET_NUMBITS32(event->data, VALID_MARK_SHIFT, VALID_MARK_MASK)); +} + +/** + * Validate the current event by setting its valid bit to true + * and increasing the event packet's event count and valid + * event count. Only works on events that are invalid. + * DO NOT CALL THIS AFTER HAVING PREVIOUSLY ALREADY + * INVALIDATED THIS EVENT, the total count will be incorrect. + * + * @param event a valid SpecialEvent pointer. Cannot be NULL. + * @param packet the SpecialEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerSpecialEventValidate(caerSpecialEvent event, caerSpecialEventPacket packet) { + if (!caerSpecialEventIsValid(event)) { + SET_NUMBITS32(event->data, VALID_MARK_SHIFT, VALID_MARK_MASK, 1); + + // Also increase number of events and valid events. + // Only call this on (still) invalid events! + caerEventPacketHeaderSetEventNumber(&packet->packetHeader, + caerEventPacketHeaderGetEventNumber(&packet->packetHeader) + 1); + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) + 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Special Event", "Called caerSpecialEventValidate() on already valid event."); + } +} + +/** + * Invalidate the current event by setting its valid bit + * to false and decreasing the number of valid events held + * in the packet. Only works with events that are already + * valid! + * + * @param event a valid SpecialEvent pointer. Cannot be NULL. + * @param packet the SpecialEventPacket pointer for the packet containing this event. Cannot be NULL. + */ +static inline void caerSpecialEventInvalidate(caerSpecialEvent event, caerSpecialEventPacket packet) { + if (caerSpecialEventIsValid(event)) { + CLEAR_NUMBITS32(event->data, VALID_MARK_SHIFT, VALID_MARK_MASK); + + // Also decrease number of valid events. Number of total events doesn't change. + // Only call this on valid events! + caerEventPacketHeaderSetEventValid(&packet->packetHeader, + caerEventPacketHeaderGetEventValid(&packet->packetHeader) - 1); + } + else { + caerLog(CAER_LOG_CRITICAL, "Special Event", "Called caerSpecialEventInvalidate() on already invalid event."); + } +} + +/** + * Get the numerical special event type. + * + * @param event a valid SpecialEvent pointer. Cannot be NULL. + * + * @return the special event type (see 'enum caer_special_event_types'). + */ +static inline uint8_t caerSpecialEventGetType(caerSpecialEvent event) { + return U8T(GET_NUMBITS32(event->data, TYPE_SHIFT, TYPE_MASK)); +} + +/** + * Set the numerical special event type. + * + * @param event a valid SpecialEvent pointer. Cannot be NULL. + * @param type the special event type (see 'enum caer_special_event_types'). + */ +static inline void caerSpecialEventSetType(caerSpecialEvent event, uint8_t type) { + CLEAR_NUMBITS32(event->data, TYPE_SHIFT, TYPE_MASK); + SET_NUMBITS32(event->data, TYPE_SHIFT, TYPE_MASK, type); +} + +/** + * Get the special event data. Its meaning depends on the type. + * Current types that make use of it are (see 'enum caer_special_event_types'): + * - DVS_ROW_ONLY: encodes the address of the row from the row-only event. + * + * @param event a valid SpecialEvent pointer. Cannot be NULL. + * + * @return the special event data. + */ +static inline uint32_t caerSpecialEventGetData(caerSpecialEvent event) { + return U32T(GET_NUMBITS32(event->data, DATA_SHIFT, DATA_MASK)); +} + +/** + * Set the special event data. Its meaning depends on the type. + * Current types that make use of it are (see 'enum caer_special_event_types'): + * - DVS_ROW_ONLY: encodes the address of the row from the row-only event. + * + * @param event a valid SpecialEvent pointer. Cannot be NULL. + * @param data the special event data. + */ +static inline void caerSpecialEventSetData(caerSpecialEvent event, uint32_t data) { + CLEAR_NUMBITS32(event->data, DATA_SHIFT, DATA_MASK); + SET_NUMBITS32(event->data, DATA_SHIFT, DATA_MASK, data); +} + +/** + * Iterator over all special events in a packet. + * Returns the current index in the 'caerSpecialIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerSpecialIteratorElement' variable + * of type caerSpecialEvent. + * + * SPECIAL_PACKET: a valid SpecialEventPacket pointer. Cannot be NULL. + */ +#define CAER_SPECIAL_ITERATOR_ALL_START(SPECIAL_PACKET) \ + for (int32_t caerSpecialIteratorCounter = 0; \ + caerSpecialIteratorCounter < caerEventPacketHeaderGetEventNumber(&(SPECIAL_PACKET)->packetHeader); \ + caerSpecialIteratorCounter++) { \ + caerSpecialEvent caerSpecialIteratorElement = caerSpecialEventPacketGetEvent(SPECIAL_PACKET, caerSpecialIteratorCounter); + +/** + * Iterator close statement. + */ +#define CAER_SPECIAL_ITERATOR_ALL_END } + +/** + * Iterator over only the valid special events in a packet. + * Returns the current index in the 'caerSpecialIteratorCounter' variable of type + * 'int32_t' and the current event in the 'caerSpecialIteratorElement' variable + * of type caerSpecialEvent. + * + * SPECIAL_PACKET: a valid SpecialEventPacket pointer. Cannot be NULL. + */ +#define CAER_SPECIAL_ITERATOR_VALID_START(SPECIAL_PACKET) \ + for (int32_t caerSpecialIteratorCounter = 0; \ + caerSpecialIteratorCounter < caerEventPacketHeaderGetEventNumber(&(SPECIAL_PACKET)->packetHeader); \ + caerSpecialIteratorCounter++) { \ + caerSpecialEvent caerSpecialIteratorElement = caerSpecialEventPacketGetEvent(SPECIAL_PACKET, caerSpecialIteratorCounter); \ + if (!caerSpecialEventIsValid(caerSpecialIteratorElement)) { continue; } // Skip invalid special events. + +/** + * Iterator close statement. + */ +#define CAER_SPECIAL_ITERATOR_VALID_END } + +/** + * Get the first special event with the given event type in this + * event packet. This returns the first found event with that type ID, + * or NULL if we get to the end without finding any such event. + * + * @param packet a valid SpecialEventPacket pointer. Cannot be NULL. + * @param type the special event type to search for. + * + * @return the requested special event or NULL on error/not found. + */ +static inline caerSpecialEvent caerSpecialEventPacketFindEventByType(caerSpecialEventPacket packet, uint8_t type) { + CAER_SPECIAL_ITERATOR_ALL_START(packet) + if (caerSpecialEventGetType(caerSpecialIteratorElement) == type) { + // Found it, return it. + return (caerSpecialIteratorElement); + } + CAER_SPECIAL_ITERATOR_ALL_END + + // Found nothing, return nothing. + return (NULL); +} + +/** + * Get the first valid special event with the given event type in this + * event packet. This returns the first found valid event with that type ID, + * or NULL if we get to the end without finding any such event. + * + * @param packet a valid SpecialEventPacket pointer. Cannot be NULL. + * @param type the special event type to search for. + * + * @return the requested valid special event or NULL on error/not found. + */ +static inline caerSpecialEvent caerSpecialEventPacketFindValidEventByType(caerSpecialEventPacket packet, uint8_t type) { + CAER_SPECIAL_ITERATOR_VALID_START(packet) + if (caerSpecialEventGetType(caerSpecialIteratorElement) == type) { + // Found it, return it. + return (caerSpecialIteratorElement); + } + CAER_SPECIAL_ITERATOR_VALID_END + + // Found nothing, return nothing. + return (NULL); +} + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_EVENTS_SPECIAL_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/frame_utils.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/frame_utils.h new file mode 100755 index 0000000..200d570 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/frame_utils.h @@ -0,0 +1,26 @@ +/** + * @file frame_utils.h + * + * Basic functions for frame enhancement and demosaicing, that don't + * require any external dependencies, such as OpenCV. + * Use of the OpenCV variants is recommended for quality and performance. + */ + +#ifndef LIBCAER_FRAME_UTILS_H_ +#define LIBCAER_FRAME_UTILS_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "events/frame.h" + +caerFrameEventPacket caerFrameUtilsDemosaic(caerFrameEventPacket framePacket); +void caerFrameUtilsContrast(caerFrameEventPacket framePacket); +void caerFrameUtilsWhiteBalance(caerFrameEventPacket framePacket); + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_FRAME_UTILS_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/frame_utils_opencv.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/frame_utils_opencv.h new file mode 100755 index 0000000..18fed55 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/frame_utils_opencv.h @@ -0,0 +1,39 @@ +/** + * @file frame_utils_opencv.h + * + * Functions for frame enhancement and demosaicing, using + * the popular OpenCV image processing library. + */ + +#ifndef LIBCAER_FRAME_UTILS_OPENCV_H_ +#define LIBCAER_FRAME_UTILS_OPENCV_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include "events/frame.h" + +enum caer_frame_utils_opencv_demosaic { + DEMOSAIC_NORMAL, DEMOSAIC_EDGE_AWARE, // DEMOSAIC_VARIABLE_NUMBER_OF_GRADIENTS not supported on 16bit images currently. +}; + +enum caer_frame_utils_opencv_contrast { + CONTRAST_NORMALIZATION, CONTRAST_HISTOGRAM_EQUALIZATION, CONTRAST_CLAHE, +}; + +enum caer_frame_utils_opencv_white_balance { + WHITEBALANCE_SIMPLE, WHITEBALANCE_GRAYWORLD, +}; + +caerFrameEventPacket caerFrameUtilsOpenCVDemosaic(caerFrameEventPacket framePacket, + enum caer_frame_utils_opencv_demosaic demosaicType); +void caerFrameUtilsOpenCVContrast(caerFrameEventPacket framePacket, enum caer_frame_utils_opencv_contrast contrastType); +void caerFrameUtilsOpenCVWhiteBalance(caerFrameEventPacket framePacket, + enum caer_frame_utils_opencv_white_balance whiteBalanceType); + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_FRAME_UTILS_OPENCV_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/libcaer_in.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/libcaer_in.h new file mode 100755 index 0000000..b2dbce0 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/libcaer_in.h @@ -0,0 +1,251 @@ +/** + * @file libcaer.h + * + * Main libcaer header; provides inclusions for common system functions + * and definitions for useful macros used often in the code. Also includes + * the logging functions and definitions and several useful static inline + * functions for string comparison and byte array manipulation. + * When including libcaer, please make sure to always use the full path, + * ie. #include <libcaer/libcaer.h> and not just #include <libcaer.h>. + */ + +#ifndef LIBCAER_H_ +#define LIBCAER_H_ + +#ifdef __cplusplus + +#include <cstdio> +#include <cstdint> +#include <cinttypes> +#include <cstring> +#include <cerrno> + +extern "C" { +#endif + +// Common includes, useful for everyone. +#include <stddef.h> +#include <stdlib.h> +#include <stdio.h> +#include <stdbool.h> +#include <stdint.h> +#include <inttypes.h> +#include <string.h> +#include <errno.h> + +// Use portable endian conversion functions. +#include "portable_endian.h" + +// Include libcaer's log headers always. +#include "log.h" + +/** + * libcaer version (MAJOR * 10000 + MINOR * 100 + PATCH). + */ +#define LIBCAER_VERSION ((@PROJECT_VERSION_MAJOR@ * 10000) + (@PROJECT_VERSION_MINOR@ * 100) + @PROJECT_VERSION_PATCH@) +/** + * libcaer name string. + */ +#define LIBCAER_NAME_STRING "@PROJECT_NAME@" +/** + * libcaer version string. + */ +#define LIBCAER_VERSION_STRING "@PROJECT_VERSION_NOREV@" + +/** + * Cast argument to uint8_t (8bit unsigned integer). + */ +#define U8T(X) ((uint8_t) (X)) +/** + * Cast argument to uint16_t (16bit unsigned integer). + */ +#define U16T(X) ((uint16_t) (X)) +/** + * Cast argument to uint32_t (32bit unsigned integer). + */ +#define U32T(X) ((uint32_t) (X)) +/** + * Cast argument to uint64_t (64bit unsigned integer). + */ +#define U64T(X) ((uint64_t) (X)) +/** + * Cast argument to int8_t (8bit signed integer). + */ +#define I8T(X) ((int8_t) (X)) +/** + * Cast argument to int16_t (16bit signed integer). + */ +#define I16T(X) ((int16_t) (X)) +/** + * Cast argument to int32_t (32bit signed integer). + */ +#define I32T(X) ((int32_t) (X)) +/** + * Cast argument to int64_t (64bit signed integer). + */ +#define I64T(X) ((int64_t) (X)) +/** + * Mask and keep only the lower X bits of a 32bit (unsigned) integer. + */ +#define MASK_NUMBITS32(X) U32T(U32T(U32T(1) << X) - 1) +/** + * Mask and keep only the lower X bits of a 64bit (unsigned) integer. + */ +#define MASK_NUMBITS64(X) U64T(U64T(U64T(1) << X) - 1) +/** + * Swap the two values of the two variables X and Y, of a common type TYPE. + */ +#define SWAP_VAR(type, x, y) { type tmpv; tmpv = (x); (x) = (y); (y) = tmpv; } + +/** + * Clear bits given by mask (amount) and shift (position). + */ +//@{ +#define CLEAR_NUMBITS32(VAR, SHIFT, MASK) (VAR) &= htole32(~(U32T(U32T(MASK) << (SHIFT)))) +#define CLEAR_NUMBITS16(VAR, SHIFT, MASK) (VAR) &= htole16(~(U16T(U16T(MASK) << (SHIFT)))) +#define CLEAR_NUMBITS8(VAR, SHIFT, MASK) (VAR) &= U8T(~(U8T(U8T(MASK) << (SHIFT)))) +//@} +/** + * Set bits given by mask (amount) and shift (position) to a value. + */ +//@{ +#define SET_NUMBITS32(VAR, SHIFT, MASK, VALUE) (VAR) |= htole32(U32T((U32T(VALUE) & (MASK)) << (SHIFT))) +#define SET_NUMBITS16(VAR, SHIFT, MASK, VALUE) (VAR) |= htole16(U16T((U16T(VALUE) & (MASK)) << (SHIFT))) +#define SET_NUMBITS8(VAR, SHIFT, MASK, VALUE) (VAR) |= U8T((U8T(VALUE) & (MASK)) << (SHIFT)) +//@} +/** + * Get value of bits given by mask (amount) and shift (position). + */ +//@{ +#define GET_NUMBITS32(VAR, SHIFT, MASK) ((le32toh(VAR) >> (SHIFT)) & (MASK)) +#define GET_NUMBITS16(VAR, SHIFT, MASK) ((le16toh(VAR) >> (SHIFT)) & (MASK)) +#define GET_NUMBITS8(VAR, SHIFT, MASK) ((U8T(VAR) >> (SHIFT)) & (MASK)) +//@} + +/** + * Compare two strings for equality. + * + * @param s1 the first string, cannot be NULL. + * @param s2 the second string, cannot be NULL. + * + * @return true if equal, false otherwise. + */ +static inline bool caerStrEquals(const char *s1, const char *s2) { + if (s1 == NULL || s2 == NULL) { + return (false); + } + + if (strcmp(s1, s2) == 0) { + return (true); + } + + return (false); +} + +/** + * Compare two strings for equality, up to a specified maximum length. + * + * @param s1 the first string, cannot be NULL. + * @param s2 the second string, cannot be NULL. + * @param len maximum comparison length, cannot be zero. + * + * @return true if equal, false otherwise. + */ +static inline bool caerStrEqualsUpTo(const char *s1, const char *s2, size_t len) { + if (s1 == NULL || s2 == NULL || len == 0) { + return (false); + } + + if (strncmp(s1, s2, len) == 0) { + return (true); + } + + return (false); +} + +/** + * Convert a 32bit unsigned integer into an unsigned byte array of up to four bytes. + * The integer will be stored in big-endian order, and the length will specify how + * many bits to convert, starting from the lowest bit. + * + * @param integer the integer to convert. + * @param byteArray pointer to the byte array in which to store the converted values. + * @param byteArrayLength length of the byte array to convert to. + */ +static inline void caerIntegerToByteArray(uint32_t integer, uint8_t *byteArray, uint8_t byteArrayLength) { + switch (byteArrayLength) { + case 4: + byteArray[0] = U8T(integer >> 24); + byteArray[1] = U8T(integer >> 16); + byteArray[2] = U8T(integer >> 8); + byteArray[3] = U8T(integer); + break; + + case 3: + byteArray[0] = U8T(integer >> 16); + byteArray[1] = U8T(integer >> 8); + byteArray[2] = U8T(integer); + break; + + case 2: + byteArray[0] = U8T(integer >> 8); + byteArray[1] = U8T(integer); + break; + + case 1: + byteArray[0] = U8T(integer); + break; + + default: + break; + } +} + +/** + * Convert an unsigned byte array of up to four bytes into a 32bit unsigned integer. + * The byte array length decides how many resulting bits in the integer are set, + * and the single bytes are placed in the integer following big-endian ordering. + * + * @param byteArray pointer to the byte array with parts of the value stored. + * @param byteArrayLength length of the array from which to convert. + * + * @return integer representing the value stored in the byte array. + */ +static inline uint32_t caerByteArrayToInteger(uint8_t *byteArray, uint8_t byteArrayLength) { + uint32_t integer = 0; + + switch (byteArrayLength) { + case 4: + integer |= U32T(byteArray[0] << 24); + integer |= U32T(byteArray[1] << 16); + integer |= U32T(byteArray[2] << 8); + integer |= U32T(byteArray[3]); + break; + + case 3: + integer |= U32T(byteArray[0] << 16); + integer |= U32T(byteArray[1] << 8); + integer |= U32T(byteArray[2]); + break; + + case 2: + integer |= U32T(byteArray[0] << 8); + integer |= U32T(byteArray[1]); + break; + + case 1: + integer |= U32T(byteArray[0]); + break; + + default: + break; + } + + return (integer); +} + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/log.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/log.h new file mode 100755 index 0000000..bddbd70 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/log.h @@ -0,0 +1,89 @@ +/** + * @file log.h + * + * Logging functions to print useful messages for the user. + */ + +#ifndef LIBCAER_LOG_H_ +#define LIBCAER_LOG_H_ + +#ifdef __cplusplus + +#include <cstdint> + +extern "C" { +#endif + +#include <stdint.h> + +//@{ +/** + * Log levels for caerLog() logging function. + * Log messages only get printed if their log level is equal or + * above the global system log level, which can be set with + * caerLogLevelSet(). + * The default log level is CAER_LOG_ERROR. + * CAER_LOG_EMERGENCY is the most urgent log level and will always + * be printed, while CAER_LOG_DEBUG is the least urgent log + * level and will only be delivered if configured by the user. + */ +#define CAER_LOG_EMERGENCY (0) +#define CAER_LOG_ALERT (1) +#define CAER_LOG_CRITICAL (2) +#define CAER_LOG_ERROR (3) +#define CAER_LOG_WARNING (4) +#define CAER_LOG_NOTICE (5) +#define CAER_LOG_INFO (6) +#define CAER_LOG_DEBUG (7) +//@} + +/** + * Set the system-wide log level. + * Log messages will only be printed if their level is equal or above + * this level. + * + * @param logLevel the system-wide log level. + */ +void caerLogLevelSet(uint8_t logLevel); + +/** + * Get the current system-wide log level. + * Log messages are only printed if their level is equal or above + * this level. + * + * @return the current system-wide log level. + */ +uint8_t caerLogLevelGet(void); + +/** + * Set to which file descriptors log messages are sent. + * Up to two different file descriptors can be configured here. + * By default logging to STDERR only is enabled. + * If both file descriptors are identical, logging to it will + * only happen once, as if the second one was disabled. + * + * @param fd1 first file descriptor to log to. A negative value will disable it. + * @param fd2 second file descriptor to log to. A negative value will disable it. + */ +void caerLogFileDescriptorsSet(int fd1, int fd2); + +/** + * Main logging function. + * This function takes messages, formats them and sends them out to a file descriptor, + * respecting the system-wide log level setting and prepending the current time, the + * log level and a user-specified common string to the actual formatted output. + * The format is specified exactly as with the printf() family of functions. + * Please see their manual-page for more information. + * + * @param logLevel the message-specific log level. + * @param subSystem a common, user-specified string to prepend before the message. + * @param format the message format string (see printf()). + * @param ... the parameters to be formatted according to the format string (see printf()). + */ +void caerLog(uint8_t logLevel, const char *subSystem, const char *format, ...) __attribute__ ((format (printf, 3, 4))); + +#ifdef __cplusplus +} +#endif + +#endif /* LIBCAER_LOG_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/portable_endian.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/portable_endian.h new file mode 100755 index 0000000..ab39000 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/include/portable_endian.h @@ -0,0 +1,105 @@ +/** + * @file portable_endian.h + * + * Endianness conversion functions for a wide variety of systems, + * including Linux, FreeBSD, MacOS X and Windows. + */ + +// "License": Public Domain +// I, Mathias Panzenböck, place this file hereby into the public domain. Use it at your own risk for whatever you like. +// In case there are jurisdictions that don't support putting things in the public domain you can also consider it to +// be "dual licensed" under the BSD, MIT and Apache licenses, if you want to. This code is trivial anyway. Consider it +// an example on how to get the endian conversion functions on different platforms. + +#ifndef PORTABLE_ENDIAN_H__ +#define PORTABLE_ENDIAN_H__ + +#if (defined(_WIN16) || defined(_WIN32) || defined(_WIN64)) && !defined(__WINDOWS__) + #define __WINDOWS__ +#endif + +#if defined(__linux__) || defined(__CYGWIN__) + #include <endian.h> +#elif defined(__APPLE__) + #include <libkern/OSByteOrder.h> + + #define htobe16(x) OSSwapHostToBigInt16(x) + #define htole16(x) OSSwapHostToLittleInt16(x) + #define be16toh(x) OSSwapBigToHostInt16(x) + #define le16toh(x) OSSwapLittleToHostInt16(x) + + #define htobe32(x) OSSwapHostToBigInt32(x) + #define htole32(x) OSSwapHostToLittleInt32(x) + #define be32toh(x) OSSwapBigToHostInt32(x) + #define le32toh(x) OSSwapLittleToHostInt32(x) + + #define htobe64(x) OSSwapHostToBigInt64(x) + #define htole64(x) OSSwapHostToLittleInt64(x) + #define be64toh(x) OSSwapBigToHostInt64(x) + #define le64toh(x) OSSwapLittleToHostInt64(x) + + #define __BYTE_ORDER BYTE_ORDER + #define __BIG_ENDIAN BIG_ENDIAN + #define __LITTLE_ENDIAN LITTLE_ENDIAN + #define __PDP_ENDIAN PDP_ENDIAN +#elif defined(__OpenBSD__) + #include <sys/endian.h> +#elif defined(__NetBSD__) || defined(__FreeBSD__) || defined(__DragonFly__) + #include <sys/endian.h> + + #define be16toh(x) betoh16(x) + #define le16toh(x) letoh16(x) + + #define be32toh(x) betoh32(x) + #define le32toh(x) letoh32(x) + + #define be64toh(x) betoh64(x) + #define le64toh(x) letoh64(x) +#elif defined(__WINDOWS__) + #include <winsock2.h> + #include <sys/param.h> + + #if BYTE_ORDER == LITTLE_ENDIAN + #define htobe16(x) htons(x) + #define htole16(x) (x) + #define be16toh(x) ntohs(x) + #define le16toh(x) (x) + + #define htobe32(x) htonl(x) + #define htole32(x) (x) + #define be32toh(x) ntohl(x) + #define le32toh(x) (x) + + #define htobe64(x) htonll(x) + #define htole64(x) (x) + #define be64toh(x) ntohll(x) + #define le64toh(x) (x) + #elif BYTE_ORDER == BIG_ENDIAN + /* That would be Xbox 360. */ + #define htobe16(x) (x) + #define htole16(x) __builtin_bswap16(x) + #define be16toh(x) (x) + #define le16toh(x) __builtin_bswap16(x) + + #define htobe32(x) (x) + #define htole32(x) __builtin_bswap32(x) + #define be32toh(x) (x) + #define le32toh(x) __builtin_bswap32(x) + + #define htobe64(x) (x) + #define htole64(x) __builtin_bswap64(x) + #define be64toh(x) (x) + #define le64toh(x) __builtin_bswap64(x) + #else + #error byte order not supported + #endif + + #define __BYTE_ORDER BYTE_ORDER + #define __BIG_ENDIAN BIG_ENDIAN + #define __LITTLE_ENDIAN LITTLE_ENDIAN + #define __PDP_ENDIAN PDP_ENDIAN +#else + #error platform not supported +#endif + +#endif /* PORTABLE_ENDIAN_H__ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/libcaer.pc.in b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/libcaer.pc.in new file mode 100755 index 0000000..6f8e52c --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/libcaer.pc.in @@ -0,0 +1,12 @@ +prefix=@CMAKE_INSTALL_PREFIX@ +exec_prefix=${prefix} +libdir=${prefix}/@CMAKE_INSTALL_LIBDIR@ +includedir=${prefix}/@CMAKE_INSTALL_INCLUDEDIR@ + +Name: @CMAKE_PROJECT_NAME@ +Description: Minimal C API for low-level access to DVS128, DAVIS devices. +Version: @PROJECT_VERSION_NOREV@ +Requires.private: libusb-1.0 >= 1.0.17 +Libs: -L${libdir} -lcaer +Libs.private: @PRIVATE_LIBS@ +Cflags: -I${includedir} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/libcaer_opencv.pc.in b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/libcaer_opencv.pc.in new file mode 100755 index 0000000..94f03d7 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/libcaer_opencv.pc.in @@ -0,0 +1,12 @@ +prefix=@CMAKE_INSTALL_PREFIX@ +exec_prefix=${prefix} +libdir=${prefix}/@CMAKE_INSTALL_LIBDIR@ +includedir=${prefix}/@CMAKE_INSTALL_INCLUDEDIR@ + +Name: @CMAKE_PROJECT_NAME@ +Description: Minimal C API for low-level access to DVS128, DAVIS devices. Uses OpenCV for frame enhancement. +Version: @PROJECT_VERSION_NOREV@ +Requires.private: libusb-1.0 >= 1.0.17, opencv >= 3.1 +Libs: -L${libdir} -lcaer +Libs.private: @PRIVATE_LIBS@ +Cflags: -I${includedir} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/.gitignore b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/.gitignore new file mode 100755 index 0000000..7d79361 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/.gitignore @@ -0,0 +1,2 @@ +/*.dylib +/libcaer.so* diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/CMakeLists.txt b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/CMakeLists.txt new file mode 100755 index 0000000..bc31323 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/CMakeLists.txt @@ -0,0 +1,38 @@ +SET(LIBCAER_SRC_FILES + ringbuffer/ringbuffer.c + log.c + events.c + frame_utils.c + device.c + dvs128.c + davis_common.c + davis_fx2.c + davis_fx3.c) + +IF (ENABLE_OPENCV) + # Add C++ OpenCV file and its C wrapper. + SET(LIBCAER_SRC_FILES ${LIBCAER_SRC_FILES} frame_utils_opencv.cpp) +ENDIF() + +SET(LIBCAER_SRC_FILES ${LIBCAER_SRC_FILES} PARENT_SCOPE) + +IF (UNIX AND NOT APPLE) + # Add --as-needed to linker flags for library. + SET(CMAKE_SHARED_LINKER_FLAGS "-Wl,--as-needed") +ENDIF() + +ADD_LIBRARY(caer SHARED ${LIBCAER_SRC_FILES}) + +SET_TARGET_PROPERTIES(caer + PROPERTIES + SOVERSION ${PROJECT_VERSION_MAJOR} + VERSION ${PROJECT_VERSION_NOREV} +) + +TARGET_LINK_LIBRARIES(caer ${LIBCAER_LIBS}) + +IF (OS_WINDOWS) + INSTALL(TARGETS caer RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR}) +ELSE() + INSTALL(TARGETS caer DESTINATION ${CMAKE_INSTALL_LIBDIR}) +ENDIF() diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/c11threads_posix.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/c11threads_posix.h new file mode 100755 index 0000000..6efb2ca --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/c11threads_posix.h @@ -0,0 +1,398 @@ +#ifndef C11THREADS_POSIX_H_ +#define C11THREADS_POSIX_H_ + +#include <stdint.h> +#include <pthread.h> +#include <time.h> +#include <sys/time.h> +#include <sched.h> +#include <errno.h> + +#if defined(OS_LINUX) + #include <sys/prctl.h> + #include <sys/resource.h> +#endif + +typedef pthread_t thrd_t; +typedef pthread_once_t once_flag; +typedef pthread_mutex_t mtx_t; +typedef pthread_rwlock_t mtx_shared_t; // NON STANDARD! +typedef int (*thrd_start_t)(void *); + +enum { + thrd_success = 0, thrd_error = 1, thrd_nomem = 2, thrd_timedout = 3, thrd_busy = 4, +}; + +enum { + mtx_plain = 0, mtx_timed = 1, mtx_recursive = 2, +}; + +#define ONCE_FLAG_INIT PTHREAD_ONCE_INIT + +static inline int thrd_create(thrd_t *thr, thrd_start_t func, void *arg) { + int ret = pthread_create(thr, NULL, (void *(*)(void *)) func, arg); + + switch (ret) { + case 0: + return (thrd_success); + + case EAGAIN: + return (thrd_nomem); + + default: + return (thrd_error); + } +} + +static inline _Noreturn void thrd_exit(int res) { + pthread_exit((void*) (intptr_t) res); +} + +static inline int thrd_detach(thrd_t thr) { + if (pthread_detach(thr) != 0) { + return (thrd_error); + } + + return (thrd_success); +} + +static inline int thrd_join(thrd_t thr, int *res) { + void *pthread_res; + + if (pthread_join(thr, &pthread_res) != 0) { + return (thrd_error); + } + + if (res != NULL) { + *res = (int) (intptr_t) pthread_res; + } + + return (thrd_success); +} + +static inline int thrd_sleep(const struct timespec *time_point, struct timespec *remaining) { + if (nanosleep(time_point, remaining) == 0) { + return (0); // Successful sleep. + } + + if (errno == EINTR) { + return (-1); // C11: a signal occurred. + } + + return (-2); // C11: other negative value if an error occurred. +} + +static inline void thrd_yield(void) { + sched_yield(); +} + +static inline thrd_t thrd_current(void) { + return (pthread_self()); +} + +static inline int thrd_equal(thrd_t lhs, thrd_t rhs) { + return (pthread_equal(lhs, rhs)); +} + +static inline void call_once(once_flag *flag, void (*func)(void)) { + pthread_once(flag, func); +} + +static inline int mtx_init(mtx_t *mutex, int type) { + pthread_mutexattr_t attr; + if (pthread_mutexattr_init(&attr) != 0) { + return (thrd_error); + } + + // TIMED and PLAIN + pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_NORMAL); + + if (type & 0x02) { + // RECURSIVE + pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_RECURSIVE); + } + + if (pthread_mutex_init(mutex, &attr) != 0) { + pthread_mutexattr_destroy(&attr); + return (thrd_error); + } + + pthread_mutexattr_destroy(&attr); + return (thrd_success); +} + +static inline void mtx_destroy(mtx_t *mutex) { + pthread_mutex_destroy(mutex); +} + +static inline int mtx_lock(mtx_t *mutex) { + if (pthread_mutex_lock(mutex) != 0) { + return (thrd_error); + } + + return (thrd_success); +} + +static inline int mtx_trylock(mtx_t *mutex) { + int ret = pthread_mutex_trylock(mutex); + + switch (ret) { + case 0: + return (thrd_success); + + case EBUSY: + return (thrd_busy); + + default: + return (thrd_error); + } +} + +static inline int mtx_timedlock(mtx_t *restrict mutex, const struct timespec *restrict time_point) { +#if defined(__APPLE__) + // Emulate on MacOS X. + struct timespec sleepTime = { .tv_sec = 0, .tv_nsec = 1000000 /* 1ms */ }; + struct timeval currentTime; + int ret; + + while ((ret = mtx_trylock(mutex)) == thrd_busy) { + gettimeofday(¤tTime, NULL); + + if (currentTime.tv_sec >= time_point->tv_sec && (currentTime.tv_usec * 1000) >= time_point->tv_nsec) { + return (thrd_timedout); + } + + nanosleep(&sleepTime, NULL); + } + + return (ret); +#elif defined(__unix__) || defined(__UNIX__) + int ret = pthread_mutex_timedlock(mutex, time_point); + + switch (ret) { + case 0: + return (thrd_success); + + case ETIMEDOUT: + return (thrd_timedout); + + default: + return (thrd_error); + } +#endif +} + +static inline int mtx_unlock(mtx_t *mutex) { + if (pthread_mutex_unlock(mutex) != 0) { + return (thrd_error); + } + + return (thrd_success); +} + +// NON STANDARD! 'int type' argument doesn't make sense here, always timed and recursive. +static inline int mtx_shared_init(mtx_shared_t *mutex) { + if (pthread_rwlock_init(mutex, NULL) != 0) { + return (thrd_error); + } + + return (thrd_success); +} + +// NON STANDARD! +static inline void mtx_shared_destroy(mtx_shared_t *mutex) { + pthread_rwlock_destroy(mutex); +} + +// NON STANDARD! +static inline int mtx_shared_lock_exclusive(mtx_shared_t *mutex) { + if (pthread_rwlock_wrlock(mutex) != 0) { + return (thrd_error); + } + + return (thrd_success); +} + +// NON STANDARD! +static inline int mtx_shared_trylock_exclusive(mtx_shared_t *mutex) { + int ret = pthread_rwlock_trywrlock(mutex); + + switch (ret) { + case 0: + return (thrd_success); + + case EBUSY: + return (thrd_busy); + + default: + return (thrd_error); + } +} + +// NON STANDARD! +static inline int mtx_shared_timedlock_exclusive(mtx_shared_t *restrict mutex, + const struct timespec *restrict time_point) { +#if defined(__APPLE__) + // Emulate on MacOS X. + struct timespec sleepTime = { .tv_sec = 0, .tv_nsec = 1000000 /* 1ms */ }; + struct timeval currentTime; + int ret; + + while ((ret = mtx_shared_trylock_exclusive(mutex)) == thrd_busy) { + gettimeofday(¤tTime, NULL); + + if (currentTime.tv_sec >= time_point->tv_sec && (currentTime.tv_usec * 1000) >= time_point->tv_nsec) { + return (thrd_timedout); + } + + nanosleep(&sleepTime, NULL); + } + + return (ret); +#elif defined(__unix__) || defined(__UNIX__) + int ret = pthread_rwlock_timedwrlock(mutex, time_point); + + switch (ret) { + case 0: + return (thrd_success); + + case ETIMEDOUT: + return (thrd_timedout); + + default: + return (thrd_error); + } +#endif +} + +// NON STANDARD! +static inline int mtx_shared_unlock_exclusive(mtx_shared_t *mutex) { + if (pthread_rwlock_unlock(mutex) != 0) { + return (thrd_error); + } + + return (thrd_success); +} + +// NON STANDARD! +static inline int mtx_shared_lock_shared(mtx_shared_t *mutex) { + if (pthread_rwlock_rdlock(mutex) != 0) { + return (thrd_error); + } + + return (thrd_success); +} + +// NON STANDARD! +static inline int mtx_shared_trylock_shared(mtx_shared_t *mutex) { + int ret = pthread_rwlock_tryrdlock(mutex); + + switch (ret) { + case 0: + return (thrd_success); + + case EBUSY: + return (thrd_busy); + + default: + return (thrd_error); + } +} + +// NON STANDARD! +static inline int mtx_shared_timedlock_shared(mtx_shared_t *restrict mutex, const struct timespec *restrict time_point) { +#if defined(__APPLE__) + // Emulate on MacOS X. + struct timespec sleepTime = { .tv_sec = 0, .tv_nsec = 1000000 /* 1ms */ }; + struct timeval currentTime; + int ret; + + while ((ret = mtx_shared_trylock_shared(mutex)) == thrd_busy) { + gettimeofday(¤tTime, NULL); + + if (currentTime.tv_sec >= time_point->tv_sec && (currentTime.tv_usec * 1000) >= time_point->tv_nsec) { + return (thrd_timedout); + } + + nanosleep(&sleepTime, NULL); + } + + return (ret); +#elif defined(__unix__) || defined(__UNIX__) + int ret = pthread_rwlock_timedrdlock(mutex, time_point); + + switch (ret) { + case 0: + return (thrd_success); + + case ETIMEDOUT: + return (thrd_timedout); + + default: + return (thrd_error); + } +#endif +} + +// NON STANDARD! +static inline int mtx_shared_unlock_shared(mtx_shared_t *mutex) { + if (pthread_rwlock_unlock(mutex) != 0) { + return (thrd_error); + } + + return (thrd_success); +} + +// NON STANDARD! +static inline int thrd_set_name(const char *name) { +#if defined(OS_LINUX) + if (prctl(PR_SET_NAME, name) != 0) { + return (thrd_error); + } + + return (thrd_success); +#elif defined(OS_MACOSX) + if (pthread_setname_np(name) != 0) { + return (thrd_error); + } + + return (thrd_success); +#else + return (thrd_error); +#endif +} + +static inline int thrd_get_name(char *name, size_t maxNameLength) { +#if defined(OS_LINUX) + (void)(maxNameLength); // UNUSED FOR LINUX. + + if (prctl(PR_GET_NAME, name) != 0) { + return (thrd_error); + } + + return (thrd_success); +#elif defined(OS_MACOSX) + if (pthread_getname_np(pthread_self(), name, maxNameLength) != 0) { + return (thrd_error); + } + + return (thrd_success); +#else + return (thrd_error); +#endif +} + +// NON STANDARD! +static inline int thrd_set_priority(int priority) { +#if defined(OS_LINUX) + if (setpriority(PRIO_PROCESS, 0, priority) != 0) { + return (thrd_error); + } + + return (thrd_success); +#else + return (thrd_error); +#endif +} + +#endif /* C11THREADS_POSIX_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_common.c b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_common.c new file mode 100755 index 0000000..c72c1f7 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_common.c @@ -0,0 +1,4021 @@ +#include "davis_common.h" + +static bool spiConfigSend(libusb_device_handle *devHandle, uint8_t moduleAddr, uint8_t paramAddr, uint32_t param); +static bool spiConfigReceive(libusb_device_handle *devHandle, uint8_t moduleAddr, uint8_t paramAddr, uint32_t *param); +static libusb_device_handle *davisDeviceOpen(libusb_context *devContext, uint16_t devVID, uint16_t devPID, + uint8_t devType, uint8_t busNumber, uint8_t devAddress, const char *serialNumber, uint16_t requiredLogicRevision, + uint16_t requiredFirmwareVersion); +static void davisDeviceClose(libusb_device_handle *devHandle); +static void davisAllocateTransfers(davisHandle handle, uint32_t bufferNum, uint32_t bufferSize); +static void davisDeallocateTransfers(davisHandle handle); +static void LIBUSB_CALL davisLibUsbCallback(struct libusb_transfer *transfer); +static void davisEventTranslator(davisHandle handle, uint8_t *buffer, size_t bytesSent); +static int davisDataAcquisitionThread(void *inPtr); +static void davisDataAcquisitionThreadConfig(davisHandle handle); + +static inline void checkStrictMonotonicTimestamp(davisHandle handle) { + if (handle->state.currentTimestamp <= handle->state.lastTimestamp) { + caerLog(CAER_LOG_ALERT, handle->info.deviceString, + "Timestamps: non strictly-monotonic timestamp detected: lastTimestamp=%" PRIi32 ", currentTimestamp=%" PRIi32 ", difference=%" PRIi32 ".", + handle->state.lastTimestamp, handle->state.currentTimestamp, + (handle->state.lastTimestamp - handle->state.currentTimestamp)); + } +} + +static inline void updateROISizes(davisState state) { + // Calculate APS ROI sizes for each region. + for (size_t i = 0; i < APS_ROI_REGIONS_MAX; i++) { + uint16_t startColumn = state->apsROIPositionX[i]; + uint16_t startRow = state->apsROIPositionY[i]; + uint16_t endColumn = state->apsROISizeX[i]; + uint16_t endRow = state->apsROISizeY[i]; + + // Position is already set to startCol/Row, so we don't have to reset + // it here. We only have to calculate size from start and end. + if (startColumn < state->apsSizeX) { + state->apsROISizeX[i] = U16T(endColumn + 1 - startColumn); + state->apsROISizeY[i] = U16T(endRow + 1 - startRow); + } + else { + // Turn off this ROI region. + state->apsROISizeX[i] = state->apsROISizeY[i] = 0; + state->apsROIPositionX[i] = state->apsROIPositionY[i] = 0; + } + } +} + +static inline void initFrame(davisHandle handle) { + davisState state = &handle->state; + + state->apsCurrentReadoutType = APS_READOUT_RESET; + for (size_t i = 0; i < APS_READOUT_TYPES_NUM; i++) { + state->apsCountX[i] = 0; + state->apsCountY[i] = 0; + } + + // for (size_t i = 0; i < APS_ROI_REGIONS_MAX; i++) { + memset(state->currentFrameEvent[0], 0, sizeof(struct caer_frame_event)); + // } + + if (state->apsROIUpdate != 0) { + updateROISizes(state); + } + + // Write out start of frame timestamp. + caerFrameEventSetTSStartOfFrame(state->currentFrameEvent[0], state->currentTimestamp); + + // Send APS info event out (as special event). + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent(state->currentSpecialPacket, + state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, APS_FRAME_START); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + + // Setup frame. Only ROI region 0 is supported currently. + caerFrameEventSetLengthXLengthYChannelNumber(state->currentFrameEvent[0], state->apsROISizeX[0], + state->apsROISizeY[0], APS_ADC_CHANNELS, state->currentFramePacket); + caerFrameEventSetROIIdentifier(state->currentFrameEvent[0], 0); + caerFrameEventSetColorFilter(state->currentFrameEvent[0], handle->info.apsColorFilter); + caerFrameEventSetPositionX(state->currentFrameEvent[0], state->apsROIPositionX[0]); + caerFrameEventSetPositionY(state->currentFrameEvent[0], state->apsROIPositionY[0]); +} + +static inline float calculateIMUAccelScale(uint8_t imuAccelScale) { + // Accelerometer scale is: + // 0 - +-2 g - 16384 LSB/g + // 1 - +-4 g - 8192 LSB/g + // 2 - +-8 g - 4096 LSB/g + // 3 - +-16 g - 2048 LSB/g + float accelScale = 65536.0f / (float) U32T(4 * (1 << imuAccelScale)); + + return (accelScale); +} + +static inline float calculateIMUGyroScale(uint8_t imuGyroScale) { + // Gyroscope scale is: + // 0 - +-250 °/s - 131 LSB/°/s + // 1 - +-500 °/s - 65.5 LSB/°/s + // 2 - +-1000 °/s - 32.8 LSB/°/s + // 3 - +-2000 °/s - 16.4 LSB/°/s + float gyroScale = 65536.0f / (float) U32T(500 * (1 << imuGyroScale)); + + return (gyroScale); +} + +static inline void freeAllDataMemory(davisState state) { + if (state->dataExchangeBuffer != NULL) { + ringBufferFree(state->dataExchangeBuffer); + state->dataExchangeBuffer = NULL; + } + + // Since the current event packets aren't necessarily + // already assigned to the current packet container, we + // free them separately from it. + if (state->currentPolarityPacket != NULL) { + free(&state->currentPolarityPacket->packetHeader); + state->currentPolarityPacket = NULL; + + if (state->currentPacketContainer != NULL) { + caerEventPacketContainerSetEventPacket(state->currentPacketContainer, POLARITY_EVENT, NULL); + } + } + + if (state->currentSpecialPacket != NULL) { + free(&state->currentSpecialPacket->packetHeader); + state->currentSpecialPacket = NULL; + + if (state->currentPacketContainer != NULL) { + caerEventPacketContainerSetEventPacket(state->currentPacketContainer, SPECIAL_EVENT, NULL); + } + } + + if (state->currentFramePacket != NULL) { + free(&state->currentFramePacket->packetHeader); + state->currentFramePacket = NULL; + + if (state->currentPacketContainer != NULL) { + caerEventPacketContainerSetEventPacket(state->currentPacketContainer, FRAME_EVENT, NULL); + } + } + + if (state->currentIMU6Packet != NULL) { + free(&state->currentIMU6Packet->packetHeader); + state->currentIMU6Packet = NULL; + + if (state->currentPacketContainer != NULL) { + caerEventPacketContainerSetEventPacket(state->currentPacketContainer, IMU6_EVENT, NULL); + } + } + + if (state->currentPacketContainer != NULL) { + caerEventPacketContainerFree(state->currentPacketContainer); + state->currentPacketContainer = NULL; + } + + if (state->apsCurrentResetFrame != NULL) { + free(state->apsCurrentResetFrame); + state->apsCurrentResetFrame = NULL; + } + + // Also free current ROI frame events. + free(state->currentFrameEvent[0]); // Other regions are contained within contiguous memory block. + + for (size_t i = 0; i < APS_ROI_REGIONS_MAX; i++) { + // Reset pointers to NULL. + state->currentFrameEvent[i] = NULL; + } +} + +bool davisCommonOpen(davisHandle handle, uint16_t VID, uint16_t PID, uint8_t DID_TYPE, const char *deviceName, + uint16_t deviceID, uint8_t busNumberRestrict, uint8_t devAddressRestrict, const char *serialNumberRestrict, + uint16_t requiredLogicRevision, uint16_t requiredFirmwareVersion) { + davisState state = &handle->state; + + // Initialize state variables to default values (if not zero, taken care of by calloc above). + atomic_store_explicit(&state->dataExchangeBufferSize, 64, memory_order_relaxed); + atomic_store_explicit(&state->dataExchangeBlocking, false, memory_order_relaxed); + atomic_store_explicit(&state->dataExchangeStartProducers, true, memory_order_relaxed); + atomic_store_explicit(&state->dataExchangeStopProducers, true, memory_order_relaxed); + atomic_store_explicit(&state->usbBufferNumber, 8, memory_order_relaxed); + atomic_store_explicit(&state->usbBufferSize, 8192, memory_order_relaxed); + + // Packet settings (size (in events) and time interval (in µs)). + atomic_store_explicit(&state->maxPacketContainerPacketSize, 8192, memory_order_relaxed); + atomic_store_explicit(&state->maxPacketContainerInterval, 10000, memory_order_relaxed); + + atomic_thread_fence(memory_order_release); + + // Set device thread name. Maximum length of 15 chars due to Linux limitations. + snprintf(state->deviceThreadName, 15 + 1, "%s ID-%" PRIu16, deviceName, deviceID); + state->deviceThreadName[15] = '\0'; + + // Search for device and open it. + // Initialize libusb using a separate context for each device. + // This is to correctly support one thread per device. + // libusb may create its own threads at this stage, so we temporarly set + // a different thread name. + char originalThreadName[15 + 1]; // +1 for terminating NUL character. + thrd_get_name(originalThreadName, 15); + originalThreadName[15] = '\0'; + + thrd_set_name(state->deviceThreadName); + int res = libusb_init(&state->deviceContext); + + thrd_set_name(originalThreadName); + + if (res != LIBUSB_SUCCESS) { + caerLog(CAER_LOG_CRITICAL, __func__, "Failed to initialize libusb context. Error: %d.", res); + return (false); + } + + // Try to open a DAVIS device on a specific USB port. + state->deviceHandle = davisDeviceOpen(state->deviceContext, VID, PID, DID_TYPE, busNumberRestrict, + devAddressRestrict, serialNumberRestrict, requiredLogicRevision, requiredFirmwareVersion); + if (state->deviceHandle == NULL) { + libusb_exit(state->deviceContext); + + caerLog(CAER_LOG_CRITICAL, __func__, "Failed to open %s device.", deviceName); + return (false); + } + + // At this point we can get some more precise data on the device and update + // the logging string to reflect that and be more informative. + uint8_t busNumber = libusb_get_bus_number(libusb_get_device(state->deviceHandle)); + uint8_t devAddress = libusb_get_device_address(libusb_get_device(state->deviceHandle)); + + char serialNumber[8 + 1] = { 0 }; + int getStringDescResult = libusb_get_string_descriptor_ascii(state->deviceHandle, 3, (unsigned char *) serialNumber, + 8 + 1); + + // Check serial number success and length. + if (getStringDescResult < 0 || getStringDescResult > 8) { + davisDeviceClose(state->deviceHandle); + libusb_exit(state->deviceContext); + + caerLog(CAER_LOG_CRITICAL, __func__, "Unable to get serial number for %s device.", deviceName); + return (false); + } + + size_t fullLogStringLength = (size_t) snprintf(NULL, 0, "%s ID-%" PRIu16 " SN-%s [%" PRIu8 ":%" PRIu8 "]", + deviceName, deviceID, serialNumber, busNumber, devAddress); + + char *fullLogString = malloc(fullLogStringLength + 1); + if (fullLogString == NULL) { + davisDeviceClose(state->deviceHandle); + libusb_exit(state->deviceContext); + + caerLog(CAER_LOG_CRITICAL, __func__, "Unable to allocate memory for %s device info string.", deviceName); + return (false); + } + + snprintf(fullLogString, fullLogStringLength + 1, "%s ID-%" PRIu16 " SN-%s [%" PRIu8 ":%" PRIu8 "]", deviceName, + deviceID, serialNumber, busNumber, devAddress); + + // Populate info variables based on data from device. + uint32_t param32 = 0; + + handle->info.deviceID = I16T(deviceID); + strncpy(handle->info.deviceSerialNumber, serialNumber, 8 + 1); + handle->info.deviceUSBBusNumber = busNumber; + handle->info.deviceUSBDeviceAddress = devAddress; + handle->info.deviceString = fullLogString; + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_SYSINFO, DAVIS_CONFIG_SYSINFO_LOGIC_VERSION, ¶m32); + handle->info.logicVersion = I16T(param32); + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_SYSINFO, DAVIS_CONFIG_SYSINFO_DEVICE_IS_MASTER, ¶m32); + handle->info.deviceIsMaster = param32; + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_SYSINFO, DAVIS_CONFIG_SYSINFO_LOGIC_CLOCK, ¶m32); + handle->info.logicClock = I16T(param32); + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_SYSINFO, DAVIS_CONFIG_SYSINFO_ADC_CLOCK, ¶m32); + handle->info.adcClock = I16T(param32); + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_SYSINFO, DAVIS_CONFIG_SYSINFO_CHIP_IDENTIFIER, ¶m32); + handle->info.chipID = I16T(param32); + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_HAS_PIXEL_FILTER, ¶m32); + handle->info.dvsHasPixelFilter = param32; + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_HAS_BACKGROUND_ACTIVITY_FILTER, ¶m32); + handle->info.dvsHasBackgroundActivityFilter = param32; + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_HAS_TEST_EVENT_GENERATOR, ¶m32); + handle->info.dvsHasTestEventGenerator = param32; + + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_COLOR_FILTER, ¶m32); + handle->info.apsColorFilter = U8T(param32); + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_HAS_GLOBAL_SHUTTER, ¶m32); + handle->info.apsHasGlobalShutter = param32; + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_HAS_QUAD_ROI, ¶m32); + handle->info.apsHasQuadROI = param32; + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_HAS_EXTERNAL_ADC, ¶m32); + handle->info.apsHasExternalADC = param32; + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_HAS_INTERNAL_ADC, ¶m32); + handle->info.apsHasInternalADC = param32; + + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_HAS_GENERATOR, ¶m32); + handle->info.extInputHasGenerator = param32; + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_HAS_EXTRA_DETECTORS, ¶m32); + handle->info.extInputHasExtraDetectors = param32; + + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_SIZE_COLUMNS, ¶m32); + state->dvsSizeX = I16T(param32); + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_SIZE_ROWS, ¶m32); + state->dvsSizeY = I16T(param32); + + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_ORIENTATION_INFO, ¶m32); + state->dvsInvertXY = U16T(param32) & 0x04; + + if (state->dvsInvertXY) { + handle->info.dvsSizeX = state->dvsSizeY; + handle->info.dvsSizeY = state->dvsSizeX; + } + else { + handle->info.dvsSizeX = state->dvsSizeX; + handle->info.dvsSizeY = state->dvsSizeY; + } + + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_SIZE_COLUMNS, ¶m32); + state->apsSizeX = I16T(param32); + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_SIZE_ROWS, ¶m32); + state->apsSizeY = I16T(param32); + + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_ORIENTATION_INFO, ¶m32); + uint16_t apsOrientationInfo = U16T(param32); + state->apsInvertXY = apsOrientationInfo & 0x04; + state->apsFlipX = apsOrientationInfo & 0x02; + state->apsFlipY = apsOrientationInfo & 0x01; + + if (state->apsInvertXY) { + handle->info.apsSizeX = state->apsSizeY; + handle->info.apsSizeY = state->apsSizeX; + } + else { + handle->info.apsSizeX = state->apsSizeX; + handle->info.apsSizeY = state->apsSizeY; + } + + caerLog(CAER_LOG_DEBUG, fullLogString, "Initialized device successfully with USB Bus=%" PRIu8 ":Addr=%" PRIu8 ".", + busNumber, devAddress); + + return (true); +} + +bool davisCommonClose(davisHandle handle) { + davisState state = &handle->state; + + // Finally, close the device fully. + davisDeviceClose(state->deviceHandle); + + // Destroy libusb context. + libusb_exit(state->deviceContext); + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "Shutdown successful."); + + // Free memory. + free(handle->info.deviceString); + free(handle); + + return (true); +} + +struct caer_davis_info caerDavisInfoGet(caerDeviceHandle cdh) { + davisHandle handle = (davisHandle) cdh; + + // Check if the pointer is valid. + if (handle == NULL) { + struct caer_davis_info emptyInfo = { 0, .deviceString = NULL }; + return (emptyInfo); + } + + // Check if device type is supported. + if (handle->deviceType != CAER_DEVICE_DAVIS_FX2 && handle->deviceType != CAER_DEVICE_DAVIS_FX3) { + struct caer_davis_info emptyInfo = { 0, .deviceString = NULL }; + return (emptyInfo); + } + + // Return a copy of the device information. + return (handle->info); +} + +bool davisCommonSendDefaultFPGAConfig(caerDeviceHandle cdh, +bool (*configSet)(caerDeviceHandle cdh, int8_t modAddr, uint8_t paramAddr, uint32_t param)) { + davisHandle handle = (davisHandle) cdh; + + (*configSet)(cdh, DAVIS_CONFIG_MUX, DAVIS_CONFIG_MUX_TIMESTAMP_RESET, false); + (*configSet)(cdh, DAVIS_CONFIG_MUX, DAVIS_CONFIG_MUX_FORCE_CHIP_BIAS_ENABLE, false); + (*configSet)(cdh, DAVIS_CONFIG_MUX, DAVIS_CONFIG_MUX_DROP_DVS_ON_TRANSFER_STALL, true); + (*configSet)(cdh, DAVIS_CONFIG_MUX, DAVIS_CONFIG_MUX_DROP_APS_ON_TRANSFER_STALL, false); + (*configSet)(cdh, DAVIS_CONFIG_MUX, DAVIS_CONFIG_MUX_DROP_IMU_ON_TRANSFER_STALL, false); + (*configSet)(cdh, DAVIS_CONFIG_MUX, DAVIS_CONFIG_MUX_DROP_EXTINPUT_ON_TRANSFER_STALL, true); + + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_ACK_DELAY_ROW, 4); // in cycles @ LogicClock + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_ACK_DELAY_COLUMN, 0); // in cycles @ LogicClock + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_ACK_EXTENSION_ROW, 1); // in cycles @ LogicClock + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_ACK_EXTENSION_COLUMN, 0); // in cycles @ LogicClock + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_WAIT_ON_TRANSFER_STALL, false); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_ROW_ONLY_EVENTS, true); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_EXTERNAL_AER_CONTROL, false); + if (handle->info.dvsHasPixelFilter) { + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_0_ROW, U32T(handle->info.dvsSizeY)); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_0_COLUMN, U32T(handle->info.dvsSizeX)); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_1_ROW, U32T(handle->info.dvsSizeY)); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_1_COLUMN, U32T(handle->info.dvsSizeX)); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_2_ROW, U32T(handle->info.dvsSizeY)); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_2_COLUMN, U32T(handle->info.dvsSizeX)); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_3_ROW, U32T(handle->info.dvsSizeY)); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_3_COLUMN, U32T(handle->info.dvsSizeX)); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_4_ROW, U32T(handle->info.dvsSizeY)); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_4_COLUMN, U32T(handle->info.dvsSizeX)); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_5_ROW, U32T(handle->info.dvsSizeY)); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_5_COLUMN, U32T(handle->info.dvsSizeX)); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_6_ROW, U32T(handle->info.dvsSizeY)); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_6_COLUMN, U32T(handle->info.dvsSizeX)); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_7_ROW, U32T(handle->info.dvsSizeY)); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_PIXEL_7_COLUMN, U32T(handle->info.dvsSizeX)); + } + if (handle->info.dvsHasBackgroundActivityFilter) { + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_BACKGROUND_ACTIVITY, true); + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_FILTER_BACKGROUND_ACTIVITY_DELTAT, 20000); // in µs + } + if (handle->info.dvsHasTestEventGenerator) { + (*configSet)(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_TEST_EVENT_GENERATOR_ENABLE, false); + } + + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_RESET_READ, true); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_WAIT_ON_TRANSFER_STALL, true); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_GLOBAL_SHUTTER, handle->info.apsHasGlobalShutter); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_START_COLUMN_0, 0); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_START_ROW_0, 0); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_END_COLUMN_0, U16T(handle->info.apsSizeX - 1)); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_END_ROW_0, U16T(handle->info.apsSizeY - 1)); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_EXPOSURE, 4000); // in µs, converted to cycles @ ADCClock later + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_FRAME_DELAY, 1000); // in µs, converted to cycles @ ADCClock later + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_RESET_SETTLE, U32T(handle->info.adcClock / 3)); // in cycles @ ADCClock + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_COLUMN_SETTLE, U32T(handle->info.adcClock)); // in cycles @ ADCClock + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_ROW_SETTLE, U32T(handle->info.adcClock / 3)); // in cycles @ ADCClock + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_NULL_SETTLE, U32T(handle->info.adcClock / 10)); // in cycles @ ADCClock + if (handle->info.apsHasQuadROI) { + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_START_COLUMN_1, U32T(handle->info.apsSizeX)); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_START_ROW_1, U32T(handle->info.apsSizeY)); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_END_COLUMN_1, U32T(handle->info.apsSizeX)); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_END_ROW_1, U32T(handle->info.apsSizeY)); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_START_COLUMN_2, U32T(handle->info.apsSizeX)); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_START_ROW_2, U32T(handle->info.apsSizeY)); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_END_COLUMN_2, U32T(handle->info.apsSizeX)); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_END_ROW_2, U32T(handle->info.apsSizeY)); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_START_COLUMN_3, U32T(handle->info.apsSizeX)); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_START_ROW_3, U32T(handle->info.apsSizeY)); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_END_COLUMN_3, U32T(handle->info.apsSizeX)); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_END_ROW_3, U32T(handle->info.apsSizeY)); + } + if (handle->info.apsHasInternalADC) { + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_USE_INTERNAL_ADC, true); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_SAMPLE_ENABLE, true); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_SAMPLE_SETTLE, U32T(handle->info.adcClock)); // in cycles @ ADCClock + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_RAMP_RESET, U32T(handle->info.adcClock / 3)); // in cycles @ ADCClock + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_RAMP_SHORT_RESET, false); + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_ADC_TEST_MODE, false); + } + if (IS_DAVISRGB(handle->info.chipID)) { + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVISRGB_CONFIG_APS_TRANSFER, U32T(handle->info.adcClock * 25)); // in cycles @ ADCClock + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVISRGB_CONFIG_APS_RSFDSETTLE, U32T(handle->info.adcClock * 15)); // in cycles @ ADCClock + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVISRGB_CONFIG_APS_GSPDRESET, U32T(handle->info.adcClock * 15)); // in cycles @ ADCClock + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVISRGB_CONFIG_APS_GSRESETFALL, U32T(handle->info.adcClock * 15)); // in cycles @ ADCClock + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVISRGB_CONFIG_APS_GSTXFALL, U32T(handle->info.adcClock * 15)); // in cycles @ ADCClock + (*configSet)(cdh, DAVIS_CONFIG_APS, DAVISRGB_CONFIG_APS_GSFDRESET, U32T(handle->info.adcClock * 15)); // in cycles @ ADCClock + } + + (*configSet)(cdh, DAVIS_CONFIG_IMU, DAVIS_CONFIG_IMU_TEMP_STANDBY, false); + (*configSet)(cdh, DAVIS_CONFIG_IMU, DAVIS_CONFIG_IMU_ACCEL_STANDBY, false); + (*configSet)(cdh, DAVIS_CONFIG_IMU, DAVIS_CONFIG_IMU_GYRO_STANDBY, false); + (*configSet)(cdh, DAVIS_CONFIG_IMU, DAVIS_CONFIG_IMU_LP_CYCLE, false); + (*configSet)(cdh, DAVIS_CONFIG_IMU, DAVIS_CONFIG_IMU_LP_WAKEUP, 1); + (*configSet)(cdh, DAVIS_CONFIG_IMU, DAVIS_CONFIG_IMU_SAMPLE_RATE_DIVIDER, 0); + (*configSet)(cdh, DAVIS_CONFIG_IMU, DAVIS_CONFIG_IMU_DIGITAL_LOW_PASS_FILTER, 1); + (*configSet)(cdh, DAVIS_CONFIG_IMU, DAVIS_CONFIG_IMU_ACCEL_FULL_SCALE, 1); + (*configSet)(cdh, DAVIS_CONFIG_IMU, DAVIS_CONFIG_IMU_GYRO_FULL_SCALE, 1); + + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_DETECT_RISING_EDGES, false); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_DETECT_FALLING_EDGES, false); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_DETECT_PULSES, true); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_POLARITY, true); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_LENGTH, U32T(handle->info.logicClock)); // in cycles @ LogicClock + + if (handle->info.extInputHasGenerator) { + // Disable generator by default. Has to be enabled manually after sendDefaultConfig() by user! + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_RUN_GENERATOR, false); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_GENERATE_USE_CUSTOM_SIGNAL, false); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_POLARITY, true); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_INTERVAL, + U32T(handle->info.logicClock)); // in cycles @ LogicClock + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_LENGTH, + U32T(handle->info.logicClock / 2)); // in cycles @ LogicClock + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_GENERATE_INJECT_ON_RISING_EDGE, false); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_GENERATE_INJECT_ON_FALLING_EDGE, false); + } + + if (handle->info.extInputHasExtraDetectors) { + // Disable extra detectors by default. Have to be enabled manually after sendDefaultConfig() by user! + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_RUN_DETECTOR1, false); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_DETECT_RISING_EDGES1, false); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_DETECT_FALLING_EDGES1, false); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_DETECT_PULSES1, true); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_POLARITY1, true); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_LENGTH1, + U32T(handle->info.logicClock)); // in cycles @ LogicClock + + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_RUN_DETECTOR2, false); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_DETECT_RISING_EDGES2, false); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_DETECT_FALLING_EDGES2, false); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_DETECT_PULSES2, true); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_POLARITY2, true); + (*configSet)(cdh, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_LENGTH2, + U32T(handle->info.logicClock)); // in cycles @ LogicClock + } + + (*configSet)(cdh, DAVIS_CONFIG_USB, DAVIS_CONFIG_USB_EARLY_PACKET_DELAY, 8); // in 125µs time-slices (defaults to 1ms) + + return (true); +} + +#define CF_N_TYPE(COARSE, FINE) (struct caer_bias_coarsefine) \ + { .coarseValue = COARSE, .fineValue = FINE, .enabled = true, .sexN = true, \ + .typeNormal = true, .currentLevelNormal = true } + +#define CF_P_TYPE(COARSE, FINE) (struct caer_bias_coarsefine) \ + { .coarseValue = COARSE, .fineValue = FINE, .enabled = true, .sexN = false, \ + .typeNormal = true, .currentLevelNormal = true } + +#define CF_N_TYPE_CAS(COARSE, FINE) (struct caer_bias_coarsefine) \ + { .coarseValue = COARSE, .fineValue = FINE, .enabled = true, .sexN = true, \ + .typeNormal = false, .currentLevelNormal = true } + +/* + * #define CF_P_TYPE_CAS(COARSE, FINE) (struct caer_bias_coarsefine) \ + * { .coarseValue = COARSE, .fineValue = FINE, .enabled = true, .sexN = false, \ + * .typeNormal = false, .currentLevelNormal = true } + */ + +#define CF_N_TYPE_OFF(COARSE, FINE) (struct caer_bias_coarsefine) \ + { .coarseValue = COARSE, .fineValue = FINE, .enabled = false, .sexN = true, \ + .typeNormal = true, .currentLevelNormal = true } + +#define CF_P_TYPE_OFF(COARSE, FINE) (struct caer_bias_coarsefine) \ + { .coarseValue = COARSE, .fineValue = FINE, .enabled = false, .sexN = false, \ + .typeNormal = true, .currentLevelNormal = true } + +#define SHIFTSOURCE(REF, REG, OPMODE) (struct caer_bias_shiftedsource) \ + { .refValue = REF, .regValue = REG, .operatingMode = OPMODE, .voltageLevel = SPLIT_GATE } + +#define VDAC(VOLT, CURR) (struct caer_bias_vdac) \ + { .voltageValue = VOLT, .currentValue = CURR } + +bool davisCommonSendDefaultChipConfig(caerDeviceHandle cdh, +bool (*configSet)(caerDeviceHandle cdh, int8_t modAddr, uint8_t paramAddr, uint32_t param)) { + davisHandle handle = (davisHandle) cdh; + + // Default bias configuration. + if (IS_DAVIS240(handle->info.chipID)) { + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_DIFFBN, caerBiasCoarseFineGenerate(CF_N_TYPE(4, 39))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_ONBN, caerBiasCoarseFineGenerate(CF_N_TYPE(5, 255))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_OFFBN, caerBiasCoarseFineGenerate(CF_N_TYPE(4, 0))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_APSCASEPC, + caerBiasCoarseFineGenerate(CF_N_TYPE_CAS(5, 185))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_DIFFCASBNC, + caerBiasCoarseFineGenerate(CF_N_TYPE_CAS(5, 115))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_APSROSFBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(6, 219))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_LOCALBUFBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(5, 164))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_PIXINVBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(5, 129))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_PRBP, caerBiasCoarseFineGenerate(CF_P_TYPE(2, 58))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_PRSFBP, caerBiasCoarseFineGenerate(CF_P_TYPE(1, 16))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_REFRBP, caerBiasCoarseFineGenerate(CF_P_TYPE(4, 25))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_AEPDBN, caerBiasCoarseFineGenerate(CF_N_TYPE(6, 91))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_LCOLTIMEOUTBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(5, 49))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_AEPUXBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(4, 80))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_AEPUYBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(7, 152))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_IFTHRBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(5, 255))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_IFREFRBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(5, 255))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_PADFOLLBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(7, 215))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_APSOVERFLOWLEVELBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(6, 253))); + + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_BIASBUFFER, + caerBiasCoarseFineGenerate(CF_N_TYPE(5, 254))); + + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_SSP, + caerBiasShiftedSourceGenerate(SHIFTSOURCE(1, 33, SHIFTED_SOURCE))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS240_CONFIG_BIAS_SSN, + caerBiasShiftedSourceGenerate(SHIFTSOURCE(1, 33, SHIFTED_SOURCE))); + + } + + if (IS_DAVIS128(handle->info.chipID) || IS_DAVIS208(handle->info.chipID) + || IS_DAVIS346(handle->info.chipID) || IS_DAVIS640(handle->info.chipID)) { + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_APSOVERFLOWLEVEL, caerBiasVDACGenerate(VDAC(27, 6))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_APSCAS, caerBiasVDACGenerate(VDAC(21, 6))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_ADCREFHIGH, caerBiasVDACGenerate(VDAC(30, 7))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_ADCREFLOW, caerBiasVDACGenerate(VDAC(1, 7))); + + if (IS_DAVIS346(handle->info.chipID) || IS_DAVIS640(handle->info.chipID)) { + // Only DAVIS346 and 640 have ADC testing. + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS346_CONFIG_BIAS_ADCTESTVOLTAGE, + caerBiasVDACGenerate(VDAC(21, 7))); + } + + if (IS_DAVIS208(handle->info.chipID)) { + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS208_CONFIG_BIAS_RESETHIGHPASS, caerBiasVDACGenerate(VDAC(63, 7))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS208_CONFIG_BIAS_REFSS, caerBiasVDACGenerate(VDAC(11, 5))); + + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS208_CONFIG_BIAS_REGBIASBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(5, 20))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS208_CONFIG_BIAS_REFSSBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(5, 20))); + } + + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_LOCALBUFBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(5, 164))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_PADFOLLBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(7, 215))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_DIFFBN, caerBiasCoarseFineGenerate(CF_N_TYPE(4, 39))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_ONBN, caerBiasCoarseFineGenerate(CF_N_TYPE(5, 255))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_OFFBN, caerBiasCoarseFineGenerate(CF_N_TYPE(4, 1))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_PIXINVBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(5, 129))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_PRBP, caerBiasCoarseFineGenerate(CF_P_TYPE(2, 58))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_PRSFBP, caerBiasCoarseFineGenerate(CF_P_TYPE(1, 16))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_REFRBP, caerBiasCoarseFineGenerate(CF_P_TYPE(4, 25))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_READOUTBUFBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(6, 20))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_APSROSFBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(6, 219))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_ADCCOMPBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(5, 20))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_COLSELLOWBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(0, 1))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_DACBUFBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(6, 60))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_LCOLTIMEOUTBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(5, 49))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_AEPDBN, caerBiasCoarseFineGenerate(CF_N_TYPE(6, 91))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_AEPUXBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(4, 80))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_AEPUYBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(7, 152))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_IFREFRBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(5, 255))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_IFTHRBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(5, 255))); + + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_BIASBUFFER, + caerBiasCoarseFineGenerate(CF_N_TYPE(5, 254))); + + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_SSP, + caerBiasShiftedSourceGenerate(SHIFTSOURCE(1, 33, SHIFTED_SOURCE))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS128_CONFIG_BIAS_SSN, + caerBiasShiftedSourceGenerate(SHIFTSOURCE(1, 33, SHIFTED_SOURCE))); + + if (IS_DAVIS640(handle->info.chipID)) { + // Slow down pixels for big 640x480 array, to avoid overwhelming the AER bus. + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS640_CONFIG_BIAS_PRBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(2, 3))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVIS640_CONFIG_BIAS_PRSFBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(1, 1))); + } + } + + if (IS_DAVISRGB(handle->info.chipID)) { + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_APSCAS, caerBiasVDACGenerate(VDAC(21, 4))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_OVG1LO, caerBiasVDACGenerate(VDAC(21, 4))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_OVG2LO, caerBiasVDACGenerate(VDAC(0, 0))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_TX2OVG2HI, caerBiasVDACGenerate(VDAC(63, 0))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_GND07, caerBiasVDACGenerate(VDAC(13, 4))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_ADCTESTVOLTAGE, caerBiasVDACGenerate(VDAC(21, 0))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_ADCREFHIGH, caerBiasVDACGenerate(VDAC(63, 7))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_ADCREFLOW, caerBiasVDACGenerate(VDAC(0, 7))); + + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_IFREFRBN, + caerBiasCoarseFineGenerate(CF_N_TYPE_OFF(5, 255))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_IFTHRBN, + caerBiasCoarseFineGenerate(CF_N_TYPE_OFF(5, 255))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_LOCALBUFBN, + caerBiasCoarseFineGenerate(CF_N_TYPE_OFF(5, 164))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_PADFOLLBN, + caerBiasCoarseFineGenerate(CF_N_TYPE_OFF(7, 209))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_PIXINVBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(4, 164))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_DIFFBN, caerBiasCoarseFineGenerate(CF_N_TYPE(4, 54))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_ONBN, caerBiasCoarseFineGenerate(CF_N_TYPE(6, 63))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_OFFBN, caerBiasCoarseFineGenerate(CF_N_TYPE(2, 138))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_PRBP, caerBiasCoarseFineGenerate(CF_P_TYPE(1, 108))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_PRSFBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(1, 108))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_REFRBP, caerBiasCoarseFineGenerate(CF_P_TYPE(4, 28))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_ARRAYBIASBUFFERBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(6, 128))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_ARRAYLOGICBUFFERBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(5, 255))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_FALLTIMEBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(7, 41))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_RISETIMEBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(6, 162))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_READOUTBUFBP, + caerBiasCoarseFineGenerate(CF_P_TYPE_OFF(6, 20))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_APSROSFBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(6, 255))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_ADCCOMPBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(4, 159))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_DACBUFBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(6, 194))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_LCOLTIMEOUTBN, + caerBiasCoarseFineGenerate(CF_N_TYPE(5, 49))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_AEPDBN, caerBiasCoarseFineGenerate(CF_N_TYPE(6, 91))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_AEPUXBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(4, 80))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_AEPUYBP, + caerBiasCoarseFineGenerate(CF_P_TYPE(7, 152))); + + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_BIASBUFFER, + caerBiasCoarseFineGenerate(CF_N_TYPE(6, 251))); + + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_SSP, + caerBiasShiftedSourceGenerate(SHIFTSOURCE(1, 33, TIED_TO_RAIL))); + (*configSet)(cdh, DAVIS_CONFIG_BIAS, DAVISRGB_CONFIG_BIAS_SSN, + caerBiasShiftedSourceGenerate(SHIFTSOURCE(2, 33, SHIFTED_SOURCE))); + } + + // Default chip configuration. + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS128_CONFIG_CHIP_DIGITALMUX0, 0); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS128_CONFIG_CHIP_DIGITALMUX1, 0); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS128_CONFIG_CHIP_DIGITALMUX2, 0); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS128_CONFIG_CHIP_DIGITALMUX3, 0); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS128_CONFIG_CHIP_ANALOGMUX0, 0); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS128_CONFIG_CHIP_ANALOGMUX1, 0); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS128_CONFIG_CHIP_ANALOGMUX2, 0); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS128_CONFIG_CHIP_BIASMUX0, 0); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS128_CONFIG_CHIP_RESETCALIBNEURON, true); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS128_CONFIG_CHIP_TYPENCALIBNEURON, false); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS128_CONFIG_CHIP_RESETTESTPIXEL, true); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS128_CONFIG_CHIP_AERNAROW, false); // Use nArow in the AER state machine. + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS128_CONFIG_CHIP_USEAOUT, false); // Enable analog pads for aMUX output (testing). + + // No GlobalShutter flag set here, we already set it above for the APS GS flag, + // and that is automatically propagated to the chip config shift-register in + // configSet() and kept in sync. + + // Special extra pixels control for DAVIS240 A/B. + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS240_CONFIG_CHIP_SPECIALPIXELCONTROL, false); + + // Select which gray counter to use with the internal ADC: '0' means the external gray counter is used, which + // has to be supplied off-chip. '1' means the on-chip gray counter is used instead. + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS128_CONFIG_CHIP_SELECTGRAYCOUNTER, 1); + + // Test ADC functionality: if true, the ADC takes its input voltage not from the pixel, but from the + // VDAC 'AdcTestVoltage'. If false, the voltage comes from the pixels. + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS346_CONFIG_CHIP_TESTADC, false); + + if (IS_DAVIS208(handle->info.chipID)) { + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS208_CONFIG_CHIP_SELECTPREAMPAVG, false); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS208_CONFIG_CHIP_SELECTBIASREFSS, false); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS208_CONFIG_CHIP_SELECTSENSE, true); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS208_CONFIG_CHIP_SELECTPOSFB, false); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVIS208_CONFIG_CHIP_SELECTHIGHPASS, false); + } + + if (IS_DAVISRGB(handle->info.chipID)) { + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVISRGB_CONFIG_CHIP_ADJUSTOVG1LO, true); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVISRGB_CONFIG_CHIP_ADJUSTOVG2LO, false); + (*configSet)(cdh, DAVIS_CONFIG_CHIP, DAVISRGB_CONFIG_CHIP_ADJUSTTX2OVG2HI, false); + } + + return (true); +} + +bool davisCommonConfigSet(davisHandle handle, int8_t modAddr, uint8_t paramAddr, uint32_t param) { + davisState state = &handle->state; + + switch (modAddr) { + case CAER_HOST_CONFIG_USB: + switch (paramAddr) { + case CAER_HOST_CONFIG_USB_BUFFER_NUMBER: + atomic_store(&state->usbBufferNumber, param); + + // Notify data acquisition thread to change buffers. + atomic_fetch_or(&state->dataAcquisitionThreadConfigUpdate, 1 << 0); + break; + + case CAER_HOST_CONFIG_USB_BUFFER_SIZE: + atomic_store(&state->usbBufferSize, param); + + // Notify data acquisition thread to change buffers. + atomic_fetch_or(&state->dataAcquisitionThreadConfigUpdate, 1 << 0); + break; + + default: + return (false); + break; + } + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE: + switch (paramAddr) { + case CAER_HOST_CONFIG_DATAEXCHANGE_BUFFER_SIZE: + atomic_store(&state->dataExchangeBufferSize, param); + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE_BLOCKING: + atomic_store(&state->dataExchangeBlocking, param); + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE_START_PRODUCERS: + atomic_store(&state->dataExchangeStartProducers, param); + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE_STOP_PRODUCERS: + atomic_store(&state->dataExchangeStopProducers, param); + break; + + default: + return (false); + break; + } + break; + + case CAER_HOST_CONFIG_PACKETS: + switch (paramAddr) { + case CAER_HOST_CONFIG_PACKETS_MAX_CONTAINER_PACKET_SIZE: + atomic_store(&state->maxPacketContainerPacketSize, param); + break; + + case CAER_HOST_CONFIG_PACKETS_MAX_CONTAINER_INTERVAL: + atomic_store(&state->maxPacketContainerInterval, param); + break; + + default: + return (false); + break; + } + break; + + case DAVIS_CONFIG_MUX: + switch (paramAddr) { + case DAVIS_CONFIG_MUX_RUN: + case DAVIS_CONFIG_MUX_TIMESTAMP_RUN: + case DAVIS_CONFIG_MUX_FORCE_CHIP_BIAS_ENABLE: + case DAVIS_CONFIG_MUX_DROP_DVS_ON_TRANSFER_STALL: + case DAVIS_CONFIG_MUX_DROP_APS_ON_TRANSFER_STALL: + case DAVIS_CONFIG_MUX_DROP_IMU_ON_TRANSFER_STALL: + case DAVIS_CONFIG_MUX_DROP_EXTINPUT_ON_TRANSFER_STALL: + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_MUX, paramAddr, param)); + break; + + case DAVIS_CONFIG_MUX_TIMESTAMP_RESET: { + // Use multi-command VR for more efficient implementation of reset, + // that also guarantees returning to the default state. + if (param) { + uint8_t spiMultiConfig[6 + 6] = { 0 }; + + spiMultiConfig[0] = DAVIS_CONFIG_MUX; + spiMultiConfig[1] = DAVIS_CONFIG_MUX_TIMESTAMP_RESET; + spiMultiConfig[2] = 0x00; + spiMultiConfig[3] = 0x00; + spiMultiConfig[4] = 0x00; + spiMultiConfig[5] = 0x01; + + spiMultiConfig[6] = DAVIS_CONFIG_MUX; + spiMultiConfig[7] = DAVIS_CONFIG_MUX_TIMESTAMP_RESET; + spiMultiConfig[8] = 0x00; + spiMultiConfig[9] = 0x00; + spiMultiConfig[10] = 0x00; + spiMultiConfig[11] = 0x00; + + return (libusb_control_transfer(state->deviceHandle, + LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE, + VENDOR_REQUEST_FPGA_CONFIG_MULTIPLE, 2, 0, spiMultiConfig, sizeof(spiMultiConfig), 0) + == sizeof(spiMultiConfig)); + } + break; + } + + default: + return (false); + break; + } + break; + + case DAVIS_CONFIG_DVS: + switch (paramAddr) { + case DAVIS_CONFIG_DVS_RUN: + case DAVIS_CONFIG_DVS_ACK_DELAY_ROW: + case DAVIS_CONFIG_DVS_ACK_DELAY_COLUMN: + case DAVIS_CONFIG_DVS_ACK_EXTENSION_ROW: + case DAVIS_CONFIG_DVS_ACK_EXTENSION_COLUMN: + case DAVIS_CONFIG_DVS_WAIT_ON_TRANSFER_STALL: + case DAVIS_CONFIG_DVS_FILTER_ROW_ONLY_EVENTS: + case DAVIS_CONFIG_DVS_EXTERNAL_AER_CONTROL: + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_DVS, paramAddr, param)); + break; + + case DAVIS_CONFIG_DVS_FILTER_PIXEL_0_ROW: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_1_ROW: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_2_ROW: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_3_ROW: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_4_ROW: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_5_ROW: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_6_ROW: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_7_ROW: + if (handle->info.dvsHasPixelFilter) { + if (handle->state.dvsInvertXY) { + // Convert to column if X/Y inverted. + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_DVS, U8T(paramAddr + 1), param)); + } + else { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_DVS, paramAddr, param)); + } + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_DVS_FILTER_PIXEL_0_COLUMN: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_1_COLUMN: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_2_COLUMN: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_3_COLUMN: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_4_COLUMN: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_5_COLUMN: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_6_COLUMN: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_7_COLUMN: + if (handle->info.dvsHasPixelFilter) { + if (handle->state.dvsInvertXY) { + // Convert to row if X/Y inverted. + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_DVS, U8T(paramAddr - 1), param)); + } + else { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_DVS, paramAddr, param)); + } + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_DVS_FILTER_BACKGROUND_ACTIVITY: + case DAVIS_CONFIG_DVS_FILTER_BACKGROUND_ACTIVITY_DELTAT: + if (handle->info.dvsHasBackgroundActivityFilter) { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_DVS, paramAddr, param)); + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_DVS_TEST_EVENT_GENERATOR_ENABLE: + if (handle->info.dvsHasTestEventGenerator) { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_DVS, paramAddr, param)); + } + else { + return (false); + } + break; + + default: + return (false); + break; + } + break; + + case DAVIS_CONFIG_APS: + switch (paramAddr) { + case DAVIS_CONFIG_APS_RUN: + case DAVIS_CONFIG_APS_RESET_READ: + case DAVIS_CONFIG_APS_WAIT_ON_TRANSFER_STALL: + case DAVIS_CONFIG_APS_ROW_SETTLE: + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + break; + + case DAVIS_CONFIG_APS_RESET_SETTLE: + case DAVIS_CONFIG_APS_COLUMN_SETTLE: + case DAVIS_CONFIG_APS_NULL_SETTLE: + // Not supported on DAVIS RGB APS state machine. + if (!IS_DAVISRGB(handle->info.chipID)) { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_APS_START_COLUMN_0: + case DAVIS_CONFIG_APS_END_COLUMN_0: + if (state->apsInvertXY) { + // Convert to row if X/Y inverted. + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_APS, U8T(paramAddr + 1), param)); + } + else { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + break; + + case DAVIS_CONFIG_APS_START_ROW_0: + case DAVIS_CONFIG_APS_END_ROW_0: + if (state->apsInvertXY) { + // Convert to column if X/Y inverted. + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_APS, U8T(paramAddr - 1), param)); + } + else { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + break; + + case DAVIS_CONFIG_APS_EXPOSURE: + case DAVIS_CONFIG_APS_FRAME_DELAY: + // Exposure and Frame Delay are in µs, must be converted to native FPGA cycles + // by multiplying with ADC clock value. + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, + param * U16T(handle->info.adcClock))); + break; + + case DAVIS_CONFIG_APS_GLOBAL_SHUTTER: + if (handle->info.apsHasGlobalShutter) { + // Keep in sync with chip config module GlobalShutter parameter. + if (!spiConfigSend(state->deviceHandle, DAVIS_CONFIG_CHIP, DAVIS128_CONFIG_CHIP_GLOBAL_SHUTTER, + param)) { + return (false); + } + + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + else { + return (false); + } + break; + + // TODO: no support on host-side for QuadROI and multi-frame decoding. + case DAVIS_CONFIG_APS_START_COLUMN_1: + case DAVIS_CONFIG_APS_END_COLUMN_1: + case DAVIS_CONFIG_APS_START_COLUMN_2: + case DAVIS_CONFIG_APS_END_COLUMN_2: + case DAVIS_CONFIG_APS_START_COLUMN_3: + case DAVIS_CONFIG_APS_END_COLUMN_3: + if (handle->info.apsHasQuadROI) { + if (state->apsInvertXY) { + // Convert to row if X/Y inverted. + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_APS, U8T(paramAddr + 1), param)); + } + else { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_APS_START_ROW_1: + case DAVIS_CONFIG_APS_END_ROW_1: + case DAVIS_CONFIG_APS_START_ROW_2: + case DAVIS_CONFIG_APS_END_ROW_2: + case DAVIS_CONFIG_APS_START_ROW_3: + case DAVIS_CONFIG_APS_END_ROW_3: + if (handle->info.apsHasQuadROI) { + if (state->apsInvertXY) { + // Convert to column if X/Y inverted. + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_APS, U8T(paramAddr - 1), param)); + } + else { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_APS_USE_INTERNAL_ADC: + case DAVIS_CONFIG_APS_SAMPLE_ENABLE: + case DAVIS_CONFIG_APS_SAMPLE_SETTLE: + case DAVIS_CONFIG_APS_RAMP_RESET: + case DAVIS_CONFIG_APS_RAMP_SHORT_RESET: + case DAVIS_CONFIG_APS_ADC_TEST_MODE: + if (handle->info.apsHasInternalADC) { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + else { + return (false); + } + break; + + case DAVISRGB_CONFIG_APS_TRANSFER: + case DAVISRGB_CONFIG_APS_RSFDSETTLE: + case DAVISRGB_CONFIG_APS_GSPDRESET: + case DAVISRGB_CONFIG_APS_GSRESETFALL: + case DAVISRGB_CONFIG_APS_GSTXFALL: + case DAVISRGB_CONFIG_APS_GSFDRESET: + // Support for DAVISRGB extra timing parameters. + if (IS_DAVISRGB(handle->info.chipID)) { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_APS_SNAPSHOT: { + // Use multi-command VR for more efficient implementation of snapshot, + // that also guarantees returning to the default state (not running). + if (param) { + uint8_t spiMultiConfig[6 + 6] = { 0 }; + + spiMultiConfig[0] = DAVIS_CONFIG_APS; + spiMultiConfig[1] = DAVIS_CONFIG_APS_RUN; + spiMultiConfig[2] = 0x00; + spiMultiConfig[3] = 0x00; + spiMultiConfig[4] = 0x00; + spiMultiConfig[5] = 0x01; + + spiMultiConfig[6] = DAVIS_CONFIG_APS; + spiMultiConfig[7] = DAVIS_CONFIG_APS_RUN; + spiMultiConfig[8] = 0x00; + spiMultiConfig[9] = 0x00; + spiMultiConfig[10] = 0x00; + spiMultiConfig[11] = 0x00; + + return (libusb_control_transfer(state->deviceHandle, + LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE, + VENDOR_REQUEST_FPGA_CONFIG_MULTIPLE, 2, 0, spiMultiConfig, sizeof(spiMultiConfig), 0) + == sizeof(spiMultiConfig)); + } + break; + } + + default: + return (false); + break; + } + break; + + case DAVIS_CONFIG_IMU: + switch (paramAddr) { + case DAVIS_CONFIG_IMU_RUN: + case DAVIS_CONFIG_IMU_TEMP_STANDBY: + case DAVIS_CONFIG_IMU_ACCEL_STANDBY: + case DAVIS_CONFIG_IMU_GYRO_STANDBY: + case DAVIS_CONFIG_IMU_LP_CYCLE: + case DAVIS_CONFIG_IMU_LP_WAKEUP: + case DAVIS_CONFIG_IMU_SAMPLE_RATE_DIVIDER: + case DAVIS_CONFIG_IMU_DIGITAL_LOW_PASS_FILTER: + case DAVIS_CONFIG_IMU_ACCEL_FULL_SCALE: + case DAVIS_CONFIG_IMU_GYRO_FULL_SCALE: + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_IMU, paramAddr, param)); + break; + + default: + return (false); + break; + } + break; + + case DAVIS_CONFIG_EXTINPUT: + switch (paramAddr) { + case DAVIS_CONFIG_EXTINPUT_RUN_DETECTOR: + case DAVIS_CONFIG_EXTINPUT_DETECT_RISING_EDGES: + case DAVIS_CONFIG_EXTINPUT_DETECT_FALLING_EDGES: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSES: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_POLARITY: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_LENGTH: + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_EXTINPUT, paramAddr, param)); + break; + + case DAVIS_CONFIG_EXTINPUT_RUN_GENERATOR: + case DAVIS_CONFIG_EXTINPUT_GENERATE_USE_CUSTOM_SIGNAL: + case DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_POLARITY: + case DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_INTERVAL: + case DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_LENGTH: + case DAVIS_CONFIG_EXTINPUT_GENERATE_INJECT_ON_RISING_EDGE: + case DAVIS_CONFIG_EXTINPUT_GENERATE_INJECT_ON_FALLING_EDGE: + if (handle->info.extInputHasGenerator) { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_EXTINPUT, paramAddr, param)); + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_EXTINPUT_RUN_DETECTOR1: + case DAVIS_CONFIG_EXTINPUT_DETECT_RISING_EDGES1: + case DAVIS_CONFIG_EXTINPUT_DETECT_FALLING_EDGES1: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSES1: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_POLARITY1: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_LENGTH1: + case DAVIS_CONFIG_EXTINPUT_RUN_DETECTOR2: + case DAVIS_CONFIG_EXTINPUT_DETECT_RISING_EDGES2: + case DAVIS_CONFIG_EXTINPUT_DETECT_FALLING_EDGES2: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSES2: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_POLARITY2: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_LENGTH2: + if (handle->info.extInputHasExtraDetectors) { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_EXTINPUT, paramAddr, param)); + } + else { + return (false); + } + break; + + default: + return (false); + break; + } + break; + + case DAVIS_CONFIG_BIAS: // Also DAVIS_CONFIG_CHIP (starts at address 128). + if (paramAddr < 128) { + // BIASING (DAVIS_CONFIG_BIAS). + if (IS_DAVIS240(handle->info.chipID)) { + // DAVIS240 uses the old bias generator with 22 branches, and uses all of them. + if (paramAddr < 22) { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_BIAS, paramAddr, param)); + } + } + else if (IS_DAVIS128(handle->info.chipID) || IS_DAVIS208(handle->info.chipID) + || IS_DAVIS346(handle->info.chipID) || IS_DAVIS640(handle->info.chipID)) { + // All new DAVISes use the new bias generator with 37 branches. + switch (paramAddr) { + // Same and shared between all of the above chips. + case DAVIS128_CONFIG_BIAS_APSOVERFLOWLEVEL: + case DAVIS128_CONFIG_BIAS_APSCAS: + case DAVIS128_CONFIG_BIAS_ADCREFHIGH: + case DAVIS128_CONFIG_BIAS_ADCREFLOW: + case DAVIS128_CONFIG_BIAS_LOCALBUFBN: + case DAVIS128_CONFIG_BIAS_PADFOLLBN: + case DAVIS128_CONFIG_BIAS_DIFFBN: + case DAVIS128_CONFIG_BIAS_ONBN: + case DAVIS128_CONFIG_BIAS_OFFBN: + case DAVIS128_CONFIG_BIAS_PIXINVBN: + case DAVIS128_CONFIG_BIAS_PRBP: + case DAVIS128_CONFIG_BIAS_PRSFBP: + case DAVIS128_CONFIG_BIAS_REFRBP: + case DAVIS128_CONFIG_BIAS_READOUTBUFBP: + case DAVIS128_CONFIG_BIAS_APSROSFBN: + case DAVIS128_CONFIG_BIAS_ADCCOMPBP: + case DAVIS128_CONFIG_BIAS_COLSELLOWBN: + case DAVIS128_CONFIG_BIAS_DACBUFBP: + case DAVIS128_CONFIG_BIAS_LCOLTIMEOUTBN: + case DAVIS128_CONFIG_BIAS_AEPDBN: + case DAVIS128_CONFIG_BIAS_AEPUXBP: + case DAVIS128_CONFIG_BIAS_AEPUYBP: + case DAVIS128_CONFIG_BIAS_IFREFRBN: + case DAVIS128_CONFIG_BIAS_IFTHRBN: + case DAVIS128_CONFIG_BIAS_BIASBUFFER: + case DAVIS128_CONFIG_BIAS_SSP: + case DAVIS128_CONFIG_BIAS_SSN: + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_BIAS, paramAddr, param)); + break; + + case DAVIS346_CONFIG_BIAS_ADCTESTVOLTAGE: + // Only supported by DAVIS346 and DAVIS640 chips. + if (IS_DAVIS346(handle->info.chipID) || IS_DAVIS640(handle->info.chipID)) { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_BIAS, paramAddr, param)); + } + break; + + case DAVIS208_CONFIG_BIAS_RESETHIGHPASS: + case DAVIS208_CONFIG_BIAS_REFSS: + case DAVIS208_CONFIG_BIAS_REGBIASBP: + case DAVIS208_CONFIG_BIAS_REFSSBN: + // Only supported by DAVIS208 chips. + if (IS_DAVIS208(handle->info.chipID)) { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_BIAS, paramAddr, param)); + } + break; + + default: + return (false); + break; + } + } + else if (IS_DAVISRGB(handle->info.chipID)) { + // DAVISRGB also uses the 37 branches bias generator, with different values. + switch (paramAddr) { + case DAVISRGB_CONFIG_BIAS_APSCAS: + case DAVISRGB_CONFIG_BIAS_OVG1LO: + case DAVISRGB_CONFIG_BIAS_OVG2LO: + case DAVISRGB_CONFIG_BIAS_TX2OVG2HI: + case DAVISRGB_CONFIG_BIAS_GND07: + case DAVISRGB_CONFIG_BIAS_ADCTESTVOLTAGE: + case DAVISRGB_CONFIG_BIAS_ADCREFHIGH: + case DAVISRGB_CONFIG_BIAS_ADCREFLOW: + case DAVISRGB_CONFIG_BIAS_IFREFRBN: + case DAVISRGB_CONFIG_BIAS_IFTHRBN: + case DAVISRGB_CONFIG_BIAS_LOCALBUFBN: + case DAVISRGB_CONFIG_BIAS_PADFOLLBN: + case DAVISRGB_CONFIG_BIAS_PIXINVBN: + case DAVISRGB_CONFIG_BIAS_DIFFBN: + case DAVISRGB_CONFIG_BIAS_ONBN: + case DAVISRGB_CONFIG_BIAS_OFFBN: + case DAVISRGB_CONFIG_BIAS_PRBP: + case DAVISRGB_CONFIG_BIAS_PRSFBP: + case DAVISRGB_CONFIG_BIAS_REFRBP: + case DAVISRGB_CONFIG_BIAS_ARRAYBIASBUFFERBN: + case DAVISRGB_CONFIG_BIAS_ARRAYLOGICBUFFERBN: + case DAVISRGB_CONFIG_BIAS_FALLTIMEBN: + case DAVISRGB_CONFIG_BIAS_RISETIMEBP: + case DAVISRGB_CONFIG_BIAS_READOUTBUFBP: + case DAVISRGB_CONFIG_BIAS_APSROSFBN: + case DAVISRGB_CONFIG_BIAS_ADCCOMPBP: + case DAVISRGB_CONFIG_BIAS_DACBUFBP: + case DAVISRGB_CONFIG_BIAS_LCOLTIMEOUTBN: + case DAVISRGB_CONFIG_BIAS_AEPDBN: + case DAVISRGB_CONFIG_BIAS_AEPUXBP: + case DAVISRGB_CONFIG_BIAS_AEPUYBP: + case DAVISRGB_CONFIG_BIAS_BIASBUFFER: + case DAVISRGB_CONFIG_BIAS_SSP: + case DAVISRGB_CONFIG_BIAS_SSN: + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_BIAS, paramAddr, param)); + break; + + default: + return (false); + break; + } + } + } + else { + // CHIP CONFIGURATION (DAVIS_CONFIG_CHIP). + switch (paramAddr) { + // Chip configuration common to all chips. + case DAVIS128_CONFIG_CHIP_DIGITALMUX0: + case DAVIS128_CONFIG_CHIP_DIGITALMUX1: + case DAVIS128_CONFIG_CHIP_DIGITALMUX2: + case DAVIS128_CONFIG_CHIP_DIGITALMUX3: + case DAVIS128_CONFIG_CHIP_ANALOGMUX0: + case DAVIS128_CONFIG_CHIP_ANALOGMUX1: + case DAVIS128_CONFIG_CHIP_ANALOGMUX2: + case DAVIS128_CONFIG_CHIP_BIASMUX0: + case DAVIS128_CONFIG_CHIP_RESETCALIBNEURON: + case DAVIS128_CONFIG_CHIP_TYPENCALIBNEURON: + case DAVIS128_CONFIG_CHIP_RESETTESTPIXEL: + case DAVIS128_CONFIG_CHIP_AERNAROW: + case DAVIS128_CONFIG_CHIP_USEAOUT: + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_CHIP, paramAddr, param)); + break; + + case DAVIS240_CONFIG_CHIP_SPECIALPIXELCONTROL: + // Only supported by DAVIS240 A/B chips. + if (IS_DAVIS240A(handle->info.chipID) || IS_DAVIS240B(handle->info.chipID)) { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_CHIP, paramAddr, param)); + } + break; + + case DAVIS128_CONFIG_CHIP_GLOBAL_SHUTTER: + // Only supported by some chips. + if (handle->info.apsHasGlobalShutter) { + // Keep in sync with APS module GlobalShutter parameter. + if (!spiConfigSend(state->deviceHandle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_GLOBAL_SHUTTER, + param)) { + return (false); + } + + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_CHIP, paramAddr, param)); + } + break; + + case DAVIS128_CONFIG_CHIP_SELECTGRAYCOUNTER: + // Only supported by the new DAVIS chips. + if (IS_DAVIS128( + handle->info.chipID) || IS_DAVIS208(handle->info.chipID) || IS_DAVIS346(handle->info.chipID) + || IS_DAVIS640(handle->info.chipID) || IS_DAVISRGB(handle->info.chipID)) { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_CHIP, paramAddr, param)); + } + break; + + case DAVIS346_CONFIG_CHIP_TESTADC: + // Only supported by some of the new DAVIS chips. + if (IS_DAVIS346( + handle->info.chipID) || IS_DAVIS640(handle->info.chipID) || IS_DAVISRGB(handle->info.chipID)) { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_CHIP, paramAddr, param)); + } + break; + + case DAVISRGB_CONFIG_CHIP_ADJUSTOVG1LO: // Also DAVIS208_CONFIG_CHIP_SELECTPREAMPAVG. + case DAVISRGB_CONFIG_CHIP_ADJUSTOVG2LO: // Also DAVIS208_CONFIG_CHIP_SELECTBIASREFSS. + case DAVISRGB_CONFIG_CHIP_ADJUSTTX2OVG2HI: // Also DAVIS208_CONFIG_CHIP_SELECTSENSE. + // Only supported by DAVIS208 and DAVISRGB. + if (IS_DAVIS208(handle->info.chipID) || IS_DAVISRGB(handle->info.chipID)) { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_CHIP, paramAddr, param)); + } + break; + + case DAVIS208_CONFIG_CHIP_SELECTPOSFB: + case DAVIS208_CONFIG_CHIP_SELECTHIGHPASS: + // Only supported by DAVIS208. + if (IS_DAVIS208(handle->info.chipID)) { + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_CHIP, paramAddr, param)); + } + break; + + default: + return (false); + break; + } + } + + return (false); + break; + + case DAVIS_CONFIG_SYSINFO: + // No SystemInfo parameters can ever be set! + return (false); + break; + + case DAVIS_CONFIG_USB: + switch (paramAddr) { + case DAVIS_CONFIG_USB_RUN: + case DAVIS_CONFIG_USB_EARLY_PACKET_DELAY: + return (spiConfigSend(state->deviceHandle, DAVIS_CONFIG_USB, paramAddr, param)); + break; + + default: + return (false); + break; + } + break; + + default: + return (false); + break; + } + + return (true); +} + +bool davisCommonConfigGet(davisHandle handle, int8_t modAddr, uint8_t paramAddr, uint32_t *param) { + davisState state = &handle->state; + + switch (modAddr) { + case CAER_HOST_CONFIG_USB: + switch (paramAddr) { + case CAER_HOST_CONFIG_USB_BUFFER_NUMBER: + *param = U32T(atomic_load(&state->usbBufferNumber)); + break; + + case CAER_HOST_CONFIG_USB_BUFFER_SIZE: + *param = U32T(atomic_load(&state->usbBufferSize)); + break; + + default: + return (false); + break; + } + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE: + switch (paramAddr) { + case CAER_HOST_CONFIG_DATAEXCHANGE_BUFFER_SIZE: + *param = U32T(atomic_load(&state->dataExchangeBufferSize)); + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE_BLOCKING: + *param = atomic_load(&state->dataExchangeBlocking); + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE_START_PRODUCERS: + *param = atomic_load(&state->dataExchangeStartProducers); + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE_STOP_PRODUCERS: + *param = atomic_load(&state->dataExchangeStopProducers); + break; + + default: + return (false); + break; + } + break; + + case CAER_HOST_CONFIG_PACKETS: + switch (paramAddr) { + case CAER_HOST_CONFIG_PACKETS_MAX_CONTAINER_PACKET_SIZE: + *param = U32T(atomic_load(&state->maxPacketContainerPacketSize)); + break; + + case CAER_HOST_CONFIG_PACKETS_MAX_CONTAINER_INTERVAL: + *param = U32T(atomic_load(&state->maxPacketContainerInterval)); + break; + + default: + return (false); + break; + } + break; + + case DAVIS_CONFIG_MUX: + switch (paramAddr) { + case DAVIS_CONFIG_MUX_RUN: + case DAVIS_CONFIG_MUX_TIMESTAMP_RUN: + case DAVIS_CONFIG_MUX_FORCE_CHIP_BIAS_ENABLE: + case DAVIS_CONFIG_MUX_DROP_DVS_ON_TRANSFER_STALL: + case DAVIS_CONFIG_MUX_DROP_APS_ON_TRANSFER_STALL: + case DAVIS_CONFIG_MUX_DROP_IMU_ON_TRANSFER_STALL: + case DAVIS_CONFIG_MUX_DROP_EXTINPUT_ON_TRANSFER_STALL: + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_MUX, paramAddr, param)); + break; + + case DAVIS_CONFIG_MUX_TIMESTAMP_RESET: + // Always false because it's an impulse, it resets itself automatically. + *param = false; + break; + + default: + return (false); + break; + } + break; + + case DAVIS_CONFIG_DVS: + switch (paramAddr) { + case DAVIS_CONFIG_DVS_SIZE_COLUMNS: + case DAVIS_CONFIG_DVS_SIZE_ROWS: + case DAVIS_CONFIG_DVS_ORIENTATION_INFO: + case DAVIS_CONFIG_DVS_RUN: + case DAVIS_CONFIG_DVS_ACK_DELAY_ROW: + case DAVIS_CONFIG_DVS_ACK_DELAY_COLUMN: + case DAVIS_CONFIG_DVS_ACK_EXTENSION_ROW: + case DAVIS_CONFIG_DVS_ACK_EXTENSION_COLUMN: + case DAVIS_CONFIG_DVS_WAIT_ON_TRANSFER_STALL: + case DAVIS_CONFIG_DVS_FILTER_ROW_ONLY_EVENTS: + case DAVIS_CONFIG_DVS_EXTERNAL_AER_CONTROL: + case DAVIS_CONFIG_DVS_HAS_PIXEL_FILTER: + case DAVIS_CONFIG_DVS_HAS_BACKGROUND_ACTIVITY_FILTER: + case DAVIS_CONFIG_DVS_HAS_TEST_EVENT_GENERATOR: + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_DVS, paramAddr, param)); + break; + + case DAVIS_CONFIG_DVS_FILTER_PIXEL_0_ROW: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_1_ROW: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_2_ROW: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_3_ROW: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_4_ROW: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_5_ROW: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_6_ROW: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_7_ROW: + if (handle->info.dvsHasPixelFilter) { + if (handle->state.dvsInvertXY) { + // Convert to column if X/Y inverted. + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_DVS, U8T(paramAddr + 1), param)); + } + else { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_DVS, paramAddr, param)); + } + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_DVS_FILTER_PIXEL_0_COLUMN: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_1_COLUMN: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_2_COLUMN: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_3_COLUMN: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_4_COLUMN: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_5_COLUMN: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_6_COLUMN: + case DAVIS_CONFIG_DVS_FILTER_PIXEL_7_COLUMN: + if (handle->info.dvsHasPixelFilter) { + if (handle->state.dvsInvertXY) { + // Convert to row if X/Y inverted. + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_DVS, U8T(paramAddr - 1), param)); + } + else { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_DVS, paramAddr, param)); + } + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_DVS_FILTER_BACKGROUND_ACTIVITY: + case DAVIS_CONFIG_DVS_FILTER_BACKGROUND_ACTIVITY_DELTAT: + if (handle->info.dvsHasBackgroundActivityFilter) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_DVS, paramAddr, param)); + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_DVS_TEST_EVENT_GENERATOR_ENABLE: + if (handle->info.dvsHasTestEventGenerator) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_DVS, paramAddr, param)); + } + else { + return (false); + } + break; + + default: + return (false); + break; + } + break; + + case DAVIS_CONFIG_APS: + switch (paramAddr) { + case DAVIS_CONFIG_APS_SIZE_COLUMNS: + case DAVIS_CONFIG_APS_SIZE_ROWS: + case DAVIS_CONFIG_APS_ORIENTATION_INFO: + case DAVIS_CONFIG_APS_COLOR_FILTER: + case DAVIS_CONFIG_APS_RUN: + case DAVIS_CONFIG_APS_RESET_READ: + case DAVIS_CONFIG_APS_WAIT_ON_TRANSFER_STALL: + case DAVIS_CONFIG_APS_ROW_SETTLE: + case DAVIS_CONFIG_APS_HAS_GLOBAL_SHUTTER: + case DAVIS_CONFIG_APS_HAS_QUAD_ROI: + case DAVIS_CONFIG_APS_HAS_EXTERNAL_ADC: + case DAVIS_CONFIG_APS_HAS_INTERNAL_ADC: + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + break; + + case DAVIS_CONFIG_APS_START_COLUMN_0: + case DAVIS_CONFIG_APS_END_COLUMN_0: + if (state->apsInvertXY) { + // Convert to row if X/Y inverted. + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, U8T(paramAddr + 1), param)); + } + else { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + break; + + case DAVIS_CONFIG_APS_START_ROW_0: + case DAVIS_CONFIG_APS_END_ROW_0: + if (state->apsInvertXY) { + // Convert to column if X/Y inverted. + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, U8T(paramAddr - 1), param)); + } + else { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + break; + + case DAVIS_CONFIG_APS_RESET_SETTLE: + case DAVIS_CONFIG_APS_COLUMN_SETTLE: + case DAVIS_CONFIG_APS_NULL_SETTLE: + // Not supported on DAVIS RGB APS state machine. + if (!IS_DAVISRGB(handle->info.chipID)) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_APS_EXPOSURE: + case DAVIS_CONFIG_APS_FRAME_DELAY: { + // Exposure and Frame Delay are in µs, must be converted from native FPGA cycles + // by dividing with ADC clock value. + uint32_t cyclesValue = 0; + if (!spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, &cyclesValue)) { + return (false); + } + + *param = cyclesValue / U16T(handle->info.adcClock); + + return (true); + break; + } + + case DAVIS_CONFIG_APS_GLOBAL_SHUTTER: + if (handle->info.apsHasGlobalShutter) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_APS_START_COLUMN_1: + case DAVIS_CONFIG_APS_END_COLUMN_1: + case DAVIS_CONFIG_APS_START_COLUMN_2: + case DAVIS_CONFIG_APS_END_COLUMN_2: + case DAVIS_CONFIG_APS_START_COLUMN_3: + case DAVIS_CONFIG_APS_END_COLUMN_3: + if (handle->info.apsHasQuadROI) { + if (state->apsInvertXY) { + // Convert to row if X/Y inverted. + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, U8T(paramAddr + 1), param)); + } + else { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_APS_START_ROW_1: + case DAVIS_CONFIG_APS_END_ROW_1: + case DAVIS_CONFIG_APS_START_ROW_2: + case DAVIS_CONFIG_APS_END_ROW_2: + case DAVIS_CONFIG_APS_START_ROW_3: + case DAVIS_CONFIG_APS_END_ROW_3: + if (handle->info.apsHasQuadROI) { + if (state->apsInvertXY) { + // Convert to column if X/Y inverted. + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, U8T(paramAddr - 1), param)); + } + else { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_APS_USE_INTERNAL_ADC: + case DAVIS_CONFIG_APS_SAMPLE_ENABLE: + case DAVIS_CONFIG_APS_SAMPLE_SETTLE: + case DAVIS_CONFIG_APS_RAMP_RESET: + case DAVIS_CONFIG_APS_RAMP_SHORT_RESET: + case DAVIS_CONFIG_APS_ADC_TEST_MODE: + if (handle->info.apsHasInternalADC) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + else { + return (false); + } + break; + + case DAVISRGB_CONFIG_APS_TRANSFER: + case DAVISRGB_CONFIG_APS_RSFDSETTLE: + case DAVISRGB_CONFIG_APS_GSPDRESET: + case DAVISRGB_CONFIG_APS_GSRESETFALL: + case DAVISRGB_CONFIG_APS_GSTXFALL: + case DAVISRGB_CONFIG_APS_GSFDRESET: + // Support for DAVISRGB extra timing parameters. + if (IS_DAVISRGB(handle->info.chipID)) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, paramAddr, param)); + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_APS_SNAPSHOT: + // Always false because it's an impulse, it resets itself automatically. + *param = false; + break; + + default: + return (false); + break; + } + break; + + case DAVIS_CONFIG_IMU: + switch (paramAddr) { + case DAVIS_CONFIG_IMU_RUN: + case DAVIS_CONFIG_IMU_TEMP_STANDBY: + case DAVIS_CONFIG_IMU_ACCEL_STANDBY: + case DAVIS_CONFIG_IMU_GYRO_STANDBY: + case DAVIS_CONFIG_IMU_LP_CYCLE: + case DAVIS_CONFIG_IMU_LP_WAKEUP: + case DAVIS_CONFIG_IMU_SAMPLE_RATE_DIVIDER: + case DAVIS_CONFIG_IMU_DIGITAL_LOW_PASS_FILTER: + case DAVIS_CONFIG_IMU_ACCEL_FULL_SCALE: + case DAVIS_CONFIG_IMU_GYRO_FULL_SCALE: + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_IMU, paramAddr, param)); + break; + + default: + return (false); + break; + } + break; + + case DAVIS_CONFIG_EXTINPUT: + switch (paramAddr) { + case DAVIS_CONFIG_EXTINPUT_RUN_DETECTOR: + case DAVIS_CONFIG_EXTINPUT_DETECT_RISING_EDGES: + case DAVIS_CONFIG_EXTINPUT_DETECT_FALLING_EDGES: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSES: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_POLARITY: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_LENGTH: + case DAVIS_CONFIG_EXTINPUT_HAS_GENERATOR: + case DAVIS_CONFIG_EXTINPUT_HAS_EXTRA_DETECTORS: + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_EXTINPUT, paramAddr, param)); + break; + + case DAVIS_CONFIG_EXTINPUT_RUN_GENERATOR: + case DAVIS_CONFIG_EXTINPUT_GENERATE_USE_CUSTOM_SIGNAL: + case DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_POLARITY: + case DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_INTERVAL: + case DAVIS_CONFIG_EXTINPUT_GENERATE_PULSE_LENGTH: + case DAVIS_CONFIG_EXTINPUT_GENERATE_INJECT_ON_RISING_EDGE: + case DAVIS_CONFIG_EXTINPUT_GENERATE_INJECT_ON_FALLING_EDGE: + if (handle->info.extInputHasGenerator) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_EXTINPUT, paramAddr, param)); + } + else { + return (false); + } + break; + + case DAVIS_CONFIG_EXTINPUT_RUN_DETECTOR1: + case DAVIS_CONFIG_EXTINPUT_DETECT_RISING_EDGES1: + case DAVIS_CONFIG_EXTINPUT_DETECT_FALLING_EDGES1: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSES1: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_POLARITY1: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_LENGTH1: + case DAVIS_CONFIG_EXTINPUT_RUN_DETECTOR2: + case DAVIS_CONFIG_EXTINPUT_DETECT_RISING_EDGES2: + case DAVIS_CONFIG_EXTINPUT_DETECT_FALLING_EDGES2: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSES2: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_POLARITY2: + case DAVIS_CONFIG_EXTINPUT_DETECT_PULSE_LENGTH2: + if (handle->info.extInputHasExtraDetectors) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_EXTINPUT, paramAddr, param)); + } + else { + return (false); + } + break; + + default: + return (false); + break; + } + break; + + case DAVIS_CONFIG_BIAS: // Also DAVIS_CONFIG_CHIP (starts at address 128). + if (paramAddr < 128) { + // BIASING (DAVIS_CONFIG_BIAS). + if (IS_DAVIS240(handle->info.chipID)) { + // DAVIS240 uses the old bias generator with 22 branches, and uses all of them. + if (paramAddr < 22) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_BIAS, paramAddr, param)); + } + } + else if (IS_DAVIS128(handle->info.chipID) || IS_DAVIS208(handle->info.chipID) + || IS_DAVIS346(handle->info.chipID) || IS_DAVIS640(handle->info.chipID)) { + // All new DAVISes use the new bias generator with 37 branches. + switch (paramAddr) { + // Same and shared between all of the above chips. + case DAVIS128_CONFIG_BIAS_APSOVERFLOWLEVEL: + case DAVIS128_CONFIG_BIAS_APSCAS: + case DAVIS128_CONFIG_BIAS_ADCREFHIGH: + case DAVIS128_CONFIG_BIAS_ADCREFLOW: + case DAVIS128_CONFIG_BIAS_LOCALBUFBN: + case DAVIS128_CONFIG_BIAS_PADFOLLBN: + case DAVIS128_CONFIG_BIAS_DIFFBN: + case DAVIS128_CONFIG_BIAS_ONBN: + case DAVIS128_CONFIG_BIAS_OFFBN: + case DAVIS128_CONFIG_BIAS_PIXINVBN: + case DAVIS128_CONFIG_BIAS_PRBP: + case DAVIS128_CONFIG_BIAS_PRSFBP: + case DAVIS128_CONFIG_BIAS_REFRBP: + case DAVIS128_CONFIG_BIAS_READOUTBUFBP: + case DAVIS128_CONFIG_BIAS_APSROSFBN: + case DAVIS128_CONFIG_BIAS_ADCCOMPBP: + case DAVIS128_CONFIG_BIAS_COLSELLOWBN: + case DAVIS128_CONFIG_BIAS_DACBUFBP: + case DAVIS128_CONFIG_BIAS_LCOLTIMEOUTBN: + case DAVIS128_CONFIG_BIAS_AEPDBN: + case DAVIS128_CONFIG_BIAS_AEPUXBP: + case DAVIS128_CONFIG_BIAS_AEPUYBP: + case DAVIS128_CONFIG_BIAS_IFREFRBN: + case DAVIS128_CONFIG_BIAS_IFTHRBN: + case DAVIS128_CONFIG_BIAS_BIASBUFFER: + case DAVIS128_CONFIG_BIAS_SSP: + case DAVIS128_CONFIG_BIAS_SSN: + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_BIAS, paramAddr, param)); + break; + + case DAVIS346_CONFIG_BIAS_ADCTESTVOLTAGE: + // Only supported by DAVIS346 and DAVIS640 chips. + if (IS_DAVIS346(handle->info.chipID) || IS_DAVIS640(handle->info.chipID)) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_BIAS, paramAddr, param)); + } + break; + + case DAVIS208_CONFIG_BIAS_RESETHIGHPASS: + case DAVIS208_CONFIG_BIAS_REFSS: + case DAVIS208_CONFIG_BIAS_REGBIASBP: + case DAVIS208_CONFIG_BIAS_REFSSBN: + // Only supported by DAVIS208 chips. + if (IS_DAVIS208(handle->info.chipID)) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_BIAS, paramAddr, param)); + } + break; + + default: + return (false); + break; + } + } + else if (IS_DAVISRGB(handle->info.chipID)) { + // DAVISRGB also uses the 37 branches bias generator, with different values. + switch (paramAddr) { + case DAVISRGB_CONFIG_BIAS_APSCAS: + case DAVISRGB_CONFIG_BIAS_OVG1LO: + case DAVISRGB_CONFIG_BIAS_OVG2LO: + case DAVISRGB_CONFIG_BIAS_TX2OVG2HI: + case DAVISRGB_CONFIG_BIAS_GND07: + case DAVISRGB_CONFIG_BIAS_ADCTESTVOLTAGE: + case DAVISRGB_CONFIG_BIAS_ADCREFHIGH: + case DAVISRGB_CONFIG_BIAS_ADCREFLOW: + case DAVISRGB_CONFIG_BIAS_IFREFRBN: + case DAVISRGB_CONFIG_BIAS_IFTHRBN: + case DAVISRGB_CONFIG_BIAS_LOCALBUFBN: + case DAVISRGB_CONFIG_BIAS_PADFOLLBN: + case DAVISRGB_CONFIG_BIAS_PIXINVBN: + case DAVISRGB_CONFIG_BIAS_DIFFBN: + case DAVISRGB_CONFIG_BIAS_ONBN: + case DAVISRGB_CONFIG_BIAS_OFFBN: + case DAVISRGB_CONFIG_BIAS_PRBP: + case DAVISRGB_CONFIG_BIAS_PRSFBP: + case DAVISRGB_CONFIG_BIAS_REFRBP: + case DAVISRGB_CONFIG_BIAS_ARRAYBIASBUFFERBN: + case DAVISRGB_CONFIG_BIAS_ARRAYLOGICBUFFERBN: + case DAVISRGB_CONFIG_BIAS_FALLTIMEBN: + case DAVISRGB_CONFIG_BIAS_RISETIMEBP: + case DAVISRGB_CONFIG_BIAS_READOUTBUFBP: + case DAVISRGB_CONFIG_BIAS_APSROSFBN: + case DAVISRGB_CONFIG_BIAS_ADCCOMPBP: + case DAVISRGB_CONFIG_BIAS_DACBUFBP: + case DAVISRGB_CONFIG_BIAS_LCOLTIMEOUTBN: + case DAVISRGB_CONFIG_BIAS_AEPDBN: + case DAVISRGB_CONFIG_BIAS_AEPUXBP: + case DAVISRGB_CONFIG_BIAS_AEPUYBP: + case DAVISRGB_CONFIG_BIAS_BIASBUFFER: + case DAVISRGB_CONFIG_BIAS_SSP: + case DAVISRGB_CONFIG_BIAS_SSN: + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_BIAS, paramAddr, param)); + break; + + default: + return (false); + break; + } + } + } + else { + // CHIP CONFIGURATION (DAVIS_CONFIG_CHIP). + switch (paramAddr) { + // Chip configuration common to all chips. + case DAVIS128_CONFIG_CHIP_DIGITALMUX0: + case DAVIS128_CONFIG_CHIP_DIGITALMUX1: + case DAVIS128_CONFIG_CHIP_DIGITALMUX2: + case DAVIS128_CONFIG_CHIP_DIGITALMUX3: + case DAVIS128_CONFIG_CHIP_ANALOGMUX0: + case DAVIS128_CONFIG_CHIP_ANALOGMUX1: + case DAVIS128_CONFIG_CHIP_ANALOGMUX2: + case DAVIS128_CONFIG_CHIP_BIASMUX0: + case DAVIS128_CONFIG_CHIP_RESETCALIBNEURON: + case DAVIS128_CONFIG_CHIP_TYPENCALIBNEURON: + case DAVIS128_CONFIG_CHIP_RESETTESTPIXEL: + case DAVIS128_CONFIG_CHIP_AERNAROW: + case DAVIS128_CONFIG_CHIP_USEAOUT: + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_CHIP, paramAddr, param)); + break; + + case DAVIS240_CONFIG_CHIP_SPECIALPIXELCONTROL: + // Only supported by DAVIS240 A/B chips. + if (IS_DAVIS240A(handle->info.chipID) || IS_DAVIS240B(handle->info.chipID)) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_CHIP, paramAddr, param)); + } + break; + + case DAVIS128_CONFIG_CHIP_GLOBAL_SHUTTER: + // Only supported by some chips. + if (handle->info.apsHasGlobalShutter) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_CHIP, paramAddr, param)); + } + break; + + case DAVIS128_CONFIG_CHIP_SELECTGRAYCOUNTER: + // Only supported by the new DAVIS chips. + if (IS_DAVIS128( + handle->info.chipID) || IS_DAVIS208(handle->info.chipID) || IS_DAVIS346(handle->info.chipID) + || IS_DAVIS640(handle->info.chipID) || IS_DAVISRGB(handle->info.chipID)) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_CHIP, paramAddr, param)); + } + break; + + case DAVIS346_CONFIG_CHIP_TESTADC: + // Only supported by some of the new DAVIS chips. + if (IS_DAVIS346( + handle->info.chipID) || IS_DAVIS640(handle->info.chipID) || IS_DAVISRGB(handle->info.chipID)) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_CHIP, paramAddr, param)); + } + break; + + case DAVISRGB_CONFIG_CHIP_ADJUSTOVG1LO: // Also DAVIS208_CONFIG_CHIP_SELECTPREAMPAVG. + case DAVISRGB_CONFIG_CHIP_ADJUSTOVG2LO: // Also DAVIS208_CONFIG_CHIP_SELECTBIASREFSS. + case DAVISRGB_CONFIG_CHIP_ADJUSTTX2OVG2HI: // Also DAVIS208_CONFIG_CHIP_SELECTSENSE. + // Only supported by DAVIS208 and DAVISRGB. + if (IS_DAVIS208(handle->info.chipID) || IS_DAVISRGB(handle->info.chipID)) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_CHIP, paramAddr, param)); + } + break; + + case DAVIS208_CONFIG_CHIP_SELECTPOSFB: + case DAVIS208_CONFIG_CHIP_SELECTHIGHPASS: + // Only supported by DAVIS208. + if (IS_DAVIS208(handle->info.chipID)) { + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_CHIP, paramAddr, param)); + } + break; + + default: + return (false); + break; + } + } + + return (false); + break; + + case DAVIS_CONFIG_SYSINFO: + switch (paramAddr) { + case DAVIS_CONFIG_SYSINFO_LOGIC_VERSION: + case DAVIS_CONFIG_SYSINFO_CHIP_IDENTIFIER: + case DAVIS_CONFIG_SYSINFO_DEVICE_IS_MASTER: + case DAVIS_CONFIG_SYSINFO_LOGIC_CLOCK: + case DAVIS_CONFIG_SYSINFO_ADC_CLOCK: + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_SYSINFO, paramAddr, param)); + break; + + default: + return (false); + break; + } + break; + + case DAVIS_CONFIG_USB: + switch (paramAddr) { + case DAVIS_CONFIG_USB_RUN: + case DAVIS_CONFIG_USB_EARLY_PACKET_DELAY: + return (spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_USB, paramAddr, param)); + break; + + default: + return (false); + break; + } + break; + + default: + return (false); + break; + } + + return (true); +} + +bool davisCommonDataStart(caerDeviceHandle cdh, void (*dataNotifyIncrease)(void *ptr), + void (*dataNotifyDecrease)(void *ptr), void *dataNotifyUserPtr, void (*dataShutdownNotify)(void *ptr), + void *dataShutdownUserPtr) { + davisHandle handle = (davisHandle) cdh; + davisState state = &handle->state; + + // Store new data available/not available anymore call-backs. + state->dataNotifyIncrease = dataNotifyIncrease; + state->dataNotifyDecrease = dataNotifyDecrease; + state->dataNotifyUserPtr = dataNotifyUserPtr; + state->dataShutdownNotify = dataShutdownNotify; + state->dataShutdownUserPtr = dataShutdownUserPtr; + + // Set wanted time interval to uninitialized. Getting the first TS or TS_RESET + // will then set this correctly. + state->currentPacketContainerCommitTimestamp = -1; + + // Initialize RingBuffer. + state->dataExchangeBuffer = ringBufferInit(atomic_load(&state->dataExchangeBufferSize)); + if (state->dataExchangeBuffer == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to initialize data exchange buffer."); + return (false); + } + + // Allocate packets. + state->currentPacketContainer = caerEventPacketContainerAllocate(DAVIS_EVENT_TYPES); + if (state->currentPacketContainer == NULL) { + freeAllDataMemory(state); + + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate event packet container."); + return (false); + } + + state->currentPolarityPacket = caerPolarityEventPacketAllocate(DAVIS_POLARITY_DEFAULT_SIZE, + I16T(handle->info.deviceID), 0); + if (state->currentPolarityPacket == NULL) { + freeAllDataMemory(state); + + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate polarity event packet."); + return (false); + } + + state->currentSpecialPacket = caerSpecialEventPacketAllocate(DAVIS_SPECIAL_DEFAULT_SIZE, + I16T(handle->info.deviceID), 0); + if (state->currentSpecialPacket == NULL) { + freeAllDataMemory(state); + + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate special event packet."); + return (false); + } + + state->currentFramePacket = caerFrameEventPacketAllocate(DAVIS_FRAME_DEFAULT_SIZE, I16T(handle->info.deviceID), 0, + state->apsSizeX, state->apsSizeY, 1); + if (state->currentFramePacket == NULL) { + freeAllDataMemory(state); + + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate frame event packet."); + return (false); + } + + // Allocate memory for the current FrameEvents. Use contiguous memory for all ROI FrameEvents. + size_t eventSize = sizeof(struct caer_frame_event) + + ((size_t) state->apsSizeX * (size_t) state->apsSizeY * APS_ADC_CHANNELS * sizeof(uint16_t)); + + state->currentFrameEvent[0] = calloc(APS_ROI_REGIONS_MAX, eventSize); + if (state->currentFrameEvent[0] == NULL) { + freeAllDataMemory(state); + + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate ROI frame events."); + return (false); + } + + for (size_t i = 1; i < APS_ROI_REGIONS_MAX; i++) { + // Assign the right memory offset to the pointers into the block that + // contains all the ROI FrameEvents. + state->currentFrameEvent[i] = (caerFrameEvent) (((uint8_t*) state->currentFrameEvent[0]) + (i * eventSize)); + } + + state->currentIMU6Packet = caerIMU6EventPacketAllocate(DAVIS_IMU_DEFAULT_SIZE, I16T(handle->info.deviceID), 0); + if (state->currentIMU6Packet == NULL) { + freeAllDataMemory(state); + + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate IMU6 event packet."); + return (false); + } + + state->apsCurrentResetFrame = calloc((size_t) (state->apsSizeX * state->apsSizeY * APS_ADC_CHANNELS), + sizeof(uint16_t)); + if (state->apsCurrentResetFrame == NULL) { + freeAllDataMemory(state); + + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate APS reset frame memory."); + return (false); + } + + // Default IMU settings (for event parsing). + uint32_t param32 = 0; + + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_IMU, DAVIS_CONFIG_IMU_ACCEL_FULL_SCALE, ¶m32); + state->imuAccelScale = calculateIMUAccelScale(U8T(param32)); + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_IMU, DAVIS_CONFIG_IMU_GYRO_FULL_SCALE, ¶m32); + state->imuGyroScale = calculateIMUGyroScale(U8T(param32)); + + // Default APS settings (for event parsing). + uint32_t param32start = 0; + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_START_COLUMN_0, ¶m32start); + + // If StartColumn0 is bigger or equal to APS size X, disable ROI region 0. + if (param32start < U32T(state->apsSizeX)) { + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_END_COLUMN_0, ¶m32); + + state->apsROISizeX[0] = U16T(param32 + 1 - param32start); + state->apsROIPositionX[0] = U16T(param32start); + + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_START_ROW_0, ¶m32start); + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_END_ROW_0, ¶m32); + + state->apsROISizeY[0] = U16T(param32 + 1 - param32start); + state->apsROIPositionY[0] = U16T(param32start); + } + else { + // Disable ROI region 0 by setting all parameters to zero. + state->apsROISizeX[0] = state->apsROIPositionX[0] = 0; + state->apsROISizeY[0] = state->apsROIPositionY[0] = 0; + } + + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_GLOBAL_SHUTTER, ¶m32); + state->apsGlobalShutter = param32; + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_RESET_READ, ¶m32); + state->apsResetRead = param32; + + if ((errno = thrd_create(&state->dataAcquisitionThread, &davisDataAcquisitionThread, handle)) != thrd_success) { + freeAllDataMemory(state); + + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to start data acquisition thread. Error: %d.", + errno); + return (false); + } + + // Wait for the data acquisition thread to be ready. + while (!atomic_load_explicit(&state->dataAcquisitionThreadRun, memory_order_relaxed)) { + ; + } + + return (true); +} + +bool davisCommonDataStop(caerDeviceHandle cdh) { + davisHandle handle = (davisHandle) cdh; + davisState state = &handle->state; + + // Stop data acquisition thread. + if (atomic_load(&state->dataExchangeStopProducers)) { + // Disable data transfer on USB end-point 2. Reverse order of enabling. + davisCommonConfigSet(handle, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_RUN_DETECTOR, false); + davisCommonConfigSet(handle, DAVIS_CONFIG_IMU, DAVIS_CONFIG_IMU_RUN, false); + davisCommonConfigSet(handle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_RUN, false); + davisCommonConfigSet(handle, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_RUN, false); + davisCommonConfigSet(handle, DAVIS_CONFIG_MUX, DAVIS_CONFIG_MUX_FORCE_CHIP_BIAS_ENABLE, false); // Ensure chip turns off. + davisCommonConfigSet(handle, DAVIS_CONFIG_MUX, DAVIS_CONFIG_MUX_TIMESTAMP_RUN, false); // Turn off timestamping too. + davisCommonConfigSet(handle, DAVIS_CONFIG_MUX, DAVIS_CONFIG_MUX_RUN, false); + davisCommonConfigSet(handle, DAVIS_CONFIG_USB, DAVIS_CONFIG_USB_RUN, false); + } + + atomic_store(&state->dataAcquisitionThreadRun, false); + + // Wait for data acquisition thread to terminate... + if ((errno = thrd_join(state->dataAcquisitionThread, NULL)) != thrd_success) { + // This should never happen! + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to join data acquisition thread. Error: %d.", + errno); + return (false); + } + + // Empty ringbuffer. + caerEventPacketContainer container; + while ((container = ringBufferGet(state->dataExchangeBuffer)) != NULL) { + // Notify data-not-available call-back. + if (state->dataNotifyDecrease != NULL) { + state->dataNotifyDecrease(state->dataNotifyUserPtr); + } + + // Free container, which will free its subordinate packets too. + caerEventPacketContainerFree(container); + } + + // Free current, uncommitted packets and ringbuffer. + freeAllDataMemory(state); + + // Reset packet positions. + state->currentPolarityPacketPosition = 0; + state->currentSpecialPacketPosition = 0; + state->currentFramePacketPosition = 0; + state->currentIMU6PacketPosition = 0; + + // Reset private composite events. 'currentFrameEvent' is taken care of in freeAllDataMemory(). + memset(&state->currentIMU6Event, 0, sizeof(struct caer_imu6_event)); + + return (true); +} + +caerEventPacketContainer davisCommonDataGet(caerDeviceHandle cdh) { + davisHandle handle = (davisHandle) cdh; + davisState state = &handle->state; + caerEventPacketContainer container = NULL; + + retry: container = ringBufferGet(state->dataExchangeBuffer); + + if (container != NULL) { + // Found an event container, return it and signal this piece of data + // is no longer available for later acquisition. + if (state->dataNotifyDecrease != NULL) { + state->dataNotifyDecrease(state->dataNotifyUserPtr); + } + + return (container); + } + + // Didn't find any event container, either report this or retry, depending + // on blocking setting. + if (atomic_load_explicit(&state->dataExchangeBlocking, memory_order_relaxed)) { + // Don't retry right away in a tight loop, back off and wait a little. + // If no data is available, sleep for a millisecond to avoid wasting resources. + struct timespec noDataSleep = { .tv_sec = 0, .tv_nsec = 1000000 }; + if (thrd_sleep(&noDataSleep, NULL) == 0) { + goto retry; + } + } + + // Nothing. + return (NULL); +} + +static bool spiConfigSend(libusb_device_handle *devHandle, uint8_t moduleAddr, uint8_t paramAddr, uint32_t param) { + uint8_t spiConfig[4] = { 0 }; + + spiConfig[0] = U8T(param >> 24); + spiConfig[1] = U8T(param >> 16); + spiConfig[2] = U8T(param >> 8); + spiConfig[3] = U8T(param >> 0); + + return (libusb_control_transfer(devHandle, + LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE, + VENDOR_REQUEST_FPGA_CONFIG, moduleAddr, paramAddr, spiConfig, sizeof(spiConfig), 0) == sizeof(spiConfig)); +} + +static bool spiConfigReceive(libusb_device_handle *devHandle, uint8_t moduleAddr, uint8_t paramAddr, uint32_t *param) { + uint8_t spiConfig[4] = { 0 }; + + if (libusb_control_transfer(devHandle, LIBUSB_ENDPOINT_IN | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE, + VENDOR_REQUEST_FPGA_CONFIG, moduleAddr, paramAddr, spiConfig, sizeof(spiConfig), 0) != sizeof(spiConfig)) { + return (false); + } + + *param = 0; + *param |= U32T(spiConfig[0] << 24); + *param |= U32T(spiConfig[1] << 16); + *param |= U32T(spiConfig[2] << 8); + *param |= U32T(spiConfig[3] << 0); + + return (true); +} + +static libusb_device_handle *davisDeviceOpen(libusb_context *devContext, uint16_t devVID, uint16_t devPID, + uint8_t devType, uint8_t busNumber, uint8_t devAddress, const char *serialNumber, uint16_t requiredLogicRevision, + uint16_t requiredFirmwareVersion) { + libusb_device_handle *devHandle = NULL; + libusb_device **devicesList; + + ssize_t result = libusb_get_device_list(devContext, &devicesList); + + if (result >= 0) { + // Cycle thorough all discovered devices and find a match. + for (size_t i = 0; i < (size_t) result; i++) { + struct libusb_device_descriptor devDesc; + + if (libusb_get_device_descriptor(devicesList[i], &devDesc) != LIBUSB_SUCCESS) { + continue; + } + + // Check if this is the device we want (VID/PID). + if (devDesc.idVendor == devVID && devDesc.idProduct == devPID + && U8T((devDesc.bcdDevice & 0xFF00) >> 8) == devType) { + // Verify device firmware version. + if (U8T(devDesc.bcdDevice & 0x00FF) < requiredFirmwareVersion) { + caerLog(CAER_LOG_CRITICAL, __func__, + "Device firmware version too old. You have version %" PRIu8 "; but at least version %" PRIu16 " is required. Please updated by following the Flashy upgrade documentation at 'http://inilabs.com/support/reflashing/'.", + U8T(devDesc.bcdDevice & 0x00FF), requiredFirmwareVersion); + + continue; + } + + // If a USB port restriction is given, honor it. + if (busNumber > 0 && libusb_get_bus_number(devicesList[i]) != busNumber) { + caerLog(CAER_LOG_INFO, __func__, + "USB bus number restriction is present (%" PRIu8 "), this device didn't match it (%" PRIu8 ").", + busNumber, libusb_get_bus_number(devicesList[i])); + + continue; + } + + if (devAddress > 0 && libusb_get_device_address(devicesList[i]) != devAddress) { + caerLog(CAER_LOG_INFO, __func__, + "USB device address restriction is present (%" PRIu8 "), this device didn't match it (%" PRIu8 ").", + devAddress, libusb_get_device_address(devicesList[i])); + + continue; + } + + if (libusb_open(devicesList[i], &devHandle) != LIBUSB_SUCCESS) { + devHandle = NULL; + + continue; + } + + // Check the serial number restriction, if any is present. + if (serialNumber != NULL && !caerStrEquals(serialNumber, "")) { + char deviceSerialNumber[8 + 1] = { 0 }; + int getStringDescResult = libusb_get_string_descriptor_ascii(devHandle, devDesc.iSerialNumber, + (unsigned char *) deviceSerialNumber, 8 + 1); + + // Check serial number success and length. + if (getStringDescResult < 0 || getStringDescResult > 8) { + libusb_close(devHandle); + devHandle = NULL; + + continue; + } + + // Now check if the Serial Number matches. + if (!caerStrEquals(serialNumber, deviceSerialNumber)) { + libusb_close(devHandle); + devHandle = NULL; + + caerLog(CAER_LOG_INFO, __func__, + "USB serial number restriction is present (%s), this device didn't match it (%s).", + serialNumber, deviceSerialNumber); + + continue; + } + } + + // Check that the active configuration is set to number 1. If not, do so. + int activeConfiguration; + if (libusb_get_configuration(devHandle, &activeConfiguration) != LIBUSB_SUCCESS) { + libusb_close(devHandle); + devHandle = NULL; + + continue; + } + + if (activeConfiguration != 1) { + if (libusb_set_configuration(devHandle, 1) != LIBUSB_SUCCESS) { + libusb_close(devHandle); + devHandle = NULL; + + continue; + } + } + + // Claim interface 0 (default). + if (libusb_claim_interface(devHandle, 0) != LIBUSB_SUCCESS) { + libusb_close(devHandle); + devHandle = NULL; + + continue; + } + + // Communication with device open, get logic version information. + uint32_t param32 = 0; + + spiConfigReceive(devHandle, DAVIS_CONFIG_SYSINFO, DAVIS_CONFIG_SYSINFO_LOGIC_VERSION, ¶m32); + uint16_t logicVersion = U16T(param32); + + // Verify device logic version. + if (logicVersion < requiredLogicRevision) { + libusb_release_interface(devHandle, 0); + libusb_close(devHandle); + devHandle = NULL; + + caerLog(CAER_LOG_CRITICAL, __func__, + "Device logic revision too old. You have revision %" PRIu16 "; but at least revision %" PRIu16 " is required. Please updated by following the Flashy upgrade documentation at 'http://inilabs.com/support/reflashing/'.", + logicVersion, requiredLogicRevision); + + continue; + } + + // Found and configured it! + break; + } + } + + libusb_free_device_list(devicesList, true); + } + + return (devHandle); +} + +static void davisDeviceClose(libusb_device_handle *devHandle) { + // Release interface 0 (default). + libusb_release_interface(devHandle, 0); + + libusb_close(devHandle); +} + +static void davisAllocateTransfers(davisHandle handle, uint32_t bufferNum, uint32_t bufferSize) { + davisState state = &handle->state; + + // Set number of transfers and allocate memory for the main transfer array. + state->dataTransfers = calloc(bufferNum, sizeof(struct libusb_transfer *)); + if (state->dataTransfers == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, + "Failed to allocate memory for %" PRIu32 " libusb transfers. Error: %d.", bufferNum, errno); + return; + } + state->dataTransfersLength = bufferNum; + + // Allocate transfers and set them up. + for (size_t i = 0; i < bufferNum; i++) { + state->dataTransfers[i] = libusb_alloc_transfer(0); + if (state->dataTransfers[i] == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, + "Unable to allocate further libusb transfers (%zu of %" PRIu32 ").", i, bufferNum); + continue; + } + + // Create data buffer. + state->dataTransfers[i]->length = (int) bufferSize; + state->dataTransfers[i]->buffer = malloc(bufferSize); + if (state->dataTransfers[i]->buffer == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, + "Unable to allocate buffer for libusb transfer %zu. Error: %d.", i, errno); + + libusb_free_transfer(state->dataTransfers[i]); + state->dataTransfers[i] = NULL; + + continue; + } + + // Initialize Transfer. + state->dataTransfers[i]->dev_handle = state->deviceHandle; + state->dataTransfers[i]->endpoint = DAVIS_DATA_ENDPOINT; + state->dataTransfers[i]->type = LIBUSB_TRANSFER_TYPE_BULK; + state->dataTransfers[i]->callback = &davisLibUsbCallback; + state->dataTransfers[i]->user_data = handle; + state->dataTransfers[i]->timeout = 0; + state->dataTransfers[i]->flags = LIBUSB_TRANSFER_FREE_BUFFER; + + if ((errno = libusb_submit_transfer(state->dataTransfers[i])) == LIBUSB_SUCCESS) { + state->activeDataTransfers++; + } + else { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, + "Unable to submit libusb transfer %zu. Error: %s (%d).", i, libusb_strerror(errno), errno); + + // The transfer buffer is freed automatically here thanks to + // the LIBUSB_TRANSFER_FREE_BUFFER flag set above. + libusb_free_transfer(state->dataTransfers[i]); + state->dataTransfers[i] = NULL; + + continue; + } + } + + if (state->activeDataTransfers == 0) { + // Didn't manage to allocate any USB transfers, free array memory and log failure. + free(state->dataTransfers); + state->dataTransfers = NULL; + state->dataTransfersLength = 0; + + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Unable to allocate any libusb transfers."); + } +} + +static void davisDeallocateTransfers(davisHandle handle) { + davisState state = &handle->state; + + // Cancel all current transfers first. + for (size_t i = 0; i < state->dataTransfersLength; i++) { + if (state->dataTransfers[i] != NULL) { + errno = libusb_cancel_transfer(state->dataTransfers[i]); + if (errno != LIBUSB_SUCCESS && errno != LIBUSB_ERROR_NOT_FOUND) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, + "Unable to cancel libusb transfer %zu. Error: %s (%d).", i, libusb_strerror(errno), errno); + // Proceed with trying to cancel all transfers regardless of errors. + } + } + } + + // Wait for all transfers to go away (0.1 seconds timeout). + struct timeval te = { .tv_sec = 0, .tv_usec = 100000 }; + + while (state->activeDataTransfers > 0) { + libusb_handle_events_timeout(state->deviceContext, &te); + } + + // The buffers and transfers have been deallocated in the callback. + // Only the transfers array remains, which we free here. + free(state->dataTransfers); + state->dataTransfers = NULL; + state->dataTransfersLength = 0; +} + +static void LIBUSB_CALL davisLibUsbCallback(struct libusb_transfer *transfer) { + davisHandle handle = transfer->user_data; + davisState state = &handle->state; + + if (transfer->status == LIBUSB_TRANSFER_COMPLETED) { + // Handle data. + davisEventTranslator(handle, transfer->buffer, (size_t) transfer->actual_length); + } + + if (transfer->status != LIBUSB_TRANSFER_CANCELLED && transfer->status != LIBUSB_TRANSFER_NO_DEVICE) { + // Submit transfer again. + if (libusb_submit_transfer(transfer) == LIBUSB_SUCCESS) { + return; + } + } + + // Cannot recover (cancelled, no device, or other critical error). + // Signal this by adjusting the counter, free and exit. + state->activeDataTransfers--; + for (size_t i = 0; i < state->dataTransfersLength; i++) { + // Remove from list, so we don't try to cancel it later on. + if (state->dataTransfers[i] == transfer) { + state->dataTransfers[i] = NULL; + } + } + libusb_free_transfer(transfer); +} + +#define TS_WRAP_ADD 0x8000 + +static inline int64_t generateFullTimestamp(int32_t tsOverflow, int32_t timestamp) { + return (I64T((U64T(tsOverflow) << TS_OVERFLOW_SHIFT) | U64T(timestamp))); +} + +static inline void initContainerCommitTimestamp(davisState state) { + if (state->currentPacketContainerCommitTimestamp == -1) { + state->currentPacketContainerCommitTimestamp = state->currentTimestamp + + atomic_load_explicit(&state->maxPacketContainerInterval, memory_order_relaxed) - 1; + } +} + +static void davisEventTranslator(davisHandle handle, uint8_t *buffer, size_t bytesSent) { + davisState state = &handle->state; + + // Return right away if not running anymore. This prevents useless work if many + // buffers are still waiting when shut down, as well as incorrect event sequences + // if a TS_RESET is stuck on ring-buffer commit further down, and detects shut-down; + // then any subsequent buffers should also detect shut-down and not be handled. + if (!atomic_load_explicit(&state->dataAcquisitionThreadRun, memory_order_relaxed)) { + return; + } + + // Truncate off any extra partial event. + if ((bytesSent & 0x01) != 0) { + caerLog(CAER_LOG_ALERT, handle->info.deviceString, + "%zu bytes received via USB, which is not a multiple of two.", bytesSent); + bytesSent &= (size_t) ~0x01; + } + + for (size_t i = 0; i < bytesSent; i += 2) { + // Allocate new packets for next iteration as needed. + if (state->currentPacketContainer == NULL) { + state->currentPacketContainer = caerEventPacketContainerAllocate(DAVIS_EVENT_TYPES); + if (state->currentPacketContainer == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate event packet container."); + return; + } + } + + if (state->currentPolarityPacket == NULL) { + state->currentPolarityPacket = caerPolarityEventPacketAllocate( + DAVIS_POLARITY_DEFAULT_SIZE, I16T(handle->info.deviceID), state->wrapOverflow); + if (state->currentPolarityPacket == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate polarity event packet."); + return; + } + } + else if (state->currentPolarityPacketPosition + >= caerEventPacketHeaderGetEventCapacity((caerEventPacketHeader) state->currentPolarityPacket)) { + // If not committed, let's check if any of the packets has reached its maximum + // capacity limit. If yes, we grow them to accomodate new events. + caerPolarityEventPacket grownPacket = (caerPolarityEventPacket) caerGenericEventPacketGrow( + (caerEventPacketHeader) state->currentPolarityPacket, state->currentPolarityPacketPosition * 2); + if (grownPacket == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to grow polarity event packet."); + return; + } + + state->currentPolarityPacket = grownPacket; + } + + if (state->currentSpecialPacket == NULL) { + state->currentSpecialPacket = caerSpecialEventPacketAllocate( + DAVIS_SPECIAL_DEFAULT_SIZE, I16T(handle->info.deviceID), state->wrapOverflow); + if (state->currentSpecialPacket == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate special event packet."); + return; + } + } + else if (state->currentSpecialPacketPosition + >= caerEventPacketHeaderGetEventCapacity((caerEventPacketHeader) state->currentSpecialPacket)) { + // If not committed, let's check if any of the packets has reached its maximum + // capacity limit. If yes, we grow them to accomodate new events. + caerSpecialEventPacket grownPacket = (caerSpecialEventPacket) caerGenericEventPacketGrow( + (caerEventPacketHeader) state->currentSpecialPacket, state->currentSpecialPacketPosition * 2); + if (grownPacket == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to grow special event packet."); + return; + } + + state->currentSpecialPacket = grownPacket; + } + + if (state->currentFramePacket == NULL) { + state->currentFramePacket = caerFrameEventPacketAllocate( + DAVIS_FRAME_DEFAULT_SIZE, I16T(handle->info.deviceID), state->wrapOverflow, state->apsSizeX, + state->apsSizeY, 1); + if (state->currentFramePacket == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate frame event packet."); + return; + } + } + else if (state->currentFramePacketPosition + >= caerEventPacketHeaderGetEventCapacity((caerEventPacketHeader) state->currentFramePacket)) { + // If not committed, let's check if any of the packets has reached its maximum + // capacity limit. If yes, we grow them to accomodate new events. + caerFrameEventPacket grownPacket = (caerFrameEventPacket) caerGenericEventPacketGrow( + (caerEventPacketHeader) state->currentFramePacket, state->currentFramePacketPosition * 2); + if (grownPacket == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to grow frame event packet."); + return; + } + + state->currentFramePacket = grownPacket; + } + + if (state->currentIMU6Packet == NULL) { + state->currentIMU6Packet = caerIMU6EventPacketAllocate( + DAVIS_IMU_DEFAULT_SIZE, I16T(handle->info.deviceID), state->wrapOverflow); + if (state->currentIMU6Packet == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate IMU6 event packet."); + return; + } + } + else if (state->currentIMU6PacketPosition + >= caerEventPacketHeaderGetEventCapacity((caerEventPacketHeader) state->currentIMU6Packet)) { + // If not committed, let's check if any of the packets has reached its maximum + // capacity limit. If yes, we grow them to accomodate new events. + caerIMU6EventPacket grownPacket = (caerIMU6EventPacket) caerGenericEventPacketGrow( + (caerEventPacketHeader) state->currentIMU6Packet, state->currentIMU6PacketPosition * 2); + if (grownPacket == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to grow IMU6 event packet."); + return; + } + + state->currentIMU6Packet = grownPacket; + } + + bool tsReset = false; + bool tsBigWrap = false; + + uint16_t event = le16toh(*((uint16_t * ) (&buffer[i]))); + + // Check if timestamp. + if ((event & 0x8000) != 0) { + // Is a timestamp! Expand to 32 bits. (Tick is 1µs already.) + state->lastTimestamp = state->currentTimestamp; + state->currentTimestamp = state->wrapAdd + (event & 0x7FFF); + initContainerCommitTimestamp(state); + + // Check monotonicity of timestamps. + checkStrictMonotonicTimestamp(handle); + } + else { + // Look at the code, to determine event and data type. + uint8_t code = U8T((event & 0x7000) >> 12); + uint16_t data = (event & 0x0FFF); + + switch (code) { + case 0: // Special event + switch (data) { + case 0: // Ignore this, but log it. + caerLog(CAER_LOG_ERROR, handle->info.deviceString, "Caught special reserved event!"); + break; + + case 1: { // Timetamp reset + state->wrapOverflow = 0; + state->wrapAdd = 0; + state->lastTimestamp = 0; + state->currentTimestamp = 0; + state->currentPacketContainerCommitTimestamp = -1; + initContainerCommitTimestamp(state); + + caerLog(CAER_LOG_INFO, handle->info.deviceString, "Timestamp reset event received."); + + // Defer timestamp reset event to later, so we commit it + // alone, in its own packet. + // Commit packets when doing a reset to clearly separate them. + tsReset = true; + + // Update Master/Slave status on incoming TS resets. Done in main thread + // to avoid deadlock inside callback. + atomic_fetch_or(&state->dataAcquisitionThreadConfigUpdate, 1 << 1); + + break; + } + + case 2: { // External input (falling edge) + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "External input (falling edge) event received."); + + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, EXTERNAL_INPUT_FALLING_EDGE); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + break; + } + + case 3: { // External input (rising edge) + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "External input (rising edge) event received."); + + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, EXTERNAL_INPUT_RISING_EDGE); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + break; + } + + case 4: { // External input (pulse) + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "External input (pulse) event received."); + + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, EXTERNAL_INPUT_PULSE); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + break; + } + + case 5: { // IMU Start (6 axes) + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "IMU6 Start event received."); + + state->imuIgnoreEvents = false; + state->imuCount = 0; + + memset(&state->currentIMU6Event, 0, sizeof(struct caer_imu6_event)); + + break; + } + + case 7: { // IMU End + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "IMU End event received."); + if (state->imuIgnoreEvents) { + break; + } + + if (state->imuCount == IMU6_COUNT) { + // Timestamp at event-stream insertion point. + caerIMU6EventSetTimestamp(&state->currentIMU6Event, state->currentTimestamp); + + caerIMU6EventValidate(&state->currentIMU6Event, state->currentIMU6Packet); + + // IMU6 and APS operate on an internal event and copy that to the actual output + // packet here, in the END state, for a reason: if a packetContainer, with all its + // packets, is committed due to hitting any of the triggers that are not TS reset + // or TS wrap-around related, like number of polarity events, the event in the packet + // would be left incomplete, and the event in the new packet would be corrupted. + // We could avoid this like for the TS reset/TS wrap-around case (see forceCommit) by + // just deleting that event, but these kinds of commits happen much more often and the + // possible data loss would be too significant. So instead we keep a private event, + // fill it, and then only copy it into the packet here in the END state, at which point + // the whole event is ready and cannot be broken/corrupted in any way anymore. + caerIMU6Event currentIMU6Event = caerIMU6EventPacketGetEvent(state->currentIMU6Packet, + state->currentIMU6PacketPosition); + memcpy(currentIMU6Event, &state->currentIMU6Event, sizeof(struct caer_imu6_event)); + state->currentIMU6PacketPosition++; + } + else { + caerLog(CAER_LOG_INFO, handle->info.deviceString, + "IMU End: failed to validate IMU sample count (%" PRIu8 "), discarding samples.", + state->imuCount); + } + break; + } + + case 8: { // APS Global Shutter Frame Start + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "APS GS Frame Start event received."); + state->apsIgnoreEvents = false; + state->apsGlobalShutter = true; + state->apsResetRead = true; + + initFrame(handle); + + break; + } + + case 9: { // APS Rolling Shutter Frame Start + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "APS RS Frame Start event received."); + state->apsIgnoreEvents = false; + state->apsGlobalShutter = false; + state->apsResetRead = true; + + initFrame(handle); + + break; + } + + case 10: { // APS Frame End + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "APS Frame End event received."); + if (state->apsIgnoreEvents) { + break; + } + + bool validFrame = true; + + for (size_t j = 0; j < APS_READOUT_TYPES_NUM; j++) { + int32_t checkValue = caerFrameEventGetLengthX(state->currentFrameEvent[0]); + + // Check main reset read against zero if disabled. + if (j == APS_READOUT_RESET && !state->apsResetRead) { + checkValue = 0; + } + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "APS Frame End: CountX[%zu] is %d.", + j, state->apsCountX[j]); + + if (state->apsCountX[j] != checkValue) { + caerLog(CAER_LOG_ERROR, handle->info.deviceString, + "APS Frame End - %zu: wrong column count %d detected, expected %d.", j, + state->apsCountX[j], checkValue); + validFrame = false; + } + } + + // Write out end of frame timestamp. + caerFrameEventSetTSEndOfFrame(state->currentFrameEvent[0], state->currentTimestamp); + + // Send APS info event out (as special event). + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, APS_FRAME_END); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + + // Validate event and advance frame packet position. + if (validFrame) { + caerFrameEventValidate(state->currentFrameEvent[0], state->currentFramePacket); + + // Invert X and Y axes if image from chip is inverted. + if (state->apsInvertXY) { + SWAP_VAR(int32_t, state->currentFrameEvent[0]->lengthX, + state->currentFrameEvent[0]->lengthY); + SWAP_VAR(int32_t, state->currentFrameEvent[0]->positionX, + state->currentFrameEvent[0]->positionY); + } + + // IMU6 and APS operate on an internal event and copy that to the actual output + // packet here, in the END state, for a reason: if a packetContainer, with all its + // packets, is committed due to hitting any of the triggers that are not TS reset + // or TS wrap-around related, like number of polarity events, the event in the packet + // would be left incomplete, and the event in the new packet would be corrupted. + // We could avoid this like for the TS reset/TS wrap-around case (see forceCommit) by + // just deleting that event, but these kinds of commits happen much more often and the + // possible data loss would be too significant. So instead we keep a private event, + // fill it, and then only copy it into the packet here in the END state, at which point + // the whole event is ready and cannot be broken/corrupted in any way anymore. + caerFrameEvent currentFrameEvent = caerFrameEventPacketGetEvent( + state->currentFramePacket, state->currentFramePacketPosition); + memcpy(currentFrameEvent, state->currentFrameEvent[0], + sizeof(struct caer_frame_event) + + caerFrameEventGetPixelsSize(state->currentFrameEvent[0])); + state->currentFramePacketPosition++; + } + + break; + } + + case 11: { // APS Reset Column Start + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "APS Reset Column Start event received."); + if (state->apsIgnoreEvents) { + break; + } + + state->apsCurrentReadoutType = APS_READOUT_RESET; + state->apsCountY[state->apsCurrentReadoutType] = 0; + + state->apsRGBPixelOffsetDirection = 0; + state->apsRGBPixelOffset = 1; // RGB support, first pixel of row always even. + + // The first Reset Column Read Start is also the start + // of the exposure for the RS. + if (!state->apsGlobalShutter && state->apsCountX[APS_READOUT_RESET] == 0) { + caerFrameEventSetTSStartOfExposure(state->currentFrameEvent[0], + state->currentTimestamp); + + // Send APS info event out (as special event). + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, APS_EXPOSURE_START); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + } + + break; + } + + case 12: { // APS Signal Column Start + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "APS Signal Column Start event received."); + if (state->apsIgnoreEvents) { + break; + } + + state->apsCurrentReadoutType = APS_READOUT_SIGNAL; + state->apsCountY[state->apsCurrentReadoutType] = 0; + + state->apsRGBPixelOffsetDirection = 0; + state->apsRGBPixelOffset = 1; // RGB support, first pixel of row always even. + + // The first Signal Column Read Start is also always the end + // of the exposure time, for both RS and GS. + if (state->apsCountX[APS_READOUT_SIGNAL] == 0) { + caerFrameEventSetTSEndOfExposure(state->currentFrameEvent[0], state->currentTimestamp); + + // Send APS info event out (as special event). + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, APS_EXPOSURE_END); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + } + + break; + } + + case 13: { // APS Column End + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "APS Column End event received."); + if (state->apsIgnoreEvents) { + break; + } + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "APS Column End: CountX[%d] is %d.", + state->apsCurrentReadoutType, state->apsCountX[state->apsCurrentReadoutType]); + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "APS Column End: CountY[%d] is %d.", + state->apsCurrentReadoutType, state->apsCountY[state->apsCurrentReadoutType]); + + if (state->apsCountY[state->apsCurrentReadoutType] + != caerFrameEventGetLengthY(state->currentFrameEvent[0])) { + caerLog(CAER_LOG_ERROR, handle->info.deviceString, + "APS Column End - %d: wrong row count %d detected, expected %d.", + state->apsCurrentReadoutType, state->apsCountY[state->apsCurrentReadoutType], + caerFrameEventGetLengthY(state->currentFrameEvent[0])); + } + + state->apsCountX[state->apsCurrentReadoutType]++; + + // The last Reset Column Read End is also the start + // of the exposure for the GS. + if (state->apsGlobalShutter && state->apsCurrentReadoutType == APS_READOUT_RESET + && state->apsCountX[APS_READOUT_RESET] + == caerFrameEventGetLengthX(state->currentFrameEvent[0])) { + caerFrameEventSetTSStartOfExposure(state->currentFrameEvent[0], + state->currentTimestamp); + + // Send APS info event out (as special event). + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, APS_EXPOSURE_START); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + } + + break; + } + + case 14: { // APS Global Shutter Frame Start with no Reset Read + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "APS GS NORST Frame Start event received."); + state->apsIgnoreEvents = false; + state->apsGlobalShutter = true; + state->apsResetRead = false; + + initFrame(handle); + + // If reset reads are disabled, the start of exposure is closest to + // the start of frame. + caerFrameEventSetTSStartOfExposure(state->currentFrameEvent[0], state->currentTimestamp); + + // No APS info event is sent out (as special event). Only one event + // per type can be sent out per cycle, and initFrame() already does + // that and sets APS_FRAME_START. + + break; + } + + case 15: { // APS Rolling Shutter Frame Start with no Reset Read + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "APS RS NORST Frame Start event received."); + state->apsIgnoreEvents = false; + state->apsGlobalShutter = false; + state->apsResetRead = false; + + initFrame(handle); + + // If reset reads are disabled, the start of exposure is closest to + // the start of frame. + caerFrameEventSetTSStartOfExposure(state->currentFrameEvent[0], state->currentTimestamp); + + // No APS info event is sent out (as special event). Only one event + // per type can be sent out per cycle, and initFrame() already does + // that and sets APS_FRAME_START. + + break; + } + + case 16: + case 17: + case 18: + case 19: + case 20: + case 21: + case 22: + case 23: + case 24: + case 25: + case 26: + case 27: + case 28: + case 29: + case 30: + case 31: { + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "IMU Scale Config event (%" PRIu16 ") received.", data); + if (state->imuIgnoreEvents) { + break; + } + + // Set correct IMU accel and gyro scales, used to interpret subsequent + // IMU samples from the device. + state->imuAccelScale = calculateIMUAccelScale((data >> 2) & 0x03); + state->imuGyroScale = calculateIMUGyroScale(data & 0x03); + + // At this point the IMU event count should be zero (reset by start). + if (state->imuCount != 0) { + caerLog(CAER_LOG_INFO, handle->info.deviceString, + "IMU Scale Config: previous IMU start event missed, attempting recovery."); + } + + // Increase IMU count by one, to a total of one (0+1=1). + // This way we can recover from the above error of missing start, and we can + // later discover if the IMU Scale Config event actually arrived itself. + state->imuCount = 1; + + break; + } + + case 32: { + // Next Misc8 APS ROI Size events will refer to ROI region 0. + // 0/1 used to distinguish between X and Y sizes. + state->apsROIUpdate = (0 << 2); + state->apsROISizeX[0] = state->apsROISizeY[0] = 0; + state->apsROIPositionX[0] = state->apsROIPositionY[0] = 0; + break; + } + + case 33: { + // Next Misc8 APS ROI Size events will refer to ROI region 1. + // 2/3 used to distinguish between X and Y sizes. + state->apsROIUpdate = (1 << 2); + state->apsROISizeX[1] = state->apsROISizeY[1] = 0; + state->apsROIPositionX[1] = state->apsROIPositionY[1] = 0; + break; + } + + case 34: { + // Next Misc8 APS ROI Size events will refer to ROI region 2. + // 4/5 used to distinguish between X and Y sizes. + state->apsROIUpdate = (2 << 2); + state->apsROISizeX[2] = state->apsROISizeY[2] = 0; + state->apsROIPositionX[2] = state->apsROIPositionY[2] = 0; + break; + } + + case 35: { + // Next Misc8 APS ROI Size events will refer to ROI region 3. + // 6/7 used to distinguish between X and Y sizes. + state->apsROIUpdate = (3 << 2); + state->apsROISizeX[3] = state->apsROISizeY[3] = 0; + state->apsROIPositionX[3] = state->apsROIPositionY[3] = 0; + break; + } + + case 36: { // External input 1 (falling edge) + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "External input 1 (falling edge) event received."); + + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, EXTERNAL_INPUT1_FALLING_EDGE); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + break; + } + + case 37: { // External input 1 (rising edge) + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "External input 1 (rising edge) event received."); + + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, EXTERNAL_INPUT1_RISING_EDGE); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + break; + } + + case 38: { // External input 1 (pulse) + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "External input 1 (pulse) event received."); + + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, EXTERNAL_INPUT1_PULSE); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + break; + } + + case 39: { // External input 2 (falling edge) + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "External input 2 (falling edge) event received."); + + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, EXTERNAL_INPUT2_FALLING_EDGE); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + break; + } + + case 40: { // External input 2 (rising edge) + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "External input 2 (rising edge) event received."); + + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, EXTERNAL_INPUT2_RISING_EDGE); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + break; + } + + case 41: { // External input 2 (pulse) + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "External input 2 (pulse) event received."); + + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, EXTERNAL_INPUT2_PULSE); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + break; + } + + case 42: { // External generator (falling edge) + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "External generator (falling edge) event received."); + + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, EXTERNAL_GENERATOR_FALLING_EDGE); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + break; + } + + case 43: { // External generator (rising edge) + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "External generator (rising edge) event received."); + + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, EXTERNAL_GENERATOR_RISING_EDGE); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + break; + } + + default: + caerLog(CAER_LOG_ERROR, handle->info.deviceString, + "Caught special event that can't be handled: %d.", data); + break; + } + break; + + case 1: // Y address + // Check range conformity. + if (data >= state->dvsSizeY) { + caerLog(CAER_LOG_ALERT, handle->info.deviceString, + "DVS: Y address out of range (0-%d): %" PRIu16 ".", state->dvsSizeY - 1, data); + break; // Skip invalid Y address (don't update lastY). + } + + if (state->dvsGotY) { + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + + // Timestamp at event-stream insertion point. + caerSpecialEventSetTimestamp(currentSpecialEvent, state->currentTimestamp); + caerSpecialEventSetType(currentSpecialEvent, DVS_ROW_ONLY); + caerSpecialEventSetData(currentSpecialEvent, state->dvsLastY); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "DVS: row-only event received for address Y=%" PRIu16 ".", state->dvsLastY); + } + + state->dvsLastY = data; + state->dvsGotY = true; + + break; + + case 2: // X address, Polarity OFF + case 3: { // X address, Polarity ON + // Check range conformity. + if (data >= state->dvsSizeX) { + caerLog(CAER_LOG_ALERT, handle->info.deviceString, + "DVS: X address out of range (0-%d): %" PRIu16 ".", state->dvsSizeX - 1, data); + break; // Skip invalid event. + } + + // Invert polarity for PixelParade high gain pixels (DavisSense), because of + // negative gain from pre-amplifier. + uint8_t polarity = ((IS_DAVIS208(handle->info.chipID)) && (data < 192)) ? U8T(~code) : (code); + + caerPolarityEvent currentPolarityEvent = caerPolarityEventPacketGetEvent( + state->currentPolarityPacket, state->currentPolarityPacketPosition); + + // Timestamp at event-stream insertion point. + caerPolarityEventSetTimestamp(currentPolarityEvent, state->currentTimestamp); + caerPolarityEventSetPolarity(currentPolarityEvent, (polarity & 0x01)); + if (state->dvsInvertXY) { + // Flip Y address to conform to CG format. + caerPolarityEventSetY(currentPolarityEvent, U16T((state->dvsSizeX - 1) - data)); + caerPolarityEventSetX(currentPolarityEvent, state->dvsLastY); + } + else { + // Flip Y address to conform to CG format. + caerPolarityEventSetY(currentPolarityEvent, U16T((state->dvsSizeY - 1) - state->dvsLastY)); + caerPolarityEventSetX(currentPolarityEvent, data); + } + caerPolarityEventValidate(currentPolarityEvent, state->currentPolarityPacket); + state->currentPolarityPacketPosition++; + + state->dvsGotY = false; + + break; + } + + case 4: { + if (state->apsIgnoreEvents) { + break; + } + + // Let's check that apsCountX is not above the maximum. This could happen + // if the maximum is a smaller number that comes from ROI, while we're still + // reading out a frame with a bigger, old size. + if (state->apsCountX[state->apsCurrentReadoutType] + >= caerFrameEventGetLengthX(state->currentFrameEvent[0])) { + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "APS ADC sample: column count is at maximum, discarding further samples."); + break; + } + + // Let's check that apsCountY is not above the maximum. This could happen + // if start/end of column events are discarded (no wait on transfer stall). + if (state->apsCountY[state->apsCurrentReadoutType] + >= caerFrameEventGetLengthY(state->currentFrameEvent[0])) { + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "APS ADC sample: row count is at maximum, discarding further samples."); + break; + } + + // If reset read, we store the values in a local array. If signal read, we + // store the final pixel value directly in the output frame event. We already + // do the subtraction between reset and signal here, to avoid carrying that + // around all the time and consuming memory. This way we can also only take + // infrequent reset reads and re-use them for multiple frames, which can heavily + // reduce traffic, and should not impact image quality heavily, at least in GS. + uint16_t xPos = + (state->apsFlipX) ? + (U16T( + caerFrameEventGetLengthX(state->currentFrameEvent[0]) - 1 + - state->apsCountX[state->apsCurrentReadoutType])) : + (U16T(state->apsCountX[state->apsCurrentReadoutType])); + uint16_t yPos = + (state->apsFlipY) ? + (U16T( + caerFrameEventGetLengthY(state->currentFrameEvent[0]) - 1 + - state->apsCountY[state->apsCurrentReadoutType])) : + (U16T(state->apsCountY[state->apsCurrentReadoutType])); + + if (IS_DAVISRGB(handle->info.chipID)) { + yPos = U16T(yPos + state->apsRGBPixelOffset); + } + + int32_t stride = 0; + + if (state->apsInvertXY) { + SWAP_VAR(uint16_t, xPos, yPos); + + stride = caerFrameEventGetLengthY(state->currentFrameEvent[0]); + + // Flip Y address to conform to CG format. + yPos = U16T((state->apsSizeX - 1) - yPos); + } + else { + stride = caerFrameEventGetLengthX(state->currentFrameEvent[0]); + + // Flip Y address to conform to CG format. + yPos = U16T((state->apsSizeY - 1) - yPos); + } + + size_t pixelPosition = (size_t) (yPos * stride) + xPos; + + if ((state->apsCurrentReadoutType == APS_READOUT_RESET + && !(IS_DAVISRGB(handle->info.chipID) && state->apsGlobalShutter)) + || (state->apsCurrentReadoutType == APS_READOUT_SIGNAL + && (IS_DAVISRGB(handle->info.chipID) && state->apsGlobalShutter))) { + state->apsCurrentResetFrame[pixelPosition] = data; + } + else { + int32_t pixelValue = 0; + + if (IS_DAVISRGB(handle->info.chipID) && state->apsGlobalShutter) { + // DAVIS RGB GS has inverted samples, signal read comes first + // and was stored above inside state->apsCurrentResetFrame. +#if APS_DEBUG_FRAME == 1 + // Reset read only. + pixelValue = (data); +#elif APS_DEBUG_FRAME == 2 + // Signal read only. + pixelValue = (state->apsCurrentResetFrame[pixelPosition]); +#else + // Both/CDS done. + pixelValue = (data - state->apsCurrentResetFrame[pixelPosition]); +#endif + } + else { +#if APS_DEBUG_FRAME == 1 + // Reset read only. + pixelValue = (state->apsCurrentResetFrame[pixelPosition]); +#elif APS_DEBUG_FRAME == 2 + // Signal read only. + pixelValue = (data); +#else + // Both/CDS done. + pixelValue = (state->apsCurrentResetFrame[pixelPosition] - data); +#endif + } + + // Normalize the ADC value to 16bit generic depth and check for underflow. + pixelValue = (pixelValue < 0) ? (0) : (pixelValue); + pixelValue = pixelValue << (16 - APS_ADC_DEPTH); + + caerFrameEventGetPixelArrayUnsafe(state->currentFrameEvent[0])[pixelPosition] = htole16( + U16T(pixelValue)); + } + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "APS ADC Sample: column=%" PRIu16 ", row=%" PRIu16 ", xPos=%" PRIu16 ", yPos=%" PRIu16 ", data=%" PRIu16 ".", + state->apsCountX[state->apsCurrentReadoutType], state->apsCountY[state->apsCurrentReadoutType], + xPos, yPos, data); + + state->apsCountY[state->apsCurrentReadoutType]++; + + // RGB support: first 320 pixels are even, then odd. + if (IS_DAVISRGB(handle->info.chipID)) { + if (state->apsRGBPixelOffsetDirection == 0) { // Increasing + state->apsRGBPixelOffset++; + + if (state->apsRGBPixelOffset == 321) { + // Switch to decreasing after last even pixel. + state->apsRGBPixelOffsetDirection = 1; + state->apsRGBPixelOffset = 318; + } + } + else { // Decreasing + state->apsRGBPixelOffset = I16T(state->apsRGBPixelOffset - 3); + } + } + + break; + } + + case 5: { + // Misc 8bit data, used currently only + // for IMU events in DAVIS FX3 boards. + uint8_t misc8Code = U8T((data & 0x0F00) >> 8); + uint8_t misc8Data = U8T(data & 0x00FF); + + switch (misc8Code) { + case 0: + if (state->imuIgnoreEvents) { + break; + } + + // Detect missing IMU end events. + if (state->imuCount >= IMU6_COUNT) { + caerLog(CAER_LOG_INFO, handle->info.deviceString, + "IMU data: IMU samples count is at maximum, discarding further samples."); + break; + } + + // IMU data event. + switch (state->imuCount) { + case 0: + caerLog(CAER_LOG_ERROR, handle->info.deviceString, + "IMU data: missing IMU Scale Config event. Parsing of IMU events will still be attempted, but be aware that Accel/Gyro scale conversions may be inaccurate."); + state->imuCount = 1; + // Fall through to next case, as if imuCount was equal to 1. + + case 1: + case 3: + case 5: + case 7: + case 9: + case 11: + case 13: + state->imuTmpData = misc8Data; + break; + + case 2: { + int16_t accelX = I16T((state->imuTmpData << 8) | misc8Data); + caerIMU6EventSetAccelX(&state->currentIMU6Event, accelX / state->imuAccelScale); + break; + } + + case 4: { + int16_t accelY = I16T((state->imuTmpData << 8) | misc8Data); + caerIMU6EventSetAccelY(&state->currentIMU6Event, accelY / state->imuAccelScale); + break; + } + + case 6: { + int16_t accelZ = I16T((state->imuTmpData << 8) | misc8Data); + caerIMU6EventSetAccelZ(&state->currentIMU6Event, accelZ / state->imuAccelScale); + break; + } + + // Temperature is signed. Formula for converting to °C: + // (SIGNED_VAL / 340) + 36.53 + case 8: { + int16_t temp = I16T((state->imuTmpData << 8) | misc8Data); + caerIMU6EventSetTemp(&state->currentIMU6Event, (temp / 340.0f) + 36.53f); + break; + } + + case 10: { + int16_t gyroX = I16T((state->imuTmpData << 8) | misc8Data); + caerIMU6EventSetGyroX(&state->currentIMU6Event, gyroX / state->imuGyroScale); + break; + } + + case 12: { + int16_t gyroY = I16T((state->imuTmpData << 8) | misc8Data); + caerIMU6EventSetGyroY(&state->currentIMU6Event, gyroY / state->imuGyroScale); + break; + } + + case 14: { + int16_t gyroZ = I16T((state->imuTmpData << 8) | misc8Data); + caerIMU6EventSetGyroZ(&state->currentIMU6Event, gyroZ / state->imuGyroScale); + break; + } + } + + state->imuCount++; + + break; + + case 1: + // APS ROI Size Part 1 (bits 15-8). + // Here we just store the temporary value, and use it again + // in the next case statement. + state->apsROITmpData = U16T(misc8Data << 8); + + break; + + case 2: { + // APS ROI Size Part 2 (bits 7-0). + // Here we just store the values and re-use the four fields + // sizeX/Y and positionX/Y to store endCol/Row and startCol/Row. + // We then recalculate all the right values and set everything + // up in START_FRAME. + size_t apsROIRegion = state->apsROIUpdate >> 2; + + switch (state->apsROIUpdate & 0x03) { + case 0: + // START COLUMN + state->apsROIPositionX[apsROIRegion] = U16T(state->apsROITmpData | misc8Data); + break; + + case 1: + // START ROW + state->apsROIPositionY[apsROIRegion] = U16T(state->apsROITmpData | misc8Data); + break; + + case 2: + // END COLUMN + state->apsROISizeX[apsROIRegion] = U16T(state->apsROITmpData | misc8Data); + break; + + case 3: + // END ROW + state->apsROISizeY[apsROIRegion] = U16T(state->apsROITmpData | misc8Data); + break; + + default: + break; + } + + // Jump to next type of APS info (col->row, start->end). + state->apsROIUpdate++; + + break; + } + + default: + caerLog(CAER_LOG_ERROR, handle->info.deviceString, + "Caught Misc8 event that can't be handled."); + break; + } + + break; + } + + case 7: { // Timestamp wrap + // Detect big timestamp wrap-around. + int64_t wrapJump = (TS_WRAP_ADD * data); + int64_t wrapSum = I64T(state->wrapAdd) + wrapJump; + + if (wrapSum > I64T(INT32_MAX)) { + // Reset wrapAdd at this point, so we can again + // start detecting overruns of the 32bit value. + // We reset not to zero, but to the remaining value after + // multiple wrap-jumps are taken into account. + int64_t wrapRemainder = wrapSum - I64T(INT32_MAX) - 1LL; + state->wrapAdd = I32T(wrapRemainder); + + state->lastTimestamp = 0; + state->currentTimestamp = state->wrapAdd; + + // Increment TSOverflow counter. + state->wrapOverflow++; + + caerSpecialEvent currentSpecialEvent = caerSpecialEventPacketGetEvent( + state->currentSpecialPacket, state->currentSpecialPacketPosition); + caerSpecialEventSetTimestamp(currentSpecialEvent, INT32_MAX); + caerSpecialEventSetType(currentSpecialEvent, TIMESTAMP_WRAP); + caerSpecialEventValidate(currentSpecialEvent, state->currentSpecialPacket); + state->currentSpecialPacketPosition++; + + // Commit packets to separate before wrap from after cleanly. + tsBigWrap = true; + } + else { + // Each wrap is 2^15 µs (~32ms), and we have + // to multiply it with the wrap counter, + // which is located in the data part of this + // event. + state->wrapAdd = I32T(wrapSum); + + state->lastTimestamp = state->currentTimestamp; + state->currentTimestamp = state->wrapAdd; + initContainerCommitTimestamp(state); + + // Check monotonicity of timestamps. + checkStrictMonotonicTimestamp(handle); + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, + "Timestamp wrap event received with multiplier of %" PRIu16 ".", data); + } + + break; + } + + default: + caerLog(CAER_LOG_ERROR, handle->info.deviceString, "Caught event that can't be handled."); + break; + } + } + + // Thresholds on which to trigger packet container commit. + // forceCommit is already defined above. + // Trigger if any of the global container-wide thresholds are met. + int32_t currentPacketContainerCommitSize = I32T( + atomic_load_explicit(&state->maxPacketContainerPacketSize, memory_order_relaxed)); + bool containerSizeCommit = (currentPacketContainerCommitSize > 0) + && ((state->currentPolarityPacketPosition >= currentPacketContainerCommitSize) + || (state->currentSpecialPacketPosition >= currentPacketContainerCommitSize) + || (state->currentFramePacketPosition >= currentPacketContainerCommitSize) + || (state->currentIMU6PacketPosition >= currentPacketContainerCommitSize)); + + bool containerTimeCommit = generateFullTimestamp(state->wrapOverflow, state->currentTimestamp) + > state->currentPacketContainerCommitTimestamp; + + // Commit packet containers to the ring-buffer, so they can be processed by the + // main-loop, when any of the required conditions are met. + if (tsReset || tsBigWrap || containerSizeCommit || containerTimeCommit) { + // One or more of the commit triggers are hit. Set the packet container up to contain + // any non-empty packets. Empty packets are not forwarded to save memory. + bool emptyContainerCommit = true; + + if (state->currentPolarityPacketPosition > 0) { + caerEventPacketContainerSetEventPacket(state->currentPacketContainer, POLARITY_EVENT, + (caerEventPacketHeader) state->currentPolarityPacket); + + state->currentPolarityPacket = NULL; + state->currentPolarityPacketPosition = 0; + emptyContainerCommit = false; + } + + if (state->currentSpecialPacketPosition > 0) { + caerEventPacketContainerSetEventPacket(state->currentPacketContainer, SPECIAL_EVENT, + (caerEventPacketHeader) state->currentSpecialPacket); + + state->currentSpecialPacket = NULL; + state->currentSpecialPacketPosition = 0; + emptyContainerCommit = false; + } + + if (state->currentFramePacketPosition > 0) { + caerEventPacketContainerSetEventPacket(state->currentPacketContainer, FRAME_EVENT, + (caerEventPacketHeader) state->currentFramePacket); + + state->currentFramePacket = NULL; + state->currentFramePacketPosition = 0; + emptyContainerCommit = false; + } + + if (state->currentIMU6PacketPosition > 0) { + caerEventPacketContainerSetEventPacket(state->currentPacketContainer, IMU6_EVENT, + (caerEventPacketHeader) state->currentIMU6Packet); + + state->currentIMU6Packet = NULL; + state->currentIMU6PacketPosition = 0; + emptyContainerCommit = false; + } + + if (tsReset || tsBigWrap) { + // Ignore all APS and IMU6 (composite) events, until a new APS or IMU6 + // Start event comes in, for the next packet. + // This is to correctly support the forced packet commits that a TS reset, + // or a TS big wrap, impose. Continuing to parse events would result + // in a corrupted state of the first event in the new packet, as it would + // be incomplete, incorrect and miss vital initialization data. + // See APS and IMU6 END states for more details on a related issue. + state->apsIgnoreEvents = true; + state->imuIgnoreEvents = true; + } + + // If the commit was triggered by a packet container limit being reached, we always + // update the time related limit. The size related one is updated implicitly by size + // being reset to zero after commit (new packets are empty). + if (containerTimeCommit) { + while (generateFullTimestamp(state->wrapOverflow, state->currentTimestamp) + > state->currentPacketContainerCommitTimestamp) { + state->currentPacketContainerCommitTimestamp += atomic_load_explicit( + &state->maxPacketContainerInterval, memory_order_relaxed); + } + } + + // Filter out completely empty commits. This can happen when data is turned off, + // but the timestamps are still going forward. + if (emptyContainerCommit) { + caerEventPacketContainerFree(state->currentPacketContainer); + state->currentPacketContainer = NULL; + } + else { + if (!ringBufferPut(state->dataExchangeBuffer, state->currentPacketContainer)) { + // Failed to forward packet container, just drop it, it doesn't contain + // any critical information anyway. + caerLog(CAER_LOG_INFO, handle->info.deviceString, + "Dropped EventPacket Container because ring-buffer full!"); + + caerEventPacketContainerFree(state->currentPacketContainer); + state->currentPacketContainer = NULL; + } + else { + if (state->dataNotifyIncrease != NULL) { + state->dataNotifyIncrease(state->dataNotifyUserPtr); + } + + state->currentPacketContainer = NULL; + } + } + + // The only critical timestamp information to forward is the timestamp reset event. + // The timestamp big-wrap can also (and should!) be detected by observing a packet's + // tsOverflow value, not the special packet TIMESTAMP_WRAP event, which is only informative. + // For the timestamp reset event (TIMESTAMP_RESET), we thus ensure that it is always + // committed, and we send it alone, in its own packet container, to ensure it will always + // be ordered after any other event packets in any processing or output stream. + if (tsReset) { + // Allocate packet container just for this event. + caerEventPacketContainer tsResetContainer = caerEventPacketContainerAllocate(DAVIS_EVENT_TYPES); + if (tsResetContainer == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, + "Failed to allocate tsReset event packet container."); + return; + } + + // Allocate special packet just for this event. + caerSpecialEventPacket tsResetPacket = caerSpecialEventPacketAllocate(1, I16T(handle->info.deviceID), + state->wrapOverflow); + if (tsResetPacket == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, + "Failed to allocate tsReset special event packet."); + return; + } + + // Create timestamp reset event. + caerSpecialEvent tsResetEvent = caerSpecialEventPacketGetEvent(tsResetPacket, 0); + caerSpecialEventSetTimestamp(tsResetEvent, INT32_MAX); + caerSpecialEventSetType(tsResetEvent, TIMESTAMP_RESET); + caerSpecialEventValidate(tsResetEvent, tsResetPacket); + + // Assign special packet to packet container. + caerEventPacketContainerSetEventPacket(tsResetContainer, SPECIAL_EVENT, + (caerEventPacketHeader) tsResetPacket); + + // Reset MUST be committed, always, else downstream data processing and + // outputs get confused if they have no notification of timestamps + // jumping back go zero. + while (!ringBufferPut(state->dataExchangeBuffer, tsResetContainer)) { + // Prevent dead-lock if shutdown is requested and nothing is consuming + // data anymore, but the ring-buffer is full (and would thus never empty), + // thus blocking the USB handling thread in this loop. + if (!atomic_load_explicit(&state->dataAcquisitionThreadRun, memory_order_relaxed)) { + return; + } + } + + // Signal new container as usual. + if (state->dataNotifyIncrease != NULL) { + state->dataNotifyIncrease(state->dataNotifyUserPtr); + } + } + } + } +} + +static int davisDataAcquisitionThread(void *inPtr) { + // inPtr is a pointer to device handle. + davisHandle handle = inPtr; + davisState state = &handle->state; + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "Initializing data acquisition thread ..."); + + // Set thread name. + thrd_set_name(state->deviceThreadName); + + // Reset configuration update, so as to not re-do work afterwards. + atomic_store(&state->dataAcquisitionThreadConfigUpdate, 0); + + if (atomic_load(&state->dataExchangeStartProducers)) { + // Enable data transfer on USB end-point 2. + davisCommonConfigSet(handle, DAVIS_CONFIG_USB, DAVIS_CONFIG_USB_RUN, true); + davisCommonConfigSet(handle, DAVIS_CONFIG_MUX, DAVIS_CONFIG_MUX_RUN, true); + davisCommonConfigSet(handle, DAVIS_CONFIG_MUX, DAVIS_CONFIG_MUX_TIMESTAMP_RUN, true); + davisCommonConfigSet(handle, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_RUN, true); + davisCommonConfigSet(handle, DAVIS_CONFIG_APS, DAVIS_CONFIG_APS_RUN, true); + davisCommonConfigSet(handle, DAVIS_CONFIG_IMU, DAVIS_CONFIG_IMU_RUN, true); + davisCommonConfigSet(handle, DAVIS_CONFIG_EXTINPUT, DAVIS_CONFIG_EXTINPUT_RUN_DETECTOR, true); + } + + // Create buffers as specified in config file. + davisAllocateTransfers(handle, U32T(atomic_load(&state->usbBufferNumber)), + U32T(atomic_load(&state->usbBufferSize))); + + // Signal data thread ready back to start function. + atomic_store(&state->dataAcquisitionThreadRun, true); + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "data acquisition thread ready to process events."); + + // Handle USB events (1 second timeout). + struct timeval te = { .tv_sec = 1, .tv_usec = 0 }; + + while (atomic_load_explicit(&state->dataAcquisitionThreadRun, memory_order_relaxed) + && state->activeDataTransfers > 0) { + // Check config refresh, in this case to adjust buffer sizes. + if (atomic_load_explicit(&state->dataAcquisitionThreadConfigUpdate, memory_order_relaxed) != 0) { + davisDataAcquisitionThreadConfig(handle); + } + + libusb_handle_events_timeout(state->deviceContext, &te); + } + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "shutting down data acquisition thread ..."); + + // Cancel all transfers and handle them. + davisDeallocateTransfers(handle); + + // Ensure shutdown is stored and notified, could be because of all data transfers going away! + atomic_store(&state->dataAcquisitionThreadRun, false); + + if (state->dataShutdownNotify != NULL) { + state->dataShutdownNotify(state->dataShutdownUserPtr); + } + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "data acquisition thread shut down."); + + return (EXIT_SUCCESS); +} + +static void davisDataAcquisitionThreadConfig(davisHandle handle) { + davisState state = &handle->state; + + // Get the current value to examine by atomic exchange, since we don't + // want there to be any possible store between a load/store pair. + uint32_t configUpdate = U32T(atomic_exchange(&state->dataAcquisitionThreadConfigUpdate, 0)); + + if ((configUpdate >> 0) & 0x01) { + // Do buffer size change: cancel all and recreate them. + davisDeallocateTransfers(handle); + davisAllocateTransfers(handle, U32T(atomic_load(&state->usbBufferNumber)), + U32T(atomic_load(&state->usbBufferSize))); + } + + if ((configUpdate >> 1) & 0x01) { + // Get new Master/Slave information from device. Done here to prevent deadlock + // inside asynchronous callback. + uint32_t param32 = 0; + + spiConfigReceive(state->deviceHandle, DAVIS_CONFIG_SYSINFO, DAVIS_CONFIG_SYSINFO_DEVICE_IS_MASTER, ¶m32); + + atomic_thread_fence(memory_order_seq_cst); + handle->info.deviceIsMaster = param32; + atomic_thread_fence(memory_order_seq_cst); + } +} + +uint16_t caerBiasVDACGenerate(struct caer_bias_vdac vdacBias) { + // Build up bias value from all its components. + uint16_t biasValue = U16T((vdacBias.voltageValue & 0x3F) << 0); + biasValue |= U16T((vdacBias.currentValue & 0x07) << 6); + + return (biasValue); +} + +struct caer_bias_vdac caerBiasVDACParse(uint16_t vdacBias) { + struct caer_bias_vdac biasValue; + + // Decompose bias integer into its parts. + biasValue.voltageValue = vdacBias & 0x3F; + biasValue.currentValue = (vdacBias >> 6) & 0x07; + + return (biasValue); +} + +uint16_t caerBiasCoarseFineGenerate(struct caer_bias_coarsefine coarseFineBias) { + uint16_t biasValue = 0; + + // Build up bias value from all its components. + if (coarseFineBias.enabled) { + biasValue |= 0x01; + } + if (coarseFineBias.sexN) { + biasValue |= 0x02; + } + if (coarseFineBias.typeNormal) { + biasValue |= 0x04; + } + if (coarseFineBias.currentLevelNormal) { + biasValue |= 0x08; + } + + biasValue |= U16T((coarseFineBias.fineValue & 0xFF) << 4); + biasValue |= U16T((coarseFineBias.coarseValue & 0x07) << 12); + + return (biasValue); +} + +struct caer_bias_coarsefine caerBiasCoarseFineParse(uint16_t coarseFineBias) { + struct caer_bias_coarsefine biasValue; + + // Decompose bias integer into its parts. + biasValue.enabled = (coarseFineBias & 0x01); + biasValue.sexN = (coarseFineBias & 0x02); + biasValue.typeNormal = (coarseFineBias & 0x04); + biasValue.currentLevelNormal = (coarseFineBias & 0x08); + biasValue.fineValue = U8T(coarseFineBias >> 4) & 0xFF; + biasValue.coarseValue = U8T(coarseFineBias >> 12) & 0x07; + + return (biasValue); +} + +uint16_t caerBiasShiftedSourceGenerate(struct caer_bias_shiftedsource shiftedSourceBias) { + uint16_t biasValue = 0; + + if (shiftedSourceBias.operatingMode == HI_Z) { + biasValue |= 0x01; + } + else if (shiftedSourceBias.operatingMode == TIED_TO_RAIL) { + biasValue |= 0x02; + } + + if (shiftedSourceBias.voltageLevel == SINGLE_DIODE) { + biasValue |= (0x01 << 2); + } + else if (shiftedSourceBias.voltageLevel == DOUBLE_DIODE) { + biasValue |= (0x02 << 2); + } + + biasValue |= U16T((shiftedSourceBias.refValue & 0x3F) << 4); + biasValue |= U16T((shiftedSourceBias.regValue & 0x3F) << 10); + + return (biasValue); +} + +struct caer_bias_shiftedsource caerBiasShiftedSourceParse(uint16_t shiftedSourceBias) { + struct caer_bias_shiftedsource biasValue; + + // Decompose bias integer into its parts. + biasValue.operatingMode = + (shiftedSourceBias & 0x01) ? (HI_Z) : ((shiftedSourceBias & 0x02) ? (TIED_TO_RAIL) : (SHIFTED_SOURCE)); + biasValue.voltageLevel = + ((shiftedSourceBias >> 2) & 0x01) ? + (SINGLE_DIODE) : (((shiftedSourceBias >> 2) & 0x02) ? (DOUBLE_DIODE) : (SPLIT_GATE)); + biasValue.refValue = (shiftedSourceBias >> 4) & 0x3F; + biasValue.regValue = (shiftedSourceBias >> 10) & 0x3F; + + return (biasValue); +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_common.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_common.h new file mode 100755 index 0000000..cf07615 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_common.h @@ -0,0 +1,165 @@ +#ifndef LIBCAER_SRC_DAVIS_COMMON_H_ +#define LIBCAER_SRC_DAVIS_COMMON_H_ + +#include "devices/davis.h" +#include "ringbuffer/ringbuffer.h" +#include <stdatomic.h> +#include <libusb.h> + +#ifdef HAVE_PTHREADS + #include "c11threads_posix.h" +#endif + +#define APS_READOUT_TYPES_NUM 2 +#define APS_READOUT_RESET 0 +#define APS_READOUT_SIGNAL 1 + +/** + * Enable APS frame debugging by only looking at the reset or signal + * frames, and not at the resulting correlated frame. + * Supported values: + * 0 - both/CDS (default) + * 1 - reset read only + * 2 - signal read only + */ +#define APS_DEBUG_FRAME 0 + +#define APS_ADC_DEPTH 10 + +#define APS_ADC_CHANNELS 1 + +#define APS_ROI_REGIONS_MAX 4 + +#define IMU6_COUNT 15 +#define IMU9_COUNT 21 + +#define DAVIS_EVENT_TYPES 4 + +#define DAVIS_POLARITY_DEFAULT_SIZE 4096 +#define DAVIS_SPECIAL_DEFAULT_SIZE 128 +#define DAVIS_FRAME_DEFAULT_SIZE 4 +#define DAVIS_IMU_DEFAULT_SIZE 64 + +#define DAVIS_DATA_ENDPOINT 0x82 + +#define VENDOR_REQUEST_FPGA_CONFIG 0xBF +#define VENDOR_REQUEST_FPGA_CONFIG_MULTIPLE 0xC2 + +struct davis_state { + // Data Acquisition Thread -> Mainloop Exchange + RingBuffer dataExchangeBuffer; + atomic_uint_fast32_t dataExchangeBufferSize; // Only takes effect on DataStart() calls! + atomic_bool dataExchangeBlocking; + atomic_bool dataExchangeStartProducers; + atomic_bool dataExchangeStopProducers; + void (*dataNotifyIncrease)(void *ptr); + void (*dataNotifyDecrease)(void *ptr); + void *dataNotifyUserPtr; + void (*dataShutdownNotify)(void *ptr); + void *dataShutdownUserPtr; + // USB Device State + char deviceThreadName[15 + 1]; // +1 for terminating NUL character. + libusb_context *deviceContext; + libusb_device_handle *deviceHandle; + // USB Transfer Settings + atomic_uint_fast32_t usbBufferNumber; + atomic_uint_fast32_t usbBufferSize; + // Data Acquisition Thread + thrd_t dataAcquisitionThread; + atomic_bool dataAcquisitionThreadRun; + atomic_uint_fast32_t dataAcquisitionThreadConfigUpdate; + struct libusb_transfer **dataTransfers; + size_t dataTransfersLength; + size_t activeDataTransfers; + // Timestamp fields + int32_t wrapOverflow; + int32_t wrapAdd; + int32_t lastTimestamp; + int32_t currentTimestamp; + // DVS specific fields + uint16_t dvsLastY; + bool dvsGotY; + int16_t dvsSizeX; + int16_t dvsSizeY; + bool dvsInvertXY; + // APS specific fields + int16_t apsSizeX; + int16_t apsSizeY; + bool apsInvertXY; + bool apsFlipX; + bool apsFlipY; + bool apsIgnoreEvents; + bool apsGlobalShutter; + bool apsResetRead; + bool apsRGBPixelOffsetDirection; // 0 is increasing, 1 is decreasing. + int16_t apsRGBPixelOffset; + uint16_t apsCurrentReadoutType; + uint16_t apsCountX[APS_READOUT_TYPES_NUM]; + uint16_t apsCountY[APS_READOUT_TYPES_NUM]; + uint16_t *apsCurrentResetFrame; + uint16_t apsROIUpdate; + uint16_t apsROITmpData; + uint16_t apsROISizeX[APS_ROI_REGIONS_MAX]; + uint16_t apsROISizeY[APS_ROI_REGIONS_MAX]; + uint16_t apsROIPositionX[APS_ROI_REGIONS_MAX]; + uint16_t apsROIPositionY[APS_ROI_REGIONS_MAX]; + // IMU specific fields + bool imuIgnoreEvents; + uint8_t imuCount; + uint8_t imuTmpData; + float imuAccelScale; + float imuGyroScale; + // Packet Container state + caerEventPacketContainer currentPacketContainer; + atomic_int_fast32_t maxPacketContainerPacketSize; + atomic_int_fast32_t maxPacketContainerInterval; + int64_t currentPacketContainerCommitTimestamp; + // Polarity Packet state + caerPolarityEventPacket currentPolarityPacket; + int32_t currentPolarityPacketPosition; + // Frame Packet state + caerFrameEventPacket currentFramePacket; + int32_t currentFramePacketPosition; + // IMU6 Packet state + caerIMU6EventPacket currentIMU6Packet; + int32_t currentIMU6PacketPosition; + // Special Packet state + caerSpecialEventPacket currentSpecialPacket; + int32_t currentSpecialPacketPosition; + // Current composite events, for later copy, to not loose them on commits. + caerFrameEvent currentFrameEvent[APS_ROI_REGIONS_MAX]; + struct caer_imu6_event currentIMU6Event; +}; + +typedef struct davis_state *davisState; + +struct davis_handle { + uint16_t deviceType; + // Information fields + struct caer_davis_info info; + // State for data management, common to all DAVIS. + struct davis_state state; +}; + +typedef struct davis_handle *davisHandle; + +bool davisCommonOpen(davisHandle handle, uint16_t VID, uint16_t PID, uint8_t DID_TYPE, const char *deviceName, + uint16_t deviceID, uint8_t busNumberRestrict, uint8_t devAddressRestrict, const char *serialNumberRestrict, + uint16_t requiredLogicRevision, uint16_t requiredFirmwareVersion); +bool davisCommonClose(davisHandle handle); + +bool davisCommonSendDefaultFPGAConfig(caerDeviceHandle cdh, + bool (*configSet)(caerDeviceHandle cdh, int8_t modAddr, uint8_t paramAddr, uint32_t param)); +bool davisCommonSendDefaultChipConfig(caerDeviceHandle cdh, + bool (*configSet)(caerDeviceHandle cdh, int8_t modAddr, uint8_t paramAddr, uint32_t param)); + +bool davisCommonConfigSet(davisHandle handle, int8_t modAddr, uint8_t paramAddr, uint32_t param); +bool davisCommonConfigGet(davisHandle handle, int8_t modAddr, uint8_t paramAddr, uint32_t *param); + +bool davisCommonDataStart(caerDeviceHandle handle, void (*dataNotifyIncrease)(void *ptr), + void (*dataNotifyDecrease)(void *ptr), void *dataNotifyUserPtr, void (*dataShutdownNotify)(void *ptr), + void *dataShutdownUserPtr); +bool davisCommonDataStop(caerDeviceHandle handle); +caerEventPacketContainer davisCommonDataGet(caerDeviceHandle handle); + +#endif /* LIBCAER_SRC_DAVIS_COMMON_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx2.c b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx2.c new file mode 100755 index 0000000..c6b7646 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx2.c @@ -0,0 +1,70 @@ +#include "davis_fx2.h" + +caerDeviceHandle davisFX2Open(uint16_t deviceID, uint8_t busNumberRestrict, uint8_t devAddressRestrict, + const char *serialNumberRestrict) { + caerLog(CAER_LOG_DEBUG, __func__, "Initializing %s.", DAVIS_FX2_DEVICE_NAME); + + davisFX2Handle handle = calloc(1, sizeof(*handle)); + if (handle == NULL) { + // Failed to allocate memory for device handle! + caerLog(CAER_LOG_CRITICAL, __func__, "Failed to allocate memory for device handle."); + return (NULL); + } + + // Set main deviceType correctly right away. + handle->h.deviceType = CAER_DEVICE_DAVIS_FX2; + + bool openRetVal = davisCommonOpen((davisHandle) handle, DAVIS_FX2_DEVICE_VID, DAVIS_FX2_DEVICE_PID, + DAVIS_FX2_DEVICE_DID_TYPE, DAVIS_FX2_DEVICE_NAME, deviceID, busNumberRestrict, devAddressRestrict, + serialNumberRestrict, DAVIS_FX2_REQUIRED_LOGIC_REVISION, + DAVIS_FX2_REQUIRED_FIRMWARE_VERSION); + if (!openRetVal) { + free(handle); + + // Failed to open device and grab basic information! + return (NULL); + } + + return ((caerDeviceHandle) handle); +} + +bool davisFX2Close(caerDeviceHandle cdh) { + caerLog(CAER_LOG_DEBUG, ((davisHandle) cdh)->info.deviceString, "Shutting down ..."); + + return (davisCommonClose((davisHandle) cdh)); +} + +bool davisFX2SendDefaultConfig(caerDeviceHandle cdh) { + // First send default chip/bias config. + if (!davisCommonSendDefaultChipConfig(cdh, &davisFX2ConfigSet)) { + return (false); + } + + // Send default FPGA config. + if (!davisCommonSendDefaultFPGAConfig(cdh, &davisFX2ConfigSet)) { + return (false); + } + + // FX2 specific FPGA configuration. + if (!davisFX2ConfigSet(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_ACK_DELAY_ROW, 14)) { + return (false); + } + + if (!davisFX2ConfigSet(cdh, DAVIS_CONFIG_DVS, DAVIS_CONFIG_DVS_ACK_EXTENSION_ROW, 4)) { + return (false); + } + + return (true); +} + +bool davisFX2ConfigSet(caerDeviceHandle cdh, int8_t modAddr, uint8_t paramAddr, uint32_t param) { + davisHandle handle = (davisHandle) cdh; + + return (davisCommonConfigSet(handle, modAddr, paramAddr, param)); +} + +bool davisFX2ConfigGet(caerDeviceHandle cdh, int8_t modAddr, uint8_t paramAddr, uint32_t *param) { + davisHandle handle = (davisHandle) cdh; + + return (davisCommonConfigGet(handle, modAddr, paramAddr, param)); +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx2.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx2.h new file mode 100755 index 0000000..4d10623 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx2.h @@ -0,0 +1,35 @@ +#ifndef LIBCAER_SRC_DAVIS_FX2_H_ +#define LIBCAER_SRC_DAVIS_FX2_H_ + +#include "davis_common.h" + +#define DAVIS_FX2_DEVICE_NAME "DAVIS FX2" + +#define DAVIS_FX2_DEVICE_VID 0x152A +#define DAVIS_FX2_DEVICE_PID 0x841B +#define DAVIS_FX2_DEVICE_DID_TYPE 0x00 + +#define DAVIS_FX2_REQUIRED_LOGIC_REVISION 7449 +#define DAVIS_FX2_REQUIRED_FIRMWARE_VERSION 3 + +#define VENDOR_REQUEST_CHIP_BIAS 0xC0 +#define VENDOR_REQUEST_CHIP_DIAG 0xC1 + +struct davis_fx2_handle { + // Common info and state structure (handle). + struct davis_handle h; +}; + +typedef struct davis_fx2_handle *davisFX2Handle; + +caerDeviceHandle davisFX2Open(uint16_t deviceID, uint8_t busNumberRestrict, uint8_t devAddressRestrict, + const char *serialNumberRestrict); +bool davisFX2Close(caerDeviceHandle handle); + +bool davisFX2SendDefaultConfig(caerDeviceHandle handle); +// Negative addresses are used for host-side configuration. +// Positive addresses (including zero) are used for device-side configuration. +bool davisFX2ConfigSet(caerDeviceHandle handle, int8_t modAddr, uint8_t paramAddr, uint32_t param); +bool davisFX2ConfigGet(caerDeviceHandle handle, int8_t modAddr, uint8_t paramAddr, uint32_t *param); + +#endif /* LIBCAER_SRC_DAVIS_FX2_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx3.c b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx3.c new file mode 100755 index 0000000..f599459 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx3.c @@ -0,0 +1,190 @@ +#include "davis_fx3.h" + +static void allocateDebugTransfers(davisFX3Handle handle); +static void deallocateDebugTransfers(davisFX3Handle handle); +static void LIBUSB_CALL libUsbDebugCallback(struct libusb_transfer *transfer); +static void debugTranslator(davisFX3Handle handle, uint8_t *buffer, size_t bytesSent); + +caerDeviceHandle davisFX3Open(uint16_t deviceID, uint8_t busNumberRestrict, uint8_t devAddressRestrict, + const char *serialNumberRestrict) { + caerLog(CAER_LOG_DEBUG, __func__, "Initializing %s.", DAVIS_FX3_DEVICE_NAME); + + davisFX3Handle handle = calloc(1, sizeof(*handle)); + if (handle == NULL) { + // Failed to allocate memory for device handle! + caerLog(CAER_LOG_CRITICAL, __func__, "Failed to allocate memory for device handle."); + return (NULL); + } + + // Set main deviceType correctly right away. + handle->h.deviceType = CAER_DEVICE_DAVIS_FX3; + + bool openRetVal = davisCommonOpen((davisHandle) handle, DAVIS_FX3_DEVICE_VID, DAVIS_FX3_DEVICE_PID, + DAVIS_FX3_DEVICE_DID_TYPE, DAVIS_FX3_DEVICE_NAME, deviceID, busNumberRestrict, devAddressRestrict, + serialNumberRestrict, DAVIS_FX3_REQUIRED_LOGIC_REVISION, + DAVIS_FX3_REQUIRED_FIRMWARE_VERSION); + if (!openRetVal) { + free(handle); + + // Failed to open device and grab basic information! + return (NULL); + } + + allocateDebugTransfers(handle); + + return ((caerDeviceHandle) handle); +} + +bool davisFX3Close(caerDeviceHandle cdh) { + caerLog(CAER_LOG_DEBUG, ((davisHandle) cdh)->info.deviceString, "Shutting down ..."); + + deallocateDebugTransfers((davisFX3Handle) cdh); + + return (davisCommonClose((davisHandle) cdh)); +} + +bool davisFX3SendDefaultConfig(caerDeviceHandle cdh) { + // First send default chip/bias config. + if (!davisCommonSendDefaultChipConfig(cdh, &davisFX3ConfigSet)) { + return (false); + } + + // Send default FPGA config. + if (!davisCommonSendDefaultFPGAConfig(cdh, &davisFX3ConfigSet)) { + return (false); + } + + return (true); +} + +bool davisFX3ConfigSet(caerDeviceHandle cdh, int8_t modAddr, uint8_t paramAddr, uint32_t param) { + davisHandle handle = (davisHandle) cdh; + + return (davisCommonConfigSet(handle, modAddr, paramAddr, param)); +} + +bool davisFX3ConfigGet(caerDeviceHandle cdh, int8_t modAddr, uint8_t paramAddr, uint32_t *param) { + davisHandle handle = (davisHandle) cdh; + + return (davisCommonConfigGet(handle, modAddr, paramAddr, param)); +} + +static void allocateDebugTransfers(davisFX3Handle handle) { + // Set number of transfers and allocate memory for the main transfer array. + + // Allocate transfers and set them up. + for (size_t i = 0; i < DEBUG_TRANSFER_NUM; i++) { + handle->debugTransfers[i] = libusb_alloc_transfer(0); + if (handle->debugTransfers[i] == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->h.info.deviceString, + "Unable to allocate further libusb transfers (debug channel, %zu of %" PRIu32 ").", i, + DEBUG_TRANSFER_NUM); + continue; + } + + // Create data buffer. + handle->debugTransfers[i]->length = DEBUG_TRANSFER_SIZE; + handle->debugTransfers[i]->buffer = malloc(DEBUG_TRANSFER_SIZE); + if (handle->debugTransfers[i]->buffer == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->h.info.deviceString, + "Unable to allocate buffer for libusb transfer %zu (debug channel). Error: %d.", i, errno); + + libusb_free_transfer(handle->debugTransfers[i]); + handle->debugTransfers[i] = NULL; + + continue; + } + + // Initialize Transfer. + handle->debugTransfers[i]->dev_handle = handle->h.state.deviceHandle; + handle->debugTransfers[i]->endpoint = DEBUG_ENDPOINT; + handle->debugTransfers[i]->type = LIBUSB_TRANSFER_TYPE_INTERRUPT; + handle->debugTransfers[i]->callback = &libUsbDebugCallback; + handle->debugTransfers[i]->user_data = handle; + handle->debugTransfers[i]->timeout = 0; + handle->debugTransfers[i]->flags = LIBUSB_TRANSFER_FREE_BUFFER; + + if ((errno = libusb_submit_transfer(handle->debugTransfers[i])) == LIBUSB_SUCCESS) { + handle->activeDebugTransfers++; + } + else { + caerLog(CAER_LOG_CRITICAL, handle->h.info.deviceString, + "Unable to submit libusb transfer %zu (debug channel). Error: %s (%d).", i, libusb_strerror(errno), + errno); + + // The transfer buffer is freed automatically here thanks to + // the LIBUSB_TRANSFER_FREE_BUFFER flag set above. + libusb_free_transfer(handle->debugTransfers[i]); + handle->debugTransfers[i] = NULL; + + continue; + } + } + + if (handle->activeDebugTransfers == 0) { + // Didn't manage to allocate any USB transfers, log failure. + caerLog(CAER_LOG_CRITICAL, handle->h.info.deviceString, "Unable to allocate any libusb transfers."); + } +} + +static void deallocateDebugTransfers(davisFX3Handle handle) { + // Cancel all current transfers first. + for (size_t i = 0; i < DEBUG_TRANSFER_NUM; i++) { + if (handle->debugTransfers[i] != NULL) { + errno = libusb_cancel_transfer(handle->debugTransfers[i]); + if (errno != LIBUSB_SUCCESS && errno != LIBUSB_ERROR_NOT_FOUND) { + caerLog(CAER_LOG_CRITICAL, handle->h.info.deviceString, + "Unable to cancel libusb transfer %zu (debug channel). Error: %s (%d).", i, libusb_strerror(errno), + errno); + // Proceed with trying to cancel all transfers regardless of errors. + } + } + } + + // Wait for all transfers to go away (0.1 seconds timeout). + struct timeval te = { .tv_sec = 0, .tv_usec = 100000 }; + + while (handle->activeDebugTransfers > 0) { + libusb_handle_events_timeout(handle->h.state.deviceContext, &te); + } +} + +static void LIBUSB_CALL libUsbDebugCallback(struct libusb_transfer *transfer) { + davisFX3Handle handle = transfer->user_data; + + if (transfer->status == LIBUSB_TRANSFER_COMPLETED) { + // Handle debug data. + debugTranslator(handle, transfer->buffer, (size_t) transfer->actual_length); + } + + if (transfer->status != LIBUSB_TRANSFER_CANCELLED && transfer->status != LIBUSB_TRANSFER_NO_DEVICE) { + // Submit transfer again. + if (libusb_submit_transfer(transfer) == LIBUSB_SUCCESS) { + return; + } + } + + // Cannot recover (cancelled, no device, or other critical error). + // Signal this by adjusting the counter, free and exit. + handle->activeDebugTransfers--; + for (size_t i = 0; i < DEBUG_TRANSFER_NUM; i++) { + // Remove from list, so we don't try to cancel it later on. + if (handle->debugTransfers[i] == transfer) { + handle->debugTransfers[i] = NULL; + } + } + libusb_free_transfer(transfer); +} + +static void debugTranslator(davisFX3Handle handle, uint8_t *buffer, size_t bytesSent) { + // Check if this is a debug message (length 7-64 bytes). + if (bytesSent >= 7 && buffer[0] == 0x00) { + // Debug message, log this. + caerLog(CAER_LOG_ERROR, handle->h.info.deviceString, "Error message: '%s' (code %u at time %u).", &buffer[6], + buffer[1], *((uint32_t *) &buffer[2])); + } + else { + // Unknown/invalid debug message, log this. + caerLog(CAER_LOG_WARNING, handle->h.info.deviceString, "Unknown/invalid debug message."); + } +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx3.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx3.h new file mode 100755 index 0000000..78fca03 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/davis_fx3.h @@ -0,0 +1,39 @@ +#ifndef LIBCAER_SRC_DAVIS_FX3_H_ +#define LIBCAER_SRC_DAVIS_FX3_H_ + +#include "davis_common.h" + +#define DAVIS_FX3_DEVICE_NAME "DAVIS FX3" + +#define DAVIS_FX3_DEVICE_VID 0x152A +#define DAVIS_FX3_DEVICE_PID 0x841A +#define DAVIS_FX3_DEVICE_DID_TYPE 0x01 + +#define DAVIS_FX3_REQUIRED_LOGIC_REVISION 7449 +#define DAVIS_FX3_REQUIRED_FIRMWARE_VERSION 2 + +#define DEBUG_ENDPOINT 0x81 +#define DEBUG_TRANSFER_NUM 4 +#define DEBUG_TRANSFER_SIZE 64 + +struct davis_fx3_handle { + // Common info and state structure (handle). + struct davis_handle h; + // Debug transfer support (FX3 only). + struct libusb_transfer *debugTransfers[DEBUG_TRANSFER_NUM]; + size_t activeDebugTransfers; +}; + +typedef struct davis_fx3_handle *davisFX3Handle; + +caerDeviceHandle davisFX3Open(uint16_t deviceID, uint8_t busNumberRestrict, uint8_t devAddressRestrict, + const char *serialNumberRestrict); +bool davisFX3Close(caerDeviceHandle handle); + +bool davisFX3SendDefaultConfig(caerDeviceHandle handle); +// Negative addresses are used for host-side configuration. +// Positive addresses (including zero) are used for device-side configuration. +bool davisFX3ConfigSet(caerDeviceHandle handle, int8_t modAddr, uint8_t paramAddr, uint32_t param); +bool davisFX3ConfigGet(caerDeviceHandle handle, int8_t modAddr, uint8_t paramAddr, uint32_t *param); + +#endif /* LIBCAER_SRC_DAVIS_FX3_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/device.c b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/device.c new file mode 100755 index 0000000..bd4c084 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/device.c @@ -0,0 +1,206 @@ +#include "devices/usb.h" + +#include "dvs128.h" +#include "davis_common.h" +#include "davis_fx2.h" +#include "davis_fx3.h" + +/** + * Number of devices supported by this library. + */ +#define SUPPORTED_DEVICES_NUMBER 3 + +// Supported devices and their functions. +static caerDeviceHandle (*constructors[SUPPORTED_DEVICES_NUMBER])(uint16_t deviceID, uint8_t busNumberRestrict, + uint8_t devAddressRestrict, const char *serialNumberRestrict) = { + [CAER_DEVICE_DVS128] = &dvs128Open, + [CAER_DEVICE_DAVIS_FX2] = &davisFX2Open, + [CAER_DEVICE_DAVIS_FX3] = &davisFX3Open +}; + +static bool (*destructors[SUPPORTED_DEVICES_NUMBER])(caerDeviceHandle handle) = { + [CAER_DEVICE_DVS128] = &dvs128Close, + [CAER_DEVICE_DAVIS_FX2] = &davisFX2Close, + [CAER_DEVICE_DAVIS_FX3] = &davisFX3Close +}; + +static bool (*defaultConfigSenders[SUPPORTED_DEVICES_NUMBER])(caerDeviceHandle handle) = { + [CAER_DEVICE_DVS128] = &dvs128SendDefaultConfig, + [CAER_DEVICE_DAVIS_FX2] = &davisFX2SendDefaultConfig, + [CAER_DEVICE_DAVIS_FX3] = &davisFX3SendDefaultConfig +}; + +static bool (*configSetters[SUPPORTED_DEVICES_NUMBER])(caerDeviceHandle handle, int8_t modAddr, uint8_t paramAddr, + uint32_t param) = { + [CAER_DEVICE_DVS128] = &dvs128ConfigSet, + [CAER_DEVICE_DAVIS_FX2] = &davisFX2ConfigSet, + [CAER_DEVICE_DAVIS_FX3] = &davisFX3ConfigSet +}; + +static bool (*configGetters[SUPPORTED_DEVICES_NUMBER])(caerDeviceHandle handle, int8_t modAddr, uint8_t paramAddr, + uint32_t *param) = { + [CAER_DEVICE_DVS128] = &dvs128ConfigGet, + [CAER_DEVICE_DAVIS_FX2] = &davisFX2ConfigGet, + [CAER_DEVICE_DAVIS_FX3] = &davisFX3ConfigGet +}; + +static bool (*dataStarters[SUPPORTED_DEVICES_NUMBER])(caerDeviceHandle handle, void (*dataNotifyIncrease)(void *ptr), + void (*dataNotifyDecrease)(void *ptr), void *dataNotifyUserPtr, void (*dataShutdownNotify)(void *ptr), + void *dataShutdownUserPtr) = { + [CAER_DEVICE_DVS128] = &dvs128DataStart, + [CAER_DEVICE_DAVIS_FX2] = &davisCommonDataStart, + [CAER_DEVICE_DAVIS_FX3] = &davisCommonDataStart +}; + +static bool (*dataStoppers[SUPPORTED_DEVICES_NUMBER])(caerDeviceHandle handle) = { + [CAER_DEVICE_DVS128] = &dvs128DataStop, + [CAER_DEVICE_DAVIS_FX2] = &davisCommonDataStop, + [CAER_DEVICE_DAVIS_FX3] = &davisCommonDataStop +}; + +static caerEventPacketContainer (*dataGetters[SUPPORTED_DEVICES_NUMBER])(caerDeviceHandle handle) = { + [CAER_DEVICE_DVS128] = &dvs128DataGet, + [CAER_DEVICE_DAVIS_FX2] = &davisCommonDataGet, + [CAER_DEVICE_DAVIS_FX3] = &davisCommonDataGet +}; + +struct caer_device_handle { + uint16_t deviceType; +// This is compatible with all device handle structures. +// The first member is always 'uint16_t deviceType'. +}; + +caerDeviceHandle caerDeviceOpen(uint16_t deviceID, uint16_t deviceType, uint8_t busNumberRestrict, + uint8_t devAddressRestrict, const char *serialNumberRestrict) { + // Check if device type is supported. + if (deviceType >= SUPPORTED_DEVICES_NUMBER) { + return (NULL); + } + + // Execute main constructor function. + return (constructors[deviceType](deviceID, busNumberRestrict, devAddressRestrict, serialNumberRestrict)); +} + +bool caerDeviceClose(caerDeviceHandle *handlePtr) { + // We want a pointer here so we can ensure the reference is set to NULL. + // Check if either it, or the memory pointed to, are NULL and abort + // if that's the case. + if (handlePtr == NULL) { + return (false); + } + + if (*handlePtr == NULL) { + return (false); + } + + // Check if device type is supported. + if ((*handlePtr)->deviceType >= SUPPORTED_DEVICES_NUMBER) { + return (false); + } + + // Call appropriate destructor function. + bool retVal = destructors[(*handlePtr)->deviceType](*handlePtr); + + // Done. Set reference to NULL if successful. + if (retVal) { + *handlePtr = NULL; + } + + return (retVal); +} + +bool caerDeviceSendDefaultConfig(caerDeviceHandle handle) { + // Check if the pointer is valid. + if (handle == NULL) { + return (false); + } + + // Check if device type is supported. + if (handle->deviceType >= SUPPORTED_DEVICES_NUMBER) { + return (false); + } + + // Call appropriate function. + return (defaultConfigSenders[handle->deviceType](handle)); +} + +bool caerDeviceConfigSet(caerDeviceHandle handle, int8_t modAddr, uint8_t paramAddr, uint32_t param) { + // Check if the pointer is valid. + if (handle == NULL) { + return (false); + } + + // Check if device type is supported. + if (handle->deviceType >= SUPPORTED_DEVICES_NUMBER) { + return (false); + } + + // Call appropriate function. + return (configSetters[handle->deviceType](handle, modAddr, paramAddr, param)); +} + +bool caerDeviceConfigGet(caerDeviceHandle handle, int8_t modAddr, uint8_t paramAddr, uint32_t *param) { + // Check if the pointer is valid. + if (handle == NULL) { + return (false); + } + + // Check if device type is supported. + if (handle->deviceType >= SUPPORTED_DEVICES_NUMBER) { + return (false); + } + + // Ensure content of param is zeroed out. + *param = 0; + + // Call appropriate function. + return (configGetters[handle->deviceType](handle, modAddr, paramAddr, param)); +} + +bool caerDeviceDataStart(caerDeviceHandle handle, void (*dataNotifyIncrease)(void *ptr), + void (*dataNotifyDecrease)(void *ptr), void *dataNotifyUserPtr, void (*dataShutdownNotify)(void *ptr), + void *dataShutdownUserPtr) { + // Check if the pointer is valid. + if (handle == NULL) { + return (false); + } + + // Check if device type is supported. + if (handle->deviceType >= SUPPORTED_DEVICES_NUMBER) { + return (false); + } + + // Call appropriate function. + return (dataStarters[handle->deviceType](handle, dataNotifyIncrease, dataNotifyDecrease, dataNotifyUserPtr, + dataShutdownNotify, dataShutdownUserPtr)); +} + +bool caerDeviceDataStop(caerDeviceHandle handle) { + // Check if the pointer is valid. + if (handle == NULL) { + return (false); + } + + // Check if device type is supported. + if (handle->deviceType >= SUPPORTED_DEVICES_NUMBER) { + return (false); + } + + // Call appropriate function. + return (dataStoppers[handle->deviceType](handle)); +} + +caerEventPacketContainer caerDeviceDataGet(caerDeviceHandle handle) { + // Check if the pointer is valid. + if (handle == NULL) { + return (false); + } + + // Check if device type is supported. + if (handle->deviceType >= SUPPORTED_DEVICES_NUMBER) { + return (false); + } + + // Call appropriate function. + return (dataGetters[handle->deviceType](handle)); +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/dvs128.c b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/dvs128.c new file mode 100755 index 0000000..a07857a --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/dvs128.c @@ -0,0 +1,1319 @@ +#include "dvs128.h" + +static libusb_device_handle *dvs128DeviceOpen(libusb_context *devContext, uint16_t devVID, uint16_t devPID, + uint8_t devType, uint8_t busNumber, uint8_t devAddress, const char *serialNumber, uint16_t requiredFirmwareVersion); +static void dvs128DeviceClose(libusb_device_handle *devHandle); +static void dvs128AllocateTransfers(dvs128Handle handle, uint32_t bufferNum, uint32_t bufferSize); +static void dvs128DeallocateTransfers(dvs128Handle handle); +static void LIBUSB_CALL dvs128LibUsbCallback(struct libusb_transfer *transfer); +static void dvs128EventTranslator(dvs128Handle handle, uint8_t *buffer, size_t bytesSent); +static bool dvs128SendBiases(dvs128State state); +static int dvs128DataAcquisitionThread(void *inPtr); +static void dvs128DataAcquisitionThreadConfig(dvs128Handle handle); + +static inline void checkMonotonicTimestamp(dvs128Handle handle) { + if (handle->state.currentTimestamp < handle->state.lastTimestamp) { + caerLog(CAER_LOG_ALERT, handle->info.deviceString, + "Timestamps: non monotonic timestamp detected: lastTimestamp=%" PRIi32 ", currentTimestamp=%" PRIi32 ", difference=%" PRIi32 ".", + handle->state.lastTimestamp, handle->state.currentTimestamp, + (handle->state.lastTimestamp - handle->state.currentTimestamp)); + } +} + +static inline void freeAllDataMemory(dvs128State state) { + if (state->dataExchangeBuffer != NULL) { + ringBufferFree(state->dataExchangeBuffer); + state->dataExchangeBuffer = NULL; + } + + // Since the current event packets aren't necessarily + // already assigned to the current packet container, we + // free them separately from it. + if (state->currentPolarityPacket != NULL) { + free(&state->currentPolarityPacket->packetHeader); + state->currentPolarityPacket = NULL; + + if (state->currentPacketContainer != NULL) { + caerEventPacketContainerSetEventPacket(state->currentPacketContainer, POLARITY_EVENT, NULL); + } + } + + if (state->currentSpecialPacket != NULL) { + free(&state->currentSpecialPacket->packetHeader); + state->currentSpecialPacket = NULL; + + if (state->currentPacketContainer != NULL) { + caerEventPacketContainerSetEventPacket(state->currentPacketContainer, SPECIAL_EVENT, NULL); + } + } + + if (state->currentPacketContainer != NULL) { + caerEventPacketContainerFree(state->currentPacketContainer); + state->currentPacketContainer = NULL; + } +} + +caerDeviceHandle dvs128Open(uint16_t deviceID, uint8_t busNumberRestrict, uint8_t devAddressRestrict, + const char *serialNumberRestrict) { + caerLog(CAER_LOG_DEBUG, __func__, "Initializing %s.", DVS_DEVICE_NAME); + + dvs128Handle handle = calloc(1, sizeof(*handle)); + if (handle == NULL) { + // Failed to allocate memory for device handle! + caerLog(CAER_LOG_CRITICAL, __func__, "Failed to allocate memory for device handle."); + return (NULL); + } + + // Set main deviceType correctly right away. + handle->deviceType = CAER_DEVICE_DVS128; + + dvs128State state = &handle->state; + + // Initialize state variables to default values (if not zero, taken care of by calloc above). + atomic_store_explicit(&state->dataExchangeBufferSize, 64, memory_order_relaxed); + atomic_store_explicit(&state->dataExchangeBlocking, false, memory_order_relaxed); + atomic_store_explicit(&state->dataExchangeStartProducers, true, memory_order_relaxed); + atomic_store_explicit(&state->dataExchangeStopProducers, true, memory_order_relaxed); + atomic_store_explicit(&state->usbBufferNumber, 8, memory_order_relaxed); + atomic_store_explicit(&state->usbBufferSize, 4096, memory_order_relaxed); + + // Packet settings (size (in events) and time interval (in µs)). + atomic_store_explicit(&state->maxPacketContainerPacketSize, 4096, memory_order_relaxed); + atomic_store_explicit(&state->maxPacketContainerInterval, 10000, memory_order_relaxed); + + atomic_store_explicit(&state->dvsIsMaster, true, memory_order_relaxed); // Always master by default. + + atomic_thread_fence(memory_order_release); + + // Set device thread name. Maximum length of 15 chars due to Linux limitations. + snprintf(state->deviceThreadName, 15 + 1, "%s ID-%" PRIu16, DVS_DEVICE_NAME, deviceID); + state->deviceThreadName[15] = '\0'; + + // Search for device and open it. + // Initialize libusb using a separate context for each device. + // This is to correctly support one thread per device. + // libusb may create its own threads at this stage, so we temporarly set + // a different thread name. + char originalThreadName[15 + 1]; // +1 for terminating NUL character. + thrd_get_name(originalThreadName, 15); + originalThreadName[15] = '\0'; + + thrd_set_name(state->deviceThreadName); + int res = libusb_init(&state->deviceContext); + + thrd_set_name(originalThreadName); + + if (res != LIBUSB_SUCCESS) { + free(handle); + caerLog(CAER_LOG_CRITICAL, __func__, "Failed to initialize libusb context. Error: %d.", res); + return (NULL); + } + + // Try to open a DVS128 device on a specific USB port. + state->deviceHandle = dvs128DeviceOpen(state->deviceContext, DVS_DEVICE_VID, DVS_DEVICE_PID, DVS_DEVICE_DID_TYPE, + busNumberRestrict, devAddressRestrict, serialNumberRestrict, + DVS_REQUIRED_FIRMWARE_VERSION); + if (state->deviceHandle == NULL) { + libusb_exit(state->deviceContext); + free(handle); + + caerLog(CAER_LOG_CRITICAL, __func__, "Failed to open %s device.", DVS_DEVICE_NAME); + return (NULL); + } + + // At this point we can get some more precise data on the device and update + // the logging string to reflect that and be more informative. + uint8_t busNumber = libusb_get_bus_number(libusb_get_device(state->deviceHandle)); + uint8_t devAddress = libusb_get_device_address(libusb_get_device(state->deviceHandle)); + + char serialNumber[8 + 1] = { 0 }; + int getStringDescResult = libusb_get_string_descriptor_ascii(state->deviceHandle, 3, (unsigned char *) serialNumber, + 8 + 1); + + // Check serial number success and length. + if (getStringDescResult < 0 || getStringDescResult > 8) { + dvs128DeviceClose(state->deviceHandle); + libusb_exit(state->deviceContext); + free(handle); + + caerLog(CAER_LOG_CRITICAL, __func__, "Unable to get serial number for %s device.", DVS_DEVICE_NAME); + return (NULL); + } + + size_t fullLogStringLength = (size_t) snprintf(NULL, 0, "%s ID-%" PRIu16 " SN-%s [%" PRIu8 ":%" PRIu8 "]", + DVS_DEVICE_NAME, deviceID, serialNumber, busNumber, devAddress); + + char *fullLogString = malloc(fullLogStringLength + 1); + if (fullLogString == NULL) { + dvs128DeviceClose(state->deviceHandle); + libusb_exit(state->deviceContext); + free(handle); + + caerLog(CAER_LOG_CRITICAL, __func__, "Unable to allocate memory for %s device info string.", DVS_DEVICE_NAME); + return (NULL); + } + + snprintf(fullLogString, fullLogStringLength + 1, "%s ID-%" PRIu16 " SN-%s [%" PRIu8 ":%" PRIu8 "]", DVS_DEVICE_NAME, + deviceID, serialNumber, busNumber, devAddress); + + // Populate info variables based on data from device. + handle->info.deviceID = I16T(deviceID); + strncpy(handle->info.deviceSerialNumber, serialNumber, 8 + 1); + handle->info.deviceUSBBusNumber = busNumber; + handle->info.deviceUSBDeviceAddress = devAddress; + handle->info.deviceString = fullLogString; + handle->info.logicVersion = 1; // TODO: real logic revision, once that information is exposed by new logic. + handle->info.deviceIsMaster = true; // TODO: master/slave support. + handle->info.dvsSizeX = DVS_ARRAY_SIZE_X; + handle->info.dvsSizeY = DVS_ARRAY_SIZE_Y; + + caerLog(CAER_LOG_DEBUG, fullLogString, "Initialized device successfully with USB Bus=%" PRIu8 ":Addr=%" PRIu8 ".", + busNumber, devAddress); + + return ((caerDeviceHandle) handle); +} + +bool dvs128Close(caerDeviceHandle cdh) { + dvs128Handle handle = (dvs128Handle) cdh; + dvs128State state = &handle->state; + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "Shutting down ..."); + + // Finally, close the device fully. + dvs128DeviceClose(state->deviceHandle); + + // Destroy libusb context. + libusb_exit(state->deviceContext); + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "Shutdown successful."); + + // Free memory. + free(handle->info.deviceString); + free(handle); + + return (true); +} + +struct caer_dvs128_info caerDVS128InfoGet(caerDeviceHandle cdh) { + dvs128Handle handle = (dvs128Handle) cdh; + + // Check if the pointer is valid. + if (handle == NULL) { + struct caer_dvs128_info emptyInfo = { 0, .deviceString = NULL }; + return (emptyInfo); + } + + // Check if device type is supported. + if (handle->deviceType != CAER_DEVICE_DVS128) { + struct caer_dvs128_info emptyInfo = { 0, .deviceString = NULL }; + return (emptyInfo); + } + + // Return a copy of the device information. + return (handle->info); +} + +bool dvs128SendDefaultConfig(caerDeviceHandle cdh) { + dvs128Handle handle = (dvs128Handle) cdh; + dvs128State state = &handle->state; + + // Set all biases to default value. Based on DVS128 Fast biases. + caerIntegerToByteArray(1992, state->biases[DVS128_CONFIG_BIAS_CAS], BIAS_LENGTH); + caerIntegerToByteArray(1108364, state->biases[DVS128_CONFIG_BIAS_INJGND], BIAS_LENGTH); + caerIntegerToByteArray(16777215, state->biases[DVS128_CONFIG_BIAS_REQPD], BIAS_LENGTH); + caerIntegerToByteArray(8159221, state->biases[DVS128_CONFIG_BIAS_PUX], BIAS_LENGTH); + caerIntegerToByteArray(132, state->biases[DVS128_CONFIG_BIAS_DIFFOFF], BIAS_LENGTH); + caerIntegerToByteArray(309590, state->biases[DVS128_CONFIG_BIAS_REQ], BIAS_LENGTH); + caerIntegerToByteArray(969, state->biases[DVS128_CONFIG_BIAS_REFR], BIAS_LENGTH); + caerIntegerToByteArray(16777215, state->biases[DVS128_CONFIG_BIAS_PUY], BIAS_LENGTH); + caerIntegerToByteArray(209996, state->biases[DVS128_CONFIG_BIAS_DIFFON], BIAS_LENGTH); + caerIntegerToByteArray(13125, state->biases[DVS128_CONFIG_BIAS_DIFF], BIAS_LENGTH); + caerIntegerToByteArray(271, state->biases[DVS128_CONFIG_BIAS_FOLL], BIAS_LENGTH); + caerIntegerToByteArray(217, state->biases[DVS128_CONFIG_BIAS_PR], BIAS_LENGTH); + + // Send biases to device. + return (dvs128SendBiases(state)); +} + +bool dvs128ConfigSet(caerDeviceHandle cdh, int8_t modAddr, uint8_t paramAddr, uint32_t param) { + dvs128Handle handle = (dvs128Handle) cdh; + dvs128State state = &handle->state; + + switch (modAddr) { + case CAER_HOST_CONFIG_USB: + switch (paramAddr) { + case CAER_HOST_CONFIG_USB_BUFFER_NUMBER: + atomic_store(&state->usbBufferNumber, param); + + // Notify data acquisition thread to change buffers. + atomic_fetch_or(&state->dataAcquisitionThreadConfigUpdate, 1 << 0); + break; + + case CAER_HOST_CONFIG_USB_BUFFER_SIZE: + atomic_store(&state->usbBufferSize, param); + + // Notify data acquisition thread to change buffers. + atomic_fetch_or(&state->dataAcquisitionThreadConfigUpdate, 1 << 0); + break; + + default: + return (false); + break; + } + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE: + switch (paramAddr) { + case CAER_HOST_CONFIG_DATAEXCHANGE_BUFFER_SIZE: + atomic_store(&state->dataExchangeBufferSize, param); + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE_BLOCKING: + atomic_store(&state->dataExchangeBlocking, param); + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE_START_PRODUCERS: + atomic_store(&state->dataExchangeStartProducers, param); + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE_STOP_PRODUCERS: + atomic_store(&state->dataExchangeStopProducers, param); + break; + + default: + return (false); + break; + } + break; + + case CAER_HOST_CONFIG_PACKETS: + switch (paramAddr) { + case CAER_HOST_CONFIG_PACKETS_MAX_CONTAINER_PACKET_SIZE: + atomic_store(&state->maxPacketContainerPacketSize, param); + break; + + case CAER_HOST_CONFIG_PACKETS_MAX_CONTAINER_INTERVAL: + atomic_store(&state->maxPacketContainerInterval, param); + break; + + default: + return (false); + break; + } + break; + + case DVS128_CONFIG_DVS: + switch (paramAddr) { + case DVS128_CONFIG_DVS_RUN: + if (param && !atomic_load(&state->dvsRunning)) { + if (libusb_control_transfer(state->deviceHandle, + LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE, + VENDOR_REQUEST_START_TRANSFER, 0, 0, NULL, 0, 0) != 0) { + return (false); + } + + atomic_store(&state->dvsRunning, true); + } + else if (!param && atomic_load(&state->dvsRunning)) { + if (libusb_control_transfer(state->deviceHandle, + LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE, + VENDOR_REQUEST_STOP_TRANSFER, 0, 0, NULL, 0, 0) != 0) { + return (false); + } + + atomic_store(&state->dvsRunning, false); + } + break; + + case DVS128_CONFIG_DVS_TIMESTAMP_RESET: + if (param) { + if (libusb_control_transfer(state->deviceHandle, + LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE, + VENDOR_REQUEST_RESET_TS, 0, 0, NULL, 0, 0) != 0) { + return (false); + } + } + break; + + case DVS128_CONFIG_DVS_ARRAY_RESET: + if (param) { + if (libusb_control_transfer(state->deviceHandle, + LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE, + VENDOR_REQUEST_RESET_ARRAY, 0, 0, NULL, 0, 0) != 0) { + return (false); + } + } + break; + + case DVS128_CONFIG_DVS_TS_MASTER: + if (libusb_control_transfer(state->deviceHandle, + LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE, + VENDOR_REQUEST_TS_MASTER, (param & 0x01), 0, NULL, 0, 0) != 0) { + return (false); + } + atomic_store(&state->dvsIsMaster, (param & 0x01)); + + // Ensure info struct also gets this update. + atomic_thread_fence(memory_order_seq_cst); + handle->info.deviceIsMaster = atomic_load(&state->dvsIsMaster); + atomic_thread_fence(memory_order_seq_cst); + break; + + default: + return (false); + break; + } + break; + + case DVS128_CONFIG_BIAS: + switch (paramAddr) { + case DVS128_CONFIG_BIAS_CAS: + case DVS128_CONFIG_BIAS_INJGND: + case DVS128_CONFIG_BIAS_PUX: + case DVS128_CONFIG_BIAS_PUY: + case DVS128_CONFIG_BIAS_REQPD: + case DVS128_CONFIG_BIAS_REQ: + case DVS128_CONFIG_BIAS_FOLL: + case DVS128_CONFIG_BIAS_PR: + case DVS128_CONFIG_BIAS_REFR: + case DVS128_CONFIG_BIAS_DIFF: + case DVS128_CONFIG_BIAS_DIFFON: + case DVS128_CONFIG_BIAS_DIFFOFF: + caerIntegerToByteArray(param, state->biases[paramAddr], BIAS_LENGTH); + return (dvs128SendBiases(state)); + break; + + default: + return (false); + break; + } + break; + + default: + return (false); + break; + } + + return (true); +} + +bool dvs128ConfigGet(caerDeviceHandle cdh, int8_t modAddr, uint8_t paramAddr, uint32_t *param) { + dvs128Handle handle = (dvs128Handle) cdh; + dvs128State state = &handle->state; + + switch (modAddr) { + case CAER_HOST_CONFIG_USB: + switch (paramAddr) { + case CAER_HOST_CONFIG_USB_BUFFER_NUMBER: + *param = U32T(atomic_load(&state->usbBufferNumber)); + break; + + case CAER_HOST_CONFIG_USB_BUFFER_SIZE: + *param = U32T(atomic_load(&state->usbBufferSize)); + break; + + default: + return (false); + break; + } + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE: + switch (paramAddr) { + case CAER_HOST_CONFIG_DATAEXCHANGE_BUFFER_SIZE: + *param = U32T(atomic_load(&state->dataExchangeBufferSize)); + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE_BLOCKING: + *param = atomic_load(&state->dataExchangeBlocking); + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE_START_PRODUCERS: + *param = atomic_load(&state->dataExchangeStartProducers); + break; + + case CAER_HOST_CONFIG_DATAEXCHANGE_STOP_PRODUCERS: + *param = atomic_load(&state->dataExchangeStopProducers); + break; + + default: + return (false); + break; + } + break; + + case CAER_HOST_CONFIG_PACKETS: + switch (paramAddr) { + case CAER_HOST_CONFIG_PACKETS_MAX_CONTAINER_PACKET_SIZE: + *param = U32T(atomic_load(&state->maxPacketContainerPacketSize)); + break; + + case CAER_HOST_CONFIG_PACKETS_MAX_CONTAINER_INTERVAL: + *param = U32T(atomic_load(&state->maxPacketContainerInterval)); + break; + + default: + return (false); + break; + } + break; + + case DVS128_CONFIG_DVS: + switch (paramAddr) { + case DVS128_CONFIG_DVS_RUN: + *param = atomic_load(&state->dvsRunning); + break; + + case DVS128_CONFIG_DVS_TIMESTAMP_RESET: + case DVS128_CONFIG_DVS_ARRAY_RESET: + // Always false because it's an impulse, it resets itself automatically. + *param = false; + break; + + case DVS128_CONFIG_DVS_TS_MASTER: + *param = atomic_load(&state->dvsIsMaster); + break; + + default: + return (false); + break; + } + break; + + case DVS128_CONFIG_BIAS: + switch (paramAddr) { + case DVS128_CONFIG_BIAS_CAS: + case DVS128_CONFIG_BIAS_INJGND: + case DVS128_CONFIG_BIAS_PUX: + case DVS128_CONFIG_BIAS_PUY: + case DVS128_CONFIG_BIAS_REQPD: + case DVS128_CONFIG_BIAS_REQ: + case DVS128_CONFIG_BIAS_FOLL: + case DVS128_CONFIG_BIAS_PR: + case DVS128_CONFIG_BIAS_REFR: + case DVS128_CONFIG_BIAS_DIFF: + case DVS128_CONFIG_BIAS_DIFFON: + case DVS128_CONFIG_BIAS_DIFFOFF: + *param = caerByteArrayToInteger(state->biases[paramAddr], BIAS_LENGTH); + break; + + default: + return (false); + break; + } + break; + + default: + return (false); + break; + } + + return (true); +} + +bool dvs128DataStart(caerDeviceHandle cdh, void (*dataNotifyIncrease)(void *ptr), void (*dataNotifyDecrease)(void *ptr), + void *dataNotifyUserPtr, void (*dataShutdownNotify)(void *ptr), void *dataShutdownUserPtr) { + dvs128Handle handle = (dvs128Handle) cdh; + dvs128State state = &handle->state; + + // Store new data available/not available anymore call-backs. + state->dataNotifyIncrease = dataNotifyIncrease; + state->dataNotifyDecrease = dataNotifyDecrease; + state->dataNotifyUserPtr = dataNotifyUserPtr; + state->dataShutdownNotify = dataShutdownNotify; + state->dataShutdownUserPtr = dataShutdownUserPtr; + + // Set wanted time interval to uninitialized. Getting the first TS or TS_RESET + // will then set this correctly. + state->currentPacketContainerCommitTimestamp = -1; + + // Initialize RingBuffer. + state->dataExchangeBuffer = ringBufferInit(atomic_load(&state->dataExchangeBufferSize)); + if (state->dataExchangeBuffer == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to initialize data exchange buffer."); + return (false); + } + + // Allocate packets. + state->currentPacketContainer = caerEventPacketContainerAllocate(DVS_EVENT_TYPES); + if (state->currentPacketContainer == NULL) { + freeAllDataMemory(state); + + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate event packet container."); + return (false); + } + + state->currentPolarityPacket = caerPolarityEventPacketAllocate(DVS_POLARITY_DEFAULT_SIZE, + I16T(handle->info.deviceID), 0); + if (state->currentPolarityPacket == NULL) { + freeAllDataMemory(state); + + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate polarity event packet."); + return (false); + } + + state->currentSpecialPacket = caerSpecialEventPacketAllocate(DVS_SPECIAL_DEFAULT_SIZE, I16T(handle->info.deviceID), + 0); + if (state->currentSpecialPacket == NULL) { + freeAllDataMemory(state); + + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate special event packet."); + return (false); + } + + if ((errno = thrd_create(&state->dataAcquisitionThread, &dvs128DataAcquisitionThread, handle)) != thrd_success) { + freeAllDataMemory(state); + + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to start data acquisition thread. Error: %d.", + errno); + return (false); + } + + // Wait for the data acquisition thread to be ready. + while (!atomic_load_explicit(&state->dataAcquisitionThreadRun, memory_order_relaxed)) { + ; + } + + return (true); +} + +bool dvs128DataStop(caerDeviceHandle cdh) { + dvs128Handle handle = (dvs128Handle) cdh; + dvs128State state = &handle->state; + + // Stop data acquisition thread. + if (atomic_load(&state->dataExchangeStopProducers)) { + // Disable data transfer on USB end-point 6. + dvs128ConfigSet((caerDeviceHandle) handle, DVS128_CONFIG_DVS, DVS128_CONFIG_DVS_RUN, false); + } + + atomic_store(&state->dataAcquisitionThreadRun, false); + + // Wait for data acquisition thread to terminate... + if ((errno = thrd_join(state->dataAcquisitionThread, NULL)) != thrd_success) { + // This should never happen! + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to join data acquisition thread. Error: %d.", + errno); + return (false); + } + + // Empty ringbuffer. + caerEventPacketContainer container; + while ((container = ringBufferGet(state->dataExchangeBuffer)) != NULL) { + // Notify data-not-available call-back. + if (state->dataNotifyDecrease != NULL) { + state->dataNotifyDecrease(state->dataNotifyUserPtr); + } + + // Free container, which will free its subordinate packets too. + caerEventPacketContainerFree(container); + } + + // Free current, uncommitted packets and ringbuffer. + freeAllDataMemory(state); + + // Reset packet positions. + state->currentPolarityPacketPosition = 0; + state->currentSpecialPacketPosition = 0; + + return (true); +} + +// Remember to properly free the returned memory after usage! +caerEventPacketContainer dvs128DataGet(caerDeviceHandle cdh) { + dvs128Handle handle = (dvs128Handle) cdh; + dvs128State state = &handle->state; + caerEventPacketContainer container = NULL; + + retry: container = ringBufferGet(state->dataExchangeBuffer); + + if (container != NULL) { + // Found an event container, return it and signal this piece of data + // is no longer available for later acquisition. + if (state->dataNotifyDecrease != NULL) { + state->dataNotifyDecrease(state->dataNotifyUserPtr); + } + + return (container); + } + + // Didn't find any event container, either report this or retry, depending + // on blocking setting. + if (atomic_load_explicit(&state->dataExchangeBlocking, memory_order_relaxed)) { + // Don't retry right away in a tight loop, back off and wait a little. + // If no data is available, sleep for a millisecond to avoid wasting resources. + struct timespec noDataSleep = { .tv_sec = 0, .tv_nsec = 1000000 }; + if (thrd_sleep(&noDataSleep, NULL) == 0) { + goto retry; + } + } + + // Nothing. + return (NULL); +} + +static libusb_device_handle *dvs128DeviceOpen(libusb_context *devContext, uint16_t devVID, uint16_t devPID, + uint8_t devType, uint8_t busNumber, uint8_t devAddress, const char *serialNumber, uint16_t requiredFirmwareVersion) { + libusb_device_handle *devHandle = NULL; + libusb_device **devicesList; + + ssize_t result = libusb_get_device_list(devContext, &devicesList); + + if (result >= 0) { + // Cycle thorough all discovered devices and find a match. + for (size_t i = 0; i < (size_t) result; i++) { + struct libusb_device_descriptor devDesc; + + if (libusb_get_device_descriptor(devicesList[i], &devDesc) != LIBUSB_SUCCESS) { + continue; + } + + // Check if this is the device we want (VID/PID). + if (devDesc.idVendor == devVID && devDesc.idProduct == devPID + && U8T((devDesc.bcdDevice & 0xFF00) >> 8) == devType) { + // Verify device firmware version. + if (U8T(devDesc.bcdDevice & 0x00FF) < requiredFirmwareVersion) { + caerLog(CAER_LOG_CRITICAL, __func__, + "Device firmware version too old. You have version %" PRIu8 "; but at least version %" PRIu16 " is required. Please updated by following the Flashy upgrade documentation at 'http://inilabs.com/support/reflashing/'.", + U8T(devDesc.bcdDevice & 0x00FF), requiredFirmwareVersion); + + continue; + } + + // If a USB port restriction is given, honor it. + if (busNumber > 0 && libusb_get_bus_number(devicesList[i]) != busNumber) { + caerLog(CAER_LOG_INFO, __func__, + "USB bus number restriction is present (%" PRIu8 "), this device didn't match it (%" PRIu8 ").", + busNumber, libusb_get_bus_number(devicesList[i])); + + continue; + } + + if (devAddress > 0 && libusb_get_device_address(devicesList[i]) != devAddress) { + caerLog(CAER_LOG_INFO, __func__, + "USB device address restriction is present (%" PRIu8 "), this device didn't match it (%" PRIu8 ").", + devAddress, libusb_get_device_address(devicesList[i])); + + continue; + } + + if (libusb_open(devicesList[i], &devHandle) != LIBUSB_SUCCESS) { + devHandle = NULL; + + continue; + } + + // Check the serial number restriction, if any is present. + if (serialNumber != NULL && !caerStrEquals(serialNumber, "")) { + char deviceSerialNumber[8 + 1] = { 0 }; + int getStringDescResult = libusb_get_string_descriptor_ascii(devHandle, devDesc.iSerialNumber, + (unsigned char *) deviceSerialNumber, 8 + 1); + + // Check serial number success and length. + if (getStringDescResult < 0 || getStringDescResult > 8) { + libusb_close(devHandle); + devHandle = NULL; + + continue; + } + + // Now check if the Serial Number matches. + if (!caerStrEquals(serialNumber, deviceSerialNumber)) { + libusb_close(devHandle); + devHandle = NULL; + + caerLog(CAER_LOG_INFO, __func__, + "USB serial number restriction is present (%s), this device didn't match it (%s).", + serialNumber, deviceSerialNumber); + + continue; + } + } + + // Check that the active configuration is set to number 1. If not, do so. + int activeConfiguration; + if (libusb_get_configuration(devHandle, &activeConfiguration) != LIBUSB_SUCCESS) { + libusb_close(devHandle); + devHandle = NULL; + + continue; + } + + if (activeConfiguration != 1) { + if (libusb_set_configuration(devHandle, 1) != LIBUSB_SUCCESS) { + libusb_close(devHandle); + devHandle = NULL; + + continue; + } + } + + // Claim interface 0 (default). + if (libusb_claim_interface(devHandle, 0) != LIBUSB_SUCCESS) { + libusb_close(devHandle); + devHandle = NULL; + + continue; + } + + // TODO: check logic revision, once that information is exposed by new logic. + + // Found and configured it! + break; + } + } + + libusb_free_device_list(devicesList, true); + } + + return (devHandle); +} + +static void dvs128DeviceClose(libusb_device_handle *devHandle) { + // Release interface 0 (default). + libusb_release_interface(devHandle, 0); + + libusb_close(devHandle); +} + +static void dvs128AllocateTransfers(dvs128Handle handle, uint32_t bufferNum, uint32_t bufferSize) { + dvs128State state = &handle->state; + + // Set number of transfers and allocate memory for the main transfer array. + state->dataTransfers = calloc(bufferNum, sizeof(struct libusb_transfer *)); + if (state->dataTransfers == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, + "Failed to allocate memory for %" PRIu32 " libusb transfers. Error: %d.", bufferNum, errno); + return; + } + state->dataTransfersLength = bufferNum; + + // Allocate transfers and set them up. + for (size_t i = 0; i < bufferNum; i++) { + state->dataTransfers[i] = libusb_alloc_transfer(0); + if (state->dataTransfers[i] == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, + "Unable to allocate further libusb transfers (%zu of %" PRIu32 ").", i, bufferNum); + continue; + } + + // Create data buffer. + state->dataTransfers[i]->length = (int) bufferSize; + state->dataTransfers[i]->buffer = malloc(bufferSize); + if (state->dataTransfers[i]->buffer == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, + "Unable to allocate buffer for libusb transfer %zu. Error: %d.", i, errno); + + libusb_free_transfer(state->dataTransfers[i]); + state->dataTransfers[i] = NULL; + + continue; + } + + // Initialize Transfer. + state->dataTransfers[i]->dev_handle = state->deviceHandle; + state->dataTransfers[i]->endpoint = DVS_DATA_ENDPOINT; + state->dataTransfers[i]->type = LIBUSB_TRANSFER_TYPE_BULK; + state->dataTransfers[i]->callback = &dvs128LibUsbCallback; + state->dataTransfers[i]->user_data = handle; + state->dataTransfers[i]->timeout = 0; + state->dataTransfers[i]->flags = LIBUSB_TRANSFER_FREE_BUFFER; + + if ((errno = libusb_submit_transfer(state->dataTransfers[i])) == LIBUSB_SUCCESS) { + state->activeDataTransfers++; + } + else { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, + "Unable to submit libusb transfer %zu. Error: %s (%d).", i, libusb_strerror(errno), errno); + + // The transfer buffer is freed automatically here thanks to + // the LIBUSB_TRANSFER_FREE_BUFFER flag set above. + libusb_free_transfer(state->dataTransfers[i]); + state->dataTransfers[i] = NULL; + + continue; + } + } + + if (state->activeDataTransfers == 0) { + // Didn't manage to allocate any USB transfers, free array memory and log failure. + free(state->dataTransfers); + state->dataTransfers = NULL; + state->dataTransfersLength = 0; + + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Unable to allocate any libusb transfers."); + } +} + +static void dvs128DeallocateTransfers(dvs128Handle handle) { + dvs128State state = &handle->state; + + // Cancel all current transfers first. + for (size_t i = 0; i < state->dataTransfersLength; i++) { + if (state->dataTransfers[i] != NULL) { + errno = libusb_cancel_transfer(state->dataTransfers[i]); + if (errno != LIBUSB_SUCCESS && errno != LIBUSB_ERROR_NOT_FOUND) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, + "Unable to cancel libusb transfer %zu. Error: %s (%d).", i, libusb_strerror(errno), errno); + // Proceed with trying to cancel all transfers regardless of errors. + } + } + } + + // Wait for all transfers to go away (0.1 seconds timeout). + struct timeval te = { .tv_sec = 0, .tv_usec = 100000 }; + + while (state->activeDataTransfers > 0) { + libusb_handle_events_timeout(state->deviceContext, &te); + } + + // The buffers and transfers have been deallocated in the callback. + // Only the transfers array remains, which we free here. + free(state->dataTransfers); + state->dataTransfers = NULL; + state->dataTransfersLength = 0; +} + +static void LIBUSB_CALL dvs128LibUsbCallback(struct libusb_transfer *transfer) { + dvs128Handle handle = transfer->user_data; + dvs128State state = &handle->state; + + if (transfer->status == LIBUSB_TRANSFER_COMPLETED) { + // Handle data. + dvs128EventTranslator(handle, transfer->buffer, (size_t) transfer->actual_length); + } + + if (transfer->status != LIBUSB_TRANSFER_CANCELLED && transfer->status != LIBUSB_TRANSFER_NO_DEVICE) { + // Submit transfer again. + if (libusb_submit_transfer(transfer) == LIBUSB_SUCCESS) { + return; + } + } + + // Cannot recover (cancelled, no device, or other critical error). + // Signal this by adjusting the counter, free and exit. + state->activeDataTransfers--; + for (size_t i = 0; i < state->dataTransfersLength; i++) { + // Remove from list, so we don't try to cancel it later on. + if (state->dataTransfers[i] == transfer) { + state->dataTransfers[i] = NULL; + } + } + libusb_free_transfer(transfer); +} + +#define DVS128_TIMESTAMP_WRAP_MASK 0x80 +#define DVS128_TIMESTAMP_RESET_MASK 0x40 +#define DVS128_POLARITY_SHIFT 0 +#define DVS128_POLARITY_MASK 0x0001 +#define DVS128_Y_ADDR_SHIFT 8 +#define DVS128_Y_ADDR_MASK 0x007F +#define DVS128_X_ADDR_SHIFT 1 +#define DVS128_X_ADDR_MASK 0x007F +#define DVS128_SYNC_EVENT_MASK 0x8000 +#define TS_WRAP_ADD 0x4000 + +static inline int64_t generateFullTimestamp(int32_t tsOverflow, int32_t timestamp) { + return (I64T((U64T(tsOverflow) << TS_OVERFLOW_SHIFT) | U64T(timestamp))); +} + +static inline void initContainerCommitTimestamp(dvs128State state) { + if (state->currentPacketContainerCommitTimestamp == -1) { + state->currentPacketContainerCommitTimestamp = state->currentTimestamp + + atomic_load_explicit(&state->maxPacketContainerInterval, memory_order_relaxed) - 1; + } +} + +static void dvs128EventTranslator(dvs128Handle handle, uint8_t *buffer, size_t bytesSent) { + dvs128State state = &handle->state; + + // Return right away if not running anymore. This prevents useless work if many + // buffers are still waiting when shut down, as well as incorrect event sequences + // if a TS_RESET is stuck on ring-buffer commit further down, and detects shut-down; + // then any subsequent buffers should also detect shut-down and not be handled. + if (!atomic_load_explicit(&state->dataAcquisitionThreadRun, memory_order_relaxed)) { + return; + } + + // Truncate off any extra partial event. + if ((bytesSent & 0x03) != 0) { + caerLog(CAER_LOG_ALERT, handle->info.deviceString, + "%zu bytes received via USB, which is not a multiple of four.", bytesSent); + bytesSent &= (size_t) ~0x03; + } + + for (size_t i = 0; i < bytesSent; i += 4) { + // Allocate new packets for next iteration as needed. + if (state->currentPacketContainer == NULL) { + state->currentPacketContainer = caerEventPacketContainerAllocate(DVS_EVENT_TYPES); + if (state->currentPacketContainer == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate event packet container."); + return; + } + } + + if (state->currentPolarityPacket == NULL) { + state->currentPolarityPacket = caerPolarityEventPacketAllocate(DVS_POLARITY_DEFAULT_SIZE, + I16T(handle->info.deviceID), state->wrapOverflow); + if (state->currentPolarityPacket == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate polarity event packet."); + return; + } + } + else if (state->currentPolarityPacketPosition + >= caerEventPacketHeaderGetEventCapacity((caerEventPacketHeader) state->currentPolarityPacket)) { + // If not committed, let's check if any of the packets has reached its maximum + // capacity limit. If yes, we grow them to accomodate new events. + caerPolarityEventPacket grownPacket = (caerPolarityEventPacket) caerGenericEventPacketGrow( + (caerEventPacketHeader) state->currentPolarityPacket, state->currentPolarityPacketPosition * 2); + if (grownPacket == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to grow polarity event packet."); + return; + } + + state->currentPolarityPacket = grownPacket; + } + + if (state->currentSpecialPacket == NULL) { + state->currentSpecialPacket = caerSpecialEventPacketAllocate(DVS_SPECIAL_DEFAULT_SIZE, + I16T(handle->info.deviceID), state->wrapOverflow); + if (state->currentSpecialPacket == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to allocate special event packet."); + return; + } + } + else if (state->currentSpecialPacketPosition + >= caerEventPacketHeaderGetEventCapacity((caerEventPacketHeader) state->currentSpecialPacket)) { + // If not committed, let's check if any of the packets has reached its maximum + // capacity limit. If yes, we grow them to accomodate new events. + caerSpecialEventPacket grownPacket = (caerSpecialEventPacket) caerGenericEventPacketGrow( + (caerEventPacketHeader) state->currentSpecialPacket, state->currentSpecialPacketPosition * 2); + if (grownPacket == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, "Failed to grow special event packet."); + return; + } + + state->currentSpecialPacket = grownPacket; + } + + bool tsReset = false; + bool tsBigWrap = false; + + if ((buffer[i + 3] & DVS128_TIMESTAMP_WRAP_MASK) == DVS128_TIMESTAMP_WRAP_MASK) { + // Detect big timestamp wrap-around. + if (state->wrapAdd == (INT32_MAX - (TS_WRAP_ADD - 1))) { + // Reset wrapAdd to zero at this point, so we can again + // start detecting overruns of the 32bit value. + state->wrapAdd = 0; + + state->lastTimestamp = 0; + state->currentTimestamp = 0; + + // Increment TSOverflow counter. + state->wrapOverflow++; + + caerSpecialEvent currentEvent = caerSpecialEventPacketGetEvent(state->currentSpecialPacket, + state->currentSpecialPacketPosition++); + caerSpecialEventSetTimestamp(currentEvent, INT32_MAX); + caerSpecialEventSetType(currentEvent, TIMESTAMP_WRAP); + caerSpecialEventValidate(currentEvent, state->currentSpecialPacket); + + // Commit packets to separate before wrap from after cleanly. + tsBigWrap = true; + } + else { + // timestamp bit 15 is one -> wrap: now we need to increment + // the wrapAdd, uses only 14 bit timestamps. Each wrap is 2^14 µs (~16ms). + state->wrapAdd += TS_WRAP_ADD; + + state->lastTimestamp = state->currentTimestamp; + state->currentTimestamp = state->wrapAdd; + initContainerCommitTimestamp(state); + + // Check monotonicity of timestamps. + checkMonotonicTimestamp(handle); + } + } + else if ((buffer[i + 3] & DVS128_TIMESTAMP_RESET_MASK) == DVS128_TIMESTAMP_RESET_MASK) { + // timestamp bit 14 is one -> wrapAdd reset: this firmware + // version uses reset events to reset timestamps + state->wrapOverflow = 0; + state->wrapAdd = 0; + state->lastTimestamp = 0; + state->currentTimestamp = 0; + state->currentPacketContainerCommitTimestamp = -1; + initContainerCommitTimestamp(state); + + // Defer timestamp reset event to later, so we commit it + // alone, in its own packet. + // Commit packets when doing a reset to clearly separate them. + tsReset = true; + } + else { + // address is LSB MSB (USB is LE) + uint16_t addressUSB = le16toh(*((uint16_t * ) (&buffer[i]))); + + // same for timestamp, LSB MSB (USB is LE) + // 15 bit value of timestamp in 1 us tick + uint16_t timestampUSB = le16toh(*((uint16_t * ) (&buffer[i + 2]))); + + // Expand to 32 bits. (Tick is 1µs already.) + state->lastTimestamp = state->currentTimestamp; + state->currentTimestamp = state->wrapAdd + timestampUSB; + initContainerCommitTimestamp(state); + + // Check monotonicity of timestamps. + checkMonotonicTimestamp(handle); + + if ((addressUSB & DVS128_SYNC_EVENT_MASK) != 0) { + // Special Trigger Event (MSB is set) + caerSpecialEvent currentEvent = caerSpecialEventPacketGetEvent(state->currentSpecialPacket, + state->currentSpecialPacketPosition++); + caerSpecialEventSetTimestamp(currentEvent, state->currentTimestamp); + caerSpecialEventSetType(currentEvent, EXTERNAL_INPUT_RISING_EDGE); + caerSpecialEventValidate(currentEvent, state->currentSpecialPacket); + } + else { + // Invert X values (flip along X axis). To correct for flipped camera. + uint16_t x = U16T( + (DVS_ARRAY_SIZE_X - 1) - U16T((addressUSB >> DVS128_X_ADDR_SHIFT) & DVS128_X_ADDR_MASK)); + // Invert Y values (flip along Y axis). To convert to CG format. + uint16_t y = U16T( + (DVS_ARRAY_SIZE_Y - 1) - U16T((addressUSB >> DVS128_Y_ADDR_SHIFT) & DVS128_Y_ADDR_MASK)); + // Invert polarity bit. Hardware is like this. + bool polarity = (((addressUSB >> DVS128_POLARITY_SHIFT) & DVS128_POLARITY_MASK) == 0) ? (1) : (0); + + // Check range conformity. + if (x >= DVS_ARRAY_SIZE_X) { + caerLog(CAER_LOG_ALERT, handle->info.deviceString, "X address out of range (0-%d): %" PRIu16 ".", + DVS_ARRAY_SIZE_X - 1, x); + continue; // Skip invalid event. + } + if (y >= DVS_ARRAY_SIZE_Y) { + caerLog(CAER_LOG_ALERT, handle->info.deviceString, "Y address out of range (0-%d): %" PRIu16 ".", + DVS_ARRAY_SIZE_Y - 1, y); + continue; // Skip invalid event. + } + + caerPolarityEvent currentEvent = caerPolarityEventPacketGetEvent(state->currentPolarityPacket, + state->currentPolarityPacketPosition++); + caerPolarityEventSetTimestamp(currentEvent, state->currentTimestamp); + caerPolarityEventSetPolarity(currentEvent, polarity); + caerPolarityEventSetY(currentEvent, y); + caerPolarityEventSetX(currentEvent, x); + caerPolarityEventValidate(currentEvent, state->currentPolarityPacket); + } + } + + // Thresholds on which to trigger packet container commit. + // forceCommit is already defined above. + // Trigger if any of the global container-wide thresholds are met. + int32_t currentPacketContainerCommitSize = I32T( + atomic_load_explicit(&state->maxPacketContainerPacketSize, memory_order_relaxed)); + bool containerSizeCommit = (currentPacketContainerCommitSize > 0) + && ((state->currentPolarityPacketPosition >= currentPacketContainerCommitSize) + || (state->currentSpecialPacketPosition >= currentPacketContainerCommitSize)); + + bool containerTimeCommit = generateFullTimestamp(state->wrapOverflow, state->currentTimestamp) + > state->currentPacketContainerCommitTimestamp; + + // FIXME: with the current DVS128 architecture, currentTimestamp always comes together + // with an event, so the very first event that matches this threshold will be + // also part of the committed packet container. This doesn't break any of the invariants. + + // Commit packet containers to the ring-buffer, so they can be processed by the + // main-loop, when any of the required conditions are met. + if (tsReset || tsBigWrap || containerSizeCommit || containerTimeCommit) { + // One or more of the commit triggers are hit. Set the packet container up to contain + // any non-empty packets. Empty packets are not forwarded to save memory. + bool emptyContainerCommit = true; + + if (state->currentPolarityPacketPosition > 0) { + caerEventPacketContainerSetEventPacket(state->currentPacketContainer, POLARITY_EVENT, + (caerEventPacketHeader) state->currentPolarityPacket); + + state->currentPolarityPacket = NULL; + state->currentPolarityPacketPosition = 0; + emptyContainerCommit = false; + } + + if (state->currentSpecialPacketPosition > 0) { + caerEventPacketContainerSetEventPacket(state->currentPacketContainer, SPECIAL_EVENT, + (caerEventPacketHeader) state->currentSpecialPacket); + + state->currentSpecialPacket = NULL; + state->currentSpecialPacketPosition = 0; + emptyContainerCommit = false; + } + + // If the commit was triggered by a packet container limit being reached, we always + // update the time related limit. The size related one is updated implicitly by size + // being reset to zero after commit (new packets are empty). + if (containerTimeCommit) { + while (generateFullTimestamp(state->wrapOverflow, state->currentTimestamp) + > state->currentPacketContainerCommitTimestamp) { + state->currentPacketContainerCommitTimestamp += atomic_load_explicit( + &state->maxPacketContainerInterval, memory_order_relaxed); + } + } + + // Filter out completely empty commits. This can happen when data is turned off, + // but the timestamps are still going forward. + if (emptyContainerCommit) { + caerEventPacketContainerFree(state->currentPacketContainer); + state->currentPacketContainer = NULL; + } + else { + if (!ringBufferPut(state->dataExchangeBuffer, state->currentPacketContainer)) { + // Failed to forward packet container, just drop it, it doesn't contain + // any critical information anyway. + caerLog(CAER_LOG_INFO, handle->info.deviceString, + "Dropped EventPacket Container because ring-buffer full!"); + + caerEventPacketContainerFree(state->currentPacketContainer); + state->currentPacketContainer = NULL; + } + else { + if (state->dataNotifyIncrease != NULL) { + state->dataNotifyIncrease(state->dataNotifyUserPtr); + } + + state->currentPacketContainer = NULL; + } + } + + // The only critical timestamp information to forward is the timestamp reset event. + // The timestamp big-wrap can also (and should!) be detected by observing a packet's + // tsOverflow value, not the special packet TIMESTAMP_WRAP event, which is only informative. + // For the timestamp reset event (TIMESTAMP_RESET), we thus ensure that it is always + // committed, and we send it alone, in its own packet container, to ensure it will always + // be ordered after any other event packets in any processing or output stream. + if (tsReset) { + // Allocate packet container just for this event. + caerEventPacketContainer tsResetContainer = caerEventPacketContainerAllocate(DVS_EVENT_TYPES); + if (tsResetContainer == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, + "Failed to allocate tsReset event packet container."); + return; + } + + // Allocate special packet just for this event. + caerSpecialEventPacket tsResetPacket = caerSpecialEventPacketAllocate(1, I16T(handle->info.deviceID), + state->wrapOverflow); + if (tsResetPacket == NULL) { + caerLog(CAER_LOG_CRITICAL, handle->info.deviceString, + "Failed to allocate tsReset special event packet."); + return; + } + + // Create timestamp reset event. + caerSpecialEvent tsResetEvent = caerSpecialEventPacketGetEvent(tsResetPacket, 0); + caerSpecialEventSetTimestamp(tsResetEvent, INT32_MAX); + caerSpecialEventSetType(tsResetEvent, TIMESTAMP_RESET); + caerSpecialEventValidate(tsResetEvent, tsResetPacket); + + // Assign special packet to packet container. + caerEventPacketContainerSetEventPacket(tsResetContainer, SPECIAL_EVENT, + (caerEventPacketHeader) tsResetPacket); + + // Reset MUST be committed, always, else downstream data processing and + // outputs get confused if they have no notification of timestamps + // jumping back go zero. + while (!ringBufferPut(state->dataExchangeBuffer, tsResetContainer)) { + // Prevent dead-lock if shutdown is requested and nothing is consuming + // data anymore, but the ring-buffer is full (and would thus never empty), + // thus blocking the USB handling thread in this loop. + if (!atomic_load_explicit(&state->dataAcquisitionThreadRun, memory_order_relaxed)) { + return; + } + } + + // Signal new container as usual. + if (state->dataNotifyIncrease != NULL) { + state->dataNotifyIncrease(state->dataNotifyUserPtr); + } + } + } + } +} + +static bool dvs128SendBiases(dvs128State state) { + // Biases are already stored in an array with the same format as expected by + // the device, we can thus send it directly. + return (libusb_control_transfer(state->deviceHandle, + LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE, + VENDOR_REQUEST_SEND_BIASES, 0, 0, (uint8_t *) state->biases, (BIAS_NUMBER * BIAS_LENGTH), 0) + == (BIAS_NUMBER * BIAS_LENGTH)); +} + +static int dvs128DataAcquisitionThread(void *inPtr) { + // inPtr is a pointer to device handle. + dvs128Handle handle = inPtr; + dvs128State state = &handle->state; + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "Initializing data acquisition thread ..."); + + // Set thread name. + thrd_set_name(state->deviceThreadName); + + // Reset configuration update, so as to not re-do work afterwards. + atomic_store(&state->dataAcquisitionThreadConfigUpdate, 0); + + if (atomic_load(&state->dataExchangeStartProducers)) { + // Enable data transfer on USB end-point 6. + dvs128ConfigSet((caerDeviceHandle) handle, DVS128_CONFIG_DVS, DVS128_CONFIG_DVS_RUN, true); + } + + // Create buffers as specified in config file. + dvs128AllocateTransfers(handle, U32T(atomic_load(&state->usbBufferNumber)), + U32T(atomic_load(&state->usbBufferSize))); + + // Signal data thread ready back to start function. + atomic_store(&state->dataAcquisitionThreadRun, true); + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "data acquisition thread ready to process events."); + + // Handle USB events (1 second timeout). + struct timeval te = { .tv_sec = 1, .tv_usec = 0 }; + + while (atomic_load_explicit(&state->dataAcquisitionThreadRun, memory_order_relaxed) + && state->activeDataTransfers > 0) { + // Check config refresh, in this case to adjust buffer sizes. + if (atomic_load_explicit(&state->dataAcquisitionThreadConfigUpdate, memory_order_relaxed) != 0) { + dvs128DataAcquisitionThreadConfig(handle); + } + + libusb_handle_events_timeout(state->deviceContext, &te); + } + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "shutting down data acquisition thread ..."); + + // Cancel all transfers and handle them. + dvs128DeallocateTransfers(handle); + + // Ensure shutdown is stored and notified, could be because of all data transfers going away! + atomic_store(&state->dataAcquisitionThreadRun, false); + + if (state->dataShutdownNotify != NULL) { + state->dataShutdownNotify(state->dataShutdownUserPtr); + } + + caerLog(CAER_LOG_DEBUG, handle->info.deviceString, "data acquisition thread shut down."); + + return (EXIT_SUCCESS); +} + +static void dvs128DataAcquisitionThreadConfig(dvs128Handle handle) { + dvs128State state = &handle->state; + + // Get the current value to examine by atomic exchange, since we don't + // want there to be any possible store between a load/store pair. + uint32_t configUpdate = U32T(atomic_exchange(&state->dataAcquisitionThreadConfigUpdate, 0)); + + if ((configUpdate >> 0) & 0x01) { + // Do buffer size change: cancel all and recreate them. + dvs128DeallocateTransfers(handle); + dvs128AllocateTransfers(handle, U32T(atomic_load(&state->usbBufferNumber)), + U32T(atomic_load(&state->usbBufferSize))); + } +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/dvs128.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/dvs128.h new file mode 100755 index 0000000..ef64592 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/dvs128.h @@ -0,0 +1,119 @@ +#ifndef LIBCAER_SRC_DVS128_H_ +#define LIBCAER_SRC_DVS128_H_ + +#include "devices/dvs128.h" +#include "ringbuffer/ringbuffer.h" +#include <stdatomic.h> +#include <libusb.h> + +#ifdef HAVE_PTHREADS + #include "c11threads_posix.h" +#endif + +#define DVS_DEVICE_NAME "DVS128" + +#define DVS_DEVICE_VID 0x152A +#define DVS_DEVICE_PID 0x8400 +#define DVS_DEVICE_DID_TYPE 0x00 + +// #define DVS_REQUIRED_LOGIC_REVISION 1 +#define DVS_REQUIRED_FIRMWARE_VERSION 14 + +#define DVS_ARRAY_SIZE_X 128 +#define DVS_ARRAY_SIZE_Y 128 + +#define DVS_EVENT_TYPES 2 + +#define DVS_POLARITY_DEFAULT_SIZE 4096 +#define DVS_SPECIAL_DEFAULT_SIZE 128 + +#define DVS_DATA_ENDPOINT 0x86 + +#define VENDOR_REQUEST_START_TRANSFER 0xB3 +#define VENDOR_REQUEST_STOP_TRANSFER 0xB4 +#define VENDOR_REQUEST_SEND_BIASES 0xB8 +#define VENDOR_REQUEST_RESET_TS 0xBB +#define VENDOR_REQUEST_RESET_ARRAY 0xBD +#define VENDOR_REQUEST_TS_MASTER 0xBE + +#define BIAS_NUMBER 12 +#define BIAS_LENGTH 3 + +struct dvs128_state { + // Data Acquisition Thread -> Mainloop Exchange + RingBuffer dataExchangeBuffer; + atomic_uint_fast32_t dataExchangeBufferSize; // Only takes effect on DataStart() calls! + atomic_bool dataExchangeBlocking; + atomic_bool dataExchangeStartProducers; + atomic_bool dataExchangeStopProducers; + void (*dataNotifyIncrease)(void *ptr); + void (*dataNotifyDecrease)(void *ptr); + void *dataNotifyUserPtr; + void (*dataShutdownNotify)(void *ptr); + void *dataShutdownUserPtr; + // USB Device State + char deviceThreadName[15 + 1]; // +1 for terminating NUL character. + libusb_context *deviceContext; + libusb_device_handle *deviceHandle; + // USB Transfer Settings + atomic_uint_fast32_t usbBufferNumber; + atomic_uint_fast32_t usbBufferSize; + // Data Acquisition Thread + thrd_t dataAcquisitionThread; + atomic_bool dataAcquisitionThreadRun; + atomic_uint_fast32_t dataAcquisitionThreadConfigUpdate; + struct libusb_transfer **dataTransfers; + size_t dataTransfersLength; + size_t activeDataTransfers; + // Timestamp fields + int32_t wrapOverflow; + int32_t wrapAdd; + int32_t lastTimestamp; + int32_t currentTimestamp; + // Packet Container state + caerEventPacketContainer currentPacketContainer; + atomic_int_fast32_t maxPacketContainerPacketSize; + atomic_int_fast32_t maxPacketContainerInterval; + int64_t currentPacketContainerCommitTimestamp; + // Polarity Packet State + caerPolarityEventPacket currentPolarityPacket; + int32_t currentPolarityPacketPosition; + // Special Packet State + caerSpecialEventPacket currentSpecialPacket; + int32_t currentSpecialPacketPosition; + // Camera bias and settings memory (for getter operations) + // TODO: replace with real device calls once DVS128 logic rewritten. + uint8_t biases[BIAS_NUMBER][BIAS_LENGTH]; + atomic_bool dvsRunning; + atomic_bool dvsIsMaster; +}; + +typedef struct dvs128_state *dvs128State; + +struct dvs128_handle { + uint16_t deviceType; + // Information fields + struct caer_dvs128_info info; + // State for data management. + struct dvs128_state state; +}; + +typedef struct dvs128_handle *dvs128Handle; + +caerDeviceHandle dvs128Open(uint16_t deviceID, uint8_t busNumberRestrict, uint8_t devAddressRestrict, + const char *serialNumberRestrict); +bool dvs128Close(caerDeviceHandle handle); + +bool dvs128SendDefaultConfig(caerDeviceHandle handle); +// Negative addresses are used for host-side configuration. +// Positive addresses (including zero) are used for device-side configuration. +bool dvs128ConfigSet(caerDeviceHandle handle, int8_t modAddr, uint8_t paramAddr, uint32_t param); +bool dvs128ConfigGet(caerDeviceHandle handle, int8_t modAddr, uint8_t paramAddr, uint32_t *param); + +bool dvs128DataStart(caerDeviceHandle handle, void (*dataNotifyIncrease)(void *ptr), + void (*dataNotifyDecrease)(void *ptr), void *dataNotifyUserPtr, void (*dataShutdownNotify)(void *ptr), + void *dataShutdownUserPtr); +bool dvs128DataStop(caerDeviceHandle handle); +caerEventPacketContainer dvs128DataGet(caerDeviceHandle handle); + +#endif /* LIBCAER_SRC_DVS128_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/events.c b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/events.c new file mode 100755 index 0000000..d55dfdb --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/events.c @@ -0,0 +1,406 @@ +#include "events/packetContainer.h" +#include "events/special.h" +#include "events/polarity.h" +#include "events/frame.h" +#include "events/imu6.h" +#include "events/imu9.h" +#include "events/sample.h" +#include "events/ear.h" +#include "events/config.h" +#include "events/point1d.h" +#include "events/point2d.h" +#include "events/point3d.h" +#include "events/point4d.h" + +caerEventPacketContainer caerEventPacketContainerAllocate(int32_t eventPacketsNumber) { + if (eventPacketsNumber == 0) { + return (NULL); + } + + size_t eventPacketContainerSize = sizeof(struct caer_event_packet_container) + + ((size_t) eventPacketsNumber * sizeof(caerEventPacketHeader)); + + caerEventPacketContainer packetContainer = calloc(1, eventPacketContainerSize); + if (packetContainer == NULL) { + caerLog(CAER_LOG_CRITICAL, "EventPacket Container", + "Failed to allocate %zu bytes of memory for Event Packet Container, containing %" + PRIi32 " packets. Error: %d.", eventPacketContainerSize, eventPacketsNumber, errno); + return (NULL); + } + + // Fill in header fields. Don't care about endianness here, purely internal + // memory construct, never meant for inter-system exchange. + packetContainer->eventPacketsNumber = eventPacketsNumber; + packetContainer->lowestEventTimestamp = -1; + packetContainer->highestEventTimestamp = -1; + + return (packetContainer); +} + +void caerEventPacketContainerFree(caerEventPacketContainer container) { + if (container == NULL) { + return; + } + + // Free packet container and ensure all subordinate memory is also freed. + for (int32_t i = 0; i < caerEventPacketContainerGetEventPacketsNumber(container); i++) { + caerEventPacketHeader packetHeader = caerEventPacketContainerGetEventPacket(container, i); + + if (packetHeader != NULL) { + free(packetHeader); + } + } + + free(container); +} + +caerSpecialEventPacket caerSpecialEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow) { + if (eventCapacity == 0) { + return (NULL); + } + + size_t eventSize = sizeof(struct caer_special_event); + size_t eventPacketSize = sizeof(struct caer_special_event_packet) + ((size_t) eventCapacity * eventSize); + + // Zero out event memory (all events invalid). + caerSpecialEventPacket packet = calloc(1, eventPacketSize); + if (packet == NULL) { + caerLog(CAER_LOG_CRITICAL, "Special Event", + "Failed to allocate %zu bytes of memory for Special Event Packet of capacity %" + PRIi32 " from source %" PRIi16 ". Error: %d.", eventPacketSize, eventCapacity, eventSource, + errno); + return (NULL); + } + + // Fill in header fields. + caerEventPacketHeaderSetEventType(&packet->packetHeader, SPECIAL_EVENT); + caerEventPacketHeaderSetEventSource(&packet->packetHeader, eventSource); + caerEventPacketHeaderSetEventSize(&packet->packetHeader, I32T(eventSize)); + caerEventPacketHeaderSetEventTSOffset(&packet->packetHeader, offsetof(struct caer_special_event, timestamp)); + caerEventPacketHeaderSetEventTSOverflow(&packet->packetHeader, tsOverflow); + caerEventPacketHeaderSetEventCapacity(&packet->packetHeader, eventCapacity); + + return (packet); +} + +caerPolarityEventPacket caerPolarityEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow) { + if (eventCapacity == 0) { + return (NULL); + } + + size_t eventSize = sizeof(struct caer_polarity_event); + size_t eventPacketSize = sizeof(struct caer_polarity_event_packet) + ((size_t) eventCapacity * eventSize); + + // Zero out event memory (all events invalid). + caerPolarityEventPacket packet = calloc(1, eventPacketSize); + if (packet == NULL) { + caerLog(CAER_LOG_CRITICAL, "Polarity Event", + "Failed to allocate %zu bytes of memory for Polarity Event Packet of capacity %" + PRIi32 " from source %" PRIi16 ". Error: %d.", eventPacketSize, eventCapacity, eventSource, + errno); + return (NULL); + } + + // Fill in header fields. + caerEventPacketHeaderSetEventType(&packet->packetHeader, POLARITY_EVENT); + caerEventPacketHeaderSetEventSource(&packet->packetHeader, eventSource); + caerEventPacketHeaderSetEventSize(&packet->packetHeader, I32T(eventSize)); + caerEventPacketHeaderSetEventTSOffset(&packet->packetHeader, offsetof(struct caer_polarity_event, timestamp)); + caerEventPacketHeaderSetEventTSOverflow(&packet->packetHeader, tsOverflow); + caerEventPacketHeaderSetEventCapacity(&packet->packetHeader, eventCapacity); + + return (packet); +} + +caerFrameEventPacket caerFrameEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow, + int32_t maxLengthX, int32_t maxLengthY, int16_t maxChannelNumber) { + if (eventCapacity == 0) { + return (NULL); + } + + size_t pixelSize = sizeof(uint16_t) * (size_t) maxLengthX * (size_t) maxLengthY * (size_t) maxChannelNumber; + size_t eventSize = sizeof(struct caer_frame_event) + pixelSize; + size_t eventPacketSize = sizeof(struct caer_frame_event_packet) + ((size_t) eventCapacity * eventSize); + + // Zero out event memory (all events invalid). + caerFrameEventPacket packet = calloc(1, eventPacketSize); + if (packet == NULL) { + caerLog(CAER_LOG_CRITICAL, "Frame Event", + "Failed to allocate %zu bytes of memory for Frame Event Packet of capacity %" + PRIi32 " from source %" PRIi16 ". Error: %d.", eventPacketSize, eventCapacity, eventSource, + errno); + return (NULL); + } + + // Fill in header fields. + caerEventPacketHeaderSetEventType(&packet->packetHeader, FRAME_EVENT); + caerEventPacketHeaderSetEventSource(&packet->packetHeader, eventSource); + caerEventPacketHeaderSetEventSize(&packet->packetHeader, I32T(eventSize)); + caerEventPacketHeaderSetEventTSOffset(&packet->packetHeader, offsetof(struct caer_frame_event, ts_endframe)); + caerEventPacketHeaderSetEventTSOverflow(&packet->packetHeader, tsOverflow); + caerEventPacketHeaderSetEventCapacity(&packet->packetHeader, eventCapacity); + + return (packet); +} + +caerIMU6EventPacket caerIMU6EventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow) { + if (eventCapacity == 0) { + return (NULL); + } + + size_t eventSize = sizeof(struct caer_imu6_event); + size_t eventPacketSize = sizeof(struct caer_imu6_event_packet) + ((size_t) eventCapacity * eventSize); + + // Zero out event memory (all events invalid). + caerIMU6EventPacket packet = calloc(1, eventPacketSize); + if (packet == NULL) { + caerLog(CAER_LOG_CRITICAL, "IMU6 Event", + "Failed to allocate %zu bytes of memory for IMU6 Event Packet of capacity %" + PRIi32 " from source %" PRIi16 ". Error: %d.", eventPacketSize, eventCapacity, eventSource, + errno); + return (NULL); + } + + // Fill in header fields. + caerEventPacketHeaderSetEventType(&packet->packetHeader, IMU6_EVENT); + caerEventPacketHeaderSetEventSource(&packet->packetHeader, eventSource); + caerEventPacketHeaderSetEventSize(&packet->packetHeader, I32T(eventSize)); + caerEventPacketHeaderSetEventTSOffset(&packet->packetHeader, offsetof(struct caer_imu6_event, timestamp)); + caerEventPacketHeaderSetEventTSOverflow(&packet->packetHeader, tsOverflow); + caerEventPacketHeaderSetEventCapacity(&packet->packetHeader, eventCapacity); + + return (packet); +} + +caerIMU9EventPacket caerIMU9EventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow) { + if (eventCapacity == 0) { + return (NULL); + } + + size_t eventSize = sizeof(struct caer_imu9_event); + size_t eventPacketSize = sizeof(struct caer_imu9_event_packet) + ((size_t) eventCapacity * eventSize); + + // Zero out event memory (all events invalid). + caerIMU9EventPacket packet = calloc(1, eventPacketSize); + if (packet == NULL) { + caerLog(CAER_LOG_CRITICAL, "IMU9 Event", + "Failed to allocate %zu bytes of memory for IMU9 Event Packet of capacity %" + PRIi32 " from source %" PRIi16 ". Error: %d.", eventPacketSize, eventCapacity, eventSource, + errno); + return (NULL); + } + + // Fill in header fields. + caerEventPacketHeaderSetEventType(&packet->packetHeader, IMU9_EVENT); + caerEventPacketHeaderSetEventSource(&packet->packetHeader, eventSource); + caerEventPacketHeaderSetEventSize(&packet->packetHeader, I32T(eventSize)); + caerEventPacketHeaderSetEventTSOffset(&packet->packetHeader, offsetof(struct caer_imu9_event, timestamp)); + caerEventPacketHeaderSetEventTSOverflow(&packet->packetHeader, tsOverflow); + caerEventPacketHeaderSetEventCapacity(&packet->packetHeader, eventCapacity); + + return (packet); +} + +caerSampleEventPacket caerSampleEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow) { + if (eventCapacity == 0) { + return (NULL); + } + + size_t eventSize = sizeof(struct caer_sample_event); + size_t eventPacketSize = sizeof(struct caer_sample_event_packet) + ((size_t) eventCapacity * eventSize); + + // Zero out event memory (all events invalid). + caerSampleEventPacket packet = calloc(1, eventPacketSize); + if (packet == NULL) { + caerLog(CAER_LOG_CRITICAL, "Sample Event", + "Failed to allocate %zu bytes of memory for Sample Event Packet of capacity %" + PRIi32 " from source %" PRIi16 ". Error: %d.", eventPacketSize, eventCapacity, eventSource, + errno); + return (NULL); + } + + // Fill in header fields. + caerEventPacketHeaderSetEventType(&packet->packetHeader, SAMPLE_EVENT); + caerEventPacketHeaderSetEventSource(&packet->packetHeader, eventSource); + caerEventPacketHeaderSetEventSize(&packet->packetHeader, I32T(eventSize)); + caerEventPacketHeaderSetEventTSOffset(&packet->packetHeader, offsetof(struct caer_sample_event, timestamp)); + caerEventPacketHeaderSetEventTSOverflow(&packet->packetHeader, tsOverflow); + caerEventPacketHeaderSetEventCapacity(&packet->packetHeader, eventCapacity); + + return (packet); +} + +caerEarEventPacket caerEarEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow) { + if (eventCapacity == 0) { + return (NULL); + } + + size_t eventSize = sizeof(struct caer_ear_event); + size_t eventPacketSize = sizeof(struct caer_ear_event_packet) + ((size_t) eventCapacity * eventSize); + + // Zero out event memory (all events invalid). + caerEarEventPacket packet = calloc(1, eventPacketSize); + if (packet == NULL) { + caerLog(CAER_LOG_CRITICAL, "Ear Event", + "Failed to allocate %zu bytes of memory for Ear Event Packet of capacity %" + PRIi32 " from source %" PRIi16 ". Error: %d.", eventPacketSize, eventCapacity, eventSource, + errno); + return (NULL); + } + + // Fill in header fields. + caerEventPacketHeaderSetEventType(&packet->packetHeader, EAR_EVENT); + caerEventPacketHeaderSetEventSource(&packet->packetHeader, eventSource); + caerEventPacketHeaderSetEventSize(&packet->packetHeader, I32T(eventSize)); + caerEventPacketHeaderSetEventTSOffset(&packet->packetHeader, offsetof(struct caer_ear_event, timestamp)); + caerEventPacketHeaderSetEventTSOverflow(&packet->packetHeader, tsOverflow); + caerEventPacketHeaderSetEventCapacity(&packet->packetHeader, eventCapacity); + + return (packet); +} + +caerConfigurationEventPacket caerConfigurationEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, + int32_t tsOverflow) { + if (eventCapacity == 0) { + return (NULL); + } + + size_t eventSize = sizeof(struct caer_configuration_event); + size_t eventPacketSize = sizeof(struct caer_configuration_event_packet) + ((size_t) eventCapacity * eventSize); + + // Zero out event memory (all events invalid). + caerConfigurationEventPacket packet = calloc(1, eventPacketSize); + if (packet == NULL) { + caerLog(CAER_LOG_CRITICAL, "Configuration Event", + "Failed to allocate %zu bytes of memory for Configuration Event Packet of capacity %" + PRIi32 " from source %" PRIi16 ". Error: %d.", eventPacketSize, eventCapacity, eventSource, + errno); + return (NULL); + } + + // Fill in header fields. + caerEventPacketHeaderSetEventType(&packet->packetHeader, CONFIG_EVENT); + caerEventPacketHeaderSetEventSource(&packet->packetHeader, eventSource); + caerEventPacketHeaderSetEventSize(&packet->packetHeader, I32T(eventSize)); + caerEventPacketHeaderSetEventTSOffset(&packet->packetHeader, offsetof(struct caer_configuration_event, timestamp)); + caerEventPacketHeaderSetEventTSOverflow(&packet->packetHeader, tsOverflow); + caerEventPacketHeaderSetEventCapacity(&packet->packetHeader, eventCapacity); + + return (packet); +} + +caerPoint1DEventPacket caerPoint1DEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow) { + if (eventCapacity == 0) { + return (NULL); + } + + size_t eventSize = sizeof(struct caer_point1d_event); + size_t eventPacketSize = sizeof(struct caer_point1d_event_packet) + ((size_t) eventCapacity * eventSize); + + // Zero out event memory (all events invalid). + caerPoint1DEventPacket packet = calloc(1, eventPacketSize); + if (packet == NULL) { + caerLog(CAER_LOG_CRITICAL, "Point1D Event", + "Failed to allocate %zu bytes of memory for Point1D Event Packet of capacity %" + PRIi32 " from source %" PRIi16 ". Error: %d.", eventPacketSize, eventCapacity, eventSource, + errno); + return (NULL); + } + + // Fill in header fields. + caerEventPacketHeaderSetEventType(&packet->packetHeader, POINT1D_EVENT); + caerEventPacketHeaderSetEventSource(&packet->packetHeader, eventSource); + caerEventPacketHeaderSetEventSize(&packet->packetHeader, I32T(eventSize)); + caerEventPacketHeaderSetEventTSOffset(&packet->packetHeader, offsetof(struct caer_point1d_event, timestamp)); + caerEventPacketHeaderSetEventTSOverflow(&packet->packetHeader, tsOverflow); + caerEventPacketHeaderSetEventCapacity(&packet->packetHeader, eventCapacity); + + return (packet); +} + +caerPoint2DEventPacket caerPoint2DEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow) { + if (eventCapacity == 0) { + return (NULL); + } + + size_t eventSize = sizeof(struct caer_point2d_event); + size_t eventPacketSize = sizeof(struct caer_point2d_event_packet) + ((size_t) eventCapacity * eventSize); + + // Zero out event memory (all events invalid). + caerPoint2DEventPacket packet = calloc(1, eventPacketSize); + if (packet == NULL) { + caerLog(CAER_LOG_CRITICAL, "Point2D Event", + "Failed to allocate %zu bytes of memory for Point2D Event Packet of capacity %" + PRIi32 " from source %" PRIi16 ". Error: %d.", eventPacketSize, eventCapacity, eventSource, + errno); + return (NULL); + } + + // Fill in header fields. + caerEventPacketHeaderSetEventType(&packet->packetHeader, POINT2D_EVENT); + caerEventPacketHeaderSetEventSource(&packet->packetHeader, eventSource); + caerEventPacketHeaderSetEventSize(&packet->packetHeader, I32T(eventSize)); + caerEventPacketHeaderSetEventTSOffset(&packet->packetHeader, offsetof(struct caer_point2d_event, timestamp)); + caerEventPacketHeaderSetEventTSOverflow(&packet->packetHeader, tsOverflow); + caerEventPacketHeaderSetEventCapacity(&packet->packetHeader, eventCapacity); + + return (packet); +} + +caerPoint3DEventPacket caerPoint3DEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow) { + if (eventCapacity == 0) { + return (NULL); + } + + size_t eventSize = sizeof(struct caer_point3d_event); + size_t eventPacketSize = sizeof(struct caer_point3d_event_packet) + ((size_t) eventCapacity * eventSize); + + // Zero out event memory (all events invalid). + caerPoint3DEventPacket packet = calloc(1, eventPacketSize); + if (packet == NULL) { + caerLog(CAER_LOG_CRITICAL, "Point3D Event", + "Failed to allocate %zu bytes of memory for Point3D Event Packet of capacity %" + PRIi32 " from source %" PRIi16 ". Error: %d.", eventPacketSize, eventCapacity, eventSource, + errno); + return (NULL); + } + + // Fill in header fields. + caerEventPacketHeaderSetEventType(&packet->packetHeader, POINT3D_EVENT); + caerEventPacketHeaderSetEventSource(&packet->packetHeader, eventSource); + caerEventPacketHeaderSetEventSize(&packet->packetHeader, I32T(eventSize)); + caerEventPacketHeaderSetEventTSOffset(&packet->packetHeader, offsetof(struct caer_point3d_event, timestamp)); + caerEventPacketHeaderSetEventTSOverflow(&packet->packetHeader, tsOverflow); + caerEventPacketHeaderSetEventCapacity(&packet->packetHeader, eventCapacity); + + return (packet); +} + +caerPoint4DEventPacket caerPoint4DEventPacketAllocate(int32_t eventCapacity, int16_t eventSource, int32_t tsOverflow) { + if (eventCapacity == 0) { + return (NULL); + } + + size_t eventSize = sizeof(struct caer_point4d_event); + size_t eventPacketSize = sizeof(struct caer_point4d_event_packet) + ((size_t) eventCapacity * eventSize); + + // Zero out event memory (all events invalid). + caerPoint4DEventPacket packet = calloc(1, eventPacketSize); + if (packet == NULL) { + caerLog(CAER_LOG_CRITICAL, "Point4D Event", + "Failed to allocate %zu bytes of memory for Point4D Event Packet of capacity %" + PRIi32 " from source %" PRIi16 ". Error: %d.", eventPacketSize, eventCapacity, eventSource, + errno); + return (NULL); + } + + // Fill in header fields. + caerEventPacketHeaderSetEventType(&packet->packetHeader, POINT4D_EVENT); + caerEventPacketHeaderSetEventSource(&packet->packetHeader, eventSource); + caerEventPacketHeaderSetEventSize(&packet->packetHeader, I32T(eventSize)); + caerEventPacketHeaderSetEventTSOffset(&packet->packetHeader, offsetof(struct caer_point4d_event, timestamp)); + caerEventPacketHeaderSetEventTSOverflow(&packet->packetHeader, tsOverflow); + caerEventPacketHeaderSetEventCapacity(&packet->packetHeader, eventCapacity); + + return (packet); +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/frame_utils.c b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/frame_utils.c new file mode 100755 index 0000000..4ca263c --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/frame_utils.c @@ -0,0 +1,651 @@ +#include "frame_utils.h" + +enum pixelColorEnum { + PXR, PXB, PXG1, PXG2, PXW +}; + +static void frameUtilsDemosaicFrame(caerFrameEvent colorFrame, caerFrameEvent monoFrame); + +static inline enum pixelColorEnum determinePixelColor(enum caer_frame_event_color_filter colorFilter, int32_t x, + int32_t y) { + switch (colorFilter) { + case RGBG: + if (x & 0x01) { + if (y & 0x01) { + return (PXB); + } + else { + return (PXG1); + } + } + else { + if (y & 0x01) { + return (PXG2); + } + else { + return (PXR); + } + } + break; + + case GRGB: + if (x & 0x01) { + if (y & 0x01) { + return (PXG2); + } + else { + return (PXR); + } + } + else { + if (y & 0x01) { + return (PXB); + } + else { + return (PXG1); + } + } + break; + + case GBGR: + if (x & 0x01) { + if (y & 0x01) { + return (PXG1); + } + else { + return (PXB); + } + } + else { + if (y & 0x01) { + return (PXR); + } + else { + return (PXG2); + } + } + break; + + case BGRG: + if (x & 0x01) { + if (y & 0x01) { + return (PXR); + } + else { + return (PXG2); + } + } + else { + if (y & 0x01) { + return (PXG1); + } + else { + return (PXB); + } + } + break; + + case RGBW: + if (x & 0x01) { + if (y & 0x01) { + return (PXB); + } + else { + return (PXG1); + } + } + else { + if (y & 0x01) { + return (PXW); + } + else { + return (PXR); + } + } + break; + + case GRWB: + if (x & 0x01) { + if (y & 0x01) { + return (PXW); + } + else { + return (PXR); + } + } + else { + if (y & 0x01) { + return (PXB); + } + else { + return (PXG1); + } + } + break; + + case WBGR: + if (x & 0x01) { + if (y & 0x01) { + return (PXG1); + } + else { + return (PXB); + } + } + else { + if (y & 0x01) { + return (PXR); + } + else { + return (PXW); + } + } + break; + + case BWRG: + if (x & 0x01) { + if (y & 0x01) { + return (PXR); + } + else { + return (PXW); + } + } + else { + if (y & 0x01) { + return (PXG1); + } + else { + return (PXB); + } + } + break; + + case MONO: + default: + // Just fall through. + break; + } + + // This is impossible (MONO), so just use red pixel value, as good as any. + return (PXR); +} + +static void frameUtilsDemosaicFrame(caerFrameEvent colorFrame, caerFrameEvent monoFrame) { + uint16_t *colorPixels = caerFrameEventGetPixelArrayUnsafe(colorFrame); + uint16_t *monoPixels = caerFrameEventGetPixelArrayUnsafe(monoFrame); + + enum caer_frame_event_color_filter colorFilter = caerFrameEventGetColorFilter(monoFrame); + int32_t lengthY = caerFrameEventGetLengthY(monoFrame); + int32_t lengthX = caerFrameEventGetLengthX(monoFrame); + int32_t idxCENTER = 0; + int32_t idxCOLOR = 0; + + for (int32_t y = 0; y < lengthY; y++) { + for (int32_t x = 0; x < lengthX; x++) { + // Calculate all neighbor indexes. + int32_t idxLEFT = idxCENTER - 1; + int32_t idxRIGHT = idxCENTER + 1; + + int32_t idxCENTERUP = idxCENTER - lengthX; + int32_t idxLEFTUP = idxCENTERUP - 1; + int32_t idxRIGHTUP = idxCENTERUP + 1; + + int32_t idxCENTERDOWN = idxCENTER + lengthX; + int32_t idxLEFTDOWN = idxCENTERDOWN - 1; + int32_t idxRIGHTDOWN = idxCENTERDOWN + 1; + + enum pixelColorEnum pixelColor = determinePixelColor(colorFilter, x, y); + int32_t RComp; + int32_t GComp; + int32_t BComp; + + switch (pixelColor) { + case PXR: { + // This is a R pixel. It is always surrounded by G and B only. + RComp = monoPixels[idxCENTER]; + + if (y == 0) { + // First row. + if (x == 0) { + // First column. + GComp = (monoPixels[idxCENTERDOWN] + monoPixels[idxRIGHT]) / 2; + BComp = monoPixels[idxRIGHTDOWN]; + } + else if (x == (lengthX - 1)) { + // Last column. + GComp = (monoPixels[idxCENTERDOWN] + monoPixels[idxLEFT]) / 2; + BComp = monoPixels[idxLEFTDOWN]; + } + else { + // In-between columns. + GComp = (monoPixels[idxCENTERDOWN] + monoPixels[idxLEFT] + monoPixels[idxRIGHT]) / 3; + BComp = (monoPixels[idxRIGHTDOWN] + monoPixels[idxLEFTDOWN]) / 2; + } + } + else if (y == (lengthY - 1)) { + // Last row. + if (x == 0) { + // First column. + GComp = (monoPixels[idxCENTERUP] + monoPixels[idxRIGHT]) / 2; + BComp = monoPixels[idxRIGHTUP]; + } + else if (x == (lengthX - 1)) { + // Last column. + GComp = (monoPixels[idxCENTERUP] + monoPixels[idxLEFT]) / 2; + BComp = monoPixels[idxLEFTUP]; + } + else { + // In-between columns. + GComp = (monoPixels[idxCENTERUP] + monoPixels[idxLEFT] + monoPixels[idxRIGHT]) / 3; + BComp = (monoPixels[idxRIGHTUP] + monoPixels[idxLEFTUP]) / 2; + } + } + else { + // In-between rows. + if (x == 0) { + // First column. + GComp = (monoPixels[idxCENTERUP] + monoPixels[idxCENTERDOWN] + monoPixels[idxRIGHT]) / 3; + BComp = (monoPixels[idxRIGHTUP] + monoPixels[idxRIGHTDOWN]) / 2; + } + else if (x == (lengthX - 1)) { + // Last column. + GComp = (monoPixels[idxCENTERUP] + monoPixels[idxCENTERDOWN] + monoPixels[idxLEFT]) / 3; + BComp = (monoPixels[idxLEFTUP] + monoPixels[idxLEFTDOWN]) / 2; + } + else { + // In-between columns. + GComp = (monoPixels[idxCENTERUP] + monoPixels[idxCENTERDOWN] + monoPixels[idxLEFT] + + monoPixels[idxRIGHT]) / 4; + BComp = (monoPixels[idxRIGHTUP] + monoPixels[idxLEFTUP] + monoPixels[idxRIGHTDOWN] + + monoPixels[idxLEFTDOWN]) / 4; + } + } + + break; + } + + case PXB: { + // This is a B pixel. It is always surrounded by G and R only. + BComp = monoPixels[idxCENTER]; + + if (y == 0) { + // First row. + if (x == 0) { + // First column. + RComp = monoPixels[idxRIGHTDOWN]; + GComp = (monoPixels[idxCENTERDOWN] + monoPixels[idxRIGHT]) / 2; + } + else if (x == (lengthX - 1)) { + // Last column. + RComp = monoPixels[idxLEFTDOWN]; + GComp = (monoPixels[idxCENTERDOWN] + monoPixels[idxLEFT]) / 2; + } + else { + // In-between columns. + RComp = (monoPixels[idxRIGHTDOWN] + monoPixels[idxLEFTDOWN]) / 2; + GComp = (monoPixels[idxCENTERDOWN] + monoPixels[idxLEFT] + monoPixels[idxRIGHT]) / 3; + } + } + else if (y == (lengthY - 1)) { + // Last row. + if (x == 0) { + // First column. + RComp = monoPixels[idxRIGHTUP]; + GComp = (monoPixels[idxCENTERUP] + monoPixels[idxRIGHT]) / 2; + } + else if (x == (lengthX - 1)) { + // Last column. + RComp = monoPixels[idxLEFTUP]; + GComp = (monoPixels[idxCENTERUP] + monoPixels[idxLEFT]) / 2; + } + else { + // In-between columns. + RComp = (monoPixels[idxRIGHTUP] + monoPixels[idxLEFTUP]) / 2; + GComp = (monoPixels[idxCENTERUP] + monoPixels[idxLEFT] + monoPixels[idxRIGHT]) / 3; + } + } + else { + // In-between rows. + if (x == 0) { + // First column. + RComp = (monoPixels[idxRIGHTUP] + monoPixels[idxRIGHTDOWN]) / 2; + GComp = (monoPixels[idxCENTERUP] + monoPixels[idxCENTERDOWN] + monoPixels[idxRIGHT]) / 3; + } + else if (x == (lengthX - 1)) { + // Last column. + RComp = (monoPixels[idxLEFTUP] + monoPixels[idxLEFTDOWN]) / 2; + GComp = (monoPixels[idxCENTERUP] + monoPixels[idxCENTERDOWN] + monoPixels[idxLEFT]) / 3; + } + else { + // In-between columns. + RComp = (monoPixels[idxRIGHTUP] + monoPixels[idxLEFTUP] + monoPixels[idxRIGHTDOWN] + + monoPixels[idxLEFTDOWN]) / 4; + GComp = (monoPixels[idxCENTERUP] + monoPixels[idxCENTERDOWN] + monoPixels[idxLEFT] + + monoPixels[idxRIGHT]) / 4; + } + } + + break; + } + + case PXG1: { + // This is a G1 (first green) pixel. It is always surrounded by all of R, G, B. + GComp = monoPixels[idxCENTER]; + + if (y == 0) { + // First row. + BComp = monoPixels[idxCENTERDOWN]; + + if (x == 0) { + // First column. + RComp = monoPixels[idxRIGHT]; + } + else if (x == (lengthX - 1)) { + // Last column. + RComp = monoPixels[idxLEFT]; + } + else { + // In-between columns. + RComp = (monoPixels[idxLEFT] + monoPixels[idxRIGHT]) / 2; + } + } + else if (y == (lengthY - 1)) { + // Last row. + BComp = monoPixels[idxCENTERUP]; + + if (x == 0) { + // First column. + RComp = monoPixels[idxRIGHT]; + } + else if (x == (lengthX - 1)) { + // Last column. + RComp = monoPixels[idxLEFT]; + } + else { + // In-between columns. + RComp = (monoPixels[idxLEFT] + monoPixels[idxRIGHT]) / 2; + } + } + else { + // In-between rows. + BComp = (monoPixels[idxCENTERUP] + monoPixels[idxCENTERDOWN]) / 2; + + if (x == 0) { + // First column. + RComp = monoPixels[idxRIGHT]; + } + else if (x == (lengthX - 1)) { + // Last column. + RComp = monoPixels[idxLEFT]; + } + else { + // In-between columns. + RComp = (monoPixels[idxLEFT] + monoPixels[idxRIGHT]) / 2; + } + } + + break; + } + + case PXG2: { + // This is a G2 (second green) pixel. It is always surrounded by all of R, G, B. + GComp = monoPixels[idxCENTER]; + + if (y == 0) { + // First row. + RComp = monoPixels[idxCENTERDOWN]; + + if (x == 0) { + // First column. + BComp = monoPixels[idxRIGHT]; + } + else if (x == (lengthX - 1)) { + // Last column. + BComp = monoPixels[idxLEFT]; + } + else { + // In-between columns. + BComp = (monoPixels[idxLEFT] + monoPixels[idxRIGHT]) / 2; + } + } + else if (y == (lengthY - 1)) { + // Last row. + RComp = monoPixels[idxCENTERUP]; + + if (x == 0) { + // First column. + BComp = monoPixels[idxRIGHT]; + } + else if (x == (lengthX - 1)) { + // Last column. + BComp = monoPixels[idxLEFT]; + } + else { + // In-between columns. + BComp = (monoPixels[idxLEFT] + monoPixels[idxRIGHT]) / 2; + } + } + else { + // In-between rows. + RComp = (monoPixels[idxCENTERUP] + monoPixels[idxCENTERDOWN]) / 2; + + if (x == 0) { + // First column. + BComp = monoPixels[idxRIGHT]; + } + else if (x == (lengthX - 1)) { + // Last column. + BComp = monoPixels[idxLEFT]; + } + else { + // In-between columns. + BComp = (monoPixels[idxLEFT] + monoPixels[idxRIGHT]) / 2; + } + } + + break; + } + + case PXW: { + // This is a W pixel, modified Bayer pattern instead of G2. It is always surrounded by all of R, G, B. + // TODO: how can W itself contribute to the three colors? + if (y == 0) { + // First row. + RComp = monoPixels[idxCENTERDOWN]; + + if (x == 0) { + // First column. + GComp = monoPixels[idxRIGHTDOWN]; + BComp = monoPixels[idxRIGHT]; + } + else if (x == (lengthX - 1)) { + // Last column. + GComp = monoPixels[idxLEFTDOWN]; + BComp = monoPixels[idxLEFT]; + } + else { + // In-between columns. + GComp = (monoPixels[idxRIGHTDOWN] + monoPixels[idxLEFTDOWN]) / 2; + BComp = (monoPixels[idxLEFT] + monoPixels[idxRIGHT]) / 2; + } + } + else if (y == (lengthY - 1)) { + // Last row. + RComp = monoPixels[idxCENTERUP]; + + if (x == 0) { + // First column. + GComp = monoPixels[idxRIGHTUP]; + BComp = monoPixels[idxRIGHT]; + } + else if (x == (lengthX - 1)) { + // Last column. + GComp = monoPixels[idxLEFTUP]; + BComp = monoPixels[idxRIGHT]; + } + else { + // In-between columns. + GComp = (monoPixels[idxRIGHTUP] + monoPixels[idxLEFTUP]) / 2; + BComp = (monoPixels[idxLEFT] + monoPixels[idxRIGHT]) / 2; + } + } + else { + // In-between rows. + RComp = (monoPixels[idxCENTERUP] + monoPixels[idxCENTERDOWN]) / 2; + + if (x == 0) { + // First column. + GComp = (monoPixels[idxRIGHTUP] + monoPixels[idxRIGHTDOWN]) / 2; + BComp = monoPixels[idxRIGHT]; + } + else if (x == (lengthX - 1)) { + // Last column. + GComp = (monoPixels[idxLEFTUP] + monoPixels[idxLEFTDOWN]) / 2; + BComp = monoPixels[idxLEFT]; + } + else { + // In-between columns. + GComp = (monoPixels[idxRIGHTUP] + monoPixels[idxLEFTUP] + monoPixels[idxRIGHTDOWN] + + monoPixels[idxLEFTDOWN]) / 4; + BComp = (monoPixels[idxLEFT] + monoPixels[idxRIGHT]) / 2; + } + } + + break; + } + } + + // Set color frame pixel values for all color channels. + colorPixels[idxCOLOR] = U16T(RComp); + colorPixels[idxCOLOR + 1] = U16T(GComp); + colorPixels[idxCOLOR + 2] = U16T(BComp); + + // Go to next pixel. + idxCENTER++; + idxCOLOR += RGB; + } + } +} + +caerFrameEventPacket caerFrameUtilsDemosaic(caerFrameEventPacket framePacket) { + if (framePacket == NULL) { + return (NULL); + } + + int32_t countValid = 0; + int32_t maxLengthX = 0; + int32_t maxLengthY = 0; + + // This only works on valid frames coming from a camera: only one color channel, + // but with color filter information defined. + CAER_FRAME_ITERATOR_VALID_START(framePacket) + if (caerFrameEventGetChannelNumber(caerFrameIteratorElement) == GRAYSCALE + && caerFrameEventGetColorFilter(caerFrameIteratorElement) != MONO) { + countValid++; + + if (caerFrameEventGetLengthX(caerFrameIteratorElement) > maxLengthX) { + maxLengthX = caerFrameEventGetLengthX(caerFrameIteratorElement); + } + + if (caerFrameEventGetLengthY(caerFrameIteratorElement) > maxLengthY) { + maxLengthY = caerFrameEventGetLengthY(caerFrameIteratorElement); + } + } + CAER_FRAME_ITERATOR_VALID_END + + // Allocate new frame with RGB channels to hold resulting color image. + caerFrameEventPacket colorFramePacket = caerFrameEventPacketAllocate(countValid, + caerEventPacketHeaderGetEventSource(&framePacket->packetHeader), + caerEventPacketHeaderGetEventTSOverflow(&framePacket->packetHeader), maxLengthX, maxLengthY, RGB); + if (colorFramePacket == NULL) { + return (NULL); + } + + int32_t colorIndex = 0; + + // Now that we have a valid new color frame packet, we can convert the frames one by one. + CAER_FRAME_ITERATOR_VALID_START(framePacket) + if (caerFrameEventGetChannelNumber(caerFrameIteratorElement) == GRAYSCALE + && caerFrameEventGetColorFilter(caerFrameIteratorElement) != MONO) { + // If all conditions are met, copy from framePacket's mono frame to colorFramePacket's RGB frame. + caerFrameEvent colorFrame = caerFrameEventPacketGetEvent(colorFramePacket, colorIndex++); + + // First copy all the metadata. + caerFrameEventSetColorFilter(colorFrame, caerFrameEventGetColorFilter(caerFrameIteratorElement)); + caerFrameEventSetLengthXLengthYChannelNumber(colorFrame, caerFrameEventGetLengthX(caerFrameIteratorElement), + caerFrameEventGetLengthY(caerFrameIteratorElement), RGB, colorFramePacket); + caerFrameEventSetPositionX(colorFrame, caerFrameEventGetPositionX(caerFrameIteratorElement)); + caerFrameEventSetPositionY(colorFrame, caerFrameEventGetPositionY(caerFrameIteratorElement)); + caerFrameEventSetROIIdentifier(colorFrame, caerFrameEventGetROIIdentifier(caerFrameIteratorElement)); + caerFrameEventSetTSStartOfFrame(colorFrame, caerFrameEventGetTSStartOfFrame(caerFrameIteratorElement)); + caerFrameEventSetTSEndOfFrame(colorFrame, caerFrameEventGetTSEndOfFrame(caerFrameIteratorElement)); + caerFrameEventSetTSStartOfExposure(colorFrame, + caerFrameEventGetTSStartOfExposure(caerFrameIteratorElement)); + caerFrameEventSetTSEndOfExposure(colorFrame, caerFrameEventGetTSEndOfExposure(caerFrameIteratorElement)); + + // Then the actual pixels. + frameUtilsDemosaicFrame(colorFrame, caerFrameIteratorElement); + + // Finally validate the new frame. + caerFrameEventValidate(colorFrame, colorFramePacket); + } + CAER_FRAME_ITERATOR_VALID_END + + return (colorFramePacket); +} + +void caerFrameUtilsContrast(caerFrameEventPacket framePacket) { + if (framePacket == NULL) { + return; + } + + // O(x, y) = alpha * I(x, y) + beta, where alpha maximizes the range + // (contrast) and beta shifts it so lowest is zero (brightness). + // Only works with grayscale images currently. Doing so for color (RGB/RGBA) images would require + // conversion into another color space that has an intensity channel separate from the color + // channels, such as Lab or YCrCb. The same algorithm would then be applied on the intensity only. + CAER_FRAME_ITERATOR_VALID_START(framePacket) + if (caerFrameEventGetChannelNumber(caerFrameIteratorElement) == GRAYSCALE) { + uint16_t *pixels = caerFrameEventGetPixelArrayUnsafe(caerFrameIteratorElement); + int32_t lengthY = caerFrameEventGetLengthY(caerFrameIteratorElement); + int32_t lengthX = caerFrameEventGetLengthX(caerFrameIteratorElement); + + // On first pass, determine minimum and maximum values. + int32_t minValue = INT32_MAX; + int32_t maxValue = INT32_MIN; + + for (int32_t idx = 0; idx < (lengthY * lengthX); idx++) { + if (pixels[idx] < minValue) { + minValue = pixels[idx]; + } + + if (pixels[idx] > maxValue) { + maxValue = pixels[idx]; + } + } + + // Use min/max to calculate input range. + int32_t range = maxValue - minValue; + + // Calculate alpha (contrast). + float alpha = ((float) UINT16_MAX) / ((float) range); + + // Calculate beta (brightness). + float beta = ((float) -minValue) * alpha; + + // Apply alpha and beta to pixels array. + for (int32_t idx = 0; idx < (lengthY * lengthX); idx++) { + pixels[idx] = U16T(alpha * ((float ) pixels[idx]) + beta); + } + } + else { + caerLog(CAER_LOG_WARNING, "caerFrameUtilsContrast()", + "Standard contrast enhancement only works with grayscale images. For color image support, please use caerFrameUtilsOpenCVContrast()."); + } + CAER_FRAME_ITERATOR_VALID_END +} + +void caerFrameUtilsWhiteBalance(caerFrameEventPacket framePacket) { + +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/frame_utils_opencv.cpp b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/frame_utils_opencv.cpp new file mode 100755 index 0000000..53d2bbd --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/frame_utils_opencv.cpp @@ -0,0 +1,412 @@ +#include "frame_utils_opencv.h" + +#include <opencv2/core.hpp> +#include <opencv2/core/utility.hpp> +#include <opencv2/imgproc.hpp> + +using namespace cv; + +static void frameUtilsOpenCVDemosaicFrame(caerFrameEvent colorFrame, caerFrameEvent monoFrame, + enum caer_frame_utils_opencv_demosaic demosaicType); +static void frameUtilsOpenCVContrastNormalize(Mat &intensity, float clipHistPercent); +static void frameUtilsOpenCVContrastEqualize(Mat &intensity); +static void frameUtilsOpenCVContrastCLAHE(Mat &intensity, float clipLimit, int tilesGridSize); + +static void frameUtilsOpenCVDemosaicFrame(caerFrameEvent colorFrame, caerFrameEvent monoFrame, + enum caer_frame_utils_opencv_demosaic demosaicType) { + // Initialize OpenCV Mat based on caerFrameEvent data directly (no image copy). + Size frameSize(caerFrameEventGetLengthX(monoFrame), caerFrameEventGetLengthY(monoFrame)); + Mat monoMat(frameSize, CV_16UC(caerFrameEventGetChannelNumber(monoFrame)), + caerFrameEventGetPixelArrayUnsafe(monoFrame)); + Mat colorMat(frameSize, CV_16UC(caerFrameEventGetChannelNumber(colorFrame)), + caerFrameEventGetPixelArrayUnsafe(colorFrame)); + + CV_Assert(monoMat.type() == CV_16UC1 && colorMat.type() == CV_16UC3); + + // Select correct type code for OpenCV demosaic algorithm. + int code = 0; + + switch (demosaicType) { + case DEMOSAIC_NORMAL: + switch (caerFrameEventGetColorFilter(monoFrame)) { + case RGBG: + code = COLOR_BayerBG2RGB; + break; + + case GRGB: + code = COLOR_BayerGB2RGB; + break; + + case GBGR: + code = COLOR_BayerGR2RGB; + break; + + case BGRG: + code = COLOR_BayerRG2RGB; + break; + + default: + // Impossible, other color filters get filtered out above. + break; + } + break; + + /*case DEMOSAIC_VARIABLE_NUMBER_OF_GRADIENTS: + switch (caerFrameEventGetColorFilter(monoFrame)) { + case RGBG: + code = COLOR_BayerBG2RGB_VNG; + break; + + case GRGB: + code = COLOR_BayerGB2RGB_VNG; + break; + + case GBGR: + code = COLOR_BayerGR2RGB_VNG; + break; + + case BGRG: + code = COLOR_BayerRG2RGB_VNG; + break; + + default: + // Impossible, other color filters get filtered out above. + break; + } + break;*/ + + case DEMOSAIC_EDGE_AWARE: + switch (caerFrameEventGetColorFilter(monoFrame)) { + case RGBG: + code = COLOR_BayerBG2RGB_EA; + break; + + case GRGB: + code = COLOR_BayerGB2RGB_EA; + break; + + case GBGR: + code = COLOR_BayerGR2RGB_EA; + break; + + case BGRG: + code = COLOR_BayerRG2RGB_EA; + break; + + default: + // Impossible, other color filters get filtered out above. + break; + } + break; + } + + // Convert Bayer pattern to RGB image. + cvtColor(monoMat, colorMat, code); +} + +caerFrameEventPacket caerFrameUtilsOpenCVDemosaic(caerFrameEventPacket framePacket, + enum caer_frame_utils_opencv_demosaic demosaicType) { + if (framePacket == NULL) { + return (NULL); + } + + int32_t countValid = 0; + int32_t maxLengthX = 0; + int32_t maxLengthY = 0; + + // This only works on valid frames coming from a camera: only one color channel, + // but with color filter information defined. + CAER_FRAME_ITERATOR_VALID_START(framePacket) + if (caerFrameEventGetChannelNumber(caerFrameIteratorElement) == GRAYSCALE + && caerFrameEventGetColorFilter(caerFrameIteratorElement) != MONO) { + if (caerFrameEventGetColorFilter(caerFrameIteratorElement) == RGBG + || caerFrameEventGetColorFilter(caerFrameIteratorElement) == GRGB + || caerFrameEventGetColorFilter(caerFrameIteratorElement) == GBGR + || caerFrameEventGetColorFilter(caerFrameIteratorElement) == BGRG) { + countValid++; + + if (caerFrameEventGetLengthX(caerFrameIteratorElement) > maxLengthX) { + maxLengthX = caerFrameEventGetLengthX(caerFrameIteratorElement); + } + + if (caerFrameEventGetLengthY(caerFrameIteratorElement) > maxLengthY) { + maxLengthY = caerFrameEventGetLengthY(caerFrameIteratorElement); + } + } + else { + caerLog(CAER_LOG_WARNING, "caerFrameUtilsOpenCVDemosaic()", + "OpenCV demosaicing doesn't support the RGBW color filter, only RGBG. Please use caerFrameUtilsDemosaic() instead."); + } + } + CAER_FRAME_ITERATOR_VALID_END + + // Allocate new frame with RGB channels to hold resulting color image. + caerFrameEventPacket colorFramePacket = caerFrameEventPacketAllocate(countValid, + caerEventPacketHeaderGetEventSource(&framePacket->packetHeader), + caerEventPacketHeaderGetEventTSOverflow(&framePacket->packetHeader), maxLengthX, maxLengthY, RGB); + if (colorFramePacket == NULL) { + return (NULL); + } + + int32_t colorIndex = 0; + + // Now that we have a valid new color frame packet, we can convert the frames one by one. + CAER_FRAME_ITERATOR_VALID_START(framePacket) + if (caerFrameEventGetChannelNumber(caerFrameIteratorElement) == GRAYSCALE + && caerFrameEventGetColorFilter(caerFrameIteratorElement) != MONO) { + if (caerFrameEventGetColorFilter(caerFrameIteratorElement) == RGBG + || caerFrameEventGetColorFilter(caerFrameIteratorElement) == GRGB + || caerFrameEventGetColorFilter(caerFrameIteratorElement) == GBGR + || caerFrameEventGetColorFilter(caerFrameIteratorElement) == BGRG) { + // If all conditions are met, copy from framePacket's mono frame to colorFramePacket's RGB frame. + caerFrameEvent colorFrame = caerFrameEventPacketGetEvent(colorFramePacket, colorIndex++); + + // First copy all the metadata. + caerFrameEventSetColorFilter(colorFrame, caerFrameEventGetColorFilter(caerFrameIteratorElement)); + caerFrameEventSetLengthXLengthYChannelNumber(colorFrame, + caerFrameEventGetLengthX(caerFrameIteratorElement), + caerFrameEventGetLengthY(caerFrameIteratorElement), RGB, colorFramePacket); + caerFrameEventSetPositionX(colorFrame, caerFrameEventGetPositionX(caerFrameIteratorElement)); + caerFrameEventSetPositionY(colorFrame, caerFrameEventGetPositionY(caerFrameIteratorElement)); + caerFrameEventSetROIIdentifier(colorFrame, caerFrameEventGetROIIdentifier(caerFrameIteratorElement)); + caerFrameEventSetTSStartOfFrame(colorFrame, caerFrameEventGetTSStartOfFrame(caerFrameIteratorElement)); + caerFrameEventSetTSEndOfFrame(colorFrame, caerFrameEventGetTSEndOfFrame(caerFrameIteratorElement)); + caerFrameEventSetTSStartOfExposure(colorFrame, + caerFrameEventGetTSStartOfExposure(caerFrameIteratorElement)); + caerFrameEventSetTSEndOfExposure(colorFrame, + caerFrameEventGetTSEndOfExposure(caerFrameIteratorElement)); + + // Then the actual pixels. Only supports RGBG! + frameUtilsOpenCVDemosaicFrame(colorFrame, caerFrameIteratorElement, demosaicType); + + // Finally validate the new frame. + caerFrameEventValidate(colorFrame, colorFramePacket); + } + } + CAER_FRAME_ITERATOR_VALID_END + + return (colorFramePacket); +} + +void caerFrameUtilsOpenCVContrast(caerFrameEventPacket framePacket, + enum caer_frame_utils_opencv_contrast contrastType) { + if (framePacket == NULL) { + return; + } + + CAER_FRAME_ITERATOR_VALID_START(framePacket) + Size frameSize(caerFrameEventGetLengthX(caerFrameIteratorElement), + caerFrameEventGetLengthY(caerFrameIteratorElement)); + Mat orig(frameSize, CV_16UC(caerFrameEventGetChannelNumber(caerFrameIteratorElement)), + caerFrameEventGetPixelArrayUnsafe(caerFrameIteratorElement)); + + CV_Assert(orig.type() == CV_16UC1 || orig.type() == CV_16UC3 || orig.type() == CV_16UC4); + + // This generally only works well on grayscale intensity images. + // So, if this is a grayscale image, good, else if its a color + // image we convert it to YCrCb and operate on the Y channel only. + Mat intensity; + std::vector<Mat> yCrCbPlanes(3); + Mat rgbaAlpha; + + // Grayscale, no intensity extraction needed. + if (orig.channels() == GRAYSCALE) { + intensity = orig; + } + else { + // Color image, extract RGB and intensity/luminance. + Mat rgb; + + if (orig.channels() == RGBA) { + // We separate Alpha from RGB first. + // We will restore alpha at the end. + rgb = Mat(orig.rows, orig.cols, CV_16UC3); + rgbaAlpha = Mat(orig.rows, orig.cols, CV_16UC1); + + Mat out[] = { rgb, rgbaAlpha }; + // rgba[0] -> rgb[0], rgba[1] -> rgb[1], + // rgba[2] -> rgb[2], rgba[3] -> rgbaAlpha[0] + int channelTransform[] = { 0, 0, 1, 1, 2, 2, 3, 3 }; + mixChannels(&orig, 1, out, 2, channelTransform, 4); + } + else { + // Already an RGB image. + rgb = orig; + CV_Assert(rgb.type() == CV_16UC3); + } + + // First we convert from RGB to a color space with + // separate luminance channel. + Mat rgbYCrCb; + cvtColor(rgb, rgbYCrCb, COLOR_RGB2YCrCb); + + CV_Assert(rgbYCrCb.type() == CV_16UC3); + + // Then we split it up so that we can access the luminance + // channel on its own separately. + split(rgbYCrCb, yCrCbPlanes); + + // Now we have the luminance image in yCrCbPlanes[0]. + intensity = yCrCbPlanes[0]; + } + + CV_Assert(intensity.type() == CV_16UC1); + + // Apply contrast enhancement algorithm. + switch (contrastType) { + case CONTRAST_NORMALIZATION: + frameUtilsOpenCVContrastNormalize(intensity, 1.0); + break; + + case CONTRAST_HISTOGRAM_EQUALIZATION: + frameUtilsOpenCVContrastEqualize(intensity); + break; + + case CONTRAST_CLAHE: + frameUtilsOpenCVContrastCLAHE(intensity, 4.0, 8); + break; + } + + // If original was a color frame, we have to mix the various + // components back together into an RGB(A) image. + if (orig.channels() != GRAYSCALE) { + Mat YCrCbrgb; + merge(yCrCbPlanes, YCrCbrgb); + + CV_Assert(YCrCbrgb.type() == CV_16UC3); + + if (orig.channels() == RGBA) { + Mat rgb; + cvtColor(YCrCbrgb, rgb, COLOR_YCrCb2RGB); + + CV_Assert(rgb.type() == CV_16UC3); + + // Restore original alpha. + Mat in[] = { rgb, rgbaAlpha }; + // rgb[0] -> rgba[0], rgb[1] -> rgba[1], + // rgb[2] -> rgba[2], rgbaAlpha[0] -> rgba[3] + int channelTransform[] = { 0, 0, 1, 1, 2, 2, 3, 3 }; + mixChannels(in, 2, &orig, 1, channelTransform, 4); + } + else { + cvtColor(YCrCbrgb, orig, COLOR_YCrCb2RGB); + } + } + CAER_FRAME_ITERATOR_VALID_END +} + +void caerFrameUtilsOpenCVWhiteBalance(caerFrameEventPacket framePacket, + enum caer_frame_utils_opencv_white_balance whiteBalanceType) { + +} + +static void frameUtilsOpenCVContrastNormalize(Mat &intensity, float clipHistPercent) { + CV_Assert(intensity.type() == CV_16UC1); + CV_Assert(clipHistPercent >= 0 && clipHistPercent < 100); + + // O(x, y) = alpha * I(x, y) + beta, where alpha maximizes the range + // (contrast) and beta shifts it so lowest is zero (brightness). + double minValue, maxValue; + + if (clipHistPercent == 0) { + // Determine minimum and maximum values. + minMaxLoc(intensity, &minValue, &maxValue); + } + else { + // Calculate histogram. + int histSize = UINT16_MAX + 1; + float hRange[] = { 0, (float) histSize }; + const float *histRange = { hRange }; + bool uniform = true; + bool accumulate = false; + + Mat hist; + calcHist(&intensity, 1, 0, Mat(), hist, 1, &histSize, &histRange, uniform, accumulate); + + // Calculate cumulative distribution from the histogram. + for (size_t i = 1; i < (size_t) histSize; i++) { + hist.at<float>(i) += hist.at<float>(i - 1); + } + + // Locate points that cut at required value. + float max = hist.at<float>(histSize - 1); + clipHistPercent *= (max / 100.0); // Calculate absolute value from percent. + clipHistPercent /= 2.0; // Left and right wings, so divide by two. + + // Locate left cut. + minValue = 0; + while (hist.at<float>(minValue) < clipHistPercent) { + minValue++; + } + + // Locate right cut. + maxValue = UINT16_MAX; + while (hist.at<float>(maxValue) >= (max - clipHistPercent)) { + maxValue--; + } + } + + // Use min/max to calculate input range. + double range = maxValue - minValue; + + // Calculate alpha (contrast). + double alpha = ((double) UINT16_MAX) / range; + + // Calculate beta (brightness). + double beta = -minValue * alpha; + + // Apply alpha and beta to pixels array. + intensity.convertTo(intensity, -1, alpha, beta); +} + +static void frameUtilsOpenCVContrastEqualize(Mat &intensity) { + CV_Assert(intensity.type() == CV_16UC1); + + // Calculate histogram. + int histSize = UINT16_MAX + 1; + float hRange[] = { 0, (float) histSize }; + const float *histRange = { hRange }; + bool uniform = true; + bool accumulate = false; + + Mat hist; + calcHist(&intensity, 1, 0, Mat(), hist, 1, &histSize, &histRange, uniform, accumulate); + + // Calculate CDF from the histogram. + for (size_t i = 1; i < (size_t) histSize; i++) { + hist.at<float>(i) += hist.at<float>(i - 1); + } + + // Total number of pixels. Must be the last value! + float total = hist.at<float>(histSize - 1); + + // Smallest non-zero CDF value. Must be the first non-zero value! + float min = 0; + for (size_t i = 0; i < (size_t) histSize; i++) { + if (hist.at<float>(i) > 0) { + min = hist.at<float>(i); + break; + } + } + + // Calculate lookup table for histogram equalization. + hist -= min; + hist /= (total - min); + hist *= (float) UINT16_MAX; + + // Apply lookup table to input image. + std::for_each(intensity.begin<uint16_t>(), intensity.end<uint16_t>(), + [&hist](uint16_t &elem) {elem = hist.at<float>(elem);}); +} + +static void frameUtilsOpenCVContrastCLAHE(Mat &intensity, float clipLimit, int tilesGridSize) { + CV_Assert(intensity.type() == CV_16UC1); + CV_Assert(clipLimit >= 0 && clipLimit < 100); + CV_Assert(tilesGridSize >= 1 && tilesGridSize <= 64); + + // Apply the CLAHE algorithm to the intensity channel (luminance). + Ptr<CLAHE> clahe = createCLAHE(); + clahe->setClipLimit(clipLimit); + clahe->setTilesGridSize(Size(tilesGridSize, tilesGridSize)); + clahe->apply(intensity, intensity); +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/log.c b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/log.c new file mode 100755 index 0000000..c800810 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/log.c @@ -0,0 +1,143 @@ +#include "libcaer.h" +#include <stdatomic.h> +#include <stdarg.h> +#include <time.h> +#include <unistd.h> + +static atomic_uint_fast8_t caerLogLevel = ATOMIC_VAR_INIT(CAER_LOG_ERROR); +static atomic_int caerLogFileDescriptor1 = ATOMIC_VAR_INIT(STDERR_FILENO); +static atomic_int caerLogFileDescriptor2 = ATOMIC_VAR_INIT(-1); + +void caerLogLevelSet(uint8_t logLevel) { + atomic_store_explicit(&caerLogLevel, logLevel, memory_order_relaxed); +} + +uint8_t caerLogLevelGet(void) { + return (atomic_load_explicit(&caerLogLevel, memory_order_relaxed)); +} + +void caerLogFileDescriptorsSet(int fd1, int fd2) { + if (fd1 == fd2) { + // If the same fd is passed twice, just disable it the second time. + fd2 = -1; + } + + atomic_store_explicit(&caerLogFileDescriptor1, fd1, memory_order_relaxed); + atomic_store_explicit(&caerLogFileDescriptor2, fd2, memory_order_relaxed); +} + +void caerLog(uint8_t logLevel, const char *subSystem, const char *format, ...) { + // Check that subSystem and format are defined correctly. + if (subSystem == NULL || format == NULL) { + caerLog(CAER_LOG_ERROR, "Logger", "Missing subSystem or format strings. Neither can be NULL."); + return; + } + + // Only log messages if there is a destination (file-descriptor) to write them to. + int logFileDescriptor1 = atomic_load_explicit(&caerLogFileDescriptor1, memory_order_relaxed); + int logFileDescriptor2 = atomic_load_explicit(&caerLogFileDescriptor2, memory_order_relaxed); + + if (logFileDescriptor1 < 0 && logFileDescriptor2 < 0) { + // Logging is disabled. + return; + } + + // Only log messages above the specified severity level. + if (logLevel > atomic_load_explicit(&caerLogLevel, memory_order_relaxed)) { + return; + } + + // First prepend the time. + time_t currentTimeEpoch = time(NULL); + + // From localtime_r() man-page: "According to POSIX.1-2004, localtime() + // is required to behave as though tzset(3) was called, while + // localtime_r() does not have this requirement." + // So we make sure to call it here, to be portable. + tzset(); + +#if defined(OS_WINDOWS) + // localtime() is thread-safe on Windows (and there is no localtime_r() at all). + struct tm *currentTime = localtime(¤tTimeEpoch); +#else + struct tm currentTimeStruct; + struct tm *currentTime = ¤tTimeStruct; + localtime_r(¤tTimeEpoch, currentTime); +#endif + + // Following time format uses exactly 29 characters (8 separators/punctuation, + // 4 year, 2 month, 2 day, 2 hours, 2 minutes, 2 seconds, 2 'TZ', 5 timezone). + size_t currentTimeStringLength = 29; + char currentTimeString[currentTimeStringLength + 1]; // + 1 for terminating NUL byte. + strftime(currentTimeString, currentTimeStringLength + 1, "%Y-%m-%d %H:%M:%S (TZ%z)", currentTime); + + // Prepend debug level as a string to format. + const char *logLevelString; + switch (logLevel) { + case CAER_LOG_EMERGENCY: + logLevelString = "EMERGENCY"; + break; + + case CAER_LOG_ALERT: + logLevelString = "ALERT"; + break; + + case CAER_LOG_CRITICAL: + logLevelString = "CRITICAL"; + break; + + case CAER_LOG_ERROR: + logLevelString = "ERROR"; + break; + + case CAER_LOG_WARNING: + logLevelString = "WARNING"; + break; + + case CAER_LOG_NOTICE: + logLevelString = "NOTICE"; + break; + + case CAER_LOG_INFO: + logLevelString = "INFO"; + break; + + case CAER_LOG_DEBUG: + logLevelString = "DEBUG"; + break; + + default: + logLevelString = "UNKNOWN"; + break; + } + + // Copy all strings into one and ensure NUL termination. + size_t logLength = (size_t) snprintf(NULL, 0, "%s: %s: %s: %s\n", currentTimeString, logLevelString, subSystem, + format); + char logString[logLength + 1]; + snprintf(logString, logLength + 1, "%s: %s: %s: %s\n", currentTimeString, logLevelString, subSystem, format); + + va_list argptr; + + if (logFileDescriptor1 >= 0) { + va_start(argptr, format); +#if defined(OS_WINDOWS) + FILE *logFilePointer1 = fdopen(logFileDescriptor1, "a"); + vfprintf(logFilePointer1, logString, argptr); +#else + vdprintf(logFileDescriptor1, logString, argptr); +#endif + va_end(argptr); + } + + if (logFileDescriptor2 >= 0) { + va_start(argptr, format); +#if defined(OS_WINDOWS) + FILE *logFilePointer2 = fdopen(logFileDescriptor2, "a"); + vfprintf(logFilePointer2, logString, argptr); +#else + vdprintf(logFileDescriptor2, logString, argptr); +#endif + va_end(argptr); + } +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/ringbuffer/portable_aligned_alloc.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/ringbuffer/portable_aligned_alloc.h new file mode 100755 index 0000000..79c578d --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/ringbuffer/portable_aligned_alloc.h @@ -0,0 +1,34 @@ +#ifndef PORTABLE_ALIGNED_ALLOC_H_ +#define PORTABLE_ALIGNED_ALLOC_H_ + +#if (!defined(__APPLE__) && !defined(_WIN32) && (__STDC_VERSION__ >= 201112L || defined(_ISOC11_SOURCE))) + #include <stdlib.h> + + static inline void *portable_aligned_alloc(size_t alignment, size_t size) { + return (aligned_alloc(alignment, size)); + } +#elif (_POSIX_C_SOURCE >= 200112L || _XOPEN_SOURCE >= 600) + #include <stdlib.h> + + static inline void *portable_aligned_alloc(size_t alignment, size_t size) { + void* mem; + + if (posix_memalign(&mem, alignment, size) == 0) { + // Success! + return (mem); + } + + // Failure. + return (NULL); + } +#elif defined(_WIN32) || defined(__CYGWIN__) + #include <malloc.h> + + static inline void *portable_aligned_alloc(size_t alignment, size_t size) { + return (_aligned_malloc(size, alignment)); + } +#else + #error "No portable way of getting aligned memory found." +#endif + +#endif /* PORTABLE_ALIGNED_ALLOC_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/ringbuffer/ringbuffer.c b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/ringbuffer/ringbuffer.c new file mode 100755 index 0000000..3f38893 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/ringbuffer/ringbuffer.c @@ -0,0 +1,117 @@ +/* + * ringbuffer.c + * + * Created on: Dec 10, 2013 + * Author: llongi + */ + +#include "ringbuffer.h" +#include "portable_aligned_alloc.h" +#include <stdatomic.h> +#include <stdalign.h> // To get alignas() macro. + +// Alignment specification support (with defines for cache line alignment). +#undef CACHELINE_ALIGNED +#undef CACHELINE_ALONE + +#if !defined(CACHELINE_SIZE) + #define CACHELINE_SIZE 64 // Default (big enough for almost all processors). + // Must be power of two! +#endif + +#define CACHELINE_ALIGNED alignas(CACHELINE_SIZE) +#define CACHELINE_ALONE(t, v) CACHELINE_ALIGNED t v; uint8_t PAD_##v[CACHELINE_SIZE - (sizeof(t) & (CACHELINE_SIZE - 1))] + +struct ring_buffer { + CACHELINE_ALONE(size_t, putPos); + CACHELINE_ALONE(size_t, getPos); + CACHELINE_ALONE(size_t, size); + atomic_uintptr_t elements[]; +}; + +RingBuffer ringBufferInit(size_t size) { + // Force multiple of two size for performance. + if (size == 0 || (size & (size - 1)) != 0) { + return (NULL); + } + + RingBuffer rBuf = portable_aligned_alloc(CACHELINE_SIZE, + sizeof(struct ring_buffer) + (size * sizeof(atomic_uintptr_t))); + if (rBuf == NULL) { + return (NULL); + } + + // Initialize counter variables. + rBuf->putPos = 0; + rBuf->getPos = 0; + rBuf->size = size; + + // Initialize pointers. + for (size_t i = 0; i < size; i++) { + atomic_store_explicit(&rBuf->elements[i], (uintptr_t) NULL, memory_order_relaxed); + } + + atomic_thread_fence(memory_order_release); + + return (rBuf); +} + +void ringBufferFree(RingBuffer rBuf) { + free(rBuf); +} + +bool ringBufferPut(RingBuffer rBuf, void *elem) { + if (elem == NULL) { + // NULL elements are disallowed (used as place-holders). + // Critical error, should never happen -> exit! + exit(EXIT_FAILURE); + } + + void *curr = (void *) atomic_load_explicit(&rBuf->elements[rBuf->putPos], memory_order_acquire); + + // If the place where we want to put the new element is NULL, it's still + // free and we can use it. + if (curr == NULL) { + atomic_store_explicit(&rBuf->elements[rBuf->putPos], (uintptr_t ) elem, memory_order_release); + + // Increase local put pointer. + rBuf->putPos = ((rBuf->putPos + 1) & (rBuf->size - 1)); + + return (true); + } + + // Else, buffer is full. + return (false); +} + +void *ringBufferGet(RingBuffer rBuf) { + void *curr = (void *) atomic_load_explicit(&rBuf->elements[rBuf->getPos], memory_order_acquire); + + // If the place where we want to get an element from is not NULL, there + // is valid content there, which we return, and reset the place to NULL. + if (curr != NULL) { + atomic_store_explicit(&rBuf->elements[rBuf->getPos], (uintptr_t) NULL, memory_order_release); + + // Increase local get pointer. + rBuf->getPos = ((rBuf->getPos + 1) & (rBuf->size - 1)); + + return (curr); + } + + // Else, buffer is empty. + return (NULL); +} + +void *ringBufferLook(RingBuffer rBuf) { + void *curr = (void *) atomic_load_explicit(&rBuf->elements[rBuf->getPos], memory_order_acquire); + + // If the place where we want to get an element from is not NULL, there + // is valid content there, which we return, without removing it from the + // ring buffer. + if (curr != NULL) { + return (curr); + } + + // Else, buffer is empty. + return (NULL); +} diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/ringbuffer/ringbuffer.h b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/ringbuffer/ringbuffer.h new file mode 100755 index 0000000..947775d --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer/src/ringbuffer/ringbuffer.h @@ -0,0 +1,24 @@ +/* + * ringbuffer.h + * + * Created on: Dec 10, 2013 + * Author: llongi + */ + +#ifndef RINGBUFFER_H_ +#define RINGBUFFER_H_ + +// Common includes, useful for everyone. +#include <stdlib.h> +#include <stdbool.h> +#include <stdint.h> + +typedef struct ring_buffer *RingBuffer; + +RingBuffer ringBufferInit(size_t size); +void ringBufferFree(RingBuffer rBuf); +bool ringBufferPut(RingBuffer rBuf, void *elem); +void *ringBufferGet(RingBuffer rBuf); +void *ringBufferLook(RingBuffer rBuf); + +#endif /* RINGBUFFER_H_ */ diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/65-inilabs.rules b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/65-inilabs.rules new file mode 100755 index 0000000..511feed --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/65-inilabs.rules @@ -0,0 +1,3 @@ +# All DVS/DAVIS systems + +SUBSYSTEM=="usb", ATTR{idVendor}=="152a", ATTR{idProduct}=="84[0-1]?", MODE="0666" diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/CMakeLists.txt b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/CMakeLists.txt new file mode 100755 index 0000000..1449acb --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/CMakeLists.txt @@ -0,0 +1,30 @@ +cmake_minimum_required(VERSION 2.8.3) +project(libcaer_catkin) + +find_package(catkin_simple REQUIRED) + +catkin_simple() + +include(ExternalProject) + +file(MAKE_DIRECTORY ${CATKIN_DEVEL_PREFIX}/include/libcaer) + +ExternalProject_Add(libcaer_src + GIT_REPOSITORY https://github.com/inilabs/libcaer.git + GIT_TAG 57466910da84c25231aab57e99f246239722a628 + UPDATE_COMMAND "" + CMAKE_ARGS -DCMAKE_INSTALL_PREFIX:PATH=${CATKIN_DEVEL_PREFIX} -DCMAKE_BUILD_TYPE:STRING=Release -DCMAKE_INSTALL_LIBDIR=${CATKIN_DEVEL_PREFIX}/lib + BUILD_COMMAND make + INSTALL_COMMAND make install +) + +cs_install() +install(DIRECTORY ${CATKIN_DEVEL_PREFIX}/include/libcaer + DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION} + FILES_MATCHING + PATTERN "*.h" + PATTERN ".svn" EXCLUDE +) + +cs_export(INCLUDE_DIRS ${CATKIN_DEVEL_PREFIX}/include/libcaer/ + CFG_EXTRAS libcaer-extras.cmake) diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/cmake/libcaer-extras.cmake b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/cmake/libcaer-extras.cmake new file mode 100755 index 0000000..298368a --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/cmake/libcaer-extras.cmake @@ -0,0 +1,4 @@ +# This overrides the dependency tracker with the caer library file. +set(@PROJECT_NAME@_LIBRARIES + @CATKIN_DEVEL_PREFIX@/lib/libcaer${CMAKE_SHARED_LIBRARY_SUFFIX}) +set(@PROJECT_NAME@_INCLUDE_DIR @CATKIN_DEVEL_PREFIX@/include) diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/install.sh b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/install.sh new file mode 100755 index 0000000..20619f3 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/install.sh @@ -0,0 +1,9 @@ +#!/bin/bash +echo "Copying udev rule (needs root privileges)." +sudo cp 65-inilabs.rules /etc/udev/rules.d/ + +echo "Reloading udev rules." +sudo udevadm control --reload-rules +sudo udevadm trigger + +echo "Done!" diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/package.xml b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/package.xml new file mode 100755 index 0000000..8dd9c98 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/libcaer_catkin/package.xml @@ -0,0 +1,11 @@ +<?xml version="1.0"?> +<package format="2"> + <name>libcaer_catkin</name> + <version>0.0.0</version> + <description>The libcaer_catkin package</description> + <maintainer email="mueggler@ifi.uzh.ch">Elias Mueggler</maintainer> + <license>GNU GPL</license> + + <buildtool_depend>catkin</buildtool_depend> + <buildtool_depend>catkin_simple</buildtool_depend> +</package> diff --git a/RWR/src/read_event_pub/src/dvs_clustering_tracking/rpg_dvs_ros b/RWR/src/read_event_pub/src/dvs_clustering_tracking/rpg_dvs_ros new file mode 160000 index 0000000..95f08d5 --- /dev/null +++ b/RWR/src/read_event_pub/src/dvs_clustering_tracking/rpg_dvs_ros @@ -0,0 +1 @@ +Subproject commit 95f08d565c3115b181a4763e1e350f4df0375c4b -- GitLab