From 7ae27412244b14b0c20161a56f64b89bf12232cd Mon Sep 17 00:00:00 2001 From: Myzhar Date: Fri, 7 Sep 2018 14:01:44 +0200 Subject: [PATCH 01/55] Added Video subscribing tutorial --- zed_video_sub_tutorial/CMakeLists.txt | 14 +++ zed_video_sub_tutorial/package.xml | 14 +++ .../src/zed_video_sub_tutorial.cpp | 89 +++++++++++++++++++ 3 files changed, 117 insertions(+) create mode 100644 zed_video_sub_tutorial/CMakeLists.txt create mode 100644 zed_video_sub_tutorial/package.xml create mode 100644 zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp diff --git a/zed_video_sub_tutorial/CMakeLists.txt b/zed_video_sub_tutorial/CMakeLists.txt new file mode 100644 index 00000000..f26608ab --- /dev/null +++ b/zed_video_sub_tutorial/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.3) +project(zed_video_sub_tutorial) + +## Find catkin and any catkin packages +find_package(catkin REQUIRED COMPONENTS roscpp sensor_msgs) + +## Declare a catkin package +catkin_package() + +include_directories(include ${catkin_INCLUDE_DIRS}) + +## Build +add_executable(zed_video_sub src/zed_video_sub_tutorial.cpp) +target_link_libraries(zed_video_sub ${catkin_LIBRARIES}) diff --git a/zed_video_sub_tutorial/package.xml b/zed_video_sub_tutorial/package.xml new file mode 100644 index 00000000..2c7c7a56 --- /dev/null +++ b/zed_video_sub_tutorial/package.xml @@ -0,0 +1,14 @@ + + zed_video_sub_tutorial + 1.0.0 + + This package is a tutorial showing how to subscribe to ZED Video streams + + STEREOLABS + BSD + + catkin + + roscpp + sensor_msgs + diff --git a/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp b/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp new file mode 100644 index 00000000..7f064cfc --- /dev/null +++ b/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp @@ -0,0 +1,89 @@ +#include +#include + +/** + * This tutorial demonstrates simple receipt of ZED image messages over the ROS system. + */ + + +/** + * Subscriber callbacks + */ +void imageRgbRawCallback(const sensor_msgs::Image::ConstPtr& msg) { + ROS_INFO("RGB RAW image received from ZED - Size: %dx%d", msg->width, msg->height); +} + +void imageRgbRectCallback(const sensor_msgs::Image::ConstPtr& msg) { + ROS_INFO("RGB Rectified image received from ZED - Size: %dx%d", msg->width, msg->height); +} + +void imageRightRawCallback(const sensor_msgs::Image::ConstPtr& msg) { + ROS_INFO("Right RAW image received from ZED - Size: %dx%d", msg->width, msg->height); +} + +void imageRightRectCallback(const sensor_msgs::Image::ConstPtr& msg) { + ROS_INFO("Right Rectified image received from ZED - Size: %dx%d", msg->width, msg->height); +} + +void imageLeftRawCallback(const sensor_msgs::Image::ConstPtr& msg) { + ROS_INFO("Left RAW image received from ZED - Size: %dx%d", msg->width, msg->height); +} + +void imageLeftRectCallback(const sensor_msgs::Image::ConstPtr& msg) { + ROS_INFO("Left Rectified image received from ZED - Size: %dx%d", msg->width, msg->height); +} + +/** + * Node main function + */ +int main(int argc, char** argv) { + /** + * The ros::init() function needs to see argc and argv so that it can perform + * any ROS arguments and name remapping that were provided at the command line. + * For programmatic remappings you can use a different version of init() which takes + * remappings directly, but for most command-line programs, passing argc and argv is + * the easiest way to do it. The third argument to init() is the name of the node. + * + * You must call one of the versions of ros::init() before using any other + * part of the ROS system. + */ + ros::init(argc, argv, "zed_video_subscriber"); + + /** + * NodeHandle is the main access point to communications with the ROS system. + * The first NodeHandle constructed will fully initialize this node, and the last + * NodeHandle destructed will close down the node. + */ + ros::NodeHandle n; + + /** + * The subscribe() call is how you tell ROS that you want to receive messages + * on a given topic. This invokes a call to the ROS + * master node, which keeps a registry of who is publishing and who + * is subscribing. Messages are passed to a callback function, here + * called imageCallback. subscribe() returns a Subscriber object that you + * must hold on to until you want to unsubscribe. When all copies of the Subscriber + * object go out of scope, this callback will automatically be unsubscribed from + * this topic. + * + * The second parameter to the subscribe() function is the size of the message + * queue. If messages are arriving faster than they are being processed, this + * is the number of messages that will be buffered up before beginning to throw + * away the oldest ones. + */ + ros::Subscriber subRgbRaw = n.subscribe("/zed/rgb/image_raw_color", 10, imageRgbRawCallback); + ros::Subscriber subRgbRect = n.subscribe("/zed/rgb/image_rect_color", 10, imageRgbRectCallback); + ros::Subscriber subRightRaw = n.subscribe("/zed/right/image_raw_color", 10, imageRightRawCallback); + ros::Subscriber subRightRect = n.subscribe("/zed/right/image_rect_color", 10, imageRightRectCallback); + ros::Subscriber subLeftRaw = n.subscribe("/zed/left/image_raw_color", 10, imageLeftRawCallback); + ros::Subscriber subLeftRect = n.subscribe("/zed/left/image_rect_color", 10, imageLeftRectCallback); + + /** + * ros::spin() will enter a loop, pumping callbacks. With this version, all + * callbacks will be called from within this thread (the main one). ros::spin() + * will exit when Ctrl-C is pressed, or the node is shutdown by the master. + */ + ros::spin(); + + return 0; +} From ba2183a00bee1cbca3549ea96b98915482d990ed Mon Sep 17 00:00:00 2001 From: Myzhar Date: Fri, 7 Sep 2018 15:26:12 +0200 Subject: [PATCH 02/55] Added Depth tutorial * New folder organization --- .../zed_depth_sub_tutorial/CMakeLists.txt | 14 +++ tutorials/zed_depth_sub_tutorial/package.xml | 14 +++ .../src/zed_depth_sub_tutorial.cpp | 90 +++++++++++++++++++ .../zed_video_sub_tutorial}/CMakeLists.txt | 0 .../zed_video_sub_tutorial}/package.xml | 0 .../src/zed_video_sub_tutorial.cpp | 11 +-- 6 files changed, 124 insertions(+), 5 deletions(-) create mode 100644 tutorials/zed_depth_sub_tutorial/CMakeLists.txt create mode 100644 tutorials/zed_depth_sub_tutorial/package.xml create mode 100644 tutorials/zed_depth_sub_tutorial/src/zed_depth_sub_tutorial.cpp rename {zed_video_sub_tutorial => tutorials/zed_video_sub_tutorial}/CMakeLists.txt (100%) rename {zed_video_sub_tutorial => tutorials/zed_video_sub_tutorial}/package.xml (100%) rename {zed_video_sub_tutorial => tutorials/zed_video_sub_tutorial}/src/zed_video_sub_tutorial.cpp (87%) diff --git a/tutorials/zed_depth_sub_tutorial/CMakeLists.txt b/tutorials/zed_depth_sub_tutorial/CMakeLists.txt new file mode 100644 index 00000000..03dda9b4 --- /dev/null +++ b/tutorials/zed_depth_sub_tutorial/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.3) +project(zed_depth_sub_tutorial) + +## Find catkin and any catkin packages +find_package(catkin REQUIRED COMPONENTS roscpp sensor_msgs) + +## Declare a catkin package +catkin_package() + +include_directories(include ${catkin_INCLUDE_DIRS}) + +## Build +add_executable(zed_depth_sub src/zed_depth_sub_tutorial.cpp) +target_link_libraries(zed_depth_sub ${catkin_LIBRARIES}) diff --git a/tutorials/zed_depth_sub_tutorial/package.xml b/tutorials/zed_depth_sub_tutorial/package.xml new file mode 100644 index 00000000..6b0989da --- /dev/null +++ b/tutorials/zed_depth_sub_tutorial/package.xml @@ -0,0 +1,14 @@ + + zed_depth_sub_tutorial + 1.0.0 + + This package is a tutorial showing how to subscribe to ZED depth streams + + STEREOLABS + BSD + + catkin + + roscpp + sensor_msgs + diff --git a/tutorials/zed_depth_sub_tutorial/src/zed_depth_sub_tutorial.cpp b/tutorials/zed_depth_sub_tutorial/src/zed_depth_sub_tutorial.cpp new file mode 100644 index 00000000..ed1e39b5 --- /dev/null +++ b/tutorials/zed_depth_sub_tutorial/src/zed_depth_sub_tutorial.cpp @@ -0,0 +1,90 @@ +#include +#include + +/** + * This tutorial demonstrates simple receipt of ZED image messages over the ROS system. + */ + + +/** + * Subscriber callbacks. The argument of the callback is a constant pointer to the received message + */ + +void imageRgbRawCallback(const sensor_msgs::Image::ConstPtr& msg) { + ROS_INFO("RGB RAW image received from ZED - Size: %dx%d", msg->width, msg->height); +} + +void imageRgbRectCallback(const sensor_msgs::Image::ConstPtr& msg) { + ROS_INFO("RGB Rectified image received from ZED - Size: %dx%d", msg->width, msg->height); +} + +void imageRightRawCallback(const sensor_msgs::Image::ConstPtr& msg) { + ROS_INFO("Right RAW image received from ZED - Size: %dx%d", msg->width, msg->height); +} + +void imageRightRectCallback(const sensor_msgs::Image::ConstPtr& msg) { + ROS_INFO("Right Rectified image received from ZED - Size: %dx%d", msg->width, msg->height); +} + +void imageLeftRawCallback(const sensor_msgs::Image::ConstPtr& msg) { + ROS_INFO("Left RAW image received from ZED - Size: %dx%d", msg->width, msg->height); +} + +void imageLeftRectCallback(const sensor_msgs::Image::ConstPtr& msg) { + ROS_INFO("Left Rectified image received from ZED - Size: %dx%d", msg->width, msg->height); +} + +/** + * Node main function + */ +int main(int argc, char** argv) { + /** + * The ros::init() function needs to see argc and argv so that it can perform + * any ROS arguments and name remapping that were provided at the command line. + * For programmatic remappings you can use a different version of init() which takes + * remappings directly, but for most command-line programs, passing argc and argv is + * the easiest way to do it. The third argument to init() is the name of the node. + * + * You must call one of the versions of ros::init() before using any other + * part of the ROS system. + */ + ros::init(argc, argv, "zed_video_subscriber"); + + /** + * NodeHandle is the main access point to communications with the ROS system. + * The first NodeHandle constructed will fully initialize this node, and the last + * NodeHandle destructed will close down the node. + */ + ros::NodeHandle n; + + /** + * The subscribe() call is how you tell ROS that you want to receive messages + * on a given topic. This invokes a call to the ROS + * master node, which keeps a registry of who is publishing and who + * is subscribing. Messages are passed to a callback function, here + * called imageCallback. subscribe() returns a Subscriber object that you + * must hold on to until you want to unsubscribe. When all copies of the Subscriber + * object go out of scope, this callback will automatically be unsubscribed from + * this topic. + * + * The second parameter to the subscribe() function is the size of the message + * queue. If messages are arriving faster than they are being processed, this + * is the number of messages that will be buffered up before beginning to throw + * away the oldest ones. + */ + ros::Subscriber subRgbRaw = n.subscribe("/zed/rgb/image_raw_color", 10, imageRgbRawCallback); + ros::Subscriber subRgbRect = n.subscribe("/zed/rgb/image_rect_color", 10, imageRgbRectCallback); + ros::Subscriber subRightRaw = n.subscribe("/zed/right/image_raw_color", 10, imageRightRawCallback); + ros::Subscriber subRightRect = n.subscribe("/zed/right/image_rect_color", 10, imageRightRectCallback); + ros::Subscriber subLeftRaw = n.subscribe("/zed/left/image_raw_color", 10, imageLeftRawCallback); + ros::Subscriber subLeftRect = n.subscribe("/zed/left/image_rect_color", 10, imageLeftRectCallback); + + /** + * ros::spin() will enter a loop, pumping callbacks. With this version, all + * callbacks will be called from within this thread (the main one). ros::spin() + * will exit when Ctrl-C is pressed, or the node is shutdown by the master. + */ + ros::spin(); + + return 0; +} diff --git a/zed_video_sub_tutorial/CMakeLists.txt b/tutorials/zed_video_sub_tutorial/CMakeLists.txt similarity index 100% rename from zed_video_sub_tutorial/CMakeLists.txt rename to tutorials/zed_video_sub_tutorial/CMakeLists.txt diff --git a/zed_video_sub_tutorial/package.xml b/tutorials/zed_video_sub_tutorial/package.xml similarity index 100% rename from zed_video_sub_tutorial/package.xml rename to tutorials/zed_video_sub_tutorial/package.xml diff --git a/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp b/tutorials/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp similarity index 87% rename from zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp rename to tutorials/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp index 7f064cfc..ed1e39b5 100644 --- a/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp +++ b/tutorials/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp @@ -7,8 +7,9 @@ /** - * Subscriber callbacks + * Subscriber callbacks. The argument of the callback is a constant pointer to the received message */ + void imageRgbRawCallback(const sensor_msgs::Image::ConstPtr& msg) { ROS_INFO("RGB RAW image received from ZED - Size: %dx%d", msg->width, msg->height); } @@ -71,12 +72,12 @@ int main(int argc, char** argv) { * is the number of messages that will be buffered up before beginning to throw * away the oldest ones. */ - ros::Subscriber subRgbRaw = n.subscribe("/zed/rgb/image_raw_color", 10, imageRgbRawCallback); - ros::Subscriber subRgbRect = n.subscribe("/zed/rgb/image_rect_color", 10, imageRgbRectCallback); + ros::Subscriber subRgbRaw = n.subscribe("/zed/rgb/image_raw_color", 10, imageRgbRawCallback); + ros::Subscriber subRgbRect = n.subscribe("/zed/rgb/image_rect_color", 10, imageRgbRectCallback); ros::Subscriber subRightRaw = n.subscribe("/zed/right/image_raw_color", 10, imageRightRawCallback); ros::Subscriber subRightRect = n.subscribe("/zed/right/image_rect_color", 10, imageRightRectCallback); - ros::Subscriber subLeftRaw = n.subscribe("/zed/left/image_raw_color", 10, imageLeftRawCallback); - ros::Subscriber subLeftRect = n.subscribe("/zed/left/image_rect_color", 10, imageLeftRectCallback); + ros::Subscriber subLeftRaw = n.subscribe("/zed/left/image_raw_color", 10, imageLeftRawCallback); + ros::Subscriber subLeftRect = n.subscribe("/zed/left/image_rect_color", 10, imageLeftRectCallback); /** * ros::spin() will enter a loop, pumping callbacks. With this version, all From b3d7eb206a41e1caefdf9c275b8ca95fd731a3b4 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Fri, 7 Sep 2018 15:27:46 +0200 Subject: [PATCH 03/55] Create readme.md --- tutorials/readme.md | 1 + 1 file changed, 1 insertion(+) create mode 100644 tutorials/readme.md diff --git a/tutorials/readme.md b/tutorials/readme.md new file mode 100644 index 00000000..81c8590f --- /dev/null +++ b/tutorials/readme.md @@ -0,0 +1 @@ +# Tutorials From f3314c5fa7723ef97d66a7c9cd64d715e5f39a96 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Fri, 7 Sep 2018 15:28:40 +0200 Subject: [PATCH 04/55] Create README.md --- tutorials/zed_depth_sub_tutorial/README.md | 1 + 1 file changed, 1 insertion(+) create mode 100644 tutorials/zed_depth_sub_tutorial/README.md diff --git a/tutorials/zed_depth_sub_tutorial/README.md b/tutorials/zed_depth_sub_tutorial/README.md new file mode 100644 index 00000000..bfa005a7 --- /dev/null +++ b/tutorials/zed_depth_sub_tutorial/README.md @@ -0,0 +1 @@ +# Depth subscription tutorial From e9bd2567d51d12843a03500312458eda1a887b5e Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Fri, 7 Sep 2018 15:57:03 +0200 Subject: [PATCH 05/55] Create README.md --- tutorials/zed_video_sub_tutorial/README.md | 1 + 1 file changed, 1 insertion(+) create mode 100644 tutorials/zed_video_sub_tutorial/README.md diff --git a/tutorials/zed_video_sub_tutorial/README.md b/tutorials/zed_video_sub_tutorial/README.md new file mode 100644 index 00000000..03fa4c9d --- /dev/null +++ b/tutorials/zed_video_sub_tutorial/README.md @@ -0,0 +1 @@ +# ZED video subscription tutorial From 1d208d6385764dff8f3186010c710f8ba772d330 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Fri, 7 Sep 2018 16:03:41 +0200 Subject: [PATCH 06/55] Simpliefied the code of the Video tutorial --- .../src/zed_video_sub_tutorial.cpp | 31 ++++--------------- 1 file changed, 6 insertions(+), 25 deletions(-) diff --git a/tutorials/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp b/tutorials/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp index ed1e39b5..f22aa91c 100644 --- a/tutorials/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp +++ b/tutorials/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp @@ -2,7 +2,8 @@ #include /** - * This tutorial demonstrates simple receipt of ZED image messages over the ROS system. + * This tutorial demonstrates how to receive the Left and Right rectified images + * from the ZED node */ @@ -10,27 +11,11 @@ * Subscriber callbacks. The argument of the callback is a constant pointer to the received message */ -void imageRgbRawCallback(const sensor_msgs::Image::ConstPtr& msg) { - ROS_INFO("RGB RAW image received from ZED - Size: %dx%d", msg->width, msg->height); -} - -void imageRgbRectCallback(const sensor_msgs::Image::ConstPtr& msg) { - ROS_INFO("RGB Rectified image received from ZED - Size: %dx%d", msg->width, msg->height); -} - -void imageRightRawCallback(const sensor_msgs::Image::ConstPtr& msg) { - ROS_INFO("Right RAW image received from ZED - Size: %dx%d", msg->width, msg->height); -} - -void imageRightRectCallback(const sensor_msgs::Image::ConstPtr& msg) { +void imageRightRectifiedCallback(const sensor_msgs::Image::ConstPtr& msg) { ROS_INFO("Right Rectified image received from ZED - Size: %dx%d", msg->width, msg->height); } -void imageLeftRawCallback(const sensor_msgs::Image::ConstPtr& msg) { - ROS_INFO("Left RAW image received from ZED - Size: %dx%d", msg->width, msg->height); -} - -void imageLeftRectCallback(const sensor_msgs::Image::ConstPtr& msg) { +void imageLeftRectCifiedallback(const sensor_msgs::Image::ConstPtr& msg) { ROS_INFO("Left Rectified image received from ZED - Size: %dx%d", msg->width, msg->height); } @@ -72,12 +57,8 @@ int main(int argc, char** argv) { * is the number of messages that will be buffered up before beginning to throw * away the oldest ones. */ - ros::Subscriber subRgbRaw = n.subscribe("/zed/rgb/image_raw_color", 10, imageRgbRawCallback); - ros::Subscriber subRgbRect = n.subscribe("/zed/rgb/image_rect_color", 10, imageRgbRectCallback); - ros::Subscriber subRightRaw = n.subscribe("/zed/right/image_raw_color", 10, imageRightRawCallback); - ros::Subscriber subRightRect = n.subscribe("/zed/right/image_rect_color", 10, imageRightRectCallback); - ros::Subscriber subLeftRaw = n.subscribe("/zed/left/image_raw_color", 10, imageLeftRawCallback); - ros::Subscriber subLeftRect = n.subscribe("/zed/left/image_rect_color", 10, imageLeftRectCallback); + ros::Subscriber subRightRectified = n.subscribe("/zed/right/image_rect_color", 10, imageRightRectifiedCallback); + ros::Subscriber subLeftRectified = n.subscribe("/zed/left/image_rect_color", 10, imageLeftRectifiedCallback); /** * ros::spin() will enter a loop, pumping callbacks. With this version, all From fbd9d56c95d54b93153e5ce07d6c6eb1168a2f1b Mon Sep 17 00:00:00 2001 From: Myzhar Date: Fri, 7 Sep 2018 16:04:57 +0200 Subject: [PATCH 07/55] Minor change --- tutorials/readme.md | 1 - 1 file changed, 1 deletion(-) delete mode 100644 tutorials/readme.md diff --git a/tutorials/readme.md b/tutorials/readme.md deleted file mode 100644 index 81c8590f..00000000 --- a/tutorials/readme.md +++ /dev/null @@ -1 +0,0 @@ -# Tutorials From 12ee09ce8fd2ff9cc6d06a8046828cb6a036453e Mon Sep 17 00:00:00 2001 From: Myzhar Date: Fri, 7 Sep 2018 16:25:54 +0200 Subject: [PATCH 08/55] Folder reorganization --- README.md | 15 +++++++++++---- examples/README.md | 0 .../zed_nodelet_example}/CMakeLists.txt | 0 .../zed_nodelet_example}/README.md | 0 .../images/laserscan-depthcloud.png | Bin .../zed_nodelet_example}/images/laserscan.png | Bin .../launch/zed_nodelet_laserscan.launch | 0 .../zed_nodelet_example}/package.xml | 0 .../zed_rtabmap_example}/CMakeLists.txt | 0 .../zed_rtabmap_example}/README.md | 0 .../zed_rtabmap_example}/images/rtab-map.png | Bin .../launch/zed_rtabmap.launch | 0 .../zed_rtabmap_example}/package.xml | 0 tutorials/README.md | 1 + 14 files changed, 12 insertions(+), 4 deletions(-) create mode 100644 examples/README.md rename {zed_nodelet_example => examples/zed_nodelet_example}/CMakeLists.txt (100%) rename {zed_nodelet_example => examples/zed_nodelet_example}/README.md (100%) rename {zed_nodelet_example => examples/zed_nodelet_example}/images/laserscan-depthcloud.png (100%) rename {zed_nodelet_example => examples/zed_nodelet_example}/images/laserscan.png (100%) rename {zed_nodelet_example => examples/zed_nodelet_example}/launch/zed_nodelet_laserscan.launch (100%) rename {zed_nodelet_example => examples/zed_nodelet_example}/package.xml (100%) rename {zed_rtabmap_example => examples/zed_rtabmap_example}/CMakeLists.txt (100%) rename {zed_rtabmap_example => examples/zed_rtabmap_example}/README.md (100%) rename {zed_rtabmap_example => examples/zed_rtabmap_example}/images/rtab-map.png (100%) rename {zed_rtabmap_example => examples/zed_rtabmap_example}/launch/zed_rtabmap.launch (100%) rename {zed_rtabmap_example => examples/zed_rtabmap_example}/package.xml (100%) create mode 100644 tutorials/README.md diff --git a/README.md b/README.md index ef9653e5..2691c36e 100644 --- a/README.md +++ b/README.md @@ -57,12 +57,19 @@ To launch the wrapper without Rviz, use: $ roslaunch zed_wrapper zed.launch serial_number:=1010 #replace 1010 with the actual SN -### Modules +### Examples -Alongside the wrapper itself and the Rviz display, a few other modules are provided to interface the ZED with other ROS packages : +Alongside the wrapper itself and the Rviz display, a few examples are provided to interface the ZED with other ROS packages : -- [RTAB-Map](http://introlab.github.io/rtabmap/) : See [zed_rtabmap_example](./zed_rtabmap_example) -- ROS Nodelet, `depthimage_to_laserscan` : See [zed_nodelet_example](./zed_nodelet_example) +- [RTAB-Map](http://introlab.github.io/rtabmap/) : See [zed_rtabmap_example](./examples/zed_rtabmap_example) +- ROS Nodelet, `depthimage_to_laserscan` : See [zed_nodelet_example](./examples/zed_nodelet_example) + +### Tutorials + +A few tutorials are provided to understand how to use the ZED node in the ROS environment : + +- Video subscribing : See [zed_video_sub_tutorial](./tutorials/zed_video_sub_tutorial) +- Depth subscribing : See [zed_depth_sub_tutorial](./tutorials/zed_depth_sub_tutorial) [More](https://www.stereolabs.com/documentation/guides/using-zed-with-ros/introduction.html) diff --git a/examples/README.md b/examples/README.md new file mode 100644 index 00000000..e69de29b diff --git a/zed_nodelet_example/CMakeLists.txt b/examples/zed_nodelet_example/CMakeLists.txt similarity index 100% rename from zed_nodelet_example/CMakeLists.txt rename to examples/zed_nodelet_example/CMakeLists.txt diff --git a/zed_nodelet_example/README.md b/examples/zed_nodelet_example/README.md similarity index 100% rename from zed_nodelet_example/README.md rename to examples/zed_nodelet_example/README.md diff --git a/zed_nodelet_example/images/laserscan-depthcloud.png b/examples/zed_nodelet_example/images/laserscan-depthcloud.png similarity index 100% rename from zed_nodelet_example/images/laserscan-depthcloud.png rename to examples/zed_nodelet_example/images/laserscan-depthcloud.png diff --git a/zed_nodelet_example/images/laserscan.png b/examples/zed_nodelet_example/images/laserscan.png similarity index 100% rename from zed_nodelet_example/images/laserscan.png rename to examples/zed_nodelet_example/images/laserscan.png diff --git a/zed_nodelet_example/launch/zed_nodelet_laserscan.launch b/examples/zed_nodelet_example/launch/zed_nodelet_laserscan.launch similarity index 100% rename from zed_nodelet_example/launch/zed_nodelet_laserscan.launch rename to examples/zed_nodelet_example/launch/zed_nodelet_laserscan.launch diff --git a/zed_nodelet_example/package.xml b/examples/zed_nodelet_example/package.xml similarity index 100% rename from zed_nodelet_example/package.xml rename to examples/zed_nodelet_example/package.xml diff --git a/zed_rtabmap_example/CMakeLists.txt b/examples/zed_rtabmap_example/CMakeLists.txt similarity index 100% rename from zed_rtabmap_example/CMakeLists.txt rename to examples/zed_rtabmap_example/CMakeLists.txt diff --git a/zed_rtabmap_example/README.md b/examples/zed_rtabmap_example/README.md similarity index 100% rename from zed_rtabmap_example/README.md rename to examples/zed_rtabmap_example/README.md diff --git a/zed_rtabmap_example/images/rtab-map.png b/examples/zed_rtabmap_example/images/rtab-map.png similarity index 100% rename from zed_rtabmap_example/images/rtab-map.png rename to examples/zed_rtabmap_example/images/rtab-map.png diff --git a/zed_rtabmap_example/launch/zed_rtabmap.launch b/examples/zed_rtabmap_example/launch/zed_rtabmap.launch similarity index 100% rename from zed_rtabmap_example/launch/zed_rtabmap.launch rename to examples/zed_rtabmap_example/launch/zed_rtabmap.launch diff --git a/zed_rtabmap_example/package.xml b/examples/zed_rtabmap_example/package.xml similarity index 100% rename from zed_rtabmap_example/package.xml rename to examples/zed_rtabmap_example/package.xml diff --git a/tutorials/README.md b/tutorials/README.md new file mode 100644 index 00000000..81c8590f --- /dev/null +++ b/tutorials/README.md @@ -0,0 +1 @@ +# Tutorials From 5c26c9be439655d941f6658d00ca2bab70d09895 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Fri, 7 Sep 2018 16:32:23 +0200 Subject: [PATCH 09/55] Update README.md --- examples/README.md | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/examples/README.md b/examples/README.md index e69de29b..b4aac315 100644 --- a/examples/README.md +++ b/examples/README.md @@ -0,0 +1,5 @@ +# Examples +How to use the ZED ROS node with other ROS packages + +* `zed_nodelet_example`: shows how to use the nodelet intraprocess communication to generate a virtual laser scan using the [depthimage_to_laserscan](http://wiki.ros.org/depthimage_to_laserscan) package +* `zed_rtabmap_example`: shows how to use the ZED with the RTABMap package to generate a 3D map with the [rtabmap_ros](http://wiki.ros.org/rtabmap_ros) package From da2f17c8599cb07826a9fe38bbedcf48a911f6ee Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Fri, 7 Sep 2018 16:33:47 +0200 Subject: [PATCH 10/55] Update README.md --- tutorials/README.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/tutorials/README.md b/tutorials/README.md index 81c8590f..74caa945 100644 --- a/tutorials/README.md +++ b/tutorials/README.md @@ -1 +1,5 @@ # Tutorials +A series of tutorials are provided to better understand how to use the ZED node in the ROS environment : + +- Video subscribing : See [zed_video_sub_tutorial](./tutorials/zed_video_sub_tutorial) +- Depth subscribing : See [zed_depth_sub_tutorial](./tutorials/zed_depth_sub_tutorial) From f1b82466b0b21b84900416d4289011ec0feb8bd5 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Fri, 7 Sep 2018 16:34:13 +0200 Subject: [PATCH 11/55] Update README.md --- tutorials/README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tutorials/README.md b/tutorials/README.md index 74caa945..d14e96ad 100644 --- a/tutorials/README.md +++ b/tutorials/README.md @@ -1,5 +1,5 @@ # Tutorials A series of tutorials are provided to better understand how to use the ZED node in the ROS environment : -- Video subscribing : See [zed_video_sub_tutorial](./tutorials/zed_video_sub_tutorial) -- Depth subscribing : See [zed_depth_sub_tutorial](./tutorials/zed_depth_sub_tutorial) +- Video subscribing : See [zed_video_sub_tutorial](./zed_video_sub_tutorial) +- Depth subscribing : See [zed_depth_sub_tutorial](./zed_depth_sub_tutorial) From 8f6aebb8b39e95960b5bc9edc9a271f5666e8532 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Fri, 7 Sep 2018 17:36:14 +0200 Subject: [PATCH 12/55] Depth subscribing tutorial updated --- .../zed_depth_sub_tutorial/CMakeLists.txt | 5 +++ .../src/zed_depth_sub_tutorial.cpp | 41 +++++++------------ .../zed_video_sub_tutorial/CMakeLists.txt | 5 +++ .../src/zed_video_sub_tutorial.cpp | 2 +- 4 files changed, 26 insertions(+), 27 deletions(-) diff --git a/tutorials/zed_depth_sub_tutorial/CMakeLists.txt b/tutorials/zed_depth_sub_tutorial/CMakeLists.txt index 03dda9b4..e4fa05d9 100644 --- a/tutorials/zed_depth_sub_tutorial/CMakeLists.txt +++ b/tutorials/zed_depth_sub_tutorial/CMakeLists.txt @@ -1,6 +1,11 @@ cmake_minimum_required(VERSION 2.8.3) project(zed_depth_sub_tutorial) +# if CMAKE_BUILD_TYPE is not specified, take 'Release' as default +IF(NOT CMAKE_BUILD_TYPE) + SET(CMAKE_BUILD_TYPE Release) +ENDIF(NOT CMAKE_BUILD_TYPE) + ## Find catkin and any catkin packages find_package(catkin REQUIRED COMPONENTS roscpp sensor_msgs) diff --git a/tutorials/zed_depth_sub_tutorial/src/zed_depth_sub_tutorial.cpp b/tutorials/zed_depth_sub_tutorial/src/zed_depth_sub_tutorial.cpp index ed1e39b5..6b057cbd 100644 --- a/tutorials/zed_depth_sub_tutorial/src/zed_depth_sub_tutorial.cpp +++ b/tutorials/zed_depth_sub_tutorial/src/zed_depth_sub_tutorial.cpp @@ -2,36 +2,29 @@ #include /** - * This tutorial demonstrates simple receipt of ZED image messages over the ROS system. + * This tutorial demonstrates simple receipt of ZED depth messages over the ROS system. */ /** - * Subscriber callbacks. The argument of the callback is a constant pointer to the received message + * Subscriber callback */ -void imageRgbRawCallback(const sensor_msgs::Image::ConstPtr& msg) { - ROS_INFO("RGB RAW image received from ZED - Size: %dx%d", msg->width, msg->height); -} +void depthCallback(const sensor_msgs::Image::ConstPtr& msg) { -void imageRgbRectCallback(const sensor_msgs::Image::ConstPtr& msg) { - ROS_INFO("RGB Rectified image received from ZED - Size: %dx%d", msg->width, msg->height); -} + // Get a pointer to the depth values casting the data + // pointer to floating point + float* depths = (float*)(&msg->data[0]); -void imageRightRawCallback(const sensor_msgs::Image::ConstPtr& msg) { - ROS_INFO("Right RAW image received from ZED - Size: %dx%d", msg->width, msg->height); -} + // Image coordinates of the center pixel + int u = msg->width / 2; + int v = msg->height / 2; -void imageRightRectCallback(const sensor_msgs::Image::ConstPtr& msg) { - ROS_INFO("Right Rectified image received from ZED - Size: %dx%d", msg->width, msg->height); -} + // Linear index of the center pixel + int centerIdx = u + msg->width * v; -void imageLeftRawCallback(const sensor_msgs::Image::ConstPtr& msg) { - ROS_INFO("Left RAW image received from ZED - Size: %dx%d", msg->width, msg->height); -} - -void imageLeftRectCallback(const sensor_msgs::Image::ConstPtr& msg) { - ROS_INFO("Left Rectified image received from ZED - Size: %dx%d", msg->width, msg->height); + // Output the measure + ROS_INFO("Center distance : %g m", depths[centerIdx]); } /** @@ -72,12 +65,8 @@ int main(int argc, char** argv) { * is the number of messages that will be buffered up before beginning to throw * away the oldest ones. */ - ros::Subscriber subRgbRaw = n.subscribe("/zed/rgb/image_raw_color", 10, imageRgbRawCallback); - ros::Subscriber subRgbRect = n.subscribe("/zed/rgb/image_rect_color", 10, imageRgbRectCallback); - ros::Subscriber subRightRaw = n.subscribe("/zed/right/image_raw_color", 10, imageRightRawCallback); - ros::Subscriber subRightRect = n.subscribe("/zed/right/image_rect_color", 10, imageRightRectCallback); - ros::Subscriber subLeftRaw = n.subscribe("/zed/left/image_raw_color", 10, imageLeftRawCallback); - ros::Subscriber subLeftRect = n.subscribe("/zed/left/image_rect_color", 10, imageLeftRectCallback); + ros::Subscriber subDepth = n.subscribe("/zed/depth/depth_registered", 10, depthCallback); + /** * ros::spin() will enter a loop, pumping callbacks. With this version, all diff --git a/tutorials/zed_video_sub_tutorial/CMakeLists.txt b/tutorials/zed_video_sub_tutorial/CMakeLists.txt index f26608ab..e977fa1f 100644 --- a/tutorials/zed_video_sub_tutorial/CMakeLists.txt +++ b/tutorials/zed_video_sub_tutorial/CMakeLists.txt @@ -1,6 +1,11 @@ cmake_minimum_required(VERSION 2.8.3) project(zed_video_sub_tutorial) +# if CMAKE_BUILD_TYPE is not specified, take 'Release' as default +IF(NOT CMAKE_BUILD_TYPE) + SET(CMAKE_BUILD_TYPE Release) +ENDIF(NOT CMAKE_BUILD_TYPE) + ## Find catkin and any catkin packages find_package(catkin REQUIRED COMPONENTS roscpp sensor_msgs) diff --git a/tutorials/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp b/tutorials/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp index f22aa91c..4f0c38b8 100644 --- a/tutorials/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp +++ b/tutorials/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp @@ -15,7 +15,7 @@ void imageRightRectifiedCallback(const sensor_msgs::Image::ConstPtr& msg) { ROS_INFO("Right Rectified image received from ZED - Size: %dx%d", msg->width, msg->height); } -void imageLeftRectCifiedallback(const sensor_msgs::Image::ConstPtr& msg) { +void imageLeftRectifiedCallback(const sensor_msgs::Image::ConstPtr& msg) { ROS_INFO("Left Rectified image received from ZED - Size: %dx%d", msg->width, msg->height); } From 6c236cf12311dc30d2aa65cad2f6c03a606fe21a Mon Sep 17 00:00:00 2001 From: Myzhar Date: Mon, 10 Sep 2018 11:44:00 +0200 Subject: [PATCH 13/55] Added tutorial for positional tracking --- tutorials/README.md | 7 + tutorials/zed_depth_sub_tutorial/README.md | 4 + .../zed_tracking_sub_tutorial/CMakeLists.txt | 19 +++ tutorials/zed_tracking_sub_tutorial/README.md | 3 + .../zed_tracking_sub_tutorial/package.xml | 15 +++ .../src/zed_tracking_sub_tutorial.cpp | 126 ++++++++++++++++++ tutorials/zed_video_sub_tutorial/README.md | 4 + zed_wrapper/launch/zed_camera.launch | 2 +- zed_wrapper/launch/zed_camera_nodelet.launch | 2 +- 9 files changed, 180 insertions(+), 2 deletions(-) create mode 100644 tutorials/zed_tracking_sub_tutorial/CMakeLists.txt create mode 100644 tutorials/zed_tracking_sub_tutorial/README.md create mode 100644 tutorials/zed_tracking_sub_tutorial/package.xml create mode 100644 tutorials/zed_tracking_sub_tutorial/src/zed_tracking_sub_tutorial.cpp diff --git a/tutorials/README.md b/tutorials/README.md index d14e96ad..32e5a79d 100644 --- a/tutorials/README.md +++ b/tutorials/README.md @@ -3,3 +3,10 @@ A series of tutorials are provided to better understand how to use the ZED node - Video subscribing : See [zed_video_sub_tutorial](./zed_video_sub_tutorial) - Depth subscribing : See [zed_depth_sub_tutorial](./zed_depth_sub_tutorial) +- Positional tracking subscribing : See [zed_tracking_sub_tutorial](./zed_tracking_sub_tutorial) + +For a complete explanation of the tutorials please refer to the Stereolabs ZED online documentation: + +- [Video](https://docs.stereolabs.com/integrations/ros//) +- [Depth](https://docs.stereolabs.com/integrations/ros/depth_sensing/) +- [Positional Tracking](https://docs.stereolabs.com/integrations/ros/positional_tracking/) diff --git a/tutorials/zed_depth_sub_tutorial/README.md b/tutorials/zed_depth_sub_tutorial/README.md index bfa005a7..0b01a073 100644 --- a/tutorials/zed_depth_sub_tutorial/README.md +++ b/tutorials/zed_depth_sub_tutorial/README.md @@ -1 +1,5 @@ # Depth subscription tutorial + +In this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Image to retrieve the depth images published by the ZED node and to get the measured distance at the center of the image + +The complete documentation is available on the [Stereolabs website](https://docs.stereolabs.com/integrations/ros/depth_sensing/) diff --git a/tutorials/zed_tracking_sub_tutorial/CMakeLists.txt b/tutorials/zed_tracking_sub_tutorial/CMakeLists.txt new file mode 100644 index 00000000..46982403 --- /dev/null +++ b/tutorials/zed_tracking_sub_tutorial/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 2.8.3) +project(zed_tracking_sub_tutorial) + +# if CMAKE_BUILD_TYPE is not specified, take 'Release' as default +IF(NOT CMAKE_BUILD_TYPE) + SET(CMAKE_BUILD_TYPE Release) +ENDIF(NOT CMAKE_BUILD_TYPE) + +## Find catkin and any catkin packages +find_package(catkin REQUIRED COMPONENTS roscpp geometry_msgs nav_msgs) + +## Declare a catkin package +catkin_package() + +include_directories(include ${catkin_INCLUDE_DIRS}) + +## Build +add_executable(zed_tracking_sub src/zed_tracking_sub_tutorial.cpp) +target_link_libraries(zed_tracking_sub ${catkin_LIBRARIES}) diff --git a/tutorials/zed_tracking_sub_tutorial/README.md b/tutorials/zed_tracking_sub_tutorial/README.md new file mode 100644 index 00000000..97b754b8 --- /dev/null +++ b/tutorials/zed_tracking_sub_tutorial/README.md @@ -0,0 +1,3 @@ +# Depth subscription tutorial + +The complete documentation is available on the [Stereolabs website](https://docs.stereolabs.com/integrations/ros/positional_tracking/) diff --git a/tutorials/zed_tracking_sub_tutorial/package.xml b/tutorials/zed_tracking_sub_tutorial/package.xml new file mode 100644 index 00000000..09160220 --- /dev/null +++ b/tutorials/zed_tracking_sub_tutorial/package.xml @@ -0,0 +1,15 @@ + + zed_tracking_sub_tutorial + 1.0.0 + + This package is a tutorial showing how to subscribe to ZED positional tracking data streams + + STEREOLABS + BSD + + catkin + + roscpp + geometry_msgs + nav_msgs + diff --git a/tutorials/zed_tracking_sub_tutorial/src/zed_tracking_sub_tutorial.cpp b/tutorials/zed_tracking_sub_tutorial/src/zed_tracking_sub_tutorial.cpp new file mode 100644 index 00000000..f60dd41f --- /dev/null +++ b/tutorials/zed_tracking_sub_tutorial/src/zed_tracking_sub_tutorial.cpp @@ -0,0 +1,126 @@ +#include +#include +#include + +#include "tf2/LinearMath/Quaternion.h" +#include "tf2/LinearMath/Matrix3x3.h" + +#include + +#define RAD2DEG 57.295779513 + +/** + * This tutorial demonstrates simple receipt of ZED odom and pose messages over the ROS system. + */ + + +/** + * Subscriber callbacks + */ + +void odomCallback(const nav_msgs::Odometry::ConstPtr& msg) { + + // Camera position in map frame + double tx = msg->pose.pose.position.x; + double ty = msg->pose.pose.position.y; + double tz = msg->pose.pose.position.z; + + // Orientation quaternion + tf2::Quaternion q( + msg->pose.pose.orientation.x, + msg->pose.pose.orientation.y, + msg->pose.pose.orientation.z, + msg->pose.pose.orientation.w); + + // 3x3 Rotation matrix from quaternion + tf2::Matrix3x3 m(q); + + // Roll Pitch and Yaw from rotation matrix + double roll, pitch, yaw; + m.getRPY(roll, pitch, yaw); + + // Output the measure + ROS_INFO("Received odom in '%s' frame : X: %.2f Y: %.2f Z: %.2f - R: %.2f P: %.2f Y: %.2f", + msg->header.frame_id.c_str(), + tx, ty, tz, + roll * RAD2DEG, pitch * RAD2DEG, yaw * RAD2DEG); +} + +void poseCallback(const geometry_msgs::PoseStamped::ConstPtr& msg) { + + // Camera position in map frame + double tx = msg->pose.position.x; + double ty = msg->pose.position.y; + double tz = msg->pose.position.z; + + // Orientation quaternion + tf2::Quaternion q( + msg->pose.orientation.x, + msg->pose.orientation.y, + msg->pose.orientation.z, + msg->pose.orientation.w); + + // 3x3 Rotation matrix from quaternion + tf2::Matrix3x3 m(q); + + // Roll Pitch and Yaw from rotation matrix + double roll, pitch, yaw; + m.getRPY(roll, pitch, yaw); + + // Output the measure + ROS_INFO("Received pose in '%s' frame : X: %.2f Y: %.2f Z: %.2f - R: %.2f P: %.2f Y: %.2f", + msg->header.frame_id.c_str(), + tx, ty, tz, + roll * RAD2DEG, pitch * RAD2DEG, yaw * RAD2DEG); +} + +/** + * Node main function + */ +int main(int argc, char** argv) { + /** + * The ros::init() function needs to see argc and argv so that it can perform + * any ROS arguments and name remapping that were provided at the command line. + * For programmatic remappings you can use a different version of init() which takes + * remappings directly, but for most command-line programs, passing argc and argv is + * the easiest way to do it. The third argument to init() is the name of the node. + * + * You must call one of the versions of ros::init() before using any other + * part of the ROS system. + */ + ros::init(argc, argv, "zed_tracking_subscriber"); + + /** + * NodeHandle is the main access point to communications with the ROS system. + * The first NodeHandle constructed will fully initialize this node, and the last + * NodeHandle destructed will close down the node. + */ + ros::NodeHandle n; + + /** + * The subscribe() call is how you tell ROS that you want to receive messages + * on a given topic. This invokes a call to the ROS + * master node, which keeps a registry of who is publishing and who + * is subscribing. Messages are passed to a callback function, here + * called imageCallback. subscribe() returns a Subscriber object that you + * must hold on to until you want to unsubscribe. When all copies of the Subscriber + * object go out of scope, this callback will automatically be unsubscribed from + * this topic. + * + * The second parameter to the subscribe() function is the size of the message + * queue. If messages are arriving faster than they are being processed, this + * is the number of messages that will be buffered up before beginning to throw + * away the oldest ones. + */ + ros::Subscriber subOdom = n.subscribe("/zed/odom", 10, odomCallback); + ros::Subscriber subPose = n.subscribe("/zed/pose", 10, poseCallback); + + /** + * ros::spin() will enter a loop, pumping callbacks. With this version, all + * callbacks will be called from within this thread (the main one). ros::spin() + * will exit when Ctrl-C is pressed, or the node is shutdown by the master. + */ + ros::spin(); + + return 0; +} diff --git a/tutorials/zed_video_sub_tutorial/README.md b/tutorials/zed_video_sub_tutorial/README.md index 03fa4c9d..2ee2a00e 100644 --- a/tutorials/zed_video_sub_tutorial/README.md +++ b/tutorials/zed_video_sub_tutorial/README.md @@ -1 +1,5 @@ # ZED video subscription tutorial + +In this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Image to retrieve the Left and Right rectified images published by the ZED node. + +The complete documentation is available on the [Stereolabs website](https://docs.stereolabs.com/integrations/ros/video/) diff --git a/zed_wrapper/launch/zed_camera.launch b/zed_wrapper/launch/zed_camera.launch index af2968e7..88fa9dfc 100644 --- a/zed_wrapper/launch/zed_camera.launch +++ b/zed_wrapper/launch/zed_camera.launch @@ -127,7 +127,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - + diff --git a/zed_wrapper/launch/zed_camera_nodelet.launch b/zed_wrapper/launch/zed_camera_nodelet.launch index 8e0c5866..6a1c9dd7 100644 --- a/zed_wrapper/launch/zed_camera_nodelet.launch +++ b/zed_wrapper/launch/zed_camera_nodelet.launch @@ -128,7 +128,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - + From 6fbe9caed73eafab18eba35db6c44500139ef580 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Mon, 10 Sep 2018 12:27:15 +0200 Subject: [PATCH 14/55] Updated the description of the RTABmap example --- examples/zed_rtabmap_example/README.md | 42 ++++++++++++++++++- .../launch/zed_rtabmap.launch | 8 ++-- 2 files changed, 45 insertions(+), 5 deletions(-) diff --git a/examples/zed_rtabmap_example/README.md b/examples/zed_rtabmap_example/README.md index d83e15c1..98483107 100644 --- a/examples/zed_rtabmap_example/README.md +++ b/examples/zed_rtabmap_example/README.md @@ -2,7 +2,7 @@ This package shows how to use the ZED Wrapper with [RTAB-map](http://introlab.github.io/rtabmap/) -### Run the program +## Run the program To launch the example, open a terminal and launch: @@ -12,3 +12,43 @@ Example of indoor 3D mapping using RTAB-map and ZED ![Example of indoor 3D mapping](images/rtab-map.png) +## The launch file explained + +To correctly use the ZED wrapper with the `rtabmap_ros` node we need to match the following RTABmap parameters: + +- `rgb_topic` -> topic of the color information to be associated to the points of the 3D map +- `depth_topic` -> topic of the depth information +- `camera_info_topic` -> topic of RGB camera parameters used to create the association of each color pixel to the relative 3D point +- `depth_camera_info_topic` -> topic of the depth camera parameter, to convert the 2D depth image to a 3D point cloud +- `frame_id` -> name of the camera frame + +The values associated to the above parameters are the following: + +``` + + + + + +``` + +The corresponding parameters of the ZED node are the following: + +- `rgb_topic` -> `rgb_topic` +- `depth_topic` -> `depth_topic` +- `camera_info_topic` -> `rgb_info_topic` +- `depth_camera_info_topic` -> `depth_cam_info_topic` +- `frame_id` -> `base_frame` + +The corresponding parameters of the `rtabmap_ros` node are the following: + +- `rgb_topic` -> `rgb_topic` +- `depth_topic` -> `depth_topic` +- `camera_info_topic` -> `rgb_info_topic` +- `depth_camera_info_topic` -> `depth_cam_info_topic` +- `camera_frame` -> `frame_id` + + + + + diff --git a/examples/zed_rtabmap_example/launch/zed_rtabmap.launch b/examples/zed_rtabmap_example/launch/zed_rtabmap.launch index efc2ad5a..b57ddc51 100644 --- a/examples/zed_rtabmap_example/launch/zed_rtabmap.launch +++ b/examples/zed_rtabmap_example/launch/zed_rtabmap.launch @@ -47,16 +47,16 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - + + - + - + From e571a6f2eb9f5a29b739f3b18bc95acd20578f30 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Mon, 10 Sep 2018 12:45:51 +0200 Subject: [PATCH 15/55] zed_nodelet_example README documentation expanded --- examples/zed_nodelet_example/README.md | 42 ++++++++++++++++++- .../launch/zed_nodelet_laserscan.launch | 2 +- 2 files changed, 42 insertions(+), 2 deletions(-) diff --git a/examples/zed_nodelet_example/README.md b/examples/zed_nodelet_example/README.md index bc1e07aa..585d5c9c 100644 --- a/examples/zed_nodelet_example/README.md +++ b/examples/zed_nodelet_example/README.md @@ -2,7 +2,7 @@ `zed_nodelet_example` is a ROS package to illustrate how to load the `ZEDWrapperNodelet` with an external nodelet manager and use the intraprocess communication to generate a virtual laser scan thanks to the nodelet `depthimage_to_laserscan` -### Run the program +## Run the program To launch the wrapper nodelet along with the `depthimage_to_laserscan` nodelet, open a terminal and launch: @@ -20,3 +20,43 @@ Virtual 2D laser scan rendered in Rviz over the 3D depth cloud. You can see the ![Virtual laser scan rendered in Rviz on the Depthcloud](images/laserscan-depthcloud.png) [More](https://www.stereolabs.com/documentation/guides/using-zed-with-ros/introduction.html) + +## The launch file explained +The launch file executes three main operations: + +1. Runs the Nodelet manager +2. Load the ZED nodelet +3. Load the DepthImageToLaserScanNodelet nodelet + +To run the Nodelet Manager we use the following line instruction: +`````` +the Nodelet Manager is the process that loads the ZED and the depthimage_to_laserscan nodelets and that allows them to us intra-process communication to pass elaboration data. + +The "variable" `nodelet_manager_name` is defined here: +`````` + +The ZED nodelet is loaded using its own nodelet launch file: +`````` +called passing the "variable" `nodelet_manager_name` as parameter: +`````` + +The `DepthImageToLaserScanNodelet` nodelet is loaded with the following commands: +``` + + + + + + +``` + +it is really important to noticed these two lines: +`````` +`````` + +The first line tells to the `DepthImageToLaserScanNodelet` nodelet which is the frame name of the virtual scan message. +The second line tells to the `DepthImageToLaserScanNodelet` nodelet which is the depth image topic to use to extract the information to generate the virtual laser scan. + +For the description of the other parameters please refer to the [`depthimage_to_laserscan` package documentation](http://wiki.ros.org/depthimage_to_laserscan) + + diff --git a/examples/zed_nodelet_example/launch/zed_nodelet_laserscan.launch b/examples/zed_nodelet_example/launch/zed_nodelet_laserscan.launch index 3fae64c7..e6d715c8 100644 --- a/examples/zed_nodelet_example/launch/zed_nodelet_laserscan.launch +++ b/examples/zed_nodelet_example/launch/zed_nodelet_laserscan.launch @@ -37,7 +37,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - + From 3701b9490f13daded1b7e77495b0049b57934706 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Mon, 10 Sep 2018 12:50:44 +0200 Subject: [PATCH 16/55] zed_nodelet_example documentation improved --- examples/zed_nodelet_example/README.md | 21 ++++++++++++++------- 1 file changed, 14 insertions(+), 7 deletions(-) diff --git a/examples/zed_nodelet_example/README.md b/examples/zed_nodelet_example/README.md index 585d5c9c..70e83c2b 100644 --- a/examples/zed_nodelet_example/README.md +++ b/examples/zed_nodelet_example/README.md @@ -19,25 +19,29 @@ Virtual 2D laser scan rendered in Rviz. You can see the projection of the virtua Virtual 2D laser scan rendered in Rviz over the 3D depth cloud. You can see the projection of the virtual laser scan on the RGB image on the left ![Virtual laser scan rendered in Rviz on the Depthcloud](images/laserscan-depthcloud.png) -[More](https://www.stereolabs.com/documentation/guides/using-zed-with-ros/introduction.html) - ## The launch file explained The launch file executes three main operations: 1. Runs the Nodelet manager 2. Load the ZED nodelet -3. Load the DepthImageToLaserScanNodelet nodelet +3. Load the `depthimage_to_laserscan` nodelet To run the Nodelet Manager we use the following line instruction: + `````` + the Nodelet Manager is the process that loads the ZED and the depthimage_to_laserscan nodelets and that allows them to us intra-process communication to pass elaboration data. The "variable" `nodelet_manager_name` is defined here: + `````` The ZED nodelet is loaded using its own nodelet launch file: + `````` + called passing the "variable" `nodelet_manager_name` as parameter: + `````` The `DepthImageToLaserScanNodelet` nodelet is loaded with the following commands: @@ -50,13 +54,16 @@ The `DepthImageToLaserScanNodelet` nodelet is loaded with the following commands ``` -it is really important to noticed these two lines: +it is really important to notice these two lines: + `````` + `````` -The first line tells to the `DepthImageToLaserScanNodelet` nodelet which is the frame name of the virtual scan message. -The second line tells to the `DepthImageToLaserScanNodelet` nodelet which is the depth image topic to use to extract the information to generate the virtual laser scan. +The first line tells to the `depthimage_to_laserscan` nodelet which is the frame name of the virtual scan message. + +The second line tells to the `depthimage_to_laserscan` nodelet which is the depth image topic to use to extract the information to generate the virtual laser scan. -For the description of the other parameters please refer to the [`depthimage_to_laserscan` package documentation](http://wiki.ros.org/depthimage_to_laserscan) +For the description of the other parameters please refer to the [documentation of the `depthimage_to_laserscan` package](http://wiki.ros.org/depthimage_to_laserscan) From 34f4b902b52c5722bfb1c00f9c753006499c1fa3 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Mon, 10 Sep 2018 12:53:36 +0200 Subject: [PATCH 17/55] Update README.md --- README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 2691c36e..86220b9c 100644 --- a/README.md +++ b/README.md @@ -2,6 +2,8 @@ This package lets you use the ZED stereo camera with ROS. It outputs the camera left and right images, depth map, point cloud, pose information and supports the use of multiple ZED cameras. +[More information](https://www.stereolabs.com/documentation/guides/using-zed-with-ros/introduction.html) + ## Getting started - First, download the latest version of the ZED SDK on [stereolabs.com](https://www.stereolabs.com/developers/) @@ -70,6 +72,4 @@ A few tutorials are provided to understand how to use the ZED node in the ROS en - Video subscribing : See [zed_video_sub_tutorial](./tutorials/zed_video_sub_tutorial) - Depth subscribing : See [zed_depth_sub_tutorial](./tutorials/zed_depth_sub_tutorial) - - -[More](https://www.stereolabs.com/documentation/guides/using-zed-with-ros/introduction.html) +- Positional Tracking subscribing : See [zed_tracking_sub_tutorial](./tutorials/zed_tracking_sub_tutorial) From 358f8e5b7b05bf9d8a78a4d34558c49ddce17db8 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Mon, 10 Sep 2018 12:55:44 +0200 Subject: [PATCH 18/55] Update README.md --- tutorials/zed_tracking_sub_tutorial/README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/tutorials/zed_tracking_sub_tutorial/README.md b/tutorials/zed_tracking_sub_tutorial/README.md index 97b754b8..94a0185c 100644 --- a/tutorials/zed_tracking_sub_tutorial/README.md +++ b/tutorials/zed_tracking_sub_tutorial/README.md @@ -1,3 +1,5 @@ # Depth subscription tutorial +In this tutorial you will learn how to write a simple node that subscribes to messages of type `geometry_msgs/PoseStamped` and `nav_msgs/Odometry` to retrieve the position and the orientation of the ZED camera in the map and in the odometry frames. + The complete documentation is available on the [Stereolabs website](https://docs.stereolabs.com/integrations/ros/positional_tracking/) From f31be14a0cf6742ead40e8a196dbd2ee5dfb25d0 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Tue, 11 Sep 2018 12:05:36 +0200 Subject: [PATCH 19/55] Improved READMEs --- images/logo_stereolabs.svg | 1 + tutorials/README.md | 6 +++--- tutorials/images/tutorial_depth.png | Bin 0 -> 147518 bytes tutorials/images/tutorial_tracking.png | Bin 0 -> 199116 bytes tutorials/images/tutorial_video.png | Bin 0 -> 198317 bytes tutorials/zed_depth_sub_tutorial/README.md | 4 ++++ tutorials/zed_tracking_sub_tutorial/README.md | 7 ++++++- tutorials/zed_video_sub_tutorial/README.md | 2 ++ 8 files changed, 16 insertions(+), 4 deletions(-) create mode 100644 images/logo_stereolabs.svg create mode 100644 tutorials/images/tutorial_depth.png create mode 100644 tutorials/images/tutorial_tracking.png create mode 100644 tutorials/images/tutorial_video.png diff --git a/images/logo_stereolabs.svg b/images/logo_stereolabs.svg new file mode 100644 index 00000000..1fbc6c18 --- /dev/null +++ b/images/logo_stereolabs.svg @@ -0,0 +1 @@ +Artboard 1 \ No newline at end of file diff --git a/tutorials/README.md b/tutorials/README.md index 32e5a79d..2c7633eb 100644 --- a/tutorials/README.md +++ b/tutorials/README.md @@ -1,9 +1,9 @@ # Tutorials A series of tutorials are provided to better understand how to use the ZED node in the ROS environment : -- Video subscribing : See [zed_video_sub_tutorial](./zed_video_sub_tutorial) -- Depth subscribing : See [zed_depth_sub_tutorial](./zed_depth_sub_tutorial) -- Positional tracking subscribing : See [zed_tracking_sub_tutorial](./zed_tracking_sub_tutorial) +- [Video subscribing](./zed_video_sub_tutorial) : `zed_video_sub_tutorial` - in this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Image to retrieve the Left and Right rectified images published by the ZED node +- [Depth subscribing](./zed_depth_sub_tutorial) : `zed_depth_sub_tutorial` - in this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Image to retrieve the depth images published by the ZED node and to get the measured distance at the center of the image +- [Positional tracking subscribing](./zed_tracking_sub_tutorial) : `zed_tracking_sub_tutorial` - in this tutorial you will learn how to write a simple node that subscribes to messages of type geometry_msgs/PoseStamped and nav_msgs/Odometry to retrieve the position and the orientation of the ZED camera in the map and in the odometry frames. For a complete explanation of the tutorials please refer to the Stereolabs ZED online documentation: diff --git a/tutorials/images/tutorial_depth.png b/tutorials/images/tutorial_depth.png new file mode 100644 index 0000000000000000000000000000000000000000..31f84a94004179ea1cb510356f4199451cc51830 GIT binary patch literal 147518 zcmdSA1yEc~*YCS=f+n~_Nbtd3LxQ`zy9IZb0KwfoI1KLY65QP(xVyt4&-=Z%zB=ct zI`>H3s#`TRQ+vu3kQ$_1lbjj=E;-rg82zzP(}NA591tQhjuV{`%gB zpX5C}G^8)ThgSuN0Z9tiRG>_r_=B`~NiN4%S&Y)T3E-$e8P)ecentrc%MlUF16g0w zaWF>#(e0rAT%e5b?{67U5m^MLFh;gw8>aoH50Ns}KmEP*-yX6x_Z(q~B1zP+EQ$V~ zE*WK61ndMWKtt3sc%{N7S(Jf#HUzuTxuTz=f&y>??f*QkA(H-UcqA{G9phmOYO1xu zVA(>qY1=*Zpr$;2ixwgUz-B&e{dPL3yOVI?{9_z9}_JA1~6?7Asbw!QXME zYttpRM}&rkdRpFpfNn>@NrH=>h{BVM+`RrE={Y<&nAaEo8T6IE*KcEHyo2 z@ep|twGe1bLMhyYIB^>di``Bk|rp8(mI>($11d{U8c?wX_N(gbQI zHo`46V+<|`l|xg%iA|3C7lf8b_b)2&jcCs1Yo*l&PFJZQzy8U>5F8ocCyrdX^!Go=~)-ttw^BwitVfL4jaHLTI@jH*;W57U zI+>7tp*%IWn5zUTPe}KN9Cnct3jRa&j@2?Cj{o6B=&!ME(&QMz4^@4)DjO^iu&gBi z`D-LX4bAVV*66zN#TJq;ST9LVHX3}e+6w+!USPJEiywHKyvs(XbEO-3N$y$??eaa=Kc{!8&zF)5GTD%XooRqj7+a}Je?b6Xy zl7z@-3Yyuh+3hV)(uVD!)c;ja`F6u$gfbN1;>5>qv@ly=41wA|c7x$EiN z&Jq%ihqJXcx{bQX9=NA7zTseKfPdaGnP-Ida5}$w!VL(7s>?_X0L3`b z=oHm%WyAH*5w%hiLG{+>qwTG>5l^p^jz(3^PnGufecE|?KsN(3AB$WnY?!V@EopK< z80@!SljioAZYeNfHie|nh58`%(pi%t=8$@Hd&kRow*4n=@#O)mRfWmdB!1Z|KG@$! zX_}?N2GddN=iiM!>yW&N%5eW<12u7J0W-hnz^>s3D zh(#(M3q)MvGj358TZ@!4JAM(Uo`qT7oipiAiuWnbT<)1K!{D)|_#=dr_*t!i$Vu;? z9sU`&XNt%Z)%L)6fFJvHu4&twD)ouMSur&wA^{SK|N3U2SL2j`+rd;}O&R*29+m!x z=P4>`uxi_3ZR96xpLLQw$t=GrJCPh^wgh6k>&5s;5P>FWNZFt&A;$}Us_Uyi1X-k; zjoxWdL2lgGw--b&wG%4v6N{s`g9Cx_M;7Uzi+A$TLo{!O@e>jvkgR$;4%|PVov<1? z(%DlLlGugzIaB`*0cOQvyoT6~#qNF8VD7vmz7I&(m)4={MHSW@@L9P9OM9XMQ7(4p zO^?Yu!Ta9=ct8}JqY6qxb**?$ZLF$;CX``g<`qsW7M-aIFSsQA_b{9irNs$#dtK*YOuRpFDzRR^lQww9xA{AJ&(<> z;FoZm4gL(VUkMI{r{YEoc$feXII|f{8N#;1FBhi@V!|n8Qn_RZix%}K@LO0|AQPkv zp`%r`QiTYHh%)!=M3Imjq*&YD92M|VJ1A?mop;tD-B@(LYRELE!G3b0MYlIwnHKXh zdR&eA{$8W73RhXaRgU+uroHYcO#WT5Gu~zQ@8H3X_R-^(s9;XVGzQ}u74tvEG-jar z9c=g#i1O9K49|xz8qOl%AnLUSca#ivnx(^fS@BOKc@I6iCNIw1pAw^IPk3yX14ub-M+EPk^ zK7&x%Y_I*kAJI{4^&@I;VIG|&EHe9f4*#c%$L2XLX*QsHYB!3M(V&kBvIeKH>|xhq zu5^jLOJ$(uBX(|_RP_mK(pjs_SD%eQKT3aAgXppJ{&KVW2V~l06AYgoH7 zEc0=uLe%P}bJm>)oe5uG)8^l&yi1s!{EQ3`1M@W<_Pg47d$f2>k$4Gn(lvO@N(NUQ za|^k)egHXD_x!xweFAiXj$2(an}?J}76~luaFLkjV_4|YjUbg6*e$({n9aIz>qbW= zfX3HdAOG*BQitSociemw9Gd#j9*gViVeNJA17kS&_0*{A5BUtf+3Li>vR`T*&L~3( zBU}Ou64Z~6r&>A?5HjM}vt?TNTX4QU*3$2RJ$ZK<#4-%b5=tSX8jQ@3=^|Hk;k*w+ zof^0-{DP1x6?rOiv&t&vP{3Y{0A#npo&E>Zej6kxz|&1p)DUS%CWL#UWb28#{DjY= zbel#XR=VDTx!P6h=#-_7p=XdrJQM2!2GI}1ykE_)rcD+eKZQ3bWb9$SQB#nykgz3Y zHgIjnxuZQ{?TZM-6f==tV3uS{Q>rU@R-zeCgIl z8tcu?gK%bsuiV$^Or;{*7*As@NBWjh$ejyTI?!3=rppf^Lvy_2My$Uv2uaj21erwM0FISzdhwLYdTQDj~p>#R*tK&`SQVF zZH)9}L0~&l_(m|6C(1taKm&1$7No=!44)}TcpZ!!hl|A})h z`_EVx7J3OKNTDIAFo$tCKZ6++%w@Zk94y4*P}6~Hlwo0`+|f-%nTGV~UBZUg^}>Fm z?1=C;apaO1L#Ayvn<@+dOo`Wl8MF?{q@Siyh>08TP?wxQ$V-W0-DC0+eGHr_CCi$) z075s=K^mVmDGdgx>8Y+C0$+ItmhuMoaDCqwNR}i_f-FYmq2j+LQT>*rf=%m-0})r3 zYNU_*!{#lC+0aJn{F!s?wWGNk?p7s=VDw3j)PVq?8)lIG_SJyHdBX}9%JL^q%lC|*mk$t#0=etUC3?~kDDGH# zAuXIV$Z6558ozo!Go8~X&K@^A9&(-5cNX2=J`%Wwa5^!oWs6fJvK@BHrS>W3<_hXA zjR%y!^FAM)g`A3p{_6KjbxQxvi2%vJZ~rb#MI2r^jWqTf2+9XSw)4>wMHuVl!k@v=pg}2mX?{~7RM--UWgQx& zkJYx1A1Y8!RZmmVLw%`XCX$W8XCo=2ud``o6Xx0FHDmeS-LUEF&G9tMCy4{KzP`>D znUt%$J7{H)E&~!&;AbJB84#V-qPvD4Yw#g%qYleY@lb6>n_a*%8_nR#c8P=gQl9fR5Cx)U8%h!gV1?1cSW+2IyGisHd-J&5`{{#g7o=@`Mh>5)14rS{1Q%xk(E~p&@ii6Q?Thl5J zjjGr}&4;Q$-AuYX-cUY92+KnW4W(J>z)-^J*W*L;$%C5tc^6@juI;!2Pb-~-ifW75 zlnswJSYU#4wIvAG00$O;3NvcR(D*CR&xPbKV5&WcPIWj}mNQ^dU;z`v{lU6Xy5i5` zd8Q=MrQZ)XNn~`d#Q^~AksVG{TN}lLh@OnKw5}n)@kb>B2|Ot)Yq$Ud!*KYGL0G`s48m#~?v) z#ZYXPaeY8l>{K}!O1wH+;{p%X$IMST%d2*MQ&l8Jg0jathmI*Jcx}VIZWUoK#-cYr zJv`cji|&bBaq|IRjr8u?B~+~2vlAhc<+7+j@_pTera?0bgl_w>b0f{f)*~2r2UY~G+`Dg#LX|kEDv%h+bfF0G=I;4-)Tu0yJ;*+l{uS$; zK|dLdC1WwLg>e>soQ+b(_k^0$b1NhT~lj2b~g}sr5>JBWrmo zvZ@0MQub~Y-=h~Q^{2jY=myp#vFz&6geoZBwDv(uyzHy@ z!$q?rR4W$aE*%Ux*fqk@5KsezC=AtfzY=BW?#+40W@gbu!%D#M>?j#xN!STha+s>6 zH91iIn%f(Q-M>O12hgKnq8N~^Amx~J26_}r&_B#Uy_7P5%G>kqd-TC?6~nV0)axn^4Q3LNq$nvW952^yi;dsEp04$72D| z5Ly<5z;N>6zQx1HYcj7lEr%3MMO9w*Q}=w=QV4ZlM#t{6|xoZ_CuYsQrOEsfJY>Y=fv($AmVZ1@O;5j{P={nbM!eLPK^1_) zkWvWPZJDHodD|y%SM}^D%9E^P6J9|>dVT+{sWr#N5tvHAz<^|+O3ub6O}UHT- zsb1sAq2)LI&G-UX zNB}2cdJid1S%?wviRM{e{gwssi;DtZv?5A0>=Pa0Q??3AoFG^fY#eL>{{hGVPvTN8 zekC8*^YdHU+ayH_V!3c=1JHv$vq%&oBjt_eCGjBkLP}DjP2uF{-^DSZQ`kxrB^j{8 z4#k)om1T4ufnbCR;BNTW1!os?wSJeiIDcb>4`Wdu@ENK(WFMS2zxJH zZN@Mu0R!rNBXzj;7>CkFR-si53l!Rs0v3cHou*jtq2+{-aH#YdnM(tnOCbt+eSnTwx;|YdjS3O`MnHiRsBBR)sF|l;x^wADtoh!T|LMz5m^R^02aijOzUTPH zr@n-{!L|DZ>S-lGX#Xx~slKNHxCO8G8^J{V!7ep|nefNzl93@BeKgUY84r_Bz~ z{765(8o-mj4|?6Tc>y8+qliAL-j)%5sYUs_BDYm^%oW<%_+cVWVEhyKpW}7`$G@!Z zX(G7i8^GYa$oLn|w~>oFY_k6crr#Wb9O?Qua&Kdhh5rW}|83MoVxN)cZBF<%*8GF? zr(D7aWFJW9Hg5iXrpE*xLGK?N_*b3bQ2M{YRHGjnwFLJ|@?(8nGNthUv;+VSpThex z3g2SWt+j0>HvY590-b?dw+>PI^4O#^j8SIe!e* z#$wgNQBdsm$+HxCOW>3+9wnASL}nCcLn(b#u`VTC7WBg$ii%=A=DzNzytM5cLwBx; zP53mRsTNbmH!wj)fVsy$nep3R(R&SDh3T!;gjYF=E3zFO{D`euZ1f}jva%pt@wf6d zHSWUbhGjfE-9@>bA<~lNKDu_>IT>8SLWD*y@8=*aEZ6X`?y|uYB!9)_2o%MD zm6qn6N7!r+)`o*nn(kY(@A;knWkl6unk}@ED2gy^ZY?IGBn7t~DQIUxErjJG*$N!Z*1T*RVkmSzfO_qAa?2p`tpIu;OsPqvueL$76MODyHm4wTBUnv*o< z#4?2>6aXYObe5#QUOEMHxLy1{(mH=9R(bG*#2GUjpZ9KM#<_>suO%q-l*ys@r87jL z+|Cq`oV7X(R(dAAk-~MQ|GN0SFC?HJwXprTom~>uU+YwW0?Wyz(YmETN4U0ZXx2ps z+k{oa=1VM<0P1ymBGzE4lDQm|~9O;O`Fuoi~6=cY1_s0Wk_q_%4B~X>!Vj9T1zZv+p(}xJ-cZ8rHC^5 zBe2UeReXc{F#i{KBh{J{1@Ohd#)14GfL@Z*uLS=`6n_gEU?}wq18OvufcBr8Onf?u9@11iRPhi z3f%Z`l-tXPiUGR&8JyCl$&h!NKtVBy6Y;S5yFxNCD#8;bQ{y<=Q{SiHw0pVgl!9Qn zp6+|HtG@Vc{8*UO{a{{~VuluXdETY*O|iAWUaYpJ=2q*rYHkV)$x)NlGLHp+ta=0* zK~mays>lvK_h#Y<;FDV_Gi-~B3v?VM>QzGk>m%m3dWZVR1h|mvPF4o36jytbC3V&D zLC{(9RxUR>4nm`rkXGj-QBvRnH?~@GmVsZmY=Cw6T)Ielkm|x)Dp}E_{|b*-_R1H& zd~(@7^!CnI>N_+LxNP|PY!7!DF`MvAs zmiKo3Mx{*+{5>;p$*$coTsu3pNOF%Sbi_t^68JY@_wtA@#I3RNZbQ&?_J!ZfS>?Gc ziW&o?<(1o)3J0zoQ0ZZf@N=M+=-N>nb&rL$y`Cg7U)Eq`pUCHG z2eDFbP?l8zNiBDn06Y!0h9)L)qFCbZtX!>lreqt_g~4b9PU4MR4?scz-_#2{p@Ezb)qd)!;J=cUZy!|q^#O&_Ni_G+c2&3@L z8E`UmxSh@QHnVAR;1?uT3>F3Q`$<16B7wzcmjg>PM%!w~N3RRnv`5>chS6?{$g`K{ zt0|3JO_~C24MvDD8+&~* zI*&1MhN|ALYLSD*EHOHv3qZ`6>iEGoQa+~BKrd|4#6*4OxE@2TVy%ES*`~%^FvtDi zUgo`8@yfsR=WM`zb7^$-p;cgehxcuBu_L7JXe<#cc(#!No4wP?aM zlhxU{N%DG(3}m4Mqhu&<)%j4&$4w1Y%%!po6=%@e+?C}03D@l7RBjBf%1%nO(GF*SD))$ z+qfNByb>1R)8Tk`aWX%%P~dl&_*9tdonLC@z3}K_`ZIN|8Xw6FYxBC>_dOvXJ0O!u zzSX@GX@*#5mP3AR?r#QU-^V!fZw~3V)YRfQn|A8q}Z=q28duGMQ*7VJtw!2A0q`VC!i#_1N zrvs@;5$$B!`NRDYSdyxvBMeMaSknC5MBs%9JPGRa*79|Kik%t)|LhTWQ8|a{C`;y#Qyd>3 zhE%?8lifVI5NA1rb!N4^mB90o;vo{|r-gKiuWBs(>z96?F9)Fja7e2+9Touib*(O5 zA5=FOK%MX3X|A6I*339$()EmF_94G=mo|hBZ6IGNRwO_)G+|suNpG>cG(IsqPeXB9 z>OCZccn~(^4o)p431$-AU#W@4tL8hqHMFnc?8;45cyRb>WEv6r&`**3)GSMaH83x zncr5WSRmfQT(+KCv)81$Qu+4L5*!P@cfOgvhO+~L)Eio6IzAEQ92~oSFl5Ngr2&J0 z_ukxAsw-hbQzs@^C+R)C(sVO0!S&ACAr%MfAxf6)PO`C=shP%%StzT#ef2x<%72va zzSaF81HsmqEWppe_~l;Hwh~BQBdcnsCuRXV(}P^CatTSP$EEVdgy0Dx+sF(3)c-osOC+R}?`s ziah=hlh^H7yk6eTDuQ{fonLNjBr`Sn2sIJyjqBN16_hm`bULs1M#lj7h3dhs$2r%a z|NL+l`DC?2yYElF1+A|lf>g;S#x?9%ks~?{`QBM;jeO<&qic?SttO|9$gPfY(=tB$ zb6!`8GxfD2!}BwBb^V5qk!puchiafc&_Bo;8~(P_C(ewlCGRnQJY7q7(x1pGL^}@+ zZmn<_P5mCl!KJz$RnIa~Uu*)U)~U9g4t2ji-Z#-jPO5(rN3*^z^veNfn`=g1Zf=X&B)^gqC+D+8Jrk zBsO++urt-eT|NVbp0@XAPy%_aqyE&_ZABqpB&k1e=;1_sU348ApvXbc;LH&lq9fF0 zM1t~(uca!0#7#g?FoLjY84k+pK`tTxv)2+hhlh&8qI)&o%bq{h+V;>t(XZd&{Odx? zi{tfCvKfELqy#Z&3f}xy!%;tGpF7m;hn|{lXPhtbDn2pJa`9n9L;~B{T(wsKcKwRP z9#`Yb*w`hJKJ_A0QarU^<7yy!U_Nf&RSwRZ-tyq$Tip+PX!x;|$rXt^+b~?J61I8Y z>SDSc-QJ1Z!&0w^Ol@$Z8O4C2zKIHE3zNr3YX9Nj;qT*a3;;< z!DOy9-#o6iE=TUU(O(=;Zz&V`(;edr4BsI4zj)yhVO$K-vw#Wk@K#&l!hxwzs+kjoLII|v zqsO6m`>m7i5j*Scfx`AGPNbRT+~?|J={<69QT;4!slH-1K%3s_0{QyHmVc8zBQ+68 z%Z8L8Ugz+!5gmU|+bU!N0M8agN%?PgNb z2h|_3(i2|(q}~7QH`zw#o<4e;wPjuK7s3dQW zF9HZBpNQKfWydE|R@y6}m6}>AN|Tkf6VFIt^JUUmK{t`>hJ<5{dYC@LOiGG;Yt7VI z{a9-TyLiN$*H=Yyw;qAIS?yppxzBfM^W-^J zicMZ0wIU{W{J)3;tw86{tR0`$s>Vg_T)fm<`4TaNpOL%$?ENV$c;I zjMuzAiP?X50g9a?t*s85UsM~2003L9u^~K-8EmWsIltT^GFRVV&68a3R1mqsWL9Q+ z{S@#RSq7u@Cp`T*F?~cMi#hXOrene4=o4pg-kbimIC8F=3_IVngm!-h0;emQS7T?N zqXz*1{(zRp!NpHVS#dnJyFG06MaERQGYB zkzc+IGRpmKX>M^-POSwSKWdWjr|+F!ZkFRyoe|-tPzk@-jE>)*CXA#VY&FBfjT;N! zwTn}k*FS6z>Wocm@S5Ld5IYP&SU|ltCL=WP^UphL*0`pzLI5c}D$dw4m!68M1^MxF zy#%-$M*G|*2f@AxJb-vC;q8-e(RRot4%*E#2b1SR3CxdOqLj~o?w@mrHhTIMv7EJj ze9SVV2y1aNX8%DC!eNQ{nWev4D-nKHb2<0E?6JLmezktZ_O>fBrBMF@htQCEc(M5J#`UTG<9HJhDxl&mwfo%$obbt8 z<6uGct_bt%KfM6}+(8>7mQT$s#SpIwhl*%wkqa2@5%v#b5y+6@0I6n8(hGyr)7MNsgJ^ADo?Q z(I9{*)?FPM^1P6?gQ?#*YWiq%Ua65<;%_WXX!(4N?N_yw-ci)!dcmR zc7IK3En*@I@oW2^!plpo5W;X8^CpJ;!axX#r4Rt%S2dWY*MK78RT6?L_A6Ue=WYnj zy=%6FSDR{6KqcTN#(v_l72!7fi>b)W4r2+ly5xMlJ{<@1h+NGW0l9Z2T^k* zyME&YiLAJduU(cx4q4P!59zf(@Pda*e~H1<)K?B!FJCJNzk$TEHJvZn0WjK5Xg^U$ zEPfj?73{t{WDC7{N+x(iiOsIgBe%$cdDka)&u# zq|r`skInFwCS0yDZQ22NZ(>UQ5NIFkbbh3MrMAxMuIz5%(|`uqAWClhDKX-vEx8*K zu!!1i-3k1!k>ROj)PF$?VaofqMVV9*$Q@MHK6t}lbWyhrjblE-(a^OH{(@joYc8cw zz7CydH~P~GZB~s-gGKZu>!t2>m4WxYQ!8q^>ioub+j)i;?o1P%#+Ij6+RXRPXUTjd z*5OWP+!{UOoV^@;UV%R`!fWN{>JDFtXI#{>LYRZQ=}?e4C3h}()C?9gw1&)iZ`9WD zNe^4T?}va5%|m-#t=Sn;R_qo>5e<$*2n+hu;!h{$CEY7m=U;i%7eObR8MqqVe@J)h z2(|L&;Rfy%1jtT^n8(Moaj{Atr;9!88k*vm7-j@%=AiiV-2Pc{^oy348dW{rJS4fy zL}wx6V{y=MwLW{nsAImQ5j4176-BsjinnX`N5#HZfARvf(|=9D!4t`(wH`}yLA}3w zN>^GBV3b&vj%a!Qu*yi|kX~<)WVp~dqV}cOteeo_@FE^Et59z z%U}SxV=La07}PTEJCh_LlBa^}m7m8p7W$R+AoS`(j!7+ylUkS4fX}cb4%rP-J%i^& z?a%H!;Ty``1P@8wTJ7B585jTnRr_Gkk#Dsr`4cXVfGt^aJ>u?oRJS3@SZLe%m3bK- zw^`*F6b#~vUUoh`w&Z^E_CPR;L0Hhzt)`PxjB&5O6x7%qhBT&~qLJEv4-sMD;ciP2 zHH}w}}OO{GE&x zqA(6W;~85k+CJ4s!-Lsy>Yyk?s`Q4TU+{ii?rhGfHKLT6C1~2Xm>i`;BjCq8^wztNN%tn-_npEAeBPx$ zNG4wojZ2q;gMq@5y+dvEgiMJ%&ek^;RQi_%p-)NG$nydkjjMe;e)-JxnaPX!fuiWU z-iM6s$Lq67@~5Xnthc{IQET}A=9NzSMdqXXiUru7cXpq)S|IAShX@mE4>ln`s1O_O zAWIx1rOq)49yd38#KqHD&X=FGa=mz5NsI5(qBjixLMWOMJub=H!Qv8Ad$!6UpPS-s z!HKgBL;2qP#5L_(i|=}W&a8CzL*?f#YEg83O@FjvS(VM<37#Gv7V2iEjq)E@` zstBT1%{&}{&f+E=@n**?DF&vaR~bz=u1GuwH92fN%dkZ__28*$dfjILQ69pl!mhGc z>D)HiAz5taXmj$-TrM*x2-NHBa=(p=aDeU~Czg0yOVVhiS*U95r2C6=RR`b`HM>7s<}^!n`VrkYT-!5tpK*6NMY^w)^B{|sa79GsRRvD0 zAn=BGa?n7O=2q=-Rel*4@~qeym-E*rThD&+v2%sx{t=@3o8izZKjyBo-OgAE;j6N1A5w|T% zsx!%832u(mX9=HQ8NYh#ir7BINOOVFtZ(?V0HkeqWTnfd zmB2ojgD)$D(;|CgMwqDN#l!-mI2%oF(C)_U-h`CXr{ntZ#v1=HhB-gEQw zW*n9jdAX+B6+Hg##^bl4ctvHkx2L`4HinuFR7^4vMs+T7VqTK#nx2hLw|)^?X^&Yk zR9b?&{PK3)dHd)f^98S=@`VoMHUIO@alY*as#qs zf-#)U4J>~c7Fu=(ilq~x(9=d$n-sCtV^RFl{3W9l>vs&YjKvDh@mn-slDQ9j)9M)H zCdk26l8W?oGV@WZ(zfuG}|l3fk-`G*<9=4X3`SA$5fIpHGgm z7f4%G?YFhtCP-qRdY`6bB0OcZ7R~IheLM*dxIF>;&KUOe6oY9f$BlY=+9KHEz6b!W zd&IkCUuNUR6iME^V_JoP#Uy2{(;11MKS?Tcqxy1^vbUKM<}A5n(*6Nwthfn@sXKGU z6)jE(3Yw2zl&PEts3@L)+|`EwNGOj=waWQIx!K-lMvTFrSc_^%-R^%|ellA=Yo7{f zZXj4?kb$wl^#MyT%HT?2Wa;yEJl?R8PZWsod1A?vCG4jYot)nGaT?E71=e}+mmdj} zyw8Lp-t|qH=|5g`F_}#;JHfV&7o~2(P8gJ;KFyx>_UH3B{XEwS_y<@#c3QBFJU%)X z&#eFW;0lEsZ?jS0L=SGPv(aH#dwg*cXiiQtU zEyMl_dnwjbH3$iu*KY;Rj5P2Zdl_%6ifJDGk=KfHao^2@2cwj!&Nvysv2wQGn_)p6 ztgje&SY(`W-MP^Lz&H?fr~DPl##A*z3#MV%ayG)-SQJGnz2>mCjX=!!n5q0@!GJMu zW@h1kqJ)qm1S{TZ`*zmLSBVHyzhF!P32@}gj&EC)Bkyb>?=5f<0RFKrWrj z@B%7c7?RpVG?D@c{>&FPs3uO07{KjqUYLd;&9=l^OJhcL;6Z6@-Jtfz?K9KGg57LF zYf26~ho!92F?LX@${*FZ39?M`~z!G|a7Y$AXr5s$nR?4Z{0 zdRjR=8jRlZyzRglJG@||-0dNmgtWseV??&&lb3^>IWrU+3qVVc&StqK6q(q9%eJ`G z7dv#u9x#n7kF~$e4P1MBmAz4Y+|@z`#l=I(Liy9w;=Ar#G+*?<4V>Kc+cXcR;);0Y zl$xVSh_|9;KvgZ(jyg(@Q%?;G=pPDG6<_W!{}wT7;Zl0;^A$=MRm;QRVfhg3P2dR% zbjPM%+x~gkK33CQ>Dkxh!x5h4)UHH9p4?Vl$c~c$gC&W3x6yj;OC^F{s*9@YQvUxX zAe8&x0)!#8a8)}M*Cze3%@ofKC5BOh(Tagu`EL=i@v{(*OhJoFh9n!_q+;Nk5E~`r zp2_}X-DB<>t&{Pk#Ik+E)%#O@3pD&HLs9=u#Uyx7hzSIjPiTblpUL6P;vB@e?p!fr zEXIdRu2=e(@N6E1&Jt})Kn_!kk#LnlAl6g|uIGnBKheyH^edBFEsFna%;Z>S2_5a- z(Q575?a8*6;GBE3iVAN11&M>%8jgOQHOI~E)LB-Piq|i-?eX!m6QRO1Q>L;U%Obv= z=N7q2^)ki4ZPRSbBZyUS{f6NASQ1;rWrl|_jq#h4$Tg~|hFNP=2e#HU<-8Y_DCoP^ zvX46@jTJ8$XEbxZP5;fuwW6)9>=c+}?@lMBR&UTxp#S)$d9avU`Z@ZE&OGiuM0^5( z4nZeY3yt$!RzsfmT(eG=!wTg6WQKS^EL$>jt)r989}O~Nh4M?u^17DaT8Xhp0RN)% z4c^Wj`H@sHR(;Wu-oq1HOHevCIx>(I%u!Eoo_i~P%9--x6%TJjYa!U9?WD(o*BMRZ zZQ<*%w_58`$98L-A7Gzu?uQ6&cd^oDa_9{1Q1mK2-Ie~H<=#jo3e`*q=O@^;_hCqDKRzM zD?zq!@tF7G(ny)tTdFs~gR|1Mx8rmD-igNlc}jQPqi?|4MI;V?ZYF}+#bk7H&q-e$Rm}PJ_siUu)-&q0%HDdVj;6Im z_W+6Xi%*{(hh54xL^rEK1q3e1?Oik6noS-gLu*5K@2wIilV!%r_o~UW!tApfm_dlK z5u1MhKfr@pc*5iVt_AovDty=TKShO?TH;1;sPGDiKehauLzRHGczX!JWA1rP6He=W$D)1?6~@+6EpTX?H{x#^KZ1MEeF%(q_N7*uEc$vrvs^ptpexJVsEwxc zw~00OCUb5~`0*E*dYk(?@5H96*Q@*33NvQ?2ovspKZCoo;%7E31)eqTT4UVuHri1N zIikPA&>_Bu67xSzdiV?T!nKLDBG!1$59yi-RXHX_;HXiYW8P|cW&$&1g&xzL#@r{c zj8}H0dsehc1%bC5*Zo|GSW$NQ0}GRILQ+rd+KxfuWDbWgfJq|k*?73+0O){z3h`&pcup;;dh8Knu| z;w*6eEQ%E=)r%GWx7nK0X{i3uewZ&Z%M;S-5ufdi#1t&55tgL!8H1bT(E9DS#_Jl9x5K!9t}@? z3Rpfs?LE!8+(B=*gU6%(7b*+88~@Pp7%D$|9wU(G@oCSoM9toM?)brKPL^XgA&(9xOQnu|<(n7LMB>3JL7sCnJG z7r8b)(5~;mf%ghEANt%C_>vF&tk0hMl z=7l{g2CxqcG~L;bndptjk9UfwA&oB;}~Lwn3sGuoMN_gl?KJ3m{pT5{KYUsZL~abATi5VnEX zS;}bt4CvYkscFa%HwJ)ab=1JL(iw%U48=6?c5@m9RNTyu*}`%hH~rpwzhjmlLe`_q zA-PgEQ4$Mb^;HxvQYjyMImIJCpE5MJLx-i3>H+;ReS!8u)9cvMltsy&YDbhp8zxWE z?i^$CI$Fv+Y@B^o1JCH*QwP8=St}1xzV32>`hc4O^Z%%AfBB7LB~5i7V5sMaBibC+ z-G+A27TpW*mqBR=`Odz+)8G|VM89g5EchQPg?m7Ho;rbaps?P0AiUx1%B-4|QM-8H z;|uXYCqI(}TX?&6y(@&N$PPbp3w^YBaM?76yF?1<{LC{-{o>i(<#E!Tm_k};uk$pz z7+ZB+Tp;?Hx`*T=lB5h+}v2I#Ih=^v|sWGdbx>+%_bZgVksum0w_ z1P2gXe(uG7hz0?SdSb9(0RZb|j(GJn^PMpS0ILI*c{hP5nlUp@jSw*a#a^KChp_6f za{|WyiCD;_@L$6OSKAM&YvPzFNh~m(`-^_CwEQ82#g$F}pH?BY0B~aH72WxEDyBb2 zkmh+~_inQeSh?Pd98q_$@d++PWVi_=b{HKq$H={3(-Okd<^=rL5yFpw^^}3W);F(L z?yQvgV(}KGPXVPCO+>7#=9C7K@nJ|3rQPtVOD*@&)&x0&?VA3`OR<_}CY7ce4<49f z*C`u#1qzH=DWRn=Zs`a5@4wiy?8Z-8c@ONyU+l(H>_&}_hhqSA%fEE&#hNbSupWWM zf)MpGa5~TkYa3Pks_*;9RcdUm0g`t^V;X=@Wmdi~nSCjN>+^O1C6QRPSnJP`xR*%g z*-eslnX{I+^_A8cMwcmCyFo!?gv4_nfzM)hABL%zB;2zGu_bJ@UdhWuVdTi+aXz=> zm3l-jJ$?&s4JQ3(^$i(y=bK=|njc{rBqMPEZz|SD);xY?)ix>>PU;OTA6ciSI&0gT z>Gb|beUicv)>bRu?$WR^YPc~fIO&Y>eVdRk;L(%mW_8Q{*yk-Pu5%oUSjK5@3p+yW z#s+m5KC1P!3C>$vyVVvGYeX`oI9J<~()y!R;qy9UC)m=CvpzLxW5-tII;M<_uAAB?p?Cmm+M}Y$(PV;;5nK)u?@8%ix%Lx7`D$=szRTvl z*>Z)JyGZp$NKFu2t97JT8s;;yIxJ|LXi$q=`j`o_J7e=CsQm?f(XS}Xf`mPDD-Sxy z#wXC%;n=z&I}$d$tc?aYKde6(gZ5erlR{f<` zXaNB7HDb=97+g*r>BrS;_=d~&xAhRjHX2gt&`*`PM)VX@XAgEE(tu8C&yV)6HTF96 zEc~S`BV@n7%(B(r(-%mr#e1OOuPF zJT#G@RD710+gAluR#b}xk9ftUKmlbu-#r%G6LI)#Y{wx>XD^bwaoH~SMX>VFod&y* zdBCB3J8Tb4^jvidU~^%+TPU>F3&DP`s;GHlFoDAh{$FQ z1p@;X^GV~RQcO%r-)3+YKA-e-gvQpzcfAA@Z-yU{XV^>5=x!ICgxL5bYKHg72Z?l6 zTJo+qV%y3YVA%d*oB{P0JWEnLWzHAQ>Y-_sx}k<3KBIVjO`D`^bKD{kCfcf&Xlw z+x7%j_<{6;;xwMIzS$Tsc-{O3{fx8vYTcz`E4OntF)}>O%eZE0z_VFjinYnDjcbVB z7H;f7_ZriTA==}{?6DLRAoj3m+K4}Bk&>yS$tCJ67x$|bz;|zqH9~-jc&4LLU!Kux zP-o9n0F#*kBdwgCFR8$w-ZZ&+KlPx@#zgX1d5M9vjh4Iz0|0OV$OcPyK#<5#dTe@3 z`eoW5aDJhmTD(=OL#6nKp;tuX^KWfKQ+*IeKXvIopJt>_BbPLNZ&1h=0A(ZA1>w=v z(*#;a?&(2bpX{yjp=7az3NbZ3&{y6y3IpLFaWbK0Y|PjPi^+l?*LdZ9*VNr8nJ497 zVJcfo57jL^*H$doE6?3BN7B%}ZtgSeRB=U^5N_+mJ*}L0%T3 z1i7Ra2kdG8@)$$D3!#N%{5peEm6D9P#gNNaQ6rjTchne=O}5=fT118 z?(E*6Tn`w)(M22LwXmEIE9yroe>MTX~eBGKft1UV+oMTCX}MQ-6*dV z%~jll7wmB*Pl+-`^MON?v(4YQ*Q5+lmz|wMIApwlf(|NXYDx)qBe=JKps0%KDcNYK zmM|%LK}viotqU~}BGfG==eXi}mT+6I9$7P7!pZraEfOqRhZYzT7Uvh5^EXBb~QfTH;3iJ9x-Q96q&$v{&Ua z;jG-}=BX2kAL8|X{;~f@XvcCg*{{wGy#0C)mu=zqO7kGA5KEVkBX!u$qj!A-VA3lp zXvcS>0k|Q|RlR<5G&V4X%5<-6>sHX&J!f~;It|1AYIJYtgEfedLNB>@(=vF9_hP4B zCLHO_lOA>RH`A(uh|5p4YZ}iM%&zp7gHk`<;R8xMtpJwMnUC zLiNsvq4RokOc}*%VYjOZLvI>~6+Vz&g zJ66SXjm_rcG49*-P8_nA&PnWAijc-HmpXgJ9kr&AY;-aDcvWMR_DeOgba+V+p~B5~ zAUPK79}-MDZ<7s?eML!7A`TRgk=Im!U+U}^s#C<8VKlctqj93-Z{5#n+4FCbROe9{ z-~lDVuFmjeYMRqI(}SH1m={5Ecu);rSR}hl`IG-y7k?1Z6^|_edoCR@H4_69=9l#P zWo0QSudW+}!O?p9v=n{334hF-8@pq$%7N2-?p;|4`?MRz)kKe=Od_(K?tixH(VVk74G#fQ>1_G$Pr`wzdP!2l?C zT9|XXA$mHY*;hcBT zfq)Nd$a-1z;`4xc=KM$iM=R_Eh5mQRHO~;n(Bn=->3Tn44QBMwBO&~L#3IHP)X$`F}RPE%v zG+-=?>}p2qVq{jalep_p*$Vl+fs2f8dWCp5P4<$!hsQ6g6czcgfeOOAZG#NjvSm|q zEmD*DpJby|)3W4OQUTH}xZaw{DJtF1guh3qy$1)dfh6SJYl<6PCAY(4bF6%x>`3VaPZdIPHf$b!Al2N)H0+6EeFpK*kxWhv4)QU8A82i1Z1e}41@ZgPKQV-H^eNGc zKqL${7tmYbd5v5jB}PUWId787OGmYxqP#cXI;GrfhgWZmMr;9F{NOIYb1;LC7>^tx zssr44FS75tyez8sNRaHud5^Xoe>Jy06vL{o$kK5YvrS>56xHor=b^d<#It8 za2OCkHu;6LK~u5X-O1r~y)`j&|LZDL{K2``6w9327X#)Mf<$5bOg;kszn+tcG0wIw zdC!mf2p-Zs=Y$LEi`2GC2gSv6GL#TL!OvaR!91*EQ#f$maCm}-pZ3Rt$nZOhr;dTx7(M`1>WM~F>})O zxOMU*z?jD7%#GzekM&AP)sHJ_41UQq6nD*20W>l(z)!WgrK(CHM10%piHZh_jm=uq zm=g#MazHByY5#$~i2+6>>HOif7TS8gJuCmA3@rXJ{U0dvp%X1Kf*F4A=HfXz#7>gr z_9QE3=*5nV#xf{6acvdD)>b|0RiGKHErw2s^#>y&1z!ZD%(af|)Q5M+5}6KrD6?yB z&Z#Ohx~XMJ$12GwM&tX0hf1j~6y6=%61Wm@|M~}id}nT_BKo@TNInJ+2#rjoy?wst z9XtPg9T#Qr6lMNInqzL`X4iz&7M-c|Pva0Rf2vy0vlj9%I0&451n5A~k+X*s{_(lj z3vTyM%z5fZsDAnTvTix;TOKfp4qV~`pB|9G@cWmbaRVkV+;a?)r#xl{e-`e|FfNXp z@orDT2?>+Jg(TQ1*drsu7uBv^2TztP4*&bgcCT3Fep-hrmT8l&>EP9MbVzf|+3Wt5r}|dO_Ez6AuBx#!9DX}!Qb}ht01jm9(dX7r z16Ron7b$QYjPF-7Z((r1bnqI53M10>ozADvPW=}_b-uCF`}*$*XKZSX9{wP6jZffc z>XX~&A&8>*YESa*cm|>&V7a`4U4-#BOyf;iB)>69fatjnn}CW%04M<^X65SBu8R_w z-?$W$VmIVU8kjukq*)T^1aicJQp!r#Ig+=Xcpm`zrluyfnL0VKcM{?cd0_lSr|JMy6 zp<~WHayERi_tv^t8r1tFklIX@CO5vn&)!lp7!TDcfh8dnL5J2 z)-~Dm9-@rJ9mQ@*r1tNTz8f?~hgzo*(`ce4U74cygMv6rcjCb%TG9@>nmZFsUwmDc zs@T_ksy2eT={~Vzs&&-gzi4h1sS&+}7&&mOjjfKC98_qp_e9uFuN&Pfu8eOOhb-_* z$C{D0>5q1nl;`D9-#qVD4^U||n9XKJBsBfubb(*Pwae!F*?p0tDv(3(ou{GPY4PYe z)1CzBK=_CD7Qg>Ks;gpqvUAy6F(>8R@w?f}Ss=+?=kcUBQM zAt!rm0PcFR7*FFq#~n(QiS{0hn(1aNL^g~8C=Iu8c(%n3L3}k8`Bddga&qpf9^I|g z?ozk=hF6>n5>Aift0|7_d;>H*Z=#107Cgk*j;f>b$ToKV=*!m2K;Onj-~A3^NSYh% z?B}g$KiOepKs3hfihbX9Czy{@+!BC14N<1%mYF4*H%(Jqfw77qLEL7=abJc2A-Yz? z(f#;b*~qJ{T{G~@2ofac&UR&o=I+m*KyMf?Exb?@msP?~U}95G$mMf#5`J)JD>y5# zA&X+xmdi|Ho%vl1#6sIjWH!1L@HdW;V=~fdty?JLFvzT%NOPTXh+AE_Z5&t}j&_)F z^fIX!juKcAAf63hb+oWgXIBasr3rWYJ#n&FP%FX%P&-@b5zW}gfSb+M^Ijkk25)kM z6jt5=@MUaf*erzubI`B!OTgFO_90arcW@Vp=#zIbM&+$Kx5x1>{^d{x6oA#x7xSC) zD6`-&@1YL^8-vP>J269sQnq3N2>i+?w=+Y6;+7y_Ug~B)G^JE;xdTbpLqr4bM!l|+ zPZ-8qQ3o4mvw1M0L0eLpE}5RQDt&f zWWfO%LO-9^yB?G);N~z3O#&AntNBRNd&`uq5SxCJqyd*csG+lB191yy{SQgHhN8S4 zr0lv=jXVXkZ%Iv%eI9vF(7<|rh_Rt7jM+hdHK-%Me8M`eh)U}aZp5YxrGVG*%s?`k z{Q0vA0i#W7B%Dp}`4#(<>`V%YhVM5?4%(DX6OR`;o|@g+_&tAVdj%6gFO7PY%A+yA z$77=lK8NG1u$Sw(GTio;PAQkWqudtZkHlhbU;L`;?)b3=j!0TKTj(Lvd#)u^3A9RK>%u2m)0VFB^9n}Wsd6Yte{!vw&okV z`vvR~R|8T~N!HG5-~p=WX&PTs)xM^3WQ^?~lYYX_VV^UrgJxfKYPc(LC}bIDd8r%- zu^k^YV+5_V(4n~M?in&%%4`u&S2@|~%Sr1`R{L7sk-EU1dio2@m^E!~O}%5<2*}MO z+s1X=bf#V@B=K>*Rrxy_Mm&0$!V(I{(We8;8|`hU_!y8hz{uWI9<^Jx7)rKdD$D(L zUL98IbzEgC_d}`!KQ%ii^_4FA9*Ufyu7i4C{`EA#2z$(ul~d{1o%mJtjG=F;CYEt$ zFm^pXzP7Jn{bdDOk2#q}I2*w#0*Eb%#Q`xlYir&U=<_a$yQXCd!{L;&`?1~$?^GsX2TetL<%;g{{H3&{ z7I-j#xrzH%PwtK;{X&EcmPiGh&zPHd32XS)za1YUH}O5|Q)E|-bMfVYt5C5cnkDv# z+r=ld?j!;Mt1XY0wl8?DS~969pS8J1^^|f~E)I~>0Nxs}?;i93Iz0#d)a3Ln^Q(Ur4Tn4{`YHL%%sz(57NC4FNh z?zSrLibQx*?mXK^st-?Hcig|-EtAEKy9Vr%fXISHLU;X|%GK7EcOLSZ(QOSvYv z&U&Q41=eq7u|{XWCL^QH`Y<@a`*D}6E~Ta+1um{FQ4tY*KALfLlRE*sYRPD*t-4a0 zDv;TKrmqDKKUWVnN25;F85Yo;h4LAZ3gq;<_5lz1#bCQ;STQ%xwvI8KE2vZgl%pEh z6!aFdeFBy_D+A{z+w@U#+mT-pj_-11z}`H1=(+5>@*=shg~J3Ode4EBX4%PLr|m|w zN7$#B8V7^*W85e&>dk&2*~<38)g@Mc_iO4z&o1+<0shPW+@&fraJf`9^OHY%iGjPL z(K+%mn*=z<-lr2RiGmck%MChJfkS3TCK9MzoT#ZKY~o4z2DP?1U1xb0r9VxiE_JpT z@q4N1Mu0tQodI&ussmv7a%BCR-$WQ4uiGy8+I|?HB+W4l5^+^#;!pmWB4+5`^c%)u z)8O$={GSnhEyy^;*wSNv1G4CBD))D|=-V;;|LFo?^JTLgb$x+~DTY+t=&J{oC;~tJ zAY)&}baez<3K&Aq2if=^4Jup`@JzG5-INy;&1h*l4~}UMr7xKW*ZX}NtsV!f2?JBa z7WA*2p@Bmsepu+zScNh@CnLO+fC7H?PAVBUb1{<$M!DV{+IF%Nr5jhHh>Eqn^QpBz zr5fKv!S%lL+J+~Z4*$xA2H`988v-0~D3IG1(vdniI66D13{JXl5fsfq=ew`X>`Hw~ zrc`nL5>sfzg}G6GN&G@~g4<2&DK!>?;5o;u3EXB!F$sSBKFjj3hi^R)jZ+Jdr z$w0o}Jc`_)=jFY!ZX8_4BJO|0aPPAb3swg9nNke(NQH39Mvbel3-%LTpshY{tU^x7k6bmGB7H{ zbxq-`2Ca*wbuZ%KlaE6vJ2HT);tS7he4TUggi&vTu&CbT_|pU z;T0xU4#|mDL`hN-Wcf`me>U5HJBq2*GO{M|JFQOD9(GdVfTW-W(PHflb%&Y7v*+MX zU*dM?HLL()@e+i?N}8f#0(cY%>bIO`;7-Fd0LSR?viiVSu*8q`*FvyFWSq^3{b4g$ zdppf;9PRaPKbv#;HfE00AdCNEIID-D{@40&`c$%JBjpla()WW1@z zTERg;UFnmb%i1?(=_{1F(IbEWkee-PR5RNpIY{*ER|=F`-sI6Hyqom{MF9L(u+ETf zxL!Wn>xOY3!`NzeV<5ig6GKa53&sbYCPhzXvWYa2lfRapLW%}r;yJ8ts*SNy;sx<|YY zotBPf*Ef5VvN|>rea~fKa4I%c3Oq^(Xl>LxVm}ZSmCMhcHa-_(;KmK-Zg`AV z?hL^v-^YQ{jhHVVrvmZGlMTl2uJIv;8xaAUIRE=g9zX&iF-vde(ig_JmPzMChtSw}}Ob+C|kTd!B#Y*+@W zn&sR5$WKtX;YBE_WaFzp7$qL4Zb}YU*ofIbucx6v28`x9eJ0(p1`gL;xTf&7Z{#LX1I*bD;rg|i1J-}{wU;TH#~Q#F=Y3?#P@9lK8DpFgY9z2 zi8pnhF~7)+tq5G(tUq?f!gP{Ld!8G*ZHka10PqVAY__(|o=R>Xy=dO6UU%Q}OXdkk zK?8uEd;9}Q_3CWdvxB|MN<%EBzUMjEu-!w4N!oE4bam<((g@)&kbgr{)6TZ$!U=o- zzzT&S6v)mA-ed(H;NNNZoSZY8gQ6*bq=xcvb6<)1f?Kq*^n1j3+_Q+fHN2hVgQQaM z2H-Z^e3K9N5okT!(k{Asd0=zfAQ05&uXS48kd?@Wf`%C?+>aR1dmxk*<+RQ!|Jr#l zJbNfhd^WQ7X!DS@aCc90!~5o@Xfx{h{1&XxnV&y+OrjCBOcn>?t$ca(#Nw9KVCjek zB&**{iqm|f!n6iKA)o;?r5v313E4-Xm0P=6TGq<#U8XaH3$XPH0B32L@QH!Rzsc%e zi}x zZ3n|g!XFH#RrU`I){btZa>L=Z!~i21n@|3ry!X>bRY!U3)X;-PT!CL2$Rimj7__v~ z=1WHc4g+qptN-EQEj(67|43dbU}6Q3ahSDFQq~pmQh(GB%JRhS@mB0*`B(IvjqM5C z3b-mP{Xt;B{)8Gpw1@CCh57eKAi3)Lq$%c2BKgneejoJFu)xlMLVo0tb_qm0Rywe^Tjw)1v@Sz#MM^z(t*}BSPRjG@gd8x% z%h1VvTKZk8U;pCsSSE2u3FpIM!K5u@MhYf|hu$4Z0?S6u``kW%KO-dY=9D++n$ne8 zSZZ_;oVH`HzN3aUhxTPmRik`S5w`$(PLe?Yz}wzygg0`a)nme7GUX~N>s-fx@9nvh zn89)vyTvZa%9ykl?GbY*1$f3DV}MES%YGZflS>BQrLJJ*@b_@ze&SCc~o_X|#`226`N zJU(UAhU>ExJrJ!$I=5TD)1}O}2J7ABS3?I9m7DLozjf7M0{^?q+cndq0CjHnv{>Ae zV>`m{}Q@i8GW&!INZaj0WP|RiD;{8m=et9op=1-R( zsksj+E(2cdrO}F+Js^PU<6FCh2N_w!^~Pi2%vBR8*(A}f>3+2LtnXvnW|AWyeD%I_ zb6>_G5+wyJM^B}##$~=FfK+n|bsCsdzt-Z6v=N#;0Xh$6Yq2AH_T=+N@X{BLl?Rn^ z+I}R39Z(w`n_MK$;EPxHq|3ZbNRl!?N<`P_$av}+oeZ&p^LJnC5kHNoxeAsPgvHFN zwNn0&*E%dx#|4BK*>f38tj^Y)lxgpdMA$Cw**t0POza!S0)r@N4g|gW(*rf7WqB0O zZ^um&l$!NsvxP|sjh`?CK5H9@X9NUci_-ZbYLL#$iH>d@)ZZa+YHh@g6NS%l2dvdV z$~~`S-QQq8j=ROl5?Y2HL~2Em7wFgb&0a$5-~FnF7E-X@`&d8!n(($++jF&xiE#!^ z(rlY=9eW)WsIl3h#~<%1$dGp=D*3d9#7s_zKNMNV>tI}<{(|$-tai|{;tqVfd%fb$ zGsgRjlMW2x71{c-d^9wollx5$IzXdRkR{cA+CM4B%`9a^Eo{y1lX`e?d-rbkVeN~z zY3#UfyRswjMNuo{Z>UwRJ%-NJT>R`Wt3B@rlj*{5=&H$H$runkdQt7 zNyyf4d7Sx1?Il_?B$MUpUK`0pp3(<}KlD~THsH5wZQ)v~54=u+h>Ny02cM=Q`^h@Q zXQUPVmnYlqX52LfzyK1c)>g4y@@=jeu<#A<`^`{!M8NM(kf_GaN|i|&Dy-ILG${sy z5tYZ_WHq}bEa_CzCT;aH_!G7co`#2YyxYd~bb$c0JuDbfZCzH$;9Q)Z>)9P1Rb>^-JIMj@G2c%E-v0q5@;Yfptr-@J^me8%wm`f2-jL&WgwQuis z+Y1M{`&9zV(&}FX?UX%HmeDA3jCSkw^L9paC=48RSN%M+2WSeIuR#XQI&gW8nI?W@ zL!yGUvXB!Ft}&98U_t?a?{)Zy5fcD#5H&OoTtu}j%wF@61mW`oq{f^J7LJb;Md7Da z;&T8$B{RRLS$il6YJy9>lZJhBJ1Y~Vh*RqmN2LI`jBS|H!iukP!vXtJvZ{`1qRzYr zd^%xVeokH}fq)@;f$SY zX9S%y>j=bP9ywn(uRXpql${gnb;013GNf6 zgxg!cOUZUYTQLrh})%UZD4c7UNq+;sx_{U=U|L`b46k2Xm1*Y_n&-w zhhY_2Hjdfa=?003ik2$%RSi%sng36%xM2PwLa=`e+M?K0qEH>XFn8Pa;h7sl8Wdlw zIv!XqZl$zuN3gFaQ~U~`^+QBTK4@oV>5g(p;*|Pao_c0U)TCm5q{HPqd7^$B!oqDm z?+|9RYG^wvbAZB=+ke(sWl+lm2N*PUbzs1kG#?vQEt@{Ae{ydgDffs=OWJ4Z$77_| zYTt7Bf}*WuVWn$gq-%0)&k`k>j_>WiuT(lmvioymZN79qWtnZ|v;&uPnEhMn*r(QN zkK$ffMA9Tfw{sF3^-^+e>}J#Olz^${QkRUpp-7IOjx}m)<#&{pg;Z)SvnQ{052$06 z)!^G8&ZxI;Evu|jHQ!B--3crgLnTSk;fcVin7ya111{>YX!0mqV?bx1r*|dlCe?#5mKhfA?5tZbuwd1_)IB~RFE_{OtpHmFbs)7_2 zmjp5UGHe5ZBW-FZp;Ns4Dv@nQAsL%3?@TpCw$x!awz~HSaw`7jomG6 zh;GT8{f_SkJbMrPy5i91G|R+Q%9rI{z3+l-KvNPRBpv#bOuZDL>1fqS>%JtAl=d;U zV%FtQ`$ib9h3o7ssFx?@vFtkj@R#Np9O=YXNvwC|pAc@F&&7?vn6WVwcBDOrk@fSY zX;AjPxo*>4K<-PN7pmhhhQ=Brz`$iKBOVYxCiA$F7S;NjA#4v2dMhHMZGIu? z2kvY-2VB^^`3^)}FMIh7O1kEps?ItL%?5u=Zl!FZ6eaqlhx!I@ynP{FEU#-&0E4f~ zz8r1|t?1idXj|KVJ8nN{YIV6{wccQN+Ox5T)`0tn%+;+v-s~5i2`rwue7>H5;WLd! zqYIl^$3#}&fkU}^45J<9Xe0awf&ly1h)}(#)S(?~EQw9wi49NeYxE-k=yj^_J7Qm*J@t9Pw(OqNB68rcUOEFOu;34{WiUbn(L zN^AIlcB0|V5;4$5&opEde0P39XtP`l&%YeOLr=PCHMY0|ZZhO9Ljnf$5zp*Bew!Fm zU|lvhcp~^skel2W=th+JU{!LnNIGkELgI%I3x4tq9fbg{=cVpGH8vpg))@hb3%qRl zcW(JbX7it=FlPMxg2J&A734JF(bLl^ko!RrELn?z8(*!|RETetDPwoJ?FGp4OjouRyaO-SbQeNxbE+gpH zZq;4P?ibH{NescNITFXOo-eI=%W-iCPbjZ)~`2xUj3G2<+%1 z!8Zv(S!9&KgR*4oNrsdP@>vG9mMZA{gyM`1zb9!!Xx53-EMD_MQ@NS4a;uK%;6A_F zaUqXEHkZTcwg>X7kgVL;l3uw%@=(bV0<6X4Uyf$_e-mjd;@|}?`-XHnC-ISi<3&+# zf5G~hsQNSH$u_iX)T>lln_n#*daeEaUam{we_Ha{Tcacr6?0^FG^ZB^GRdLT-Uc1d zv!E29Iwt4zjAUlP7bC1^Yk#9)2lmsL$vHuId~S}GZ6A!o+S#lV;Jit{OS|}u13VHH z7qRTb7lv+nXM&EN|C(P)J0+K%p)&*$o9+{~)_Ck++X@*Qx{e~+0F7+wi3rOM;FHhV zHY$!uOV@bDP{d#`^?Pv+nN>uDVFPqZv^lV>4VyP4!BSo_8~dM}55+Hn5vW;g|4m~A z+_t~&73N=--Jd8o{r^UFOGy%q;YPm#E6}+|P3QvdJcn}1(BQ#^{}&^Uwd!vpE_BW# zK&u{-^6B_0DiJE`RC2?OQQq@9a;(|Vi<66L0OThjRwxkHeA?VyTSI9i>%L!QESMqf zRv4x$*b4l{<`k7BV|)9H%=AO z>^K|vl?Cz-uj6sZRzTh96YWRNhGCJSn;)X0$GfKnOfxUJeWR~N!hLaIYp>~>#5=E) za$WO*muS4Lcx{%Gs}x0;=L3C5Bq{5UWm%X`s!G#RbKgGJy#d2cNKVp`Q7q^_Y2@Xe z7l2Y|{34Q@k?iQLK2MU>5tNokmPTKK(zIMja4Wi6|49gQvuhG`D#{l0wb>1$nZ}oF z(*>|-SjHI%byny@+l&kCn}9z`gIe=Jx5RA&Vrx^K%fr{Pvk3v8hkj-Axzc8Yq$-71 zPz9FLNu(6q%F`iC%A*d)r5DI0u^aO^!q@#X4%rXwG&G3_dxY>>1+({oty@&6!Ta>4 z-R~^uaq`EU)2nOq!or~5YPU4oz3F~Q3hFGHO0)F!wl%|xGaOq&IiU6}?P5(hB0W~3BbwCUAt`4d z9zoCh0J7KgqEkEOI}ffl<```F8KdL{ro{^0YW)a4^7^I0@|K-^pw!*VZQ;~|eoRB` zb02cR|BEi1RrbYbBBeTc6ODLjj_^Wjg{=UOyMXvF|DX7;0Y4%U=Q@x1 z51so%(U5#UH%0@b|0PuWu8)rnl%;|p6|v3l77)xmj_|0#|NI?r^x^o7YBzZ8N%Ed< zeooL0;guJEt33kI*_}#pLc9Osq9VWu6kmXbAMmEj4j7Wko0_Ltf?BV;x41F}&*HGU z7?Bee_vGo-Z@Lau#;1_MP87XKCcFawO<xFJSz*&#E7D921`z$=~J=6?o z6O2jtg7GHu!&Zf$h${#TU@&)dP;rrwiQ8&32lTwjthW1cIZ5q*;H)2pw>2+gthm3Waql6KWl7)sK%#^!-8cTzjz-1&(tlm7lE+r|d;l!)#DISx3 zes%?fbcL~w0&j5af9k!n#rDS4$QSFV(QCOvEj8ZQ3Rg4TZKIw3rwgza0hJ!U<5$kz z4~c!cK@d$E5gBVZ8j*|J&BX49v$Wyr!iehjKe?HLnm zFiX0Es5s?&%5Z+8C8u2x5|o(wH%=ah2a1{wAm;B0G5i#eJt)wp56-ZNf$sITM;PP> z255a=G+^4hZj{GFafMX%&jHZgVPvves=zxEBRXUt#RZRbluuQ;cn+XSFJ9ur!?mDZGQMw*nG|^t0!Ds6E zKF8f?sF-{NI_)rjGVs0LqFj3>4eDxcY~AO0mKXhDuT+iO{lO>Y`glgzDeRqE(G8qm zZ!ds6&DsH5=j$$V?98co6(s}ABc>6f!=4!6tK}>$NB-)=5WG7;N+kxySdqdfQ4Y`H|hNU zlSbS;X9RkX6{fzCZtc67_JK)t9zyz>g^H8;n?xG9-h|dB(`&MJi?JRKQSEy)vJwoKog5`?m5qn!I=`beY;kFiu zl|t~}MjXHVtV+Rxq;^^=c+r1Com&B!~P{bYT{z0%?9yL;h%R;nh#b* za{->#m~&d*;%c3KB{6m^jGww@rJR-@plQx5qmzS9HYL6*zbQREzJ-ySR*3~i;@((u zcy!mbWE0NprzjY0yf&bL{(dy!Tko9droPT`CW2A>Y}On7CNDN#is+o;2Md zoBNyt@-Dvwe+_Bwbnyvc+c@p1*MkHGIRPEu9e*C1F(Ve0QAy&S0>6v4-mt-Wm9wyy zFaCLJu7^s5xcSYKrV1L+*mtpkuAg{L+25a@lcZnk;}>55yx)%CGbKvECLt`kEKwdj z^4z4=M&$byC(Z`TORo?N`M-u#8~hoU_**QeKFr=2PPTVBwt3CLHS8IrUpc-_Sv%|e z3dvEm&ur?e-EXW=cCT999(<#~#y{7JT#f(KQU@ujEy9YJ&Acbn@hMDCU^ZygCr(Er z`B<{UdFhk8im-@Lo)HduDloHJ^A-E*3-~YbW*f>^97#B!E&ji8;v zTfkX`nOtv|80kOAsNyXB$*6*D90a8Px5=ooN74Kq6beM9$*cRsq))o>f-no~SnsJe zmZu`bGW$QZI1Ucz|$8em;5<(>ObLK*wEv{s=Y4c>Zu%>l}Bjv`vWG z`?5$Oz4g=Pjyt|C-}a6sHXZUa2Jj+=Lt^(zb^=cadv7nb!TEqAoWgnVvVgt0eHAd} zyh<)e>YIt!P*)1M1UcgKuY;^XsuRI5j*HATi5II)>ioq^)P4x*%f8^Q{Ge}wN=;}x zi^qM-x;*S$G-tLqqVr_^nH`R&D0?X>khvPts`Y-6YRdrx%bO?> zj^Go8Z3{v2_;vs=g#!4uIaT*7u15h>J=_1812uI0I|u5z`w4y-c?88waLXk`H-e^{ zdZfgk$CZ~{*BXYCO@;_r#J757-n=ruVa_&PS!HdhtJ?5DbeEI|w&nJq_hK7DtNX1i?Ghz!6^`lFreTv}mFr^!y*@V8KScyea&V2eh+leR`Q@|fhL?Z6ABCiaFbi-zISQjuYe&NYvf+Mn zIoqN3dEHS=94mj3MhHP8%7 z8|@1&;yIS;p$_-gkGps5tQtMr&RID;UU%NS(hA0Zs&cK%nM7pK`{2@r=FbDh&@2e! zRu-V9hGqvM{u@e(KX0VE#{fEUz>EQ~wW;gGl`gf9bM$=5FGLJZ1g++z5eR(LBc*@3 za_?jPLU+1{3z9!wP5y|Yf3Tc=>3ygbh`Om8Mc-gpbn^>k{{|F5sxGV#cv=vAA@QL3 zJvRT?`~BE96?2+TesUVGL}NuRUS&}?5P{aslO>40#!`lZ`S9mE#0s+9WSam0<=y;}J!R#ZHceUQ zLi*>57E(n$M1O;-5Wi2?!1iU(XCeCWX|dfM%P2t_w={*Dh$nd~=+-bfNfHR@7tKcB zX9m7uPyql^A{w$zKR>!e6c3g)A`@Kg?E8yn_niQs7-MqqTC}doQ$Ju%-eLuHUQvAs zzl5OEfc?^Uw7{Kky*)UisLKj0VcvKiZe7(w%i`0u^c1lyl}mNx1~kzzmizaS!XaA; zPR--<{onF8`a;(pZg)azYM%kUo3k-XN|GoI>D$ajR{1i;_e~q6)he`ok za=`s->}LEA>=vT5NDaR7o74rG3FY%^;9*axC*{wzHY4dy0SZ3FsiGoMT=8h{h=u+} z+Ukk*eUpoNuM8$W#l50QK~^iG`H=P6FSM?W3#PB{+~ey`gOlHp&Tt+c;*bydeFdtE zU3RJ$+XiQ*##f9fAupR4n4cBJUu;=DSKkgC+S*25Wk1%HuxqkBd2>M_#zy9S=}u)2E1iYfw(SQcg!jU3@1r|h1l7)6FQ(T2 zpzbY$>iE9(&&Ek`x8MYq00DwK!QC~uySoMm?(XjH9^BnExV!tDe1G@Oy|-%a)PHK` z*39e|r|J|%SNG}Nz1RM%=UJ;`q&qe4j2w2&1Wbs9>MvV+ho3f4^Plo!n22O&AK0;D zcuy}rVffzN4gGkawoZpysFLtl8TZ$csrT=Yto=)E%EIGFf}Cm$nN)Knbr4+JQ;C@o z!*Q)x%ty12sAN%c(T7K@4ec#|@f8yFzZq1$!x`W{1U74l+e7%|%eyb^#J=p1 zs=aNizlj~FudZwU)vi&*|I=?5wzm_?wC*H|upI0kUQb-RZk>hQ(RfKA7 zCjXb%+P9}WbFW~RzliVUeOuyt%u%gg(Ph~0{t+am-iNW+9pnk)n}&=G{>s*G$sj@8 ztp;khfshunl9hB)9v3ImZF6QeNP=SM zRMeIog0H1x{$a-OtQq&uXhtgcTbSzfVH|FA?;$hRt;ZhqEES`okzscq^_?U^1*w3; zw*>D`k*?1fLs`t*guH8=gFa8U>`Dg9gX~WG^lRhN!E_faF=(Wss@k(3*89Q`19QHs z6~}788=j$E75VWSGv)AT*=Q849i`}hg(&smoHzo(GkKStx1Xd2eae)`IVA6d?)&%) zLRU~1iBd%$_*+Ef6lGmkz{14%1zMc1c$&D zBIm2{yPXq9)jYoPLk1Y2@kyWGFP#VR3apQhrn1#qua8SQK_&{vF>CI>-Uv%7u!d)# zUS3@sT{7WMeU#Ikj_BgdU;65%z7q-|@m>5_8jcTjJ%q4X zPZW%|k@)3TdJmsKj}PcSu4*6n_IHmwJyK%Q{%pBh?mNVv<7tyl3)U$GE7IXF5eVn< z2421T0*NF7-4$AOjRbsE&)vU&|9<2R*tcjN4LqtDrk2~t9Hxe?V{8?atG(iFE?yjP z*$8?nh$%p1bgeEd*BvEfl=9H?nO}q;=MmFE+%rSeV_7)b+ok0IQ462JNQC3}jLx)=G1MlY zK+@L;=WmFqf-z-n-ey56j2fn^HQeJFn>S&$Jf@cC_!Od%4ma;J5;UYY;=wb?FWp^`9{|M-w@>!?{qtslHB#r1pq z{f@(s=Uj4|qPvRtrnvS}Skrhd)7m+5td-Ejo2gt{T)!ro_2-3@-P?LqC^&6mU(wfm zL+{vYi}#ry&FI7z$2slSfX`-!4QRX}9j+Z}Y8n}ONq_#OvnX~&n_<72Si!1C1^ArdeDnd0MkN`Nj~D8gyQE^!m%djA!q$;)dv zCjQ=&Ckq$(fj@|)753M(T})U`WU(66O(oRHR_Qb170-Z?_(Za+T^cA@5C08CBwKKL zb4vt?jT_{QKL+~AM+8zsP|-q{c|sA?wreF1Us2pQZZLr;+^3OG&C`Dbe>+bn0f#Gy zp!!nGv$5=n%2KkdOl%3_&MU5WPK+O;TKL`M`?bwud9`&a_^RiSgS)6nu?-pR>Bm!? zqWc8?it#TLU7YFJg?=C-h)@{a@A+d4r|<>Ix?S3Jf`&p92X0g z+&3B>cfTWXU?6JBuGQq?BIfhLLLP181NJ8_8txF?w%cZF2!^%$HwfCn~g|(A{3Iuq~*kw3s?!%B6bbSj&)1Du> zLH`V>hUZuF)6;<0XarEo;I>^2_N+124Z;H4Yo`|nj_QTb@dS6*v>E%%AoC8XD72uc%I!i#^GRD}W zWlHi2M(2+bg{und!>LVNm*kx@F9wbe1g@%{=XS$y;hT zWPQE9kB4X;-b32nn3>V>Y&)lfZjNWPSy*d?^1c36&2asTbPwVA>7IYBB#aJKK?n1MnZA2%TT|LR zkys^4v5kI@Bk*lW!IU_ZyPG23Ttwv*^$D&uL>-w3nK>$Mu1FWhe-@whnlX zSj;%~OM4qe)U`Rd^&yk|(0~y2r+uwhvmwy99h~T2*F7vqZ>4X~nzIW~6NKfqFtkYY zgAzI4oq|9DNSfm+q7?fhl-_q57q@J>i~2?;X-Zk4_hg(nnjLD#ezWj$vm9p)clZHT7i6e2iCHVi*KE*)JiqmEjL!h%8WSYNYm z(&YDN6AK)sq!??zazFvYR+|uPaL@2oUh3%mj@$BPcU6G`$Ub{)R4%}+KpR~JFQJLm zMs_T7+_0Xl;p29XF<(kq{6_si0|)R4xX0gHbn6$E4(aTDTI#z$xs!1{aAbEh zGY~ozovEg>>dcTag#w%oTb=WRlRR&{|p1SC6P36fRTJy=-hj+YzhKE$d<}OSJ|k;J(GzDD_tj<0Pk9jbYRLp zF6P^xeY@>He_sCFOw_U_CSy5#9li`mzkD^;5=y`CuE7fx);fPm{85luKg9#b7dMqr zv(?48(2BMAMB~To0)f+damVV9xe zyw!q-aMPK8iP8SfQPwpC^SPN&HtH!QSZ*&nTjcyDT54V_hR%KO9YxHhlnSy?TQ#qj zZ=ajVnn)v7-Qa)P!+aS6$@IPfvWk;kU|o~4CV%=Hhp`RokHuIVZd#3H-bUv4Mhhzo z3l7dt_h~PT;uE8>oM|F-;-Ny2m9{tT%!D;8A15bSytZ^g}=eAH+uK?m15`=D$p@>v$$@aM}JAx)3=X?r|&P9KkQKwaRDsNm_B=C%AlI>7gL#hoQj1A?b%jz=(stYK4Pd=+|0@ zmAfQXmKL&n!iy2RYFY{N4<|o&XT2++YL57DAYCM8w(K}UWMef+k3NAg;Y<=fnpvmu zut%qG=&T^qmCH3s*;9^zx*XG~r)0j{-LG33mW+oz`$b7sK=`LX00$!Qg$AzV4;F$N zDxgqRq-3JTH&vg^pyF}NTCTqwM#OpA7;4VWWAFUnX(T9mP`pcl7U9ymsBRNA)$57^W9Ifds}Ou;E4vRVe@4}= zG7mZ8S5}fs8!4lqgN~A2kOiKekEAaVGO6J(iS263!VEAr&+kJy=s7X8zL{^sMtb<> zocr-52MguQ; z;y@I3i-}GW!aEJ82E?wNFWd|D!)f_t`0s=E6*LzlM($hS6xNO^DeDtr$Q4K$_%{S6 zKJ08{X1ey1>71$hI)l+d17|53JRTHHuEW~odvnozjiIrXd-bG`<$FNH<@gY`sTnr{ z6%c?7G=*nQ5C6FEXm4Y}!TLS9=u7fG<|s4hoAeF$I36e3@` z(og1ubLvS z>OY3KQAZB7XmNKEtOMqwkdP!Rj%&#gC=N;zn_^25b`N=^tjO_tDPhtI922ypN@>@H z+#7psLGWFnq_PjpU}KY@SOous4LpKWN5P7Q%+;iGq|)M)8!2q^key!;4rR9E@q8S4 zUnTNb!txohF!G%Ru2eW~J_~l#d4!C>IOejOfz$ajrE2iY`>wvSC#|SQdt9IV&cEKr z391|4*klb2Dd!S3lbZUOHuIf+%`-70?uwDTUIY?B?eniB z!7}>cTxWtTeE9pm$UygmSVgV($KMHke;2kd2Wzyn{F8InPPOEGY${aIHZ?sOn?d6MCCE{j7i?w zFYjMr3fVr)(w)WjGQFH*RRccJC|>jgHj-?ac-Pp``1 zS2Cn=E6a^7f9$FJM?_oQuKbra^+@bo|+>_}kuA9G50RVe2M=*r+a_IFL5i`m$lk3wE?Zzl8UvA$}f-7sEQ zC*WS4s97(@4>KnmS%}lwMw(3tBra;r>GKmGT#J_E&%+OW#iW>yN)Q;Vc~7cgaT}W2N<5Ti*NQ$$>y%B+DEHe?`7!q%wF8rINJOLge?a3UbE*|tS#pN{VK1Vg zaiHkb?G5;5tvOq+!{X2!7VSk&={aJhl>KN+oniGQ@kKu}T_-r6tdWQ1YBYu$>!FO? z8;`928`SsYk;YejLYF>*E3W-=j_3iAyd9VbwG*rDGD>JZhF_6f^%ocU4(o7OyLIqm z>G&`sXud0|H>_I$ms2!t^_)g$AMmh>U(X2mvtfKQ9%sF)_oddC(|@3dsDW;61-lVZ z9QV-sGVIvUn?wVeN4n;DYBZSYt|>#C1>zdzcQAm=f$OcMNxOiY<}fp~vz*(Lp}xR# z_=BJz0GQCZpedPJ$Uk#5)NE^%QNz(oXga=3K=A2K{XU3*nr=b9hPwLz{{sus$~KC< zX=d*J>raK(v-u1tm@SU>`Cs1gKYzKwCxD``1zA;_RJ};`cln(f=bpfnx?=J)vNA969D`J+grh}EWOl5Qbl^(&js?L7bIG!HAZ>}JY&ip%pt z!^t3cD0GGUe%E~WUxohVk>`kzS@|5Kclv7kZfxF*&(DtOujb(3-j;OXoT9B*YKXxB zkaB${1GY3!B*2#to{mM+{pW_|V~`EY;-N^<8lcD1&S*RI{hi|=WA>F>#b#v2{%c3zOTHU7W8{{4LD zaV7=pP!0Ll$$%mWLI@;XTN|4I|3RrQ@A{2DD|YUcAz}U*000(+>%2#Z%iVf-uzCFV@qmgUc?mB>Xw(f`RZR; zJc3_x^kr~S$CnW?PZfh1hB|_-zWp8V-X1ujOdfRKvB&X^n(k~GU^`t=3C|wW<{77r zXK?AI3&8;*f90Q3wfYq}*NDp`l(fOaF18{%9|51Qi?2f}#Rp4~o+6FH36M2+IopW@ zibgXBIC9m6^AoZs!T7j3mUw30oRcaZa z6wh%+&Wz}E{hB`qnP>Gjs=h0MV4c(GK<8?Ld0o&RtkMM6!QFKr=twLiM}MxSrb*0$ z5d_j(Zp{QiFx!`w;d@TnCdYXpgI-FF=}la4VvtH?;vr^?gTzlchEZxbW&eBbjRJHd z1TdVt{MySPqGHP}hu6337SItN)jYDU?QVH^q{O6cF54UITZZouDp3xJm#KwH5+W=j zbEXIdAK&s(ne!5N>(FxK6p5gIVQmXN6#wDHGz2}#!%zj7<-2nBTDs)dX%uV{L8bj`e- zga&cgxFt&(v1O$yO0a8{fgg z+;1QZ4<$xb#3a2P?Ve*JbCHX0njhxor@ts900Y(fNsijPp$~QFP&k++OPy~?9(czH*>@zrp0MLVX zy^-f!Xm6Vw|HvLsrfdpVbsQ?sRLj{{*_B;L5tV?i<330ErSkcbqwJ}Bwz3ii8Lz=^ z1ohVgf^=bpN)AvLfXcpXIieM)GMaf0s&N;yToLpMAy$BniyRVv{)B`~d_;^Xgr~qL z-+`SrP0Pb^gMWR0QSy+TStep8hB%M034k1~OYa~E00g%$DstHaMQzkf6y)^uk;&QsUH0eM01WKtDe56TB=Tr?ujmCYq1uRu4Z{ppeq!yKoM zDI%0UPuVT17JoVVN!&dsYokD-I^Q)Yi%m8Mh1GMPIvYq=ec?Gn*=CIjgPVDiB#Yl* zdbfUWsr5MJk64^k_oL~|U$3jC=0O_e1gr_fioXbhM`3T69?v0wdFO6JQjMS)9Ow_0AflRI-tXJe<~7ts7YE z8aQ6KGASKHx;A3~?BYByO(fB2&XzWy z%zaf`?X22jx?dr|U{e1{7X*4im<9xTr$RY}t3VovL=wNo!;fNyC#ttHUZHe|6k+OZ z@a;8b`aj+b3S%W;?yS}!K#TUi#tg%HumZ}ix7`ejHBI_=tkz*la^sO&*GwEaMD>R1 zaG@pQE4~R@a|<0E!+9em-?qTEZ$3rGYuvsg7++mt4T{3-rdMfXuuy!WZ@COw_aBYp zPbEC^vX2=k&T+wj`ic8jxArQ_ALNlq+|i17k3^J2vxamq zr$nhxkzgRTC?FOh)HRO`7t?Z!!dC81Z>~LOYXGS!_@8hdT^817rF%EsUtgHfC;!fq zVr}p&iVSV%LX3ELiwcOVT4KwB7-d&m-WAd zs{((xEe->!^uk}-TNEJOfi4HC?sf#7r1<3X^+NbT;eC~YfqswqLED>8`DBO>(QBZP ziWmI#ns3Z-4+=lrj!W0r<6R9)Zoj?iq+d@CtN!hC(xI_s-2^zYVO?R_H=EJhGpL5Q zkU#M2eEsxo?PGs>h)ys2HP%3mS|glqT$DRROeMqeQO?(9y`>zW_7oTMI+%JjBKwkh zs1hI~q^brGz1GGrU6celrL)?AlayEFlgr(#zVipJDq8xr{chQHYmDeD<4<+z7lNJ@xx zJ7kE^P!tmO{DD>=m#U$RpGRh}8w=KM7T^&Y{fX6(GP=x}g(v&E(Lsp{vSk&mY&uLl zi*oqm;~KAWVEeK=4Wp0_en@4n$}KHR5(+7N9Ua?X9qLKA@?-njZ{9movfGQB8fj7AryFy%}?`1i}#c z58X@1$RVYGlwEj{J<-M|X;AvR=rx1t`W2H-9%*QBTZ*IVC^W`Yc&P54G5%C^%093%OZM zS)?Z9;{I6}Une7kKCRxi_YRT+Ac8P*g9I7ypR85SF*F8H7%|@6JhNLx7CvMrzib9>o|+H_IV_+Oso0&5Hm6OHFZII`1krx>WbUrayZ0c8JQKrkP&@R zc&$2y(ZKik^m1Rj<}N5NjDK27++0cjzWIl|Et35H7kfkR`ODtCZZ;aojkGTgoyWhA zo~G}qb#u_3mhqO8`R}kz&QgbIM?xb|#C{e$hUd~dK`42w zoT!-Z>`bVs9Ak)Wf_wx1ih0@bbqKLh%^9CyUY`;vMqR;y*!VtL!kM=g4ED1+3yH}f zwU}f%>6@Nm-pvJnqVQ#hTCQ>VYAL+CYa#4CaQdT(0Um`H_e@Q?1qKL?FCErvQ5O`sN3pmu3Da?qjv1B(ccY#;aPMToR~;< z;b`$;T3;WLC%td$OZ9U3YnkO2cfF8hXAB`%f+tf7GCK}oiQmIeuJz%YvTsONO-)mq z6q21y-u%O=MteQlqX$Y?D;hN=7kf!RYp(lIB4)PqdB&&)zQ2-S0$-TACk&I_PjBsv zAUlo1ot8M$<7_BT(9kpjU4frCVa}xy7h4$8 zp1RVW&lrl~B7mN)l@X3V9Plpy_aD#=xB4%1gJ6#Da?=g2`Wy22l@lup(mvpPgj4>V zUjCbg#B!WB5sB-TtQ|a>FrPQYao^wvX6=RV22`uhMkOTWJI>qJR>UHIhaw!Tiu~ZJ z_Uv1G0RppzS$BQ6AM&wbEoMETD>5UCo`X>gY287_^qf!UNZjIgug{k3Chue`yC0pT z_69h%s0YT5o8BkmM9t=N^12sMGn*-_SE2(ub9N9|zX0Xg}>f)=P zvb*5joeO`s0`Q3>qbq*{*B7iqEm)cYQ!Eer?<*_%vrgRJKpGqU(R?Lti)OzlFIrrO zVPnbU%Qp-ewj_zS>Va{FUhx=>Ok7u^p$s?=%#=<9RQ)u++|k{Yw`!y|JtWtRYvuGo zeNy==hyhxsMq6cch^)lk?-}YY5Aq!6KSS-*1NX)w{C9tKS<<@U*>*o1V5~3WGv5b< zht7IAM`lg>^G$dhbuM0$Tl-2^!RCUrnaB&Dn30DwcDyYE_6*)XuYBl`uDBl?1j?@J zu(Vl&tm1M30F{HlTT7EcAvXSIqHkk9qa#s$hKKQIHYk-`huQY4;G30gn{&b!+Ov=0J56!g?`k#1&XyDUSv&0Zy0W>i&*>D(skW zHP0_^UOIms1InzV7PfJkH3=?!3r`PcB7klVrQl(J$Si-Oa9#S;c{CUhIuWHz-MEDR!vV`cf7x=<%7~?OR5=mD;&<`CEX!^2-&xiZ9NP8gwa%Tf zZq(jlP<3Wii$7oIXQ#cZ7*mPpOKE9D04m|)jE?@hpbD&UBvC>RJj8#-cxQiNI3(#B zyNIR2P83y_Pd)N$FuFinhHTS7Y z2_))T)0?oOMTKKyN~d1L@X7`RmNd>$o1sdXLvBy0)-E^V9ou>D1fw;(g{PyrCV71> zI}UT~M)w+Y01!1xd39nsJLPl(N#1TAmVRTn?Nm-Q5X%qH)^U3uDr?&bL}!8tLq=!S zfb=!uwXN78nEDk0J2+<5){D6%AezOwx2t z*8eTDuHilcE$=(W)B9n5Jc`@r-a|<*U0bW?sU~a?tYnm*pw;vg^usFnWnR9DR+qE+ zd%z75@HMkxve?K8vriq(g`?6xy?4>%*?76$sx_4)qMmrC8Pz`uvY*FfRPr}+CAbKQ zs=#TzHDsX{LLf%YqgZ_0&@Nov4L1Ns_}oMr23onk%pxzSd-du%I337^#&KL7&jdad9+Kk@oNXDb$ zW~~HvUnM`*UnC(rsMdx?QPNQiQ9dQ5#0$KuchPsWoD-efTNK=+B~uKT4k1rtYXabg z%hEbX0zTQcE(=qi1j(9c>xwBEtBX!+7o%8sM&i~9tM8?(!GPlI&e3QZ1Rit`itrCn z9j6x-%)El!$@ZpmkcOo8`o#{7>7W+Vxj->q9);maJ?rE4?e0f(4FpN#_-2s372AED zP{V1h@Y*7kPw)dhT&^}Y2|P;@JC?Cj>!4mX095kS;f^+O*_KiNO6b9i$>!Vr$uF;E z!|2f|X1Rz8x4{KAS#3kuj$muF^NqedXQGS&AaQk zH-FTK9*}dLpW2R)xCtzZLE$@AAQfEY7SuD71BhhqhMFw|pa7dEkmCaYGVk$H@rMm{ z4PbpJ@hYy>d5!lLvvKX@$pEJ%h0s1uf;n9ku;|C3n?)~;P{xl!BBo~XBz*iU_qgWW zOm`8WBRolsxX#ha!~s8868fQ=%U}nsP;$6TFNR5xoF^tpNP(Nx z#g+BemveMxuo+x{FG^9TYUr{teue@u2K>i@!S|-}dqjr)AL<~nljUEr(}(wnH5#NY zsJ{~?9ss4-(mJd-#S}uKv7TwQJ+4B2K@96am)U+0dl5NC`wxDGmBwE0=iT8`c%wa>m^t2X||l{BV`7Q=pQWq1)!}twluj1lBj9}s3|i> zG^8=4VFlE`t}cQoWmwXQ6FfPR=3nK)h;qFj+`63Vd)u8@ui5ZBWYp1ZY@Z!)zyV~c z9xq00b^EyyhxYB|*XV;!`xg*1D-C;JDbl|%X}9h=(xB^TH7_b|^eS#FUTT8jaS8&A z^~rn3;lU_g?sR2rI2!C~_-z@KwBJanClESn%(cjoj*;AGnQTpWejdE|qwv1vT476-_RK)!%lreJN(KU%*&7TV`p!KP|#CwK7|nPl`IgE@thYa`E7YtRfXxvkQvlnm%Vw+48g*re0buRledQ4{F$=IY4S`c;zce@rj46Xg{%+nfafsHtGg~B^{>F2ZnTLxA zQax*tsk#DxrtNhCL8~I4yt?mI8x&`_h`7#(H6*;b>`mjtD4B>=t-535mN{DJ4}{;K z=>S%x8S+EuV3GS0@R_OxWpjR)je6Yk81m6`bTV^B_t)D3g`rB;5%WiZeX*Ud6*HIvzi<#v<^^Wg}-tKmen|e$)@bf(eja=(J`S z>X@<)mU|-@8!b}DNvx!U($A+`>JbyG_+FVy$f#~+k3#{ZAV0o}i}4pQOBeTkuSHk2 zdSAu7WX9gxW&PNl1z}0RPt?o-EIQTDkgOEeyHjWOa<}-PTMh5Kh0FnLO$&9TZa9PC zWib{k`UfQloG&w^2WK3!-aT%Wi!Bw|@FHs13GYT#G(1W@Kzim*G+UpR9~3wkF<&2D zXt+uZha3BFQPC-ZVix5`KI8_fLKvJ7Sdgib4>=n}A`z}BEKYVoPR1dTR;R{kcf3$T zljP1?+nox=9jl~izOs@28znEdr8gygBr&7IRL2**Hx;J_=;2*(tOuoknnREdzs@Nj zO-eVm%I7Ki@w0zI-+ib2t6I2zJ@~Iuwl(DcC#7r_{~=}bqx)Z$vT=CH$=^?|SzP5P zween~5dtxhi=*rr^W3;6d2JUp4|5V#qQSU%zm0;d)nmaeSlyi>br?ss3fo{E*w8Ue zgf)dw!|dv3^Bu-Ib`>;1?I@0O`f%7YJ6?9Zt&k0QArhBH!HdCmDjg0a0zFJ0(G!u5 zKp+iL`aNfKPdQ4F$k`iluR)n?gUj9K@Wr*Cxcu6=X)H&N=3fYH{|1E6Hu5R*J;KDw zQTPRw#q`YZ>#)GWdWh~-|i4m@&sIp(qTDb7!YD}*~=|@Qu(ew=V*y!Z_+F&=E;pQ zzoMW!8hvY$!W`kcu1bOe$l`IVj7l*RW%RupoDxrbkxB4I_s~?gL@5@Vcu|10e3*z@%O$wG*&LH zZo+_HW_HyNjMXLFHj?SR7yHL91(|6Ybw*?*+vrWYy~jnEJH=5tZhxNbzy5k@Q>Y89xi(|x$ke2xdt1c z{t*6mGBsKippew7jI_dTwJqWqNlUDGvu`7M*8=?3*gCQpqxzEYBi^^T-?iQ`P;Q1= z-*vVtJ3>O_j`c%8P)~_Z9@1u=M=xVmPDRJ0_ML%qclfub~m_PyESbbpG z`(Zm*#ii6{bQO)2UjBKF+fM)qocp@?U2h__P1yAJzch`S_M?21?lJH6C@Hb8i53(O z9L?)&q!3lZGukdopIYQ1zyZ+%mlsFdc1bDaXUXwl6(W0KyM&InS5+2wPaUf4Ih({#v+AF={YlxZ@`As}1t)N= zo_{<1!$Xm|B4k1zax3=oY>IP3EC|*&+it6UsJ(Ug<9NFj0?ed%Jor_0zIlC&@b1k^ z%lJLTr%OjeVjFS#OgI68gqUBEaoKiN+!q!AS+N+LmLEG#O~66?bT6RHDfZT}0YQVD z2D-~=cJFiBR-@)6OIf#l>KIMqH!H2pD-g2+)DsE!pEvmxp$Zx14{T}RoT%Ezkli-H zzHqQ6Y;^t2b5sgoQu zN=Nud(*;x5`Grwu`c+~bq=`){`6BzP4_aDZitZH#ulB=M&2Wt#WR!f|(cyX>VT<-R zULwx}i@%#C(0IoMDdNH$TH_9(fzJb24ELy~#wG8#Of!+5ACm^3DVmKlqCd-i zrQtV3*@a(l<@H3FiId7L6l&vYb88!2nEKd&>oMFdF07bTM|vS`3ZikCk6T^S(efmU zIJH#I(@PJ6QM0VJEne@gTA)9^(DF>WHoFmK7LZXiJ!r46YwbPfQ{2K(OIWK~R5QvUVyrl`!H6~2TYk`n(uB-O{$ z|I9PX7XQ^Tcqo+H5<&kh*mMgGqOPCd%ca;8sMcI5QzjH3l+V6jd7c@Iab$+C#fM{j ze)vMEI6e9G4{5Gc^V5|$5LKafbECEDas0V}%j>r?8^r+CN5EAJl}KLE)N1dnUOW0$ z6Zlhe9gaPq(stf+IbFz2C!$5JSX0J@qcbP#!i(Lo9841s7_+ z64~E}{DC?&+RbS52oJTbN?g-?HzNxJ0f}ec9)MN!kJWv~G)!ADAkY%UG4CAMzIxot z#LAS?2bXhw)6peR;7zM-2rkC`I&$r!65uelSk6!?M{EY`OT_(;$8>kxnyiOXLeu;a zC1`3X`#YWd(O_;Ofz66-YI6RuST0;`U{+0)eDr^7SRGYNl3EHH@5i!Dcl7R9<7Peg z%6c8Dru8+BSGo> zeK>n7j_#8nOY*(dvU%hp`~@6D=oy}00@hvM^X?9Y{^ zy;N3CPi+<(Vpb`$(V+5F%!~&L_|{=;DJuAwBfrqiXDPFu1l5NQQ}hg zQnmLT*2lw<1P-EoaR{qUtsJ9x*`fxR6zjZy9Jl0+n6Z3{xQ-8O2R^$ADh|PB-4;g^ zpJfm;)>8se6wf=Ftl8keH&0P}aKLBcIeZLpx8@5IBwrlDf@^suv;B!I0y`Bd(0Wqb zw}l^hR8{IT_+sE@(OKSy4MmdswO$-0E9=xfoJAMM{X3{8$!ozb*KyOh49TF6Eha@< zS>hp;I8cQvq3^G$3~A5^E0^)rWj8vg)z~B&1#q)Eu{_s$a}G)NF+~7~L`xVJcOF)T z57A)6z^cq^NLT0GgA(n(loJPJG%z(t{0{KWJdcO@b2q*MEAoG8Oy&8YDu^F6f|LG}a7g9cWIQm(ImhRs$#*yr6)bv;w{oiVaho2 z2oJvG@f)Q`)D*7=_m5WfEp5)!$5g}(3c8O?O`a|AU_fx3ZYMT;dGnEB%ew99o2WyC z{e$nJrG|YJLY_9Sb16* zqP7e=W*SQTKD5qKy*ll3&y?#}2WN5FomEHz&mzZq@9dB3Ilr@^ya57^#<4tNk86%n zoKn_`yB3>MEv1!Q+Q2Iyje2>F`%J?qwSw8{iN-!}H-CmE5E*O*mk-zA(D^j*da>lY z7wa9O1l#GV;~`Xe0_iBOz=1A}ek(dH(!KqDv22oiH_WyW&YSfA*_?(Q0Jz7y&s+thWuf`jkI*;`le?1j7n&F z@H8^iDgyAGUVCxWpfn}TMWvhmgAS(l7<4KIp6418Br>Rkn zqOw1t^2Ly#RI&8>yk?r0RtZ$AxvYtt&a(?oQc_1=&McsxldF7l2s z`v%e`J4OH41@n=Z@Wjag+5E&zp@y$9Prl+(dD3;Fd@19f+Sp=_#Rf6KxwQ~b|5iU1 z$eA8x=q@`dKa|z|mBU{!2c?ahaJ5X=YtM0D%?B^TH;YLVxa<)bxpBQBKfQe{cZ||DdK}q|K zH@Nt-u@T1uJCA$arL=WnWQGEejns9_g( zXbN~+^BViIm9~YosRk&P`=!cPF)r)IbAPz}7Vz(HVEmX5U_Yg3? zF|Cx3d|)S2CC*Ikn?p&n8#s;+Or z@;yih?gV%D0KwheEqD?fg1ZxfySoH;cMt9s+}$m>!`tM4Z*_H7-Rf8Jpc6iz44x-dEilnH455omCc7)yu&?t^ zycgl+{ILJUUbH^%@Grdr;_&%iD1ry%n1Oj<@qR5!n}|qYE$b^fvX2DI{ObncN#3gz z#>QO#J2*|JBi-0RRZXukBVGQp9et$g+d-nATFLJcCKY{?w{R491==`Mdyf(o9(a{^ z9_Tf52%@9N1LAN(@a;(m*^Fqb+c!58C8K%(V&w|*?_z?G!)*noAgJ6 z5`9EVg@(X`%SPNAH?-`;n!8R}aD{~A>G_kayBD{gVNc;Hejr$l z%^`6!7PCbLe_-)%08p;ck4=Fv0?3kK3`GAdUE0R;CtVtN3}gSzur?R}f70j}*WalB zz=0OE)(G;6vnr%6daI!-YQs=nR)ZxVq$3QrcUqjJ9a`04m^f(~6247!tT`;tf)W!<(B1Woec%f2mGLKNx& z*Fn%p^tSX&+0vbTh;;Y!h&ki-r&A$}+54-RH*dG|^N*2wwwcKM85S^&x?ToHX9OCx z*TCChJ>AUR^(#)x>%81{z&?7Mv;8fU`cKBVMeHP(j{H^AkIDP6%dUQGWFos=5;2Up zOaH4UE}hH0*O~zk2!({8K})^zriSmG+jJM3{h+rxvY`Y;Z8_nT$y(^np=0K!4#XqQ zxk|6m;_UsEu|*4~Eg+DZL$BMA(Q7ccDE1nL@3VY1xWZJ$)v331oB!^I^U5y1FK7B+p}bInV?z8xC=r84Tyi;!IRhj6!!)=A^0EqU3Yn+*{3+aOrCr?rp(w63-<7F zfSUB{eKMbK%-x6jT=DqRsaTTnWrdGFFlCLul>5a2o=`c zJ+)2|?NK8jtIgXJ8r>&NIBAoXm%77>(IoZpFNyA+;>t>oi&A1Ioczlu8kY%uqmINY zkkNubfp9}dS=jV^@x3(hbz^*K2}HljK73U6%gUpHA=7YJMp?L$B~R+nQQI32#@y{R z6Rt0qf*A^rLnFBTG)c_QZ@jU;2R`WR#wZ=Obn(vWe%%2$O@*Z1?hxMYrb<>}id4Zb zDy5xKNmlTvMWxL{2C?_;-W%8OLVPNi zfYMmq-gueg9&5;pE|17q@>_fuKllv6TP7hNGmn+d!>CZ;KNuC4F9smgY;#O`yxoGqoP)$=a^1A&T}Pwkk# z2arNgGVGGz3a{1lgCUcrHaIWlVIYIl-xBi(Ev%Q}qL5a)<&+jem>FCan9+bM> zblNwm&e3ZA)Cep%qfK@^L@`M(Yf~<6FYRTw#ZQb!)TK~VPnXpDyXE9?8ETffcXrx{ zv$h>&4yIs12lCG?{yrxj`3|j&fH|w=l-|}5egukQ^h7U4^)%G zRXbmqP@O)|eMD0nq)_l&-exMK<6XWH4P<+* zQPazD)A-rq}q5Wq~7&og(ULUnv(~Rc*>GE~H zkGkZAnKD4DIOUVaxN)M?5d~UczbcJb4dcx+;7N`$5-mWNp+U;>Q6 zVH`|1Yq=jNKp-)-Db_kin}c!@NZr5lDst*S3=bda*OeIn^-4b@p9IF7T^E)vD7<{+ z8ek}2QN&Z&g^1+xw(X8W`oH$?v|!psQ%3RG@VhYP7CH38hy$Ly54){FbnL9f&+JXwEd%!JE|O-U&$UQYV~a0U7Cto;bFSgS zc)~gG9c!sQqi}P3RPA056ss||se?E5j$`wEUet7DyMB67iuUu0Ew7z=UX0eu)s7Zx zBpTj3SwO&*Cz=QpqlLTKHpge&oZY(keDw=75=Tgg2M}mA00OP$gs@e<&BG1X!xDuM zK%kX>KJCju?%9|A4mss)ySvZ3o`U-b31rOe#Ltb@m?;WL=m2h6^s{FM-@H!@Pe zbF&7E6RLwEpik)T?v=|xKuU`hAkcEsIv1w+l!xf-2>}FJwrnoSliD9(-Q}ORGnPN; zv`v^^eECD5T}ocUTJ?P!Wtf`ooIRwj;ViLl=`)@NJ^p0!9ViKZ5ry_=hVu6;AC2JS zoc*g)Z+MGTJ{|sYy1qr3Os-hw`CoSGrLW#eKU2{OMrW0j4Fd62fLF0HwD8sE53d5O zpJuD9O!jd44@*{I{x9CdMjIOaCkD~IjWu7l{hi~c0c7y<)c@0lcS{- z17;THub4rARs~$MAujkn7W=XK-vCzpV4wq<_7L(odhbuu*hqnO9P(@L9T5oh9#oaN z%1x6tbADresxXiN04rj#zv*o$?$={pp*5-t!TnRI9ufebeVTS(_%w**@k~|}s&(*% zMKJq{6#!PWkjfuyjLuzQR$d*?KBAw!7WUn~^dYO(4t(I!mD(=tv(c zw4mn=({!?d1x`v1jWMM1MRi!Vt!hLS($SKhJI4ayK>`P-fIY8zucnW$OUpGLQlr&H zoROC*UvYmwYJze`M%DC?d#ZhfdE9x2X!FjCC)eqU^;l@gZvdz4Sl)8M0ww$=R} zW=PtxMV@I_YB=NXUVzf?*#(L-9zpKnNe}*fML!hxYYHMTm)@DyJB}~~e{)zn-gWpu z!%Gg3XtUOt0TQi`f)z4GnEHw9JxS3wv0Tc4cCH5dn#Y7>-(4!aGYh}OnmaT6FdQcF zb=oVR?oF;Dx07Q<09_%dIR>CBo_1M*Puth{>ODkKN&sYABW$i(>pY}ZGZq1K1=QXZ zxsv@A24EdH#@}dvD9fOCf6-^fS)unJK8OS03dzSRb>d>41VBuj#@;P+8|#Okuemo&PtE+E zKa`DZst@-P5&F)iHg_9Dq};K0fVc}jM4rj!I%>pjoF6m@;>4Hx*^iE`+dI0givn;a z)+)_zQ(ncy{qqOPIv0#8RRqiv$20iseBArrPT$G;;T^c1_!*ZkBWXKEJsa=*=1a9U zHxdDEg~VA(^QAv}`&-JwW&@|Sji$GR=A1xI(|0q|Z8sOdMn5s@S;lr*MhxxZc(L-w z3_@lt9KmH0#GsCr)ddyp-K6aDm0KqjDW>SD+KTr76igJ7Tow($3z!r_TqK+AN7Snr zvskn++JTm*!Jk#+*w9L2?R~yHjx)nw@uZO93D0iY)!hRgNMO$M;7jW=C(W*>ch}hz zPSv$D8ZT!jyX2j57jRTm`M$_Xn5Oj3So&^%%?}*~y69p#1T?M$(!C(gi7-F2?XUbk+@mw|WOxGv2)n&nLxva{&ibmw`?wvtFg3@fG3Bfvtub^2> zZyfa;iPqLH0cRM8yQ`lgG)!A%0Z;{+@K>H*NP?;TPh^8sQY^51c?J|tb111g&JL%Z z&%1l@N!XL&xCeu1O4vLgpQWwiHUda5{mF{(QqFKmXWb=#pW9oX_%T$7_&Yk4S55_c zDGaC|!Yd>5Bc46co*WGtk;PEQetdo?z?sccLj^dqvIC};i(^X+Ti`h*ao7oM#e&&FqjdW1t*Q_WMpBSm|ZO+MZ&v_w{3-(I_yCQuXtG%|FVp>U14ce&&wYpG?{E2 z7P}OE8p0}p!=1Me4=v$3gC<*G$kU$O?o+019Uue^_=Z|)l#Y}14#jD0P$d3ojKh2= zIA|?3@&F#N>9xwzBNr+VENvvD3tKApFJ#5=32 z#x9gGK+jhx0BzN}m$%Y=@EB8gO}1(?nLEflyd^1#$Q)rRpN2zF$pL-5>Y4af7V=~& zOVS;4&&YXcy{n?50q>oT@8LEZKIsITQcS>(=Au3ma{T@Q1|VwL5>!_@(|lr2T!fed6(T zs=f?8tsn`TO?2Nnr8-7P*(nZA;1Xj>&V$>J&{IE8$?Yu(q{P??nsgWdc(MY@2YPwc zGIjnUe-IUlQxB2JShi+^ww*h360yYXj9U4tk2{`U9HdVL92WGXr(Dctko5V-Cw0Am z;=0VPjD;?ypg7FDuWchX+Mg?=O)RB%!!)8)e@?zn$)ywr{iMpKI7H=Zm$z60`@|ev z_0xjN!sLv&o`k#-YZ5!3npz49kps5z@tGEcjNzcl5*b!+ ztyln(>=(<=21cI^UP-cH8LuSS4~MK2-M^LHzN(e8>uk4}y<9mfrmit;xABYN*Zt4&o z5BH~9o#IPEog@Nzyt{@$~b-6boG?(qT@EW|ET29 z{axUtAQcKwc-$QQAunu)-8WNy%VYtq-jTnm7g*DN&)u2*N?1pAT<3K=4MJ*V$d?I* zE+;T!qM1LAup1Zw{bcZbX~U|v*JGmCfv?5OhQ}(Pdqc(?;&IFK zX|VlW9%+tVn;9fQHVJJrfQ>~M!O)n`FroW{sAxoaM=*q3U6S)`XR$j-)-?A3iD3iw zMM-t%Bj<(1QB&41SLBwO!wD1$89FPqLee$yxy~1ix869jX0K!1`SM8p^E|NZNKDRW zGaq$~$z-0jJp}8+wH3ql$U`BmE2(PIx(3SJfBRcEImdzh77DiZoxM|QLIqoMn{qL7 z>3u*N@Th969-7R`<})|ubU{>(gRC)R2e1eT?tm$efQ9n6bmspW!TK zu%)~w)o=|imyFJ7K^cBuc)>Ex3P3tzOv1iSN zP0#R*EaQ-j`0?TMHpzD_@l|!3Or`-ZKdTpo`XBOTe>6Xz7N9vTTJzyP_=)a%gX0KPakf<PAhMM0qK$|t z@Cl&Bj(2|((fD3mX>;73YaYq8XDwe5JUJvNCo0%|`h13ZG_#;p2qvbf;7neZWo~?N zuwr@R;xTriz4F+dQg4~je9qD2OD*;ip7Xitel4$OGT=Jb`fw-(-Fu3N{?ohsR(7(Q zUK}c0G{!c%!^^;N7AyN>8YiSwu2rd7lAkw47e6=8y}iM{^%>fMkp{9x1B4Ld)r?bC z%I@ND#7joFOoj+BFC1+pMZGsg0Cp1};tuG6F;yf+Y^EIL zW3@_Gvvx)F8vmxM6)8e5k>wdkGn<94RW0%mWW^9LVgS*96-O$B@D`M~?Sk>Uxegr0 zn|f)A4q(LMe&*Jy{5@k~wpf8J`1w2oGr`W?$ddai3890S@*REzcg@h%^M=m8%-T%r zl^vG7oS<@=4=Xd&*Cv2XvA+sV0TQIc*13Y3F-{g=TaH_rG@o@AoweT+hPIDYI7>Qj zFJ)F#_~ykoY%aagJ@mLbgD{W7sM!J%4{D1g8NFw#7~)eEB7D+|tzh@VzlVne7xS*t zVmmA|sGGKB$S!HJTlE3z>=Y5tJ8`k^abr*ds z&)($kX7$mN8qN!&DCdN*ew4e2mv`Tqh$4WP)p}(`L90W&?glEM4}##8NOAK@q(Il* z-MmF&(g_2Vx*u|lZCf{JcSQVQ!d~2ZS{WPcK&An2?M_?Ye$0C7!wub?PK9blxFrFj z-^24XvXxPstNIw}3Ke3ZaqVTI}%pCa?5}=>uFR=;q>Ce2|!k979!mm>rZFAhm z#|JnR2i$JUc{U$%YZp?%J{s)Y2; z5w2qi&tvXJX6#qI-RR+!27Tcu!e6RN{4Ii2XW9eZ7#>%!uPnn*fE~8>F3;ElknA2B zLs-EIhKI&DDra{*k~W?jO#}(QFJ}KPn%yzj6n9L6h-(F*is%YQJplS>(-);CHPY1-+YoJ6wHl$9~5NOIRKo!kkwFzt69pyyiBzMYNFPi0%RAt^S33*YEaFvWaYCE4HCiDcLOY`4@V8xfecs8B89~> zvGL}0r-ub(m$@n$sS<8V!nvPR>8#TIk^Dr*KpbX^3DFMjOP&W z@gehtgXB+VBX?&S6%(Ta%nxEpHr2k@6?~vL5^}cgw0T^X&BW8(3X~4@Rj;xy(ln-2 zsv;`@g5a_nSEqH5gILtr2QQTi=~X{lEgU69h8D5P{ZHs;FUv;Gxnf*zMKx(_A2*S$ zd%$dYj5Y9wKI0@3V{bfq@itrZn#=N5Vj+fh-RuijX7MI;fl zb!If{8xdAJkh?XzLHZxPb?u#;+(~D@vvcZ{ z?pl-a@xo8hD$s~1VMdxWnIMRwo~_rT(qq(7+^zoUFc&PD7D%+(Z;Dl6LHI3Y1+2(z zUY|N#H_H0<`j}+gdZot;0LTmMPhe*&YV_Odm*~ z1}+WlMswUAsDV2lv#elP-K%k_Jba@?4YHKA47KX~-p?#2-!idXOvjUB&n~zp26-#z zKmZ6zuC$QC*bu_)>bv3@sphtg34jaF=sb#29_s!;YlRv$UzOrTeGtH{+E@M^x2l_{ zF?RY$?u8ytB&n#TZdmzESx;5=)X;)WP)Sf$&`KgA@by(&5+L%# z(tC#r@6a5(4h0ewAHj6Vbvk~tyo!5AEzWlrvHcP=Rcq&F*NEI2nXbb2=L%$gSf9+{ zwTyoYJ>l>f1=`o-eGk)&*J%wl@l&lX_R6nnvi^e+Zr6Q5&M+zYh)}*tqarD- z)y(Is_;0-|Z?VT-HmO^S%S|yg8DwUxuU>*#tQrqJugtX1B_c{*;S=GM5FqcG@a>E~ z{gt--$%4!7zOidYw#X;fE^-pXE$wEz1j}u*9*opvB1(VBkGfTx9>J#gc%ordC(>Ko zgG=m}if_UIG0&rAtxlr3);wGhz68RGzdT!UpL#v&0TUqsMJp58*A-%nOq;k2DQIxB z?#&W)p5lHX3gb0Bmejj0--I95*dn5van0#%fo6ctHn3if$be73I+O7S?fM_q$CM~6 z+BC(p#fBA43flms%$c1|z=;I(x~=|l+Y#SaQcOo(j(qb}SkeO08sfH1E|w$I)7#T; zV$ZD0EXW+8Ge0pk#=CM-`R>gpV0X#KlF`lRhEX+W_nK-=vpH$H2_24l(~69pZ}z z+XIDip6kidQ=$r&tD6i0(kvN|ARcyfQwSm_V!j_R&SnT2ZY@FSci$G-!bo}esi+x6+Rl7#B|({S;j*g*8xG)FS~Mb zDEOP54dHMuc{9;>x5t7iFoMzKj*jV5(wNXRQUIR&WHQK`=l2bEaF5_ypOYMBuwQj} zsg^E-a{|v_&Bz5ux))+ocj}&okA)Zn1~rpx_TAJ{o}Ny(nHk#ty62J&LImMR1MPDS z*la5`%O@92;cq7jx1wNDX2*E18EQg9^gE>$8sPtd6#nK z;Ib-cMacklaXht5tJeik?a+yjjPJx-j=zf0pken=W6*$H=vU1d;bd1?fTa8$yZW#u z{$v}s?-f%G=T5C_=C@#UP;nav*SJF^f2pLev(gKB0KrLW5p4+Acy+eb>4MF@95I@8 zD^M3_TFQBt_N>ip_?4d-)ExZoq|QkFBlX)^T#~&5)m|j(hEE>Gt}8W$N4jkb(+ z6GxV!AcD1}isc~Cf2GKFOX(PqH`Oju2V=o&s)aQ^O zqCtdvkItV(#k%jzQ{&ylt&JOek5hhCeaL4zOAOjS4|`z~UY{o4c_(J{PApH(_+suB z1{~e^h5&LEWEtzbExv~oJl>&!(P6VzI7``#SZpEg|jXpW$4BcRxy(QF2w^N`iNgSx}= zZ+1%^F?;9E)PxKM+ATX$gCx4bXO%jfq_#`>Zqqf4XrF53>sg!D zg-#YqKHWKRnlkHH`pe6{GFx`^NQOG>B?)D}z#LOYUIpt1P@;d#hgWPn-v%hSOg$7NSi&l9Z;P(+e+VAX$KK_*^XqM!#JQA+i}akw-?J=eeVFE zV%6+Vi1an>bY`jBv@LD6bTKfA_}J7f&3u=+zLS<`X+e!A+hyzV1!W0O1&l%DJ(_>! z61v|m7F%PYsj9+dJ)9fYj*5E<>P6)j^iGb&{k&cYUnvDEaKJz7SSFJd(kicjf=NW7 zY8W2Jvf5ilJ6HlCX{ox4!t3LkMe&Aal24>fx?}^Su&F8A*#iNJNPnWC!v$JtlrN@? zM&>PEN2GkN}wQ0nqLvKFT0fu>CRej zy&?P+2MywIGISyZy&qy(@sc=+8A;Pge}{ji!96r!msmvhgT5IB*zK%6JTfHq4a4x@ z6;=#C4~;b~n1rv~Jn$5sU6k~WRVTMl3fjA!3xCc_tDI&@CStb_UQcF8^1pT(D<@dE zb~AT;KBh-2IZ}J{*u5|)SEt-HMFRuH%qoxykB$_tm&Y(~W?Q)&xoQ_1*2(C>&XO@R zf+Fu6;=qZ-!+6}g;3FnAwbz!+z)=-L%P=17Y}6DYuLqG zl0QyQ4hLAj&>L^taB73TrQz-iqP;~m%-0DEGr!xGmGxbGA2~6x*HTJf%+dNceyrXj zWRHlMcho!dwusWbg+U$N<;7#Za>JRlAvb*Y4v!8p2gyn?zHfj)$FMb%-5J|(pR>!D zdi9Nro?gJ!%}T-~j8$QaLf2hmW*;Tfcx7)v^@QMW@}VVHlmcbV&0;My(PP<>Bc#c< zzHKlt2=IuZ9dI$^Q&$pTh3&NKHUe{2lnwDTBvem-Ft?3d@h)EZp%KS`b!wYwP5!$y z%|Wq%s#08o{%a8(FFj57=bP^N{GE|WSh=xvB(4fGxafj6l2b^E+nP1{=J6){XCvDc zNnb&YZMGr>>mX1yPdT{ftQry6d%u)q(VaK8q+g9`->o#sTHvygQpr4DY}kg64O`^% zRTFb;b!Tnb1UNRX=(W(M!7Me^dm?@xr8X&2t`O_>mYpR?A%D{P2{h4>XCJO08*Hpm zqaO%6stVFmnG{HzC$jeVfs`~C1_fRe2DZS$VXPT~p|L+^m=b(*Qn!^a*V)9-AzdNy zvHZ#KpaSD@>804Yg6_D7fC7yLHfT9t(i}anHq;nebuijW!H@tafINM3@L#UhJzB&C z`M^G2eAZn|pw!)Ysk7{#;duV;p-w75n|3ltAO>Ox=-P($L>C57rWt)VZrr3SlzUrl z#~AUXB5k|@T9`M?nEuHg8f#F@-;GDrOoPLQ?;6{adTwn2q6QB`#9J&FQqb=M{@i$h zmw71q(|08O*Mu`jgV9nN4HOeD1Bgs1a)s`fRQb!=go>(O@BI`bmF9m186+t1Z+)*y zw_OC`M`&n8s(;M3aF~|k0l8hXCiB4^WfJEct$KcS=Y$|8NW}hp0ABelX)#7r0X2F2d@`6S`U5c zMEg9Khe5i<)l~W~r93=N9wSn?eh-88U*j>5Z+=};Q()G}7@5H0KW{VRrU+_k)Lq!U zFK?vV-${CcGa6$?uuN|qIcA4#16ZkO z>I5e!;kQ1Bg*)3C;%S^f)TOPd9-D8uLo6o+?pfsYJ(5ansQNf4lOuV$d;$kL z>ww;PBTcvCGuzLQPeV8-O~$a)Cjxtv6m5UGpvKcVG#fd|AC({4aGI&u^48>2vbp2G zBId?RA%0wIax}5)jG_Z#v0^hbv$#1dCY?1d*YWx}D|l%xT&>&KAn|{x@ZtG!P~iDF z^U1Wj@^qZ9MR_Exu*YoYA1!66Uq^Ix*)jlMEyyE25WdoAh_^YRS6?*ciJb*}N68-@ zaAI2aN4E8+?d5sA8jjBECA(a2H2GhH?{hzkb!j+-zcpaKAWY@5I(?bN@Tz_Be((w(TGwQlt7V`ksua|f&OYfm&L=-2AfrN-dlqgVlFM%uMjX0- zzNkaL^iYH0_dF;cfyrvmst2QuC05<;^?*XSR=GYu0A#Uj9WCY;T*@ z!a=s;cIWYyZq5YY%zBU(HfRXBef*0vyD@qcmSi)0qcj(|R(#5@UP&JJA(n>ZR4m@c zbt9}y*Dy5_;LOTdc&b^LgQFk2g1&rq6q7WkKeC1V*+?rY272}WApL4(DDe&V7$32q zw~ClpI{TBtH7oVhnO%P`maO+_p*IbOWO6f>SI3BjOwxuZD81vtz1yl~3M4}NHl zDI;P1#Yy!`vv8X*z?&8^a+7oD;3Fa~DQ#iI2d8=m#VF7Z%pS4SM7Q5cI4^!7!A-q0 z402C#fj^5GopC*fFMne^FX6L1B$m?7FD{e5H{c&ta zRGv1TXz%*0=2L!=_YhwND)}{qsayBfGS(Ihlyk|;psh`+7ngKmxZ^nyT@Mh zY<^m3UwQk8TM-AoHnY`xOTiQPmloVM z*eNXKgyw500&0mQp?TfIcY7iGWQKmrTrIxHmLFwpTpIE+reV43kD-L{xS~Hr51OQj zd7=HIpMCtB3(lQ!xMbJqIhr3fE z?)?crs4gA;@OV>Urz zVp@Gq$*RUF@Pz;xhWbmYMAF|)cbT~)j_lyjvI_Rrz+(jd|M+Q0e?~PvRz2_m$lmID zmu};8j;Q8Glrvs3EvG0fDol+V#k1bju!P@p7YPaw{@`@YNRr=3Xoc0-ZlnVd6^(K@ zExU;s_2*49UTneR^XL%xN#JVTdKuIN7Sq$e1tr0XsXK9Ceq?~Dov>qT=H!-Df$HD4 z1{cfg|IO^ka1&gx4F-x(?OOfQYnQOfUpZ17S!&i`T_0kM#k)Kn(2h$cXjCw{|KhTr z7oZK}cs(@2IBdC$gV{$$$0!!Ox|GYFb1NH~a}vG$E#wd&L2QGNsnEg$PSO%Q9b2!4 z+#3}Un|T>B%pa#8WoXa>&8iuFU1g*=ninXFvR19qA6hyMi^MEERR=JLA>Mw5Jv%4a zpL=`jf*5!;f0QDVbkJybqp!5Tcg)1f!*j*~YjfVoST!z9txbGc@Shd>IAAtb|3Ir( zbNt2(j3Onx!Qy#PZ(g7h+^(;RF$i>f zWMSq)l;Rgd1j;jN`DH#5YMKpYMjI^&I*QI`+gT)-Uc&^7dFj~*tWO(}FeJ(5$Q61+ zRKD$YY?!(4=Kq?b-3itx)?eU9{_Fv75$;l|Yx0BS&Cepna725ZBYAUF;`Ax6fy@Bz z{DZ+Spv$AZ#b(FUHsyXuZ7ZPHSkrveHJ?902756A{%2X1Uvud^hT34ql|OWoYuuSI zEW^juB%lotyLlE*!+AO1;X|_)iZ>;XU<>q(JouhYkTZdqq<(d`ApMadP0$cNVY*P6w9%bPz!ViZo@&(E>x<=S7BO;gl~+#ct2}=kJZrP3lpRCc;w`#57gHE;*ZPsbCWu@|q z*%kE~p23Yk00^OQdg8dsvHT^s@WL-Nla?V(8$dnYu7H%awac z&*w09$@ESt@{yKvdjc@5q_OYyuIX-SD_o@FI1M|tzru+@3Qz8*gtHe~I7aitlYP-e zqy&)n;@cnkaZ47fS;!I-^mlMqeT`A$FoE;s^y#vF-@Z}xnB?2l3b@mGH+gq}@M@?e z;(VnLqBvmbl`3rs1#&!lxampEeF$b^GA`K0GW;oENKF(a3F+?F0IeJtgDEK~4Q3WI z*a+K{{A-ZRp>W|*DsoySo=hOy`mY(Aw#xd<8CDdLVPaFhj8la#lVRhlsKh01 z9wIB#RPg9S=jVS*xC=}9_X>ARz7U|u`?1njg~nGXe` zwWeKUGKew@B)<*TAVr;`7IT268q{K}&p|pg`W;Q#`dAc6BN6agFg>NE|DX zEDL)qVOW)hans9H1}=@$m&K1wV_iME0D;obuc!v~7H^54gV2k$NiF#aH2Bh~xBekumG7YP&yt-E-b zqVE&p84b_((9lP*T1m?n0JA~oMQ0T8xe}}*6{^}mjKC`82EoXtZ376LoBh{!3PiF& z9Bn|Qd!g6)9x50BwA!WWBHGfxl6c-kBz&q@vm|I4S7wh}{!J4OBG_4NdRThDhW zR{(J9Qe58zxeU|26B$Cx^jmiNbiNu!KP|nL98eCFDOfefaVv2q>x@8Diu0MFM!vZ3 zU*dz?C!9R5lL?PTGku{ng;RTK@HO&4xBNigf2Pq1v_k+gP^<6%#!#0h{omA3ckVyl z5~%v7_Q#J*k^%i0bWCswQ&U=qCt>oK0LpZ~d<7F-Z(~#j-G)vp#O5Pq^2>=AQ5ZMn zxy(%wqEC=i&4$${Qbt|*IG&rm%9`8#AKrnH_7k<0A_FsVIt7>I$;34=e zpa9n1%HGD5xM5W+gRZicfpoFZ#&gE}Qtu#K*Lz0zr3oF3dHW0%eOC?zF`;YS_6>h9 zF|c79+k9wEi%LSXKX1K;9YP^lP46lVaZ7>|9%-YqhDhpQF)selBevrnp$fV2{cIcB zq{~H{0O>ud7{IjhlA{0iT#cZ)LN5||%wIwnOCDEcEt_=_jsJx$P3dk=QLcI3Gpp$N z6Kpn7ZdGo|5JRSC|64=e?K&_ng6cY=@(QuVgNiuY>ssm4J)(GcrPcXEwqs4Mtcc(D z;~JSiS~vhEK~K*5J5p*O`x#v~5DS(Xnm;ewupvr|9-CkiLj+8CJp%CJwcoYgp`}B2 zv6W&G&sL(cdIS%=Va-Na>bxwG*L$|*4`F@ZtIt;Dy(E53i@+&wVnCJCC}`&khiAGL8L^7TbV$&T|PO5SEy7W zsxWae6<@BuNyVT@t#aso5_^+lTyq>z{Z3}{_N|NBBmbd33`jEIt1+Ie#c{bKJ$PW$ z4-ThbqJxuCto%yJqb?NSfa&c-tKvtW95b)9Hrr&JUjjV0Dkj50Ql zY4!t0(Bv>R!Ij{;AUIRxF%xi}M?OV=K<}%GqbTgY<#9)rw+Be!fw({D?3hU|So+ z5dPPE$Fv@ZS*Gv-9N!P(|I9?Ht=UDjnHJiQfASIPK{~R6Tc4qJHwL|)N487dG*zH- zT??|;*S7GA+4Wt#{pqqiNwS*U2nUCPMkzzO?powfR{7O?mXrbe_oV z$f`#=&B>`;Q}C3;?hgs`+;}fM@G=g8@LjrMea^3;B{_V*mX>EkMZvvw(Q$3QoODQ= zK6=Jxl~vY;D0`8U{62tN@h4>AbtiAl{cQBF+3beEd{eA}kN`+BE$Tqwob1M&@&iR$ zdVAd3VatA7E*+@&!9i(e#*{%d_GQbmmjpDSzTS=H70zCD|X(n0Y(k^k}suhgHRN- zJvzbvcM_@l!T+xlsos<F4V7+g0C#QoN%4~Wu&4t7IC0wW&G3&g+0?aAcRK?Y-JH!LdKU#|(2-6-Sq>^kV zTD#9>4^m+H)TAd}Ts@4Lo2a<{s-6QSh-&h>Cr1-(9=KUN#J2I*yM+zFj~`0s>>beB z7qTyKcY7iE`l2(*9XaRQvw#PNDlV%90wcB+#gl52>5xWxkha^yi-wl*=gfI{>Q2#Q z-z?^R;)!g51(lfz%TTi00=D=Q{xs1Kq;b5~v0=)yAziVUIIqIW>)f24c&e1B_JJz!{r6 z!A*4P9OT_sv~CsNwG){$beb`@quQ^=s@<^I!xEZqx!1MY5=F!^wSW22Vm~Qd2Fd-f zy@P2~f8zdKA2lA6w8!e?7p~IdjJT51z{$@Z2cYTB76cs&(Ol+{E7`5aI0B=cxOr z(Y>i5pI3~gGcPRMSEoYw(hDqIm-J-}_wM)I_-a(P#gP_DP|eVm94&2ASw;N%=|bDv z#}4OmL&XR{ipTX`;%Pg$@Z*s^-dZWBC`TvQc&a0BK=WsO8VMtS33wEya1`LR&M!`# z3$Vda3W8)toO5TBu_wh4rqsw{Ky&2s7Q^+tsFl>%6fYq?C|2AlQG+64Hd21D0=h#t z3qwMaH}F8_{(c0bTCK0fi>UJ+YXR> z2edaoQSWrj;gKH+)35>p`P9s$UdeeeBr(?!Vtea|!Z~SG)0V`3KLo5*K!-*Ex;Er0 z^>Q$Xrv+;o-|xTDarbY=S}C|B|6{RM!svgOxo=?mUB%i#lr|R?`)V z{BNn^sVQ5YeILmlp`-ZPkUV?$AxZJ=s3lV|++v08v`VpqbnB>|o8H7ZRR}48x3XYs z^POiS%bap8Hi-f4MO5cEw#z9%TT2!Te%J~9B#&H)n@-qZ8GT~VA=H!3eo_(6|{%P|#c!T#g)Yq%OQa9*?0;S?m6TGbD{G4vK|rCug_!r3^hS#m!- z8;j*+m+9E^Dt`7x9cPg`(Arf`noh#_kyAk6D=}8V1M^N*9GYBkvK$O%hpESdNWGe$ow3 zvT{dDmjt4bASG9|<~%e4ZarDE4X-YS7UNUiGoS`9RuW}>T9{spy!pw7p%EK2*K@jx zsULqr+uNO*8LuA;1`(I*Ekc3v8)JiLM&qBk>bBYA$x5dKmh4X(8QgTbqFx5;r8Hp` zQdCA&$ERb}C<>*gchr4K@~X(daQqVB`fxc!doTPsTwuQcLo412CgNoBVUyh1wrvRM zO;H2rtg_Kone=D|8_xw}nVDiW75C{}5*xP*n+}^wL;oXNanE5mGDrp8~dMnTBiR}>5@P6m_97hkh`1os~u zz0rdm zN^R%Iks5I~PX2g&dgj8n6OlZ2b8*+gcY3<}?7njW!>VVA9GTkr?s$rVfdQm&JG$cP ze8t_?%pvk&~m}|gU4z-&c$I(TlLN68)3D~=309qY1tM6k4wQx|dm^x|gY`5MAE06PU*(qIaQ0unNBl%^IGwUFj7)T z<^Xn3QT$4YCZq2yI20sbL>ELT(S!^eaJJ*_(l(Wh+|IzqQNirKxN*b)r!I8eX^Xou z`z_1SiyR&juDyx|>OdhylXf4k-#B1VBm&NEf!DC?#pexIX40LHH z{i+kT?DWXu`IHkG$I*;@rIWhSZ6Adsljv)Im!v z=_4p3|N4}4#jhMkWBazxojU{mgmbTMZSz^G&V}V#f7MpAp}V;vmNV^3f`xu~spvpJ z_a93yUP;DEc_DX1kwBz~B+WtCy|{J%DS-v%y&9XKi}?R=_s-FEh3(q!3>r3SjK($^ zHfn4%b{pF^n#Q(mH8vXCwrx9SwePzzzVV$u_CEXDXYB9KHO5?PB=ec`!SBBA>+;*f zsm-7hlEdRR1r+m@f7zsU_vLYPx|7%LzP>!m9Nh{b_-!Z}+NevrrF2sjw9~cMecu@gC z%eAYT^qOx)>w0$22>gfN1JwE^lRD^RWvEF!%vh5pKx_U%vJ7tLh-=~!wRqDHH3*6U z4w=oZPQkz|>vbh^p@I%dr_X{Cb5hgE335Pk@6VR#;nWtS4Bxx3=;6c*H9B*`JB4Q< zK`U@H2{Ua0u>HhQ9Lh;%Ze>Z_{t_xj0_dwHY6YuQ&hx2dPQxq_sn(NeYQYy7a0AK--1f|lzxTGgcUrBYjXLGwC#mI z5g>!3j();A6sh@-Ksxvxq;QiD=)YU0`3?byn>7X0-acL5p_e5-o)_WrPz>s)w`mMR z0fvU%3+A{PJiO(@k$cBhE4NZ4WFOy;>1}-8=mu?3nVS@Pi)!;1-}6Z0p& z37qKpEIM>NsTAYhdy+QGqdMfwXK$|6%2z2U$tMhz`R5+kF-vl>Q|C;Y#g?c*B`JGJ z>Hze&d>zh<-pBEYmxU+G7KP-xE6kTczO+-N3&7d=;DZT53u%aBXKfb84;(mX$BmN_ zqIf36J^Ui5w9vuAZbeaSuc0;%V#*XHv;(hIrt`TWpX7E??%X*D2X8RetLGV~?1VVJ z$y;8k45OE+@>=XKR3j2xi(wH~JhXe)#Qa&-A*b&&ZFyT6jsvsTG8kz1-*9*6WvxxC zS7%WZxGHo8-U70+7VhuI65$Yi9#`lqisCMUtb%bGV}G->%R`AMd5CJG(zlgSaze9N zTGx%XrmN4A=X@?E;15#`8WA_TB_HNGbzoE-j83VmEBblUnOE9F)4w&hIc8ittgK%0{|@1|BQPPuVFPN@JkFeW$>J_vS0Jg$P1kPlU*FsGoKr{f z){1(a@7q|vfx`#9Q+?(LFqLU$3=5v^z8?iEI8B=J$#8B^LIU1(otTwMhPw`9TP0i` zG>ZwPw+&~HK8wB(vRukvjsz`sImtHKSY*DB_ex7Z*EK(-Wm}tRuPpOec?mpK%77jX zi@%S?2TV--P6U65cFx!SVuFyB+fp^u7FCqYvg?yIinAeP?;bO;^BVi%wYGtYtqv|1 z@4DprsDKI`FN)tnL>1Soyn8{=w@vq}!~&8wEmoHqNJCkeV8Ma;ul`3L#=f3O|GXV_n;6sC9xZrX|94Y;Omu=P!jXl%Rllt3BUdIEuC> zd}NSmxUWkcH^3kCEXVD{q#6RO6CEDJ$9~YMxWhH?AG@X$hmEGtt-M-CLafhVlHRul zg_dpK_Tun(4rQ01nLt2NnF1|b5~%`zMVgbOR;syPfIHlQlUmKB$my zxwpesIx?8qNRuhU|Fpzg^JP^2em^(s4f^_DDIbjJz6f}YYVbcl-$(c~{epoM;7%NL zPFZtY#2NImAo_bD0DJ?sE5Y8zv952&T3bmB+UxSm<&55WMT+Vzt8?=oYr&peKiCsJ z5`HzT^Fo&rKl>bl-Bt89Ym-!RqJI+6cmBN?K3s&AJZ*tdwMv7C*ZB!&6I9#* zzj*5l_(?i7X8B{__&Yfb;sn|KNX)VInP^RTe7cNT3u71@;EkY)Gn(0_#fqv4^2AHQ zOnKnwNCbJ};T&V%1TjFp_?*?B@JRY*zxwK7g5Hr&B8KMA12a=IpC1vW$2_r3ncWfx zIx`5EU0tP``|ZC6>#4kG$9qgEoW(j-YAA-LWFnz^; z_UM=tyO=Vw3Y?y}Voz;$X5nKkn)hNB2B(m>p^~|z%W+~tqZ<_op=6Bp*SUW&t5qs5c=l0AV_fFrY8t=6e_UmnB-3B?oy$W zo|CB)rDwUuEc_6RoMU%tbi9-20e$V|GgH4qr3{0p!sXV=bGcqHyTt0ZBzL{x{~TqvCZg116jHwMq22l0%k(EOpaH~F&IRD4X<027K+buIsW z4WEauR#3&lDm!Sg8~HdIjIoL>g&Sac?xIW``P5Pc7 zs09ueEMd#19Tu`hN=-` zF2W0}%BGKP8I#fAE)ZryhRM;?{Nmc%mpRGbEF-6au3f86NfkWcHmZL-*KVLeFVY21 znaUK@dstBEd~Bf>e&5MlXU_^~KXlT${&|4cgqoHb?@Nn)Q>i~Rm!fkZ^qf`gr-8b0 z4fIK)Fg|M7^n9Xhf4bp1{+V4Pn*kk(U8lb#(AdpNPf-C{J&nclsB1JFKTFXsaX*4P z4G$hQ6WFtf!&cwm5V#x5VTxw^26I>6Td3bQ)3f{9Nt7S+5Z-_0mHa*%imG=L3v(dF z3;0~VIPx(FWCp1T&CTNViQ8+o>~3yvZ{D^W{G`3p%Ds5}6{90U14IVAa!BUUZhz}P zvB%)=We6}-e@elkN|UZ2GEQDhjAG%g%V<>Ugb>rnVPvu!qrO^8*D2oK7(xzG1Qn9E zB~1hYK+3G{4gq@ibVd|Y>*^%&I!1)(rxB%1WX+yd;JlGGX50AenQ+W~i}*rDWEO$6eroZy=C!^1o>B~6K>jL#q%Rc{2Vp|F+j}k& z1NHFWBaTWR1kfYi#+fh-3azHMn$!a25x(%U9QiexrvhM%(lK$oB}OAyEQ%`rQsC>c zd^NT6j_vq-u!)oG%A$7`zdn|U=*QuQ$M zN{iW|6JQ1k;_*)^T~&nMVb0;`?jLCMR(!QaNw3T+2D2W*4381p7O~=Tu;}XkqHpN= zycSdyLrZa8;*8UkF1~iS$c|F*shTe>uO<{ zYNi80LB-^nxI0KOEv{kFN^qDea+M z)sF1#E5HC)4#Rh@Kkh0fQyxJ6>A}S3$u!AJ7X2kMl2lz#(s-0KGC##~Q5n>;V%Z=8 z>@;DbHoY94*3sP>2ShPyf9IbcLY6bnj7)VeNu&x)#hCBAJ{71-CuC*7WjPQ8qr`?H zX~8cuGrC0NbS*msoJM0nYR@xE2LXW4;4cCSq_Wmcz1l^Wo;Ivi+PT1&sm1!;np`|~ zR*lLF7u;A)HQnz9=9UKLyY6+7eguTx!yVXcCDK6?uWsflWh~WBm3-E8YMOhYg`A(a zFT)L(Wm{6U63$xFdS8u2wbizFZFZGo=5(lzPo=*P|E_LNWEUybG2!z#STx|>t7t2> zB>1blQ=WQVJZZGapOIim;Hwf@)Z#Ya`~h=63rqr^-%94R`V`mhoU9kGrth3&t`Un<|zc@nkaJ@-=0Q~o=s%pa(Tt53y2m`qutcfZelC^7CjV{ z@hHiD_GbalNMZPjYeSFay0Hn0_+)>RH~kTm zDSJAxno)sX%RU@TVkkp6(<1~0-Mhn1gI%^#%|aWSVRf3Y9K1&g;wk{=OJ1|#2mA(2 zaSL?!E~>_@2CG4y3`r9Oz3d|q^)Q#ci>pQ_3!sC_?WXvB^=%DqhV@TnfBAs-N-+>0 zl7u=`0{!ek^F!?9PyR_Yhk3!X@TE(m8_m2`nr@a@Rjh#mWrA{$ldxS~<`cM}lRi}F zA<_+O&Ee@?=Xb8FmDyr$weJqsGIU6UoR!|pJceEBIXSXhOB7*CaGM!IJxqkBH%~-U z=^9DcgM2QF;O>SFGL}OfB8W9gd)vDc3(?Rpav6?1#9Z=|J$jSt4~SRjUo}5^2uipB zum^`%@l7zx9ASA2VT3~^C%k$xk@DDL{>h)F^A|&n3T@M>+O0zzC@iWGk1wre7+q@brcvrM?)9Q8nERZL>pM_a#}}Uc0yk z^SCJJqhKmb&XNkghS5xn9fA=qnI&9g%U$h2felcZPsmtoZh`~;XUAm$DrQj}S zVO0D32(dJt_FT*g2F1Kz94-fYMA#!*i+8?Anr5c0ty@P#ad&it zaG3ea4K7E^JJ1(9w6GvCoyC+=z%rdt_;mJVa$pH3*-z);$Fl``@j1Xo z;TG}+Om2io+!Vqr9i+}mC#vgdmAsv?HN5RvJ4CtSD)2dAb1uSHge;uILtsEBz-J9H zc6iCi87ywG5N0_Ie6c~UpCs3~$&%F)O{L=()C3s_74S=iN(}TIjxs`W+f9D2ujSne zvT#&esqV-2c4G@|_uzdfAVS%n>=#hnF9#)Wz_0CA*p?+_r{*b-fD400GKYYA__Z1? z1@;hXirqyjdH}9Lr4tH>p0!6ZJGnbJqfuwN*-&72m5CkT_NY%p0EUMHs~6aK-P|>k zh{hJynog2LB)G8B`#POEgFy5`-@YJJ!Avq_^r%HAP9Zr_u4U$SKAbG2%LKhj(9>3f zrRrp40+0MpKPu}u0h{ssHa0w7S>I4A2iudq;S(09AN6x^uO(*7a1mqLgXzHrw-3}o z_ZDUB=uZS;P6Pt~uMR0dAQ{LMN2+al7u|xg5{4BG@wjs-MUYkxZKYoWEtQ{Yk7a!q#)d0RyD<#qEkH=f#3X%QzyK5v}L z4=FLD$I^)o%V)YjzVFAWoSAV}6)zUgRC@I&+q&t6rMDTRQVZLAYo>-G{Do0F@O`kL z4aIA<*qnbH_BNKSp2pJw6ND3YFytvbdz#W1PBVA!FbvG-e1n39x%2X1fSLKW*V4&8 zfhoh7l~@R@YQq!viR4FhO7=xE(piz(7lMM!A(_ZC9;1T`cSI586TZdHsozRkP~P&% zSa!CrSs~bgo(b9a7~QTl}g))&ka#`F0StaK7z)vYYJnP z9dZdw=pPKT%1`7j;IhzHHf%iF)pY~IHzVXp%S;$>6n@kr2=JSuaRvZeC~YrI)iTAD zw97I7G8&l`@sbygogX>K0I&$B)2*D8G{+NBad=&(_~$%lB8ZpE!VsR-O|&e>ah|dj zQTkXpZ!wn4`a1+2Y*AwE)#I}5J(z0CPe@tGzUPw^JRZc-7--`X7hIS7#~Y^)QfQYF zXD4>)&fh9R&gh71(E6Up-yVM9xuRqS8XxL3&|lErtk(RVv%-ZMSC7Gdt81}q(pWuy zxJmxqw&U}KuRe|pFLNcR2#}HqFEnU6No>VI0TO$x2&|m0-4>$4{6nmUV6}F$j`x~~ z+@q@A0|9CY8P`(t?vDk(LPpE$ix&4=7A8-Spg93;k1xJ!DgE;jmR6+`TlKU}5>agY zk=alkR65SWNPmX71i6KT7g zQOLibBAu-+5#K0$%xZ2R^E$CdH-opXGxyVpvGzLTZ@wa)tEGe~|9!t}@@kMS`VVZV zCk$1>daY$81pjpT@n5t6|A0({$ek!nQ2<>$$aMmADd@k@`$zHu5-5#jw?3`z=cSIu zpBar1G{9JZi+Km%C#cpJJF7FXg^IEwnrXG)1lto>^%zLVZYlzwJ$OMBEHE|+l;^52 z`82BAYkkP89+zmk(cNHDpO!+q3isiwK9~7+!`UF8O4@7cBD@0~>JE2l!tB+Dxea`Ow7F6XuG2r$ZE@U? zSHlJnR#=_do}A{ma)m`bI_X9p>85Fi=Wq8lKWMG+N*^6LRxtS!J*o>8r~BAOxaN2W zJ|_Sa)j=2YwH#t<5Mp1iK?Az^2K~ig$cS||Rz*qD)swoJvH$lYn?dHw0qT*2`^asZ zi7~y!skL&=`Rcb1cN&`2k-YpG&z^Q`u}DtnRV8rq0RMEN!|7t1+QRqKl617My<9HM zt4J~Im2mDu=9qJG^6vn+nc?(RYx+-G%*k837PrDf?`YdsJm`PAptj^*b;ChHJD zh89BuUO*SwfXWI_<4D1e945yJOO-PikzG}t-xiUO{!ya^UUw5i@0;-sKgh``Mn7HD zQQ(0v9@7-~E<-atg|UbJP5d!poq4GHQpY<&If@LJwPwPrW3Chm;aDb_=2rSNvxm`5 zDK7ZHWV<(*yX42+W9p@bLohz)v%4VW!jIJtCJ3^j@9~5lIz!;+r`}EQc65sy8ubwCE4g>B{jEfFV)eJyyF#%1)2@&ySA%F zau}@pN?Y2Vz8J;CGHO&@{0@L}upy-`>}LsC%Qt90vL)dt*dAPk@NM6!Ml&4YU{aP1 ziX7dBK&D)?y1OEVOimQGw-~WW73%9TqnDAPw|vtu?6+ML#;HL1{9sT64!G<`R4Wb& zApTsIF#^+nwl&VLZ4Zi?T)4*Z%`XbW=IqjYO41D<50lOef#Pg>Wj8dZDCtaEN; z`KpPBW-a2_I&LEMxN^#4Di!5WNLl=H<%PG8!LarmEHIf5k8`(W+&Hj~7^>xGO`@Fa z*?0pNK0qmRInt;v^A50fi8%$;`Oof>)Ch(Rwjg1=O_EEm)p*Q$6SJDA^*;aw&sk+X zbx$|<;vKPVm0V3$ekaDP#MQKA>K`+Iy|}IHY$UmffPP`?=Sr#)Y#OwXYI|i}pNBFX z^VbB3Z|reB(9LR4lNvpN6bRb3_p74^uEAIU3H$48`NsmQgkQiM4!|EdmsCIMaujWX z3Ka>)QG0D1G1E*;-Ow1r)JpKiAAK9Z72+YRWB$#7w|lg7Qg{j+04# zW}AxTrawdHBfr^Wg`u5P{g0k_Cs3HG{L>vtEi+ZJDVqG>Fjazt3RYt`8}_{NR;Ns+ ztvRxnhh(<94>~N&>8-8nCahw=Y67-MXh7o;;tClZOv^8WvXrS z*eDyTx;qEwmj~yEAIyoM`S^h(9~N`vln*&Cck|`yMuum)UhC>r4Wrodc8>i!ABXhQ zojIH7*W5mby)dO*4id9Ru+%5Fyh?m`vVzk?On>QVVbXn(csh`rqrc+xx>0g?lKT^n zP@jA|XE_$eQl^~T_#DMLdAdn8L?qNv4;2YD|De-)%9a1v*6ufzpD}B(W^=(*7EUt? zf{hy*@w}oz42XYt6H)1YkasStVW>=cyZ=d6t~^GFb3#Hn0(IiH?PkI2q_pLqeL#CZ zW>H~7TxEf5X>-%i>iVmHxh2{a3%dR9wc&YbSKQ5%z(GMppD3l(Ya5R^r35X6;-=y% zAiC7)4vkkwu~p`4HZzS_H3Od}KVW#9Gfua<_geng&@GD7^!W8K90icOGd>%e3tq%E z>_K6nh&YhmaF@R8G08Vwfz4U`c18;LqX#uplYob(-!kH4H5c z*6-hurYQyRT%R`3c`1)6eb9ZzPgV(iKVgME21_7vSu_(+LeAcsO1IzEG5#?LEay?s z1H7#1snt4h)V;ozT2@*0V=KtFQA~z5Qz~NN*X;iO)cq~zL!IwEXjyn4==S2-U$dud z`14XWy$;AwON&`z{uKpbF~iyDVqdon20mS&6%i;CYp<2`$+@k|-5*UwbS?5LKEFWI zV@n=AIJ=CVi6cq>rD^ln0jj_eG zDK5}T_Ekw0+X(M^3_y;%E>Jz?JA9pU39mE|%g_9{j<)h>aG3)3xHZh?_Q=iCliosA z6&ONgViryG)*H8PbOS`5)DAhz7e3hfd2gfD85gkG*noL=I^E88m7H<%mL1H04*Jgk zCvKhWtxlHMx`kODSJ`8BP(t?V^4)Zcu7Nw)KX6kt@5r8w3m~9C^WO@a2HpMvn~*i| zG7DG%AdpfhdVk~Up1;GpW6#Ff8)f{g0|fKe_9W>rFOD|-AZWVk=|)ehYRL5&XzMpT zK2n9!Y~nbNwaRNiU$N^_``s*=)WnUD|baS4Uz)!pqpN41J*PCyoDphjbFF?opm+nA%|B_S{IDBW4*(W<9m~`X81I!<;!`1I zmwyOmxoXwRhDiOs$B~NW@b5K$>XN&wk*kzX1nIV1iIHQmxJ}=z8vM>FK5O{(?LiRy zAUnU(*kbW33Zz5iDF*}ior(UHG4*MHP7@Op5C12{RR5ka{fER<$Y+wOn%M|FCGC4A zJSM-t{_fko$Mv4>LaYvledwvt-#zgO9s7waxY1D}6)58)f9m)%wmhkjl_3lG6o%kJ zmc;2o!29luELmW;T791XwBSDI=PD#+>}<;q@NuRzkn!I&L&VG^)TL?gO5gA2y1{8& zBgE%VPT^|COUoAcd~z2(el4qLg8iHh_nSHu%wJbq!z4@M_=%c7ah9bU>su91l!YIp zvAW*I=fTPOZW3xCoJYy{i+#X3o0pz;e5=ZX2JIMlX(mTNngmuTq{-~})A7*JRpA>j zFF$uDOQY#&>{|x=jJl3G*-U3b;KS2UQP3JsGuzu~E~Y`XVh##|&nwGzbqsACHh-c> zt9IA3sF`EGC}Ky>;TKy`PHD#LD0V@C_w+k-{b-sl?KJdl`h6{pAERFdej4`+478rD zbg4giJU#_0OL^Q+hoz%}N;+$Fh7bS?%cgl<*cd*6iebOqZM~&iepEE#&%Mg?G;0v` z2C!GCwx$;+v#+?$RCZ#?$^=p+0^U&$2-g7!IBYJx z;G#ztwhZATylD%(P#sYd;n|f-?-=Z;rHtCtT{&bk!NwByL5t1IUqzI}zbT>;W?MM^ z>_*FDu>P-0RS+j zaYxZGFx0-|ZY!Ru=V%k^^EaZL5HrzEB@OW$YLL-Iwxqn}_xE=8)bISDzmmJPTS0CUQ-kvEDjkw_B{y%} zRG1ewnp;w|uwOMlxDD{b11j1Ge}h6A%*pE6XZJ5OFcNZH@d?G`A;eVvp6L1DznA(> z%zGE?^`#|SxfVsdK`L!L<;cqmzPvBBN|2cR<4blRaQ($K@n3w&sD>>t9N)e&f`D{h z@y*;fJMSe$jlO+7P+Wnsnu6L-K;OYu_AdYC;EzP8wf~=S1+T2U=A>8$HcTL|cZmo! z+S>!Y5Lt<-@ZEPZ$j>p0EbShge-uwv|EhR`?^N~Q(9wYS3yVP0KM`IQF6_82)jvOP z@ygo-xOzABO=ff-DH6Pwp9jBzbX5fJ$Jx}7M)V_C)ii3VIl0d)pMyPX0QTGN9BNg4)=>;vjY9@bdZAxX>x7@gJu^G>4vqm*XN=BL7R5Ttrd!`g0A zEl9|rdbqIkRH>JpdTd%TllmUmh7nb4l)0R-)8pxYUO<5;R@H~6p)|eAGbqk9u?mVK8RnS+WM0XB9b6fk%$018 zvR!-ErMdXancpQ}y9sFtBvc^Q<0LBmVg3+YH!-Krm>Eh+kqW}P3ANw_S@&8PtqO1G z4WXf=li7MS<%v)`PVL$OD{`^72Uh@dSG>6f4ujN zX`|r%_dDZKW?rZydDRE3kkSgcEVe)UZdvLjoBV@eOo2`^qezO-5K1UIV;M+5hnLu_LZD?oQm+>-!zH+(s@>FJ?H=U! zKMPEWLjPBTDQ3?&-;i^6N)Vaqqlwdni<0{vAcR8r4+^0m?PI_?P-|jAeU1}T9a!%k zSP6Ec{ynFfZ7hqKl_REO(9+~+>n3L3e@aSDe1@4S!ij$W$~aP_JY}$7AYi-_pbJU1 zB{&CO|6Xc!YoF0+C9662oeyT6lmamTL@^)t4G5Z5+^d#3YF9G+WFKPHeXF@Gpn%G`HhsRZz)isPNyTjM}{Vj${gSFvNlXKqp3ttmzG%7`Uqc#S{B!P#5Lw zaD60zw)wI~#Y}|i< zCwZ7Y>{5!s)f>gI*ZH;|KI|?3lEv$zyz-*W0XmN?smD>!l!mVs?SPR|V94e7nX8)F zUz@l;rMhc;d5$UMfa-4bLeT)rObt;a7jwaNn-Qx{ z56~Ut#2AB2$c(mm!}{NWOxmsmMmVqPQo{D1R7CWu@7YxwFTe%UxxI?!MN!5u025JR53a7!+%EI`iRtrm%fx>^WR>HTimHr1_aS>~iJz69@fLaYc`iGXpf3xGUVZ#qrQ|MLv$6 zeqB5Qm&+g{A$Xw2KTH$A^N&8JMkW^|{As#*?A0fJ5rKdR=5lf+oA_@S>v%C=(ty~dPg+&==lN}jKsg0MAsb@3!cWah?>f~ zNGp{M@|(tERs~Nj;4pKchAKK!VWulO;u2qv;_$c)P5Q*R@l96atam}INE&<=fR7^m z`oPVL%t(0df`|VN^7=C)XdFcEznTd=H{Gvy44zwrR5#O>!7jiLSvc!J2QR+FF(T9Y z4HaV*3R;+!<=PQue6&R6p&vH6i*0;`$Jqa2xC>AIaUP+ksAf}f@u-3N4;Q$xr6}H6$x+F=@WFbrhxFW1=}~a{A@WjSqZT&QHaMq$G0ZB>=j*Z&jPPJB-@k z?Fi5f8muom(IxBnmiIAQtzLpdIPaU~3~oHzTs&iTyA))gQ7@Bh1u>5ioRDAjjm*yP z-PiqoL3((=|4Dqr?FTVDvLmv6AZya%IsmfEU=hlNJ6(Ri6I%Rsk z;bW$h^t45DTCVy<>ZdayZ;brJ*ra8RW-Cr~EXQ+nd@wN}OYq;b0hXo2@3>0uPM5!4 z9-g_V%c@`0Q9b>O7T}lSc_rs76yeRUu2Q{&;W7O}M9}#FGo1kz*@E)>IW=mw!nfGw zG@?8+a?=q>N{5l2Bh=>Pg}72{ z+f3r*H0#>1xPX}Y6i;dGT0wh-anE#s?8-i;Jo(l2iY^<#$U-t|xO9JfVPo)<+sNyv z&IpI<;F~i({2D9;NXQyFk;W`jMn}h0VK*1`Um>g*8YD=!8{;!*2;hL-;ATNMc&Ti)3jb)OV%ous> zxWq%sEvtokSxAHGVB(jt&rq+foN`xpfdSX9nTU*;hUx8(GQKAW7H2V+F0*_m>M1C( zlcl*iEBE)aUA8g|;An95``R63ds9!H;gpXr4^`mT?eeFWkOgc<7CbgZSC4VeURXHE zVG(bkMeE3gYbTe<>ew0g`GrxE*xXmR2HzBCoVHmvHkX2b%4y~@5E>`wi7MHOPu@7*X*v43pK(e??Ab9^nZ8Y6q$8Fe zG6SKL-H9<*NLs_jI+_2wj=-h4Q|~yp<=;o?7@jgOz2 z_+mxT-A#YQPfx+uBR^{{pQ+P;|Du^Bc;dio(f$pxC}lZ+-0C#VTRe{SqBqyFIh0X9 z>2txt^9O)&<$L0~!Qqxu7k8xuf8h;g{n|c{IizU}Jm<+uICTP3mN6>WyEJhV$_db- zSFTOCC`Y``-bbKzqgT0<&T8h1NdsOJ*Y@(X?ST#c%NYSSJwE(liJj9GPn7~`T=|Oa z^8DuLj5LuFWL3Yk$9>VEjk%^FWK0!)C;fW$ofFgziZU_XZmqSccGzm-SFy(SKC_mb z<<-Jv&%VB8;p&Lh&tnL}&(o4dl7qh)RRJt96;FQ1eu>GAl^9?QS>s(j-M_0M(SgBS zi$`r57F-x}5WFWgzy=Vj>G=+leyQEde#cDHvQns>aH-B)B0#hSS{{8N+u5Tk5d}n{N{l$T=hx2-3Rlt$Hy3M3)b3uNs7(tqd~Qy@ zimMx3dXfFXSx7AZY~W+?Zyf17)qyko4qK&I`-)?ZXq{qugym5>Lf%hpMh)tSER{Ju zSgqkr`=jW>{1-)6dv8D(Bnc0_p$ou&z!cKM>tXIMZn8Mh(gEx1_0?^+o}mDK0{TGO z5Tq9Y{b3hYU$9CTpUuqv$ie>VuYQo&lYpty3jg!-b05E!DrkbkmojJ>vHEO*u+v_L z{P#itU<5Aby}gXzyFTr$u0~bqXeg)@R{Qex=P+5);S=7L|8RVC2lX-{Q?V?y!{z7R zrS*hvOnW&ziz{X{49_@L-S+9-GtRsd&B2KoHOHdeJzSD~p#C4y^w(_hU)J;o2ch!Q zSa5^tSdPo#Do%up&M>`-Kil|fbBM55dKtsMITXaj`nXr$ro?PzqnEWr&X`lIVJ;tc z>E}*)iwmZ(io7VG8tG>bc8n!FTT<3$PNr(wK(77@SlJcAxrf-4cZKYW?A>0lLW)!$ zoR5={@=C$}H4zb1!Npu#*C_hwi4aJL(y?3A@tEwtj{e-9YAxzy7ZKv z)mYQmr8d#&<|n>vWiul12v}S^jd&>VE-UqyQ-6a1#NPxRz z>$)u-Vgjj-!`(Jp#)t6UdEsWQRuZfvJ&$+wUp}CTaAmx%h%&Go+ZIale~}kI?JKbX zX^wh&q~H_VkDF36Rme)}^__kh=xr}S(E~nQ4?_2=?~;t>7PzUhLv0pM91b*xoG^?g z)%d4VpF|txrrC{D7J8MC?tiiRNFOb4-9*z)TkY;3zVp1Z?&F&Y!hP{8C2@c#oAIf$*YzI$>iV{+{H}658%6vYZJNktiJjv^U&u=&%9R|Pi zVXh&yMY#telPs=y+;ZWBvC;f$AAXsMrsB+Ve1Vi~c-GAQJnM@VUJxAhC8&I0vT)Y4 z3^PjASas*Ues)jmuf`%1I-@|G%kls~4&E)jw7~d~8=`1w*x^x3*jyxs#KeRwy~Sf! zEjvZ^9(BohVwVB@_>Wt(aaECiMD(5LRQ$3N<^Lfu*WmqIa zi?Gh_VV;su@wkYf^A77J5pNpz zP^gl((&0@W*0X^(~(tHBwJq@BDG1 z{ln$MjP}3m`WdnM8WxdJkQXO&8|33ZT$Ml=OTW#ShabfMn!h~NAZIjv^UPHy7gh)( zHqD9=`gpN*Sqo*saGF0|dx!YR@VP0MPiJaZd(%v$x4Isay9^38{?^7`HNd~SMey-u35_1L;*6uc$j#019PU6$9@II_zqooomJ&i{Zgb#TKw0a2+16B z%Bk;R_sJndTZ}<_5oWFs0rx%;H`lZg6V%oBjw}_%*xj#NVYQrRmWH=$7jr|MnVie_ z1@F31?0yb}NLM*ygKo(6i)I7o3rwUrzD-OGofujmE$Gd#S-Sq{XVO)~gikgfz`xEAjD-|83dL#pzZV2lV z6R(roWsWJ+yrdxlHIfth^eQ|7NOv>9#5?V6=BQk+`0VL3hsC4G%I!x?f~muX%~GPD z_-zKy)bEfk9)3ZCR4nI^AdeTq;(e2Ep}x;J^xmLKW;{yb)so|KlBmb8LxQTM}XL^sCk6fIyX1p3x| z8RCyZk=0`o$7YDcUB;?yqf+MXU}uy~Eym8^dUh=dWvRv@8#nM$5ZxzAdvTnteXw|- z5K>rLSlqiU@nrMLf2Bp-R?!gKzbD zwK{XBR|=cc?L!gyvyHcoqD)TeYyOLypWi(vx%NfIg;cgX7$A0_>O4%&ZP$=K&vgx( znjKIFUBF}0p3Kd|U1~UeX(K+`t}SK?1;`9M-H|0W4kZUM?HQwEIqWl%{WE`Hb6g3u zplrZ_iQybYaGLSitKT%m(@+rJgLlzrLW#=@;vasXalTyi%Zn3($UB59_GVTUj|QZj z)i8)4kVKvr5c;U|X9F_EPPl%LqX&J-fflfMUsiS0W}Vn8P#_H#Rg#e5tU3Y_7%>u; zhHY6b{?=WxAOHPicX_{moDxdNqaT-RD`ThEbuy|V8H53chfQ%b$9#4NhfB@5G@c7(amMW+OhQJEd0 zH)R2f#X=V95`pG67A?G#S!Q{LJAMI`)Ep5d zC`DKC?R4O7hTB-;T4O5@eG@P71f+2Rxr_~0?15ay(2Qi{Bj4j)2%zg8_O_qRg=^N| z=(VmdwRW6u4gmnr3*F2K&pmIDhgMz3xPcZ-iQVu^QV^m=pob@UZ0iz$Y>L9?wZMwX z_TphH-}1sf)PK*Vg?b!a0~e_jk9o1mr|rw5?nc8p%?}Y=-lObzX72g2w31#y(4^I` z6Knl++6q6HE}T%+9r#In#rS37WXLe$YtAJOHSZ8ak-T~btxTV>n6cEP$~u{5IPKYG z;CQpKeMPL>&;B8>rX_H9PH$7=vzPI3+kxIi_GSach6Fm0-`T&pjLnMuaT&Yj@nEIs zt_VUrr$Jh%{gg8`o$OuvYq_ZfC$kVKwky*CNAv3!73^ZvlAezc54+a5`|`gXpYliU z*jQ&^B!)~r+JBovC!d5vH6h5R{#Y=}1KVyq7z3zw zN{`vKxcg@}-x;5D8A3i}c(%7BA8|S*IN?M4`i{}^d~_P_I+$RN_=ItOxc0b+ z&`!wbOo(o#i@4&sl_b8&=T8gxsxto|;)jySY!E;DYsk1_huhFadJYjIq7Q;FP(5}k46^6P*dD~U#D09q0*L$J-1U;x}PDD#J4>D9Q^y1vx3MU3j1rN{JQ!yz-1=GX>A7r!NqK=_Z5o6H2 zFoWy$5xwkC3dmYW%}XGq6Wh0Vvkt#n?u;tlZ%#LXH2;HFRLLw%^8!>>q^|7-c=G2GVCu;u7lCwGaT4>701^nvhBX+WLT-p34Xfaj-P?_ zH%1h?*#B#|t}8e~6}VdB+0Wbb15PS7NbOxlAOZ%D`S|MleD>Ha_Wj zhmy0r^(gvV*|~U3EZnw(vkZeN)(AG8<9$M(xjD2Mxzya=7jFl*%@c?3 zm}40xc+-4730GrpkzwgaStOP*f~L!LFLU9^f?wO_fJQWAE5;)D@hDWKv6{IhMC?wg zK^*p{B2v>Dcx3f(#Hz0RW!38D?5aWGaMbWc*@KFCD26cC|>2mWJDT7yq>{CBoH%7j;Z*cS!EHgI-RO zQ^%n!p=bDC_JSFld?I4r02;8#!!E~bG8}1pxT1N%$QhUFB$b%N^fd{E*|dfcx1S=7 zXE7ukpvY-so|NLfyzMxz-dJ&&wL=ySl94?{Vq8$7nailj=f*P^ppO62MX*)v15JG@ zA;AH^7O({n$z*H=vI^#Mh(o9IPTOdGy=X7iPWEFz@rkQh2C_oZIKs_eTuEZyI68JG zrywM3ey8}t(g%@3PRhN<+#0^Ou`xgWb;pI7065m9Gx~5Nm*xuCSiiRodR-kMV;wD2 zl@Vx=zM`5tbxZ`VE*|!9>`{S0GT}!%s;%`CvIcAqm&4dsqq|)H?-@pT*d!Uq-^$?^eJ%7O2VVgeETlLT#JP`E<-@xFzXfZ!?V7lk(IV!I+%DnpKSwPA) zbC6*kjB%?qd%4D}qH?77g09<3tl)EPo2E;E|5TBgPFu|W1mpHaWx95by<;;4ev|cU zaafDnY-xA2G3>|$1gJ2U!lV&Rc ztLs=uU%S^N+9L_CXK{gYpGVC_`l2m)2-`*G9pusoIiwOM&N zE%78M_XvSDU2@ojZL=&cFeN3*vvS+t7|OspzWYVJEcXqcI3L-AHYo7)fS{k-@K}%v zVdRF9ZJAPsJc-8pG)3u6C z&|#*aug`i#3e_MpQvJ_%=JR$J3?APZN>(A$BI`@}Ufy^JWMF-v*H(RJ-n>;xSiu~_ z`*jCZ&Fg~6@CWP1`qzk*Mi}*nhu1}IRENY{rsnrd)YRF@6J;?+u|GiVbbqex>q_UA zZv8*dwQ{qX=2bN(QaiSV^eG(C-p~JWcP7!i6Z%XI}lY8LAa$}iUO`-LpwwGf_TCk{N}0tZp-Mp@2Rzs zYvWirr}+8LN9Cjpxqu+Vt4a1YJ-Shyq(6ECnAwDrBZGf$e`S|5RcKG&WR&LohLkLt z6hsGlpa?VUq2A786cU5QgVI3QD06zcSnZw0C?b%H8TXI+Xj^YWAY@Kzc`h%6;DuyW z-l^HMMOf@|=!XUG7|mCS|ZoMDg5;ipdvPuTu>6(PH_D_r+mLELqxZ(ek(VO@J z_ksR(*&>hfx#gc3y{Fb3=6!krdBo7@KdZ?+pVB^@ivohxA2YL1Q*;U~F_v_!4 z&&6Nt7X^|>aD<-KGX#PMW7K&xWmRpS-V^4Vx|3A%pQeVz|0uO-+im(G4&nwr0a>-$}ufOzJ-3 zL;}wOnhaTbX+4<&S9nvCRb&c|GV;1^+Q2;6BuVy|Wn$s-s*9;>i$mhZ@40_NyWU3?vGA;b?> z!f$XSO=%c?hN_;brXuy}o$|uN%k1u*5ls0NcS}S6)O~wjWAA3KGi%TANH5dj*e@|K zFW=q$PZa5}dbc!&>f4oIzQ0)ZI!C@au=v-NM+_(6+wAS$vwdE)ZCIl;4ykXfgabtu z8algtckp|NR!IB(<$Kk)XEt)*R5{8ohDGlMyw1$;&UyHOh4`A%l(!kOgP-Ci&JCD$ zD!q&gd;8Acqc~QpoH!-?hp9X=UK=b5p!DGF&qwH~2F;h=RHDO}tP3t1gIY?ZD>RZP z=uhDBGXgIveLz37ARUqWOR}?fm64&}F;|mUnK~oev#B#fAe6|=LxQk&fe&BXDov67 z_?Y$gk_lz66TB_YpvdYysuYPqBk1e{50BhTETL?Z2G>P^-XEz z6Q6!E+GC=+ZLAhKPoCkYtezMvcQ)<=#X!m)UcJ42cqI11ty4Gmbq<}($BWOm`y5>h zQ?kd}k;|dVA4V{QRxNWytE%rjc_)N_-at*$H|t zXr7wW)a)Y|#JU%PGzM0a*@KHk`v5cwLSLe%DQiY`|BS4Qv{4rayck=(=HAZx`_A|^ z@}ROy?d;2q#5DCo6A%&7lTo;^7k^ zm#Mcl#Xdm-A4~pFKw-*Ql`UCW?6x9M#xGx6;$ogC!nd0k>ApM^4E>cc-t_GjvX;x? z6v$;8*@ODX@CqxIMpvto_yUH9gI{>n><23)AqI6HO6}o(zKUIacy~rr{_9^@0N`yI z@8cJa;I&xC%`vJG`X$W59|=5S?1^~@W@EbQHLLN-EM1>y2d0cIV%l1Ge8;GLu*O&) z>AAA2kD_5id2B%ktjcPtl4|oJl)*fg392cMDQkREzswHse+@qx^a!>V?ZnI@g-*|9 zFf`E-PV&@zH$WZ2%r~sHSlZ48)>@b2((mzLB5K8&$+Vw9vPGUFztqD zRP7dY7M8)p{o3obd{rVE~hM2W!!To9MSCvUYKSMhD@Z!$Dk)0`G2BpzYkx%ezLOt zPfk+G(w=7IM`@6%wsxCY(@ zXjy9Un-_zY38S9Hu`RXNbTX|;0s=X>H=8e;Y1mzuR`?c8hP&31l~%LcT{-z<2%?ea=-MgE^X~G6ApNWP;20+wB6z)7aXK0qy=TLy{l3ae!7_$Af$xL zDMz}rG<;~fY+6O$Y=M#T$Dx2LRhRF#$ri!eyUWspnAsm%1RDIvnbSyt|42PM1@mnEox&*@K1fG8(sH{T z3mOi^6l!bGxo^rY&7(wEvSqge)&PIG*{#o|K+$s=5B4v_NU(22K>W$J$Jx2&JXyoV z>mFmi`1u-Yg1Q3_5|rxeG~n1s>bmJ3D}CKS`&j*v>m>MTX8T~{D|=3SgtYz3jj$3c z$X05#jj>}`XI3VZTfDga*Qf8)l7E+0(Y`aVoO^BrshhUicGB_%C}e|+Ch0ryk!@uEgM8wQV+ z(hu#HKiysC1cIKHWyiy|DYB20x}tTV1Dtze;z44}M2DYN$FX1OIA>$RJ!c?2jg5@e zrq1VjiwehDc>oicpk}prc-{u0X*)N2F}78q2gJ6ga~m1F;fr1)8T1ar9N(k zx<_uSy5LVyN>IJe7gjy|{=)@!1}Ly@+-IXz99pJ#nHrjw>Q7%YCw@2hhKk_^&7^O*?59$)fZ~SGJ+x>?9v{7 z3{uvX7cH99|9^-BRsBHNonFD;GChIc`nvHRrsjSZ9oD1ZNX{D6Ju-X?z{SCUfN&0n zerL)bF$94;uN?XB69DehMNNmz60Wpb-cqsClxJ;L@kQd~K@D#@h6V-nl6gVtcJB0F zGO(AsOzi7Y-@TVvxxaf}j5@0IF2Te}JFNlfA!gz%dI(hKXjfL;j+|a27TbOx_@{|A z|Iefgz-2mdcRiDe+(yCEUe0GYHyJ8NpZBk`Ky%Iiv{~T0J92374`>9s8yd!U{oREO zB@k{-Mw0x+wYl#Er9LUcVi6W~9~e7f%DFkCzaM`VLh(?ZF8o_l+GbI6peg1-zsEde z(dhg)6$ofbtpQExUsT|mrWC*3gaXQj5WlF-^dNhN)>&Zf5Y5?k=#Vz){?l^wV%us< zz3k0{MiVJBw@l&Jd>G*pD8dD1901(AC!+ec#*edxC9|>TBz8G?J_j>(>ysW#ckedU zzqY9fXiEQ$81QgmD^a9l%ifKzBjPXJ!1I0+WASf$@Uhl8ZG$q(%OmdQ$NGM4ETc;! zKivM%L|(lI2TKt-y%G{+!V=YRUk|Pfpn5CT`403a=r~qsJh^=B(ux>d)Z&_mN}kSO zD_P_zJCrR+w$%NRt)R=0S5edjGEO5=duDQECw7t_%{Mw+=?R3Np{ky!r&4TYw=7J3 z)EnpW9$6Y%(&{Dugn;%2+OZJH-*EjN6#?M8sO!FCQUW(ayMHtC3$FVm{6CHRUO^0E?-XmQ%~LBh^2^{%|J7{%yX1ezU*Ti@_TVX- z0UddOx@)}KM;0*FoyUWSU2%E5K`vKbN$cL#G@c!wg^z{E7Orx@Y3~|sYa_MQsJ{us z{P|)ctUScrGXZTde<%NB@*9r8L$CVgX)8J7@b#3hU=G|Vl7anXGmLCwYS4;puV?3c z7}LX2>PFr)c1oe#$L-9Gx&RXvEv>EtYdu(t-NhD-ftA?GA(>vrNF0%Tyx$= zW5}mZL9x{5LERPmyWsOgmy^4j<8hzAds)fsG2ynKqT-V79AtI&x5Wxqu3g66X23HZhr{_du`h`J4tMHeMQ7anVC|3KSdJD^ zGtD_b$RU-J(n)~5v<)g#X1>XRBzfIf4(z^b=NWt(j)J9ETho#7;MI?{EDIz#9XRpoNg zoy#3P7aHm2ky17UIi$D2^~Fsa8qdjEJ@Xf8sLY1@sWp>yDL^Vv9Ac+ooKoeHQhK#9 zG6@<{%^)Cba-x+C^%K^;i1~IKgG6Y1-Yg!F-)TB_--XT_1O z+r;EMrfN2kA;r7fbg=azV0}oSy|edf;UGEub+PN5r9C(Ihq+jjT$wTnIH>A;YG|ca z*Jde1>-YWcaAw@-rEWL}vGg`Mh-)}GwSLY&pSCqf$JRTWVtC_+b8x4s*VT*-l3PNC*g4UZB4=hrYP3 zsbf;6>X z_y2~QyfQ0bV)zOEfL2a4ec02b{djOj5Bc^Nz<-1HzI>~9_+dge4{r8fVz=*Rr?C%H zeHkxJLp`Knf|qHt0=+ZdGRp69zyw^()XRkB?7PFZM}Rp@Z=RemFLGZpxn~lc`jB;F zw`W-`V(In7z9!1|cG#EKiyg7(-5TTEx2&!>VzS3|PtrbM310IlEnTj-jqlr=XrS`l z*YO-{tU7BzG@ywbbvrrd3y20L?O~q}>7bvJ_7daM$^Eho+%E^W;DFc-1I5d@OJ?V` z^;6eTTG#tML{9DNBL^{;wr+YhJuIU?kFRlt%T5z7hg0?26=g~I=)K2j!oURF0r75I zM!4HkI*=ryraybRCh_kaAtd~mu7I~<&~8YH!BXG`0xnvb9b3QwQuQQ^U15>idq#?l~mfmzUb=I;qIp^XaLuUqToc& z=5kL!eaP(|c#*%1nGxsqu$RG5wZI4Rog+*s7;WY;OXUfUALt0nvQd6 z`!FgLlN>3krfY*EGAFw!xHVPwp;(w>Z1puOk4C_2**Z=k?XcP9sn(4&F1RH7Ui|yA zypE*JCIqso55M=Mchrl56C8AN)jQv zoacfC|56lWvBEi=#BQCK4-RZXQ+rt()gBf8kR4!ZAdJu8GBsdV3+|_rEK`B*w|QvW zEsCsu&H?@fJCBj(8)kgMAHTu2O63~L^|H(9pxUjef)Q;scg0`ng!v>bdMYSAOw5&; zKw@gwA0s~U--Uek#YF%SNm$U$TfRR1#EyZE0^^#wX4*p_a2c$x2ND?+T5(5a(w8bvw;2n5nmZcgid&Nit32SM+5Y;4&es#{I0#a$fo3iCSNwM7` zZ?+Bbg#`|6ojsntwmVWiDOJHAA&Kv^QtbPzcXv>r=2?Dn5HfnTDwCMC9J;z;Ye2I5 z;ZX|a&v&^&f7rCpV+hRHbVO6X3&=PZ-T!w^~$7(&P7-(b4ga zMHoIqUWBH@&T(ayNP7e@8&`VKYByx3y`yYn(PS0EdA91XLtYw0OM^qQZ%n<#N$o0O zN(Xz5N4UG`&R?Zr`_(ZAYF{v6NQh1^jkqujw;<}o%Gim`x_SY1l|4lEr9l}_j*(!# z%I>df?(DUsMK^uKId{uLP#@1qK?3iRq3mefgqDwqnB`P$ur<*jk}9N_yV<9uKQzS@ zIjCst=;UA`qb_$Ke!b7Qa?v>~LlO?^}cwAPa?PJN@=2-W?dK=d;bo(d?nH-bxKJL)#Avk0elqY@ zVZ4B+!+$2x+Lr0;F3G2-mG#z|6-3&92sCYc?wNi(ziQB-#A+mAHoX@76_%yyoYv6u z{}RBxSNPuz;Hp9}IwGqvG#O(hZL4qI)9r$F=Tb5Lwl%G>I}Bkx6pB_~aY9QW%3?}{ zQ!OMUStVC-05i3-qS*LrK+fHX62LW3l`d8H=;y82q;|!uA=X7c&3-A~qtm}1b;3Xz zY(uQTnn0H0lm@D}k|>Ch2G7hUC*S3Yb?5ANAPFbaFf!Q{{Sv-$wL*3lN%*`Hn+amr zc#E1ls-zp|w=9{WOA2Z^lLDVO1=pG}hfQ`M@ggGijGlIC%AAvPke>C;nR}-7e-`%0 zKMDM7%>YyeN@E&FSTb?=>;`{=9I&^n2(`5Zik`hJ%TN9HQ8g%=muoH8SuwVuv zA(PALM9C{K{-Qyoja~PQEe*U%c@sC9L;x?X;N8u`jkY370O|5v0>rN%#MZBfvC__? ztqWFL@>~z7)`wZ;Ho8>VUlM|#T~C^lRA^`I)&36O8vds5SdQE+wTFgyYBol5gp7Z< z&skY5kei_s71J?pw)k9pK>JXb1&yO{&0kyTLF@8xW8>n{8o%I3{OUALp3pM|BlYuc z5qNcHs(ijuAUa@&5X`8{vkxw*sp)$iJ`p*dm|Na1U5}@+x`UGSuhX}sG0zgr#itWp z;H-8sz%YAmwC`Q``GWb4ZJmQiGw0fYr8$AD^4)-Y_6acW9pa{VW5;C855F;@Rfhp^T3X%p=&|JpInX2@11;;yr(yk+{OMz!^ zH}*M)Q-(7>L`bL%4R@Z?#P3r%Mg(Sb>oaXPHMrhF-sgfev)y=&&%LZM-9B(YF}K3d z5qb_2^aaAW0h;gg(A7eH$Hzvsc6gG`OY-*aldy7r>R20y0=_0V=>3<>A1%~})3|Rw zgV?p2MMrvoMF9lt>^dH@fB6iG&Sw7I!Mc05w5Vp5KQ|rK&lx5p@ZPIzmv!~CFi)qo zz>BMM`~C#X6L?I5grO~1Z?v~9-ZSwvue7MR53aW@yEqOXqx8l$X8J^TJE>wA;gOXIo<{yg-SCAM#xPc8+VRu5z{Dlz|wqX zs(>4Rw=S5bk@VMa=XO#2DN#Y}Z5AljF?JDV|GuQL^G~*>Y{(Xdlm=&6vw`nt776n! zPOH1mg`A)dQ<#!NfA&vq$OMk)t-+tl^}Bz6J6O7Z+zliFf%$d%sS|vN2j$e2PsE(y z`Hn3xH)NV;_R&fW4ZmE*q^L8F4sCj>eZcL9pwctjm-PpKNX3tV#}RXYhR1)|sYp&1 z(hQ!w;Z9uBPIrA;-srj7!-ioWTif}=imt~eVIe>DZMdqhjL$VAIr5sCra|+4;PK}D zwr2JV4{02OmCRZ8M2pg?qJQ%uCBv?A>#(?N1>X${(M94-YRm~C^1cTAxY*MUQ4pi{ z-vQdQjz9|Y+s`^ZtP_(|v@7iR)29{uB)`|+eOxCQLO*#?qenV9H|~KKw6H)QAvQUttCF{D{NIJ3s}g<6 z{?{SVqS6o52RCvVez{g#nU7aDBk-bR{@{Tyyst0e?M553n7UMt8L+bSeQ4sipYF(cedWbZ_ZC?D2Lb+EJ>FVEWmGQ6PS=pMem*wXyfO|9N z`_c8~{(J<~jkZSVf^zpsso-#` zvab5+K9r76hWbd9ii&zks4KGK=!q;_qt+mo?9X$^1}CT_Co5P5c0f!gs&SAvTzgjz z1mNr1h}oWhkqlAkPG8A`=AlZV)6^8r5|S-Ip)- zaOv}2mraiFtL2jQ67Wu&OxHw{>(A00F$*gY{ZQh6()$3@yH(%t>fA62?76Ts?AAZC zVp@nB!Ggr>Ebo&7#mjSRWsG9bs}bn&PioMD+ij>kah(V6?`vioc-3a9EhsOAFz0;N zyV@muP7QXQo17N4>tXwVZ8`}=Y+hukPY!K}!phlW*=z4~5tj&)ltJ@G)Ql^o5z91N zZ{34N-Nt62G9J>6m7O*946j7(6^`w{^asgTYa%LGDbs&G=yag;CFDK^5W@IIA8hpB zCJihS4M92E$t+{RvENM3aWbGqy?c*F@TYfw>&S=Nak0(Lpj`=0(BYz>ZHzCD2o$1@ zxm7vLVRFZzwbzxB2bNsS|B>JMNG%!*BCvUr66S=GkbiyME#jSQ;6(a`&qu~UT{5a} z*%RD8bcP=5B}={*=dYlQ;>m1*IOk!PslI2Q<>`<0gJZ9AyU~eV)!#Rad?h7OWl}AL74mPv|i`7YMxW-IQL1w|wgI0Imx^k~b#GwfjglA8O zn*mkuVP&^hcQQuaJSaFk!_sqqyeqg|-rBcspc*IbKR~tC&Tf0fIiK2a;KouY1)=(8 z-Bg)ldR+LJLPT9o!zcu*w69w$JDvM0*;4$MWXr-+LxO4WL8_4zgqFdkb+|f4k?|j! zgq0fMia|dQ_$fxOX(^lhasY1y>bIx#_+<9w0T_>7t;o-j1Zr>6O}QuWDh<+KuZLHZ zif)%u;>CrBRv8;zXtMGFvwdk*6Q~t8Cv%>d|F9wSCE!XX&m~6%Ief=0*6Y`Ym;;XP4{@n zpWz1sv=Oub%cd!EorJ&|xAcUFQ0{`r`bOGKl#gMrJY&?2dwz|*IC@o&wwn`uDwf}h z?rSu5R>7)rfx`we;qQsB-aNY}9?)sM60Wy*8%B?@<(%3iN_`B~4YoVha{Ag?cPbjp zGM%1^`L6Nfyih+ej0(jp5n_|n`=_MdoSTo118#-JT61_ghg#6f9*Xh+ht@@c$cRr$ zS}WYKet(z*lskpJHYli?n-|-EO}S{77ff|x_Sf-{(qNU{xW2Fy0RjcGz!siHdw*>Y zpCSN{lR(RJlEJg)cUP1KBD&Y`8yD@OiJ=1OgJ3ybPUkU&r&eIL&iGe2PE=7T?ON%o z=_~RY<~uW`ZmtRk^pmgfM9unJdT-tEi?!UEik+&%Vkugho@Z|w-nF&GKdr~>PW%O& zm~J?P_n+rJFV9=&CpIi#i9KV_P-P;G<9YRWvu+IO1|I*^2Hq2>?rPV&*~*EX-`)Vf z)V5BR@iL&LaT)HOx-C)E)z!d2EOEo9r?w1CdZBTvWTr-KYD4KF@lEQ+ZVm(U z2}efre*6C7c~$yxbRDrbrzNV2__%Nq>5(XNQ;%O>AHCZ zzldmMcvz_NddtZwc^p(&8SHoTl}4LW8(RL>?7sB`#99F{$=Ewyaf z6Fe-X$rX}Y$T3ewk$c9(wsEEkx3NoSPva=>kF048y1)QWJARooi&Yq)g8z0ZOqv`n zG|(H8(8-(!OxCB-De|Uxul4+fB*IAPxf>oEqkQD%PMqeQpa%2^k%*W*duBzIDsb^f zmrK^c#y5YWo8HYHGdCMQWFy@s#?3Bxcds%L&ks83w@(nKg^FN9nF05@?a*8~UVn$5 zWrSSIj~JkteHKF~N{OBz|6}>47HwGXpk5cAwGlg+POl3b_^mB?E$;-Z#zBYR z!S4pnx`i2FzI?|C+;HT6;^1cmzd=ea1Zh^MR=*fs`15{dnj4zQ$T_Wgo$8_>5xM0I zZ&yDb$-eyAGv`Lq3t|d*+PstC3(7(6!<1t?9|RsG{&oBl1gDXd;PZ08k}?7Ta(%9F zI~*>K=`D;gP15IUkDA8RZgm*Xr7(<&n@fS7aEjp?zpp;(E{Ytfy7MtD9F!-l(;`4PD$YnH>$sizpf7|BP+>n`aZnX`?>q&QMI&s%2C{VRQ;LXOhO9 zOm8VOZ=q*53i_@VT`)3Bv6V5;%3tv3E8p0D-TIHoGHD8?!*;OTF&Pb2a*eMJmSl(h zdTLgaR^C@sS^0S`nJh;U=nxM@@$&itOiFq_jmMRq5=YYn;gWQEiO~yXRxu&|c%SUG z+|x@2hlN`k2l((cz(Hd8cQG8qXI@gIgrFG3Oi+16Nds%8InM|8H~JJI^` z^x!__A4k%rZ0AP*90@%f1-O>hxq*miOpCvSE~nC5^yd60P0WOcY2BI){0A-zwaWHf zKFS&|M_uvC9-dihG+F2O)$eeXT^82Wtkm|TxSTayMyqw9qa&a=R>fYVpz#H$PcQ;88K{D$);B}~ zi>$_Oi>Dt~T zrDULi#r^1P_=nXZ#{`1NL)OoB2}Uc^6g{IELlyt*{A@Dc{)bb7_C5F}x0vl;!z`1_ z7Gtuo?Zd7p*C|VZZM2Kl;QvQW)_bG+0OjlP+x2S7Q}vjF@84%aHTf9^9_HXBM*y>@ z+iNQ%tBVFJ^DbT~cn%_dJ{c4lOR#S_G7u8GQxM1#moa8dw8scde)bvGc*>e8nyb;~ zCgvtncyEb#f*-wJabgwbx+N8QUxgd4DpQIikg??CpGAxMO$;eu5lho(4v{6lV%#i7 zc>8dNl0fYWv}xdAWD>MwIVo^K(`dxkz|G0S!uAtPk?=BT^xmYQBHeMjm|~rkmbEGw zdd?xUfrXVeWfVg|$aisD%cWC4Nq+~;H@9ZoJxj(vr_|&NGZGPnsGDElr{XYWy;Mb{ z=;p(+6(awD&M!17dEP%<6BI_EGJ9&00{(J+9?hfy3Ns0b0rj-HFLe`CNw^INz8?@Y zzLlm|{n+50)8M0e<>}TJ`NXwCX9Q}d5arTWnK-Qm;Unu-KMZ1m-yYOBA?pv2g#@4QXL8w?FjQs{5jv76Y~+G$mma~}8@kOVWq4>qQP zP^cg047PY)60+oaGpE=)7$l298b)p?XU|*Y^EowjN}mweGWRttjqXNw=h{|I9v-un z0{@7@)}5_3*`8=PQcH)v;Q#NHRk2j7Q|Q|hAZ%%B+e0MC{uiLMuwVZgN{iO`PYI>* zd^;+p+yoQPGSvgPGzwDrm;Xk88H|cx{Ao7Zwy}E;xXOm@5nO-A?^W4-^Ki7vXqoQ( z=Thno_J3bWZH4-eE2S!mW&tg>A4T)`m{GQ_+6)nt_lj@L$5ukGJ0~$Ux%Gv+WQ*Y& z5%2mybwbP}_#By5I$MY&6o)-ppYX8$gAi57&2Ke>D7Hv@SNERn5?ElqYmsS6aGF;) zTCMaVnWkX`kUPOfmfA6>OnyQN>DeM&)}h}tzz=E4&;w-$ygDzdvkX6@G+x6 zgWJt!|3+2vydZ(#gVZM*RJ8uR<3#OorexO7`{#hIVfy`~RBYK;$DiHH?xj6M#&m%( zu3v6140{=c_nShR9?1lT=^veUI-aHja^)2VX7s5HG5aXzP;ch23mwf2+%dyWj?{=cYa`gDk^n7TQi*tu3JcdAiA8lXnO?N~9@t2ja^Z^!}$Oqk`D zjh+*C6^ydfuxC)+>~3pkRL7fu@UZC>-lsA&B`bWTxN7OCu&kBP`-mEmgUqSd`Jp>X zQ9V*)&KXa&3e5L&Y@F`kHpKs^X(_7CDdgArEzQSAe7(~42%Zt`c`P75-r#2rLhtXh zjN7p<=zO=Wrbl;u>;f~dD{gY-P=`c1=8HYJlAQ%{OQ!#U*;z{&EXJBPat5rH)$vG` zHF-Rnv}ri-4w_s^-(a}`g4sdNO{XCT)A89$mt9;*QKy1sQ%Honj&ow)ntF?ky7R;K zrmCWEdNqiIrZ%z|6}T#2imyxHX_>n@&Tq@&%lqE1UTrelu5p=__~@)1Fc}xw2p-P1 z9Fk0J#S5&NQa|tUYn^2}P5x=zwp|l_VsLh;mA3rfz{wu5RiLasNsD{Xi;|qo2_TQpgkBBpic1r!Jr{izo*U~+u9{M&f!e$_swe?r%-_%0gASz}Pz<%qOy z5Kx6GHI^kX*hChOO1Qc_+|8H}QmEI3b*)oDf_!)XaH631Qn0^@sM~g5%&=Z?!ChRE z^9d=kK#~^nZ}fp>8oF~;dcoCk^xOOCr0&B}GAX#8Id*x;$xqcvGoU0g2)f_aung}kUNGOx)J-o4r>->uUKyy~S$>myDP1SNn` zkc+CYE;`w#p#uKUzzp5f+8g&J0!^S^{BJ~L@X2NOIRC3nQsAyETqgCltXwXP#h4?o zdNuu@t->@u;WS`VRz6eIyhP2nI6OJL9cfkNA4ht{2)JM&ZLNd;`@ruYg_*!HQ8NdW z{_%CU&->{>V6-l~1C2uSrD0A={?P*-AmM<31q6a1in#Lv2YyMvEsLsYI?DYhAxOZ~=SjwAD`TQuIrt^cfdLBZ4^<5(s*=*u@c zVXW(4xV@#gRw%I;BDpQs>_otVVzst#8&8Ok&n|aJu< zoD~?XwwjEag$9`T5bEa3Ke%_1lQ&*8&dgy)EPb2_V~A(qNmamKP+2;^SIe2ZecKFGNT@+rt(dNq2mY`1Y)>k<3Fz`tEjJ7kzsbIVh(*|Em9OD%;bKI3^wUZXn|WmZ?FXBjD{O* zuhvsT*H4Z}uZ;SZ8o2op;yJWW?}8Ud%F0T>L54I*D=Qn?Us}mjDCy=mj=u=V!V(os z!D1!RbjhzZEq-hcf19PVI@0C9V~}jzoJi6+6~&9YkiO+^T=|+Cc4xVQ5KY87xVqLNYPKv5%>I%~PZ5MJDVMn(%TL={wfJ!5VA zjzny-yX-Lb(ZOSP5ViH^t_?x~+qkn?iKc}+;+0m)%&X0Zt4BWpkOJ>TY|eMXM#9UiFd;gm&zz zN%zz5sbMi)R?QTUgtMmBELWLXl0RXEA*#1VhHxm zc2&_qgd*&W7R;fj$dl00%luObjqK(jE9z+khXiBkzRe893&QUAfn+(X z6AG^JiPsp?jyMue9%_*?pK}xM2!5fAVI292z`Dbxk{T|O@2|(9iLKEPgzrVl$bu=8 z*wQLn@0ANwp!Q;>c|@j4LIBR5`shHp!G>svl33LiUvp-9oC25bBMA&_?c;|FZ zq{RE_uP&+ZTbFb$?&v1T=9H52+yjP&)klv%vB3P9Y2)L^t(iUrdH9p?ypQjrKARCs zg*bD`(!e`}QElJxY1B02@i|pBxK~1g0(fpsbc83GuGI)YBsqd$)ip(NXP>G$=o`Q% z(sPNa2j6F1)6;L9_SC~mXW6p84Xq>u-G_x-Uh`xO{mItpq1lnYrjm-1Fni^bMvo#e zW04h2?I6tN8PN|C89hMO9LvHI8r?s?X}7|W^uRyfv*Pm1sAghvTyo?F2O%4Mf8{ay z{H#hCQZrh7E1pxOLy9D`2Z&9j`M>HnnqOH^#Omm@_ILIVclJ*|crwFi5&H)8${f{D zbpP^g;jrLHTx^)fZ%!xsi%|PuZ!`xNjHx?XMtip+Y2bsXT)o*5e_@QF%%Mwv>XtG* z|7ou-nO)pk+lsTx{24AIWDa=w`n?jX7sA%U%;nD2I^C#ZaeAk`M6otOE(M7kyq43K zt(#+g5n-;PCIb8zKP}#JzTs%nK@&nfmQ!SWNC|^+9+H^NU0^B%2iO@7f1w2sK1Wq# z_pd@abywQ%C|6`P6$b2A5Eu)1a(FGK)b2gzUJ4tA2{F>pcUG$qFfcHC7OX@yD0Mu$ z!vhF&o+sCYfzAm7$!W!d2lvB2>?T*x=7ir$qt_*a@nc8DB|*oU3e!rlkjM?ID=@Bn zUjcnY_~0*+k%mi0Vlb?QvCdjIz59Y)2S6WDduu;f76lqVw_LNClfFj)7`2k%+@O7! z4!;VhQv0BzyHiA@E%d|(${K@Uk-RrX&18o+itCy`-h|UHU zvvSC&Ll?vuFf{~pL{Th-+e3BvTMEG%1v9a%cz$c~F3cTRC3u_b>8Gp4+?;wHX7V}e z%8F@QMyZum-2s4Fd&F^XN5=yJRw5XCgetNpTkk`_w}WS&#^A=&z@6&YU~Bmo<O9EB$0HHffbAxr`Hu;b3Q1`IVPWW>((FrXe*Ur?n5Xay`$yx! zZA&BLF^7-osne^_7sa1;giV){zh6JtDQ{$HqX}l(O?DL^k}AC~ryz5FjxUoF%UojZ zDC;i)drR8dp8AyL3tE7rEsQPeSW4LH>~xpCZROzZF#RrYvuA+QW~J43$4;AEy5u7c zg#}_$${0?bn5dTd;*Q@m4gDANf?`fGHcA|t%z-S%A`dj3*XD^PrBmEZ5t}n}UwKT0 zur!EMZl#w+Lm!T|qY_&^0|Hknq<8O-U8!K80(@T)-vbvO@7K)P09ORN4!;=`-gqMy zEdWcyj9*fj2BF<_*uQfuAp@{9+D~3mE%gpWdid7Ta+dX{gI<;Y!UAli7hZv5FigK6 zqT5e&1SHw{<5J3|X9gB*4ss_}L%RE>)O%LYVwU2_xYOK={7s|VLU_~|yC2i3w*gI4?jaeoz@S=(!|6j7) zEecc=0Ja7a0ve%>I_(CzK}`|f`oCQlHdTjQ_*afGYJ9eeq#Nd&6v&-?nw%yiZw}1* zK3zb)FZ>FBCpr(`T3O7gK!D^5G(z>(aP_c7gdDGLYk?Ap;kZosdQ(T6EH@ovu z<}LTGA_Jx<6jF~Z@TV0Y;?7x2O{o9CMYA>@nq)2g8wX`8Re+*#2FKg}8~0W0(g%Gw zXnjn-dm{YZccxu#R1q-mV2MHJnwL|wLMG|NuPefkKS%e871ES?deMUAfB`s5jGEJl z9DfGDj*9+_q9SIdiQl%dp)$Fe;2WK;vJ5fe@q=K0n64+O($OLM_FNyiWCg{P6yl zA=Zht1<{g@mxs3}@h=?gOrxZRhm04v5RnnXD_P^33O~Ldmw^b+id2!ef9{3H*^)|$ z9UuP-d2ay}*VkbCHWnm!aEBzg6GCwJ;O-V6c!ImTy95jF?(XjH?(S~ykpK71H+t{X zt(o_x-aSQiRaZ4#&}a8Kd#}CL`eEuqSmMFmN;Inm*Ree7;IxLVSj6cC`aakPwkSQI!d*p(^GhW8w zY=uBE>Y8B}_H3f$h?X7Vw75r7vdtTp&JYcCJv(Ah$VO?EMXmiwFf-iz?MZ9*cjnt5*`8E8MIX*ps8}$w^XuXxc?y3*IWTLzQ&1 z1-I;$O8P0J{OOj=t(<4hX;3OD`_jZ0r$cmIzr+pz6Tn{8d&iC{KdFSe(KbuZ$;1t- z;cw?XAS?rbN>b{F`W+Qnj!r9hsy!{8=v<9Cbmceg{k988M7d%tOU_`N7`U>Z6 z1~ilK!RcrLM8Z04w9OSCJ2~c`+nKt4%SkcjqjZf4ahIPY!S@@)aKO~=BHup5@Jw;P zPu>0mZsX6ze6e07&+u80J_z-#^uWjF118T%wXIK6iK#2Ds(pKYd>%i<2~wI4oekV> zWddJTEDCr|pzq9;e(YCpeMT)xVkzE!5?7KjbA7h6Mh8NjeKRJiHtOwukp{(u!-YVo zQ*&Y#+r%@(F!sY%`?kbztOJWIWjrci%LJPY_*BMxw%B|-NA^f3h~ur{q9i}^$DS5a zhbuR96vpDH*00P!Cr^yYw!|PP_B&HcK zsa4|hnIEsVa0=uS@(aF}nP6bFqCyi1p&`Ql9B z)xra$IGL+$ZKh>DfR|)lnoYt^WGLO5*tPbv>zoKJp8)(+SHN>AH9~#fJXeO#Qw#H+ z2H=KF5-?#=rlPs-c~?g>1=XNDYAl|p$%1AT_C{O|k(P4#0Nl%E(=(g~l~QW*qs8vE zLe5Fnlv|2lTPZRK6yIf`Yy5QxN3&<@$9-b#j~m^kkLup~LWF>6OD2%-cSh-IRX4uI zg-PDRvdw{KoD3*_i|~c@N(2zuDk+vH7SptIqP%+A5XM1+^*QsP_bYP^_wud{gyS;ylQ z%}I371OQZ3I`_H2A0N=}X!~8gpbxt`k1?j60CWiR`?AN@0Q{HC%j4w}R;@29#80rF zf${h{Bwyg#zW{}8^Kbro{`%Mkvnb+D7rPFu*8d!jVIFomKY#oX@FM?O`m9$I;&EB? z84{Rk0|y8MMij>WKo^qI@#0i#5xrScoyR^o*Ooe%F=j!BOLATa$+hCr{G*xw9?SHF z!awO)D##%8_j3+FRz1%|Fa9hy$=%|MB%^MBC~CD{C&5M%+WZu0q00eWRuP8*v?}w5 zgy-t_Av^Fanl@jAgI9pswo_N31JgaL??Y)5c>wPhxd6sd@{oBV)C;I>yU=4yO=Ttl z#5Ze>ROg?VoI7PJVUMqg&6?BOENEudPmTs(7xSu^qS+r1X-cXQnNpY*?awTv_L^KI z8b+Ooqkoz_7xp%9AKWo%l7Z80c`=lLMh()4fBt!b3uxV|DMl-D%GP{;5_>2-}Z1w#zX*SHwfqLS8 zky$v`ce<@6m3e1$*GPr|I_`=5eYKA#N^y9ucH{ib-o@-R9u6n-{?;1$#ui({2R@fs z!Lv#lr9`XmV;5TugvgU}A2^Dd+2H)eqHH0T@_N(8CNfe9l^FvUjRf61CFmiIIGN%O zZc>@IM|UY+K0wydP8{xh7jyJXe5p#Fm})k=!HK}m&k@Sp-ygWiXSsL5;zowalkKc6 za~iy1C}l_$`!hD|tmUgY6sB_cA88rtPKaBK(TEpO* ze@ZAYgNWn?c8_3pz%M?gvAI5DAYtz0iGiS&%z1j{u{EcU6}ZMEI6$jqxa^2MYd=KC znQx?yPAN8WgVpMLrr0A>ScgkCKE0N=?J&9B?;7}O!CJAZDa*#*+@!np$MtESfPbi;(HD|B1xPstfz`4uQfT1=*dpqCZC0HxOQH$ z&O(ypwcL-?H1uFBB3W`IEQ?J4GEFBFzoq=u!kjeDvyfG0T(rkJXkpgR0$m^m7~0}b z)U@@uW4-{#%gOG-o;ru3gpN5vfW{bNQug>{VG`|=(&{)9s;GEaNxd)Wui2q((r8WbLr$_pM4ZJk30A`>_-Hos`F^09eA^MpS+jsT=3tGc}eDZ@1un+9ZOmXQ@&Ht z7rjBcO{$Ha>V_c7f401=z0mDQ+ed>O&92;~mpUn(eS-!fk9xACOOycvsdHsE0Mn*1 zSGfUx2UB<-U{n0eIJK(6Fcd#K>(${#nL1BBf0m2F{?>mH38UxQq8vLz;G2Br6eR@O zMazsTc0`>W8X$gH%nxh4Te0EshQ~3qYBwB`<=3YG*@_FQmnJ%BOE$o4h_VfYaV&E3 z$9aNAFV@W;j@hhof}!G=BjiaQj@LMNV(%c4)F=uY>gUS`5y{V~Uvl^LSH)^dGfOIAJb>E@lQw)S-@6i; zt69P_Roo@a0{ zM~q5EBVaU!m?NsMQ;g#C2$Z#bu8Gbu|Ewehl(k9sJQs?SJH{>dL+}7)ZSK{IRp&1L z)7c-Dh~}d{eGp6_hNt!ceHRvo1qncDpnGd7OZT8B)4>j95xZ`rb2JU_FgmOU(vRl8Qa?uIo~O*t1{(-Mq{^6Yzxfi zt=7-eN!6S0NV5w*w;1rvO>G5H2M?gorNN_j&92!-a0SQT?{T%o#l0Ne%>l04#j-XGegyah>X_e~8Q9rjQL&!R`lBr-;?*$I`q zVG<78x?kr;#3^#NBRVgWeq3=A*@D8%!R1(q`)3P2@}!_2l*>&8Jk*?KWSyxQQ$&+# z9nqQY0;DLVG-!yi?UFEP84}R8CS(t6O=hbB=ft8`Lnuf~PUciv%$8gAteUkjR7G50 z0yA?dkR&LWa~q3&D^ZO~<>f^2r9VZ#wzma_rdT^3Mf{=|8rym6L`#1upxe9KHi{)x za5NXj^9i%INXfpee|@&e5sio ztwvJ_f{f2BB@!745QFoJjgNTMw{T!M6XpU!AL%>k@j&jG6|JrwU&{-;v_x3pkW-5} zR{FE}yNzf^%-@JsHt!^H@$&I{!P#J+=simm?|_e@atC?iB7ry@mj`+|02`bnonkV( zTTUN&f{71}`x=5u#*iyhz?j-m;jyCIo-RWpagt^%BS>#_;6Z*yb{s~@zM~>JF8DEAi~6pKoh_qlv>fP<>H?A) zG4N0TrgO(PDN%DW<)Tw_$8U9GfX?rotf+-I1@_dmad_8!m@n2(0#9b` zr*ZdT_9dWJ=|Y+oj)-3TzecAEc106i`ZlCvccGFonfo0mGv^3b&4Maix4!cA-WK48 z`owxEXcI=v_cx_Zx6^qA9QQ!9&E4Wbfb zT%Jqvzxb#m(wf4G#s*o-Z0n}qz3|ccb%BK|M1ACY50G4$yQ)qLVmSbkt9mC|0!A;+ z?1&tBgH7TztC>*vi-XfHW${W9KA0dL%vzi7P2Kc&@yfdi3Z< zdhj+a*R#}HHWY8&0nvyPB_CK(hVwEtd7cytjTEXKyqh7{t}9n-4%~DrV~SAnZCRl^ zY}}p&l}u1Ai@YBPb|KhvyNK6NlYBIRJ{>t}rBRT=C(@ zUwBa*)#)+AUqFpW^$^wg>4^`x6tPe(P_sWIHg9gGw=-^_47s za}b>JNWW=mW@%>h_w56qI)2`y^%roG>qGQ4q9uIYi#Fq9deib7Y0w*Ip!-98GECmJ|NwCDVE zh&hwzA!Iq8M&Gb`wA(KwHVRYK=20c}78GvT>3V%;{l-@$xYBWt++1H)7iv#9h(R9M zcoZG@b}wx{J;6~ZfxiAl4Eei_vpi$4Z4Gny5rM$b-I))NVQ`Pt-`;k+r=m8-$eC%= z`)}9s1O_24v)&-z>%a4v}MAHTR74(Ptlqp>c{fQ5EmdPWgxK^iT>2L}nS2uEOX zqoTj0xI4PPvjZ?}SPGZ}WqXE0;2lfXqm~RTn zI&i4v^YXCaiiFvQL}RKl(y~2oJPXqfvI7t(RJw{F^`EdM38Frh4|7rLL4ZWfeEqT< zWgKM`*wZ<5=M6?gQ4P%n!mfO%tL4ekA8Avn0VlpDGWZ z$-ezZ1Jy~)lZ^Ffvd%d38rEi$yI2_2n9b3T<_7>U9dAG%P}aZExHPTJcjOGJ?`pI1 z?hl=@8ZzGLf#8{LrGppwng(;}z0QXBMV`rUy{RDkZ&c-yL|sJ-1pm5vCqpr2+^ZO3s(M#>D);2 zy|mx1921?UIC^v8BesEzE|_s$r=5$Cv}Hk3w&TUcf)o|&lQcQ9d0$6GT=K{v61Ujd z%YzyE?i10<5uBvUbdOMa%tiN9quU;3{?N!vXz@C7F87_IL_w(dt@QX{%v8da7ssdx z4!fR2>DgdpruuAS-yGwKkQkI4AJA^-&K5yhO`5WR$^GE{k|p9*T5uA$&l(xHA6Ug; zrdQyK0zz+lbE#dY^1Loj{8$=D$od zne7^aBYuAVqIY3#6LDWVB{icW{!-RMOf)F@YbF}Q#r7;E=+jR(yK%M5?pp6oWvcU+ zpYZkTFi^`@MUrSgkjvLs8G<;DG=Orp-7VO$91OhX=r#cPO0|ol*1&c^j_NTZd;fXg zdvA>Dv5H-LE4kF}{mIQG93nTcy_sW(;jnTDAYawJBQSuQym1&de2f%ai#4BGe?r#+ z%rour4GmDvmVdd!b?s*^p9a|J?ls+fiem~!B%fKVAMz(|#`n2LI<%F6kv+K1!oZwu zfKakwT<=V!o|bukoBGCMyxohAO^Fw`qi~0vlu=--U`9K0N?7=3px0;iKK#YKV>i`U zwVUJVlso8k!A6b!cb@n@U?t4QyT7!=m#&M|FdKuxTd7}eNAiRLSVNk`S;{sd6nior z2cmiS8|`Tq=O3HhA@U5QaAW6w56NWsi#zLfi7;kaKV3!LxQo19$kcHC*tOb z@RwS*)8a`lY0z0y4ffY_;8B13|2batRyCA?`_dQ@+`Gb;Su;JNry_*E zR7t>r2I}1yeiqNzIej5G#{GC#WVVlJV|z+=@%?gPz}KIH%45VX_4VK5db8jLN0Rd} zk)8lVQul77ayg8A3Wm_GMoQNB(J%>|#*^&LqeA^NELt`bvBF-(%ZryVDFo5%mLri3 z){YP*{9%+07OBYhjj3a7YWH}mR=d`e0Pe4o(lh0q(@^EcZyL|>$N0e=!;oHJHv@l! zOlwha#NqJfeaoxWj)uc^k5>XQBnA7Oo$(R;)^IcbKtWMQ@T-paxFF|fp*0Tlv%%;u z{^F)8w{X~ZJu_B6$0}JY#^^pt`3h{U8JP_nk!`FrX8;miU)T%lcXN@u^H#uWH|QyW zNxMWTB1(-APeSD@qO2O-=Zem{geMqOrTE_Vi*bZoXU04r-;rH!Xb}ula@h@`7r-!VieGDhQ}zuD1& z*E?QbK!^)Puv?%~wo~^%Lndm&j5`|8&YWnE=M=as z95a(J$xDTZOijg|C|F!R(7O_~BAOQBHbC2InSf*rF6a3EOgkb%^MiYgiwg?#&~Kjd z4%dmC2H4ASYz-yN$uF3eZqo9q8mr{Ks%$p(eYp;sRRnVZ87zV^wQNfDV3nJ|&4GC2 z6I|BrpXcV*j!iVt212baZC%i4%}h~lBidMs^YY(-z8PaTasFkt>ls;DUt8x;fc^b@ z0RaXu+YQV&^^?^HK!Z4J^?KI6yqfK{pY!m!^zmYTir>^a3Xe1O+}R|(5e>)Qa^99A zTpB#3(xEkcE8c(3MHmu9j2esa{^-yXoh6g4UICEgZXgp`xNm1WU&#zf!Lv2=7msfa zFh7>-;osP6G>=|Sq+9J#6Xg#-P_>)P`(2or>YDgHuDi67iDkPU#>Uy?!Z3Mz6iLUQ z#oOsPq*!eIUB-Jz;6V{xAl@y!8HH@2dCr@}UT(PIAXNxi!CvVF?t&Ql+@3&f+kL@{ zbAyv<+Y?bw)LzK9qCQf`a_^G#JGBl9gh~yZg6Ur=9gox5&Q=0YpWk?bH&`%(vaz2^ zk%4dE4tthG#!rHRZ2B7C&f@RTl5$4Iijr~9R6q8x12VIElr)%ODR&(j5gYP891R?R zeek7QX;h}vNgl{MU?vCAl&O2zF4)GMp&uAR{OB&MOnD$S+}QkqTLRnWSJeO;zz8=U zJRW8=m$!uYb|+e6$*y$6N>cCWNyjAFbgW_Z}R+A>C4fF~wWhV#J*bHL2r0s9wbI3yH)f#%9Sr$1%K`kl{W!GR$wY)o;P7>?kve--!m z3cf1ORi#q75#i6@hg?TU9eT9#jY%k=H&>)U;SKq=TS*loiPZ^^P5r%6ncP6yeBcg) z{b_jHd*oM^Z@(<)FgCDOo8_W4$rhzM$~ue144P7eNPZ(@>xzu-CWz#I>fkAr+D3{gIg0F)IqCtuogftM`tW3__y?1#f5mnh2 z>{;uE`hhG_3Qzuu@kf@L^0<;}YAbNn-Xnx4eIGIt>v$NZToiH~q|iALDjj05&$qpy zWP?8>t7d)~rFuT8QomVZfzRV~f0At_QSH+sf4#`)Aq|a0QpNO5A?BM8jdf)1dpC_b z&D6VXS4)T%Aeee_v*qQGKaKQmd4fsP1^%jX^jLYm134fDBfavw-$Z6P{fs}K>qwMB zqFTQkOJV_;IEW`#&u#i6T9dfN78nsw-NvIg< zu+w(N1PA6DH*M~dLW}$HOk^zT7gZB(X!9DRCbq?tIU7vxyG8Bf)Zfau=8}w7P^xj2 zl$7I?oAAnr%b@aXI@%Ggo_RAbe_*A|2>i6uKj8zZ{f+zW!nVs=>aP)TfU{~smve{% z3qlyVezI-yUZIy08vZ3>?C*+5o9S@ao~nHE zJT8Oc%v$v(x3{Z|K3Tb|BqqkCc3@}`^XSco^yWhP+N(fC4ud~HG4>TBx)N`Z^ElU^ zJ5$9WV&~LxG+=)iyHByYhlGVfpq$ii47+2gOL@y9{z#2#4lq`C9q8U)0M|s;CS{xB z$7IrsZ^h`7%BIzwG(u@lN{Q&!2S)1_IU59wO7<>(`49~|Qjvm=&;>gKHYu4;}bg?P93)#i< zdHLtHvzD#GNBxLd5)Z)uqxXciTT$9CWV-6W;)NqR2ppzT&GB|pM<8%*%Dc08Wqhg+ z#@dN=7CnLaPp6yRi!$6p<&C0oZUkVF70o?bT58;`0k)5pE}EqqzuavXEnpUNgcf`Y zs1ok@-^+682dONMO8qYU!L7&o2=v;g(geuJM5oe-a4@`u38t^}FAu|i<(8{O{g-Yz z?tkl+`=8*Dlk%qQw2uB_X9FQ~+chiz5L8`TN-qZF=)_!AxW@~mbH6Y6-H(%oD=Ecp zmf=wKgEBu=MY}&Yhju}P{y>4D>o4J|>dYH1@#4MbCMU7zueV`W3P+k@YQ0^}Ct(mz5i7x8S~$r9KZNhfrE`Q@DVqjRQHlt>h%61YT&+Li`Y`^RoI4 z7QOWU7f!i~uDr}9INK$qKe!$UDW*5rEv zND4HwM&P6N{LFP(nbbI%zcF&(3GE*J{<6sq^rW%`&__9}0D$;3f3ZWLvFVYHTZ^@VR!q224R5FgCUJir%(TO{Vva6 zh!#Cr=0Rk#TW_SxFQ)jDidV(WH>&4bKw$;az$}PIHgQcSPcvFmekznaEWUcqDpFuO z;UUWur2S1OWu*Fg?qH)I#$o7r%N-nSCMTF=N}>)L@V-tD6pZ?3t|D2p0-d_#D?49SmcZE4{t}%yd*jM za)p4px2N7_D@O7}g>$0SbpF*7C2)n8VCP>GFq6dhlY>Ds0MMGs%~vH_*xT--pa`)Obc*><-l|_8tYW&H3qE#Pg zd~wl|QSb$FU#eMiB7XywEBcd_zKy{X5z^(a?qTJ3rW_R?C@?=;SXK`HK_b|t8Cza@e!`Rd%Ad-El^;!D!Ms@O~>(4tY;pd>cqPV*P$gx z>BlYaZ$nPbirxo<9$V1bU$U&M)1Y>)v+QlwyLs7R>Sdu*yPqubV{VD9Khmh7wa12X zS9v~5l?(d-)5@2)&N+k+XUoQFkGDvK&|3I#yV@Iqo2UB~Eqx2=hFyxScBJd%Gs?W! z#$)8Ot12v@vVKVDW+@)v9B4}Ze0O)k1DZcz+~88Q9kN^SYiiM&S!rRU-(@ineB_;P z+NI=qB_NQphb~Z{fVs=upWR79ztkk_P|w;Mn9sr?Ik?S8ponh)1cYE;&rT)JSgK}k z4NKPyn<0Z8nr(BpIdQPxAwFl%gan=PRu3B?nsMd1t;bD#f6jjQjO*neD>J9}Pe$L3 z;pWCK&zIm)11onYK*Jl?^=2Qvo67+E)_NrnU5#;GbN0JroPGTT;CKVabkN1wav1+t zcD3L&yP9Y5+s)AIpJi7qZn9lw?%MAV_k>H=UNt;mL)*}K9w>R+kc|b3iwLzU2Mvkb z7U!Wivk3=~l4j4O#7>T%QZ8QodZ~Z+>)n+Q1xI0@6`8%Rx&As(f?Go%Z*?jDQu$uZ zY*_Y~7=YmR$-f=)fZKKfOT^8D|F6Fk1VRR#*H*lY@3KC&_&o@Tx|$@`^C#m!_Hp1m zU6&J+jEJpXEd8_`m{y-_Ex@OEI_;g`%i`?bYlk$lyWg&B- z;AY?L-Nx$|=Ldj2$RqB%tidCW}YuJ01qHI!9tvZZ(V)Tm@~x4id!8Au8ORT$Yvq=!>5_7>Rew`^Z?QDT#7IJ zfN{t*G&_^5_D*YoRpV&Ewge?1&CysOzqr}C#4%&V?+n5toKi3tw}BfGiy36FHJalG z^D5`K#f0|9{vQczhUovZgf&${(WNaX&!I#@XVZ0X$W)7hViF=ne02OP;jqPA^q@MtPu{cOCwmr+r*ecnff6qIoWWX-pM?MiVSyp|U-{##RdY|NFG|NzRW+530<7Ug zU0lC!x>or5cYS`gP!;GQ{l74S>Wo)v3|dR);u2^#i^AEkzQ4~Fo&P4pyT}b288t+P znD2;PJ5EErM^z;CdUv=C1DlQLHWBB%7A~9?y6K`^HxkYjVzME=I4h_RHOQl3xfi8z z*r(PwpQ%Co&G}?EQAfJau1D!4$xAfZ<|T3j|EKEhZSrf?n^N(NVRK#TV(STh?%<=# zopwt8RfqS@Wv~(xxv2Y^qHLt|O+`SJumA0WJ<9*B(bMi?*;3^5FV< zlQp&Z53;7I{+~>bwxTuOgZ*BcYhEdiJH-V6r7G`45yp@_A@ts=Zo$u-Ea4M$Q_){Y z8TX(Dh`jRp#f8YIm~}nPX~b-+ zK&Ut=9vCOsOf+d*A5+fwev>6@I%OJ&SzX?>r@V#djKE@ar2o`CVeFLh*6%y*54Dn0 z-I%U2rz>(ES-!Nx;9ZFWgs`UIjgda4w;P%q0a^Tq59w(WT59n)A}#iFZ#aa^%rz5* zn4sgU>KyJ^P0!H5KV>iZ2a9R@N6CPQ_NYs>h@uYnS21Nn!8>!PMrthg!hil6s7T~R zEjnS%kqVa{{mrM*{SfaKbx;Qs1&olabwhx{Qf?R-k$^gxi6DiY;T0oBv29hIx7zmn z)88vrzUp2ovKKT=Y1J#kTfpSRWx=~EWWfmUZj6eK;PBMut{_Da{ZEz9{ttX^1t{-| zk;O0jB=gIxS~-RLwGt0Uwl8wB|GA!)QP(3&&N0wF(N0ds5ZvSbm$^+j4jhEEl@0=D zXZbI(x4jm={qJ?O_P^<95C=bRy??)+5-lVY4321MNJtotXfJR+WRp_ASBvr~{Nyj> z5@OmfrEI!A<%j0tCg9iYmWhEl?&)00h#sMW^rBEM`nghhn0APp1s!I60SI=BOg5UW z?LNPB5}@#-5D&A*(NvA#j$BMb42A=$2C7nSF)dlC5#0-aQKR70fm-t^ihZ=IHbp_y zYb4pdl|0j}t|@$TMGKX~MogZMBMbaWKcBV_VaV5clyCF&$=-$C)-SQ#41EKef4nZ- zIDLDL* z{?gVg)krjI&y-a#VyDREG%ZLr zm6L;y)P+f(=}WVSsY7?$U%brYz_IG_8{XB$!dbtR5c;_V9Eb+Ppk3V&qeAs>rRT1u zVZHhpYV=l@hkGeuSf3;ZrpI|U7pz9NJ28Fe`wu7Hu!LhX7^YY{@qKOMIRuEKnH_jw zW?zuD&OpS(kRVNQSI3XLgG`$(YW_T9*qo60a{06IBx6Q0LcfO6r#T(vNA+PNa?`mz z`^hB=HteieV=8Yx{?5#qWaaJAV~)XyV>VX7uafO=u-(&Q^VbK6qsxwVE9h^$96P;; zd}c`^L$}rvO+-Adahn>hDaQU?H(M;yWkIL5ourVU)Gr_21#PKbc%K+i}vfQ*2k!6IQQ(no3jk^Erf$9X(;gw3@MHZI^OV&b5l3K|c}pGN`6 z2%nuKBYQclTA~p^!GpaQbJJW-F6!9CC3D>MN6C_69B2_E?HD?lK(iOBs$35h!$kUd z!)Mu~bMM>nqt88dG%KjQ1(A65on}kq+kSd=@F0+PVHQvW?sOZS@D`t%Or(jGYv(Je z8@#*D8^XW{wcI#tbOZWj75u)JZ(cuqlu7=Tc@4lS7r(mKek6)nCUTL9{ymGzXs-;% zP(l5PhCs+c2b&J=|Gx^FGakr$5)_}_%qj3kZY{VhdP|jdgluUA{c^;B(~!amI>u!g zVlMgBpwZp?1vjb8p{8EMWpO{}pfKxYb^{sNfNaP_EQqVYenb##z)%Z1kAaq$VLI^9 z4bQ9i3!lf0dciv=JnzCU_Jbr+PD%hE!O?;5G7rj+PXBbKpzq()&nWT!bNX4mc0AkP zy#W6eS{l4hyI|!0h8qr~*juFLU3DU}KN(Gbm85ob-EY|MX$sHVd*l9-LfVs-(+>8G z{5bPzRH8H=k%$7Myu7rMG}?@3P`wERI&S*vybLefF6};?vI;vT?Qef7^6PTj2=oCG zPdHvSZ_=h4WKkDxWGLb~SfaoY_7_4z_b67Y?L~^6;jadVi`Qo1P~VFk?M_yw3i?pL z0tIs?CqMC8ENY@gBwh>V9y(txYSHS`qy;`#(Iv;#Vmh(S-rt&cfw<(egj=Z0)Q+>g zHQdz47AiQ1PG5NpE|u&k`tE(b$Pd3vIm=ajU_gWIc2YHScg@Bwx9uSo!*D9w*}Dg( zxYg1!aPA$2eIZW7rgiI9vrsuKstTr-i;c5e7P#0TO*744i}t2oOLM!%vArDXdhxw{ zKIAEg)qwg*|JMSq1|My5L+#y{$HVw{RuZ(A=Rm*QllARbMq9IEY)#-t?3lh4@jB$D zaLK>-%W?W7Og)CapbfU8X68{oP5uqT;5ZjA5w0k&6iotBiCLTjYD?rmCYR>SptC6YpdKyP?HU%E-Ww#yx# z5YRpqnHeM52#pF~d=E|xx({jskffSgv;uUQK`}=Ko)o)}-?_}luL_#oP!)RUtg2IT z&-SpmzB(+g319upF@+Yh=W8aKtDz@&t%`nea>f%GcToazsH~m#U10T)D-Mwa`*+^c zY~vF~S3B9#V4%`x@eZuZ+<|P*plTROE0T%Sd)x>h>;kbw=n@;q>$b~O{;~XnwDk@? zt6Rxyy_~QRp%%MB6|?Pk`!apN>q^{x;pQ^9d&qD^GTCmCEQ<3qrFN33e zUKOiC4;%=%euGwicBS5)!hPj1INzQ$cfE-op#wM!!b4S@R?kA_vg&Co0uHbO>F4QR zPbt!BfPia%KAp@exz$Q3bc{8Q7s1uBMUCKmDxX!bu{OH(g(xTRPOxE%HQzInTKUv{ z?2#3^Ef5+N_;MIz-=`dF&?h~X^$L94P*@I26=EI-_@$>i(6J#hyU3B+lYNPFQxirg zR%qM~Vwp}2l&Hy=p&6%WwmIdnenbT(+typhQK|re_0q!h_XSCjd9y@csLfeZqgmkX z&P;~3rI+;sY95$`UdeRwPDk zd_Z?!w1uT-R0vHi)ALahz$XOV9;&t>yn5iO*N@MNGzIaPJABxaIZK$v5nLc^cu_Zf z*;5_|#K|}>b^W8)vtDkMhfih;m(K< zO5a}I;GrE<%&{b}O6hEa)2F5fxSJ{_YTQ+$BEPRPFDDa$2fh{-(e0G_G3m z`$KO?6}y8~jAH|}Kz&UCiHyVA7dR~)7Rp5F%qzvGE90Ks#RiY-9$AyV`FCHfw_so1 z3HMvUK`7D&?=QrQSv3jo+BO|hBf?z_Uk#zHvMhE0ec z`*2ZAyJqW3tBm98B5%VAYrmn!FPu5z+iLLk@1#P9;nUw>@(NfN&58VlE2n}?lPMp86Z<(Bp%Q{7U?YErs*!wsx!*l>6v z!%=)%C^&IUA2d<#OXbjv7qYggW7E_3(D%R?EGeVsYA)Tf%i|qz!N_mo{C<*n4F>A< za!W{)M{VT3Riu1NWH#Wj7wg*n1};ag0A`<5F?;h`i*&@_uXaEWQY$!0UKn?FKQh=unxM1X6TN3L(6LK)+3J(_olTsw0W=TX|o7` zIJ}n2m8)8P{_@=Xt-tp955!^7tmx*7k+ztnb962zcqMCmFHf8m%-(FvR0TiAwfze(<|h6#@tI4bi$2Ox!xX8bNaC`yV+=#0|< z$m#XK`IX}k-3jS*r2w??#Iy2vSc$m}_chJ?qpk+4V+;sLai=dN0q5=VgEefybZ|cr z2TWkyRbo_poDnKi>dzrT!EE+ao=0NhEd>9~kMzLQyl22@}A$C6s!;`6YZ+jN05nl1nvZPzZD-iJv}G2>z{Y zy(-pf@$0PN(A2=<%a6EEbgPRNa%eCho@m1JfzGz6xJK$}w&K}$ZHa5nE+^5kMXVA5 z!V+JVOz%su18Hd(YUmj&=oxJ|l1JKozY6cm6u=QwJh&d4@qU;+XA)}6* zD+NUfgOB7URN@eys+3NlRxbn*mOnsIRs?^#Sl@7f)HdLPy&Jk1Y(Y3Ln$h=S)5w z-IE>fft8aS!*Ae>I(E_!Nx(zVWLng!Jg2QPAIYd?iL3L$DT z#LJS*PCKAAX^H;9&LU1A{Q|hy1aQ#72|Wf>K~s@V3nvX9)V7YIbD$lU| zYEnGlm}N*sjkuBrU`>0r`=mljH7tJII#>_jDOqV=RtU?$`#V0kjz+&wf4$OA<+K3j zs$isQ5Uogo7>ZGuW3{f{gab2{E7n8`(-)JK1`#17nJ_8Qj?E2|)y6|3N9D5_=0)*z z=g|!pLK|t?^k5QuMn{sO=Z`N7HA@z5gO9Fr1qc9HS7)K?i-S2JOc?*Ggv(_3bJUt; z+yxG(2lrek(K#FCeRZLxW5c5rruZtt7%(s(R&6NK+e|3H*(M7jklhs`&bG}g zQ%#o-11ooPZ{}4(Q{LDAegjP696eL!rbi67-rxsXa~K;s-mKWBS3BvjA_z8_iU!8m z_6yyhfn<2?#@CztG%QlLuxJn^G2y=@c_ylnl3vc>>($RK9o)fQ3-~!fsek3=Plm6X zq4jCWg>wIjWRc-RY%p;3xbbc-U2y32yw?#bsUa3MTHG||+njtL&B@B3kh|U7Y_iVk zs|PCb3ox)3zno|Pf|d{kqjG`vt%KUB1-;hJ!Cf3IgdVn|1^S##yLRJQ*s4%;H8#Oy z;IQ8>mE}B|nQWv^FgAD@#XmQT@67E>z+UkQeFd%)yxxg%--Sh29mYz<38C(|A}8&f z3F4rMK3Rw3GaAuH=>DMiTzuq)jq?qDz6#b>)Dfz;fHLrInLDMO_NXZa`&%ZIAf_G_ zd)zOr7vsc{Aodi)^BpqHhMyOMU4CO()UfGfk-mMuAc})>kWR$6nB|?NA!RcP!xfUM zm&3<#41afubKDd*c2M!%G>+BfEHa;}iM>re0E1iwF6{09V53HTC&2|yMl(3))sVca zgtat}!|b$R!VyNX_n{A9nJ57Z6yk=0ha6ZP7jw*)PL`+H!|TQLTi^+Ut6E_-s$OYy zP$k~0^W;nc;HV!|bx@DY}?HG+_YQmFmh}<9WbjRj}fO=kTC%Ik3-3Yk)Hp97gZ}KmUZOB@W(dVyLU^sFZt|Tpzc(4RNeL}ki37GrCUWyi ze>HkXo|mwRFuE*G@Ccj?9PB;M9m2sCCX<>8YnY1W1Viik8L&(FGtrVQO`7l4nF~b9 z_08x8jEjkN(x&tM(_PSZiE{bT8EM=pC$3V`Nc)NpWzoe!NCo14nAGe^Sf74Bd`b=b zpwKPZf}>Z@4g{e$`sskv#@qLz;(O{yM8$2k5Py)VZs@NVPYdCZv~z z*(2Y^`&vT>`o+TyKpMnlv#Q?ro9$gpnH3~rjc>&x*87qQyr)n*4Cv7}X;K#J%fjz1 zQ(|!aRsUz{6#4FM^nj5d#z9lIs{J;v#m^?s0?bWm@&-C$3gV?*6j@C)AasqGX;?O{ zf@1oXTt%ln0QWu@H_~FxltK1&O<2Umu*B|4GkYbcitC5?#)g>4dm14bSRhSg7DeGz ziyc;>CL8rem7uoT7frij>_QH>r#8+%9LK)fra^yH#+LwzuzhFR5Hap4#qMcB4LChV zJs}r8NA*M&UTdWagO&0|DWel_ZyJ}Z=)n2{VTF?5u@5Ai&&4fi*Y5nYvE24@fF7oin z6_IOIa6zBM+y6e-?LxI4a7A?cmkzxJ_i{TN-R*N&g#J3rRxGBdh}I#@RFr7cgM8?v5;U9a5w}B`GwXL^03bI~6 z?2|gvLJmJ?EDhsf=J@ZTh$w5lDy}c8?|999`Znnso9a=j)zU&ofpHxXZhtS-3j~W`TRi zZq#OfsUfE4(hzTwcj^LRaD zL>OzyTQ}bK05xo%ud`^#RZUuZr@;aHkxlqx>%%rbx(VU4b8)+!q54eecWHz?Nv=qBkPY(Sr{VPGW*ynXH!dhI zeQw7@tp>wyK9d;bUnAt%%x00QlGNWFbJNc7yUbn(mL@=_@0i z@>eu>h1*%-exeqt7YYQpC&VsM-$uY4y{?{P^QS5L3Ys-9C>epto|vhaB#y7|b{_Gg zB<1F#*wH7)Rx2Qlmzc+QUNz%g`vn2?CTH{bvauFvA~_T?eBZYEGd*r+I6p0b);f#p z(Zo2gNMq1@6x#-8oa@>*l@RN~#_61wbhymj$!IgJmEKIouckYR&CTJyG zx-s3e!po|C`B^joHZrFvA8lBH6Yxr)mR;wKm`pW&5)7vTyb^~Gybl6lf4ma6hRyRf zD4%U_*?XV8S8Hu{Iog>pMtq0l)^&Nw8M#zH_iOVVdJ0kwc=gdu8)-qFiY#?DaY%YT zoR`QN>{)LJA}JorS&FZtcTxIY&R@Q@uR)Ar4q}A7rfltN{BXe8g+;LxKO0c=`f7shi!Qq< zW-j&wcHRpCRSK8ScA5|d+-%&jh`yjdC~mdn*nzy$zW(&JElA$;r{`BS_f3?o0}HHt z!XZRF$}93BCkqd!C%|~{cddjTvR~Hxh@A~AuzY`_dCy1*vj`AJ45|ORUi|)}1RELur<+gukeQ+$BAJ#snt+wa93uTEk6yQw@&M>xp{k(A9I8yj+a)WS)B58o zLqH^vOz`^!c5?|Y2zcsu?Ls3nC;xir7v%IGLqF*M9rUxR{72}ArYiX_g?`V2^TJt( zdtUO8tZq!K_EdhRv@2J%v#PEc%JxSg-_8myjkTgC$KCrh=N=nhbSP=G9Ck#vr)q*3 zRN4;Uv?|d7HAX5fY*twn$ZlEGkY4*XyP@PTZJ1IC+9~`w( zk>*Cn=3~(kN?!Y(($ex>FY&dX@>Wrmf(Y<6m>AGFm4dIMJ)!|dy7;E0%^zenfvW1q4-;FMqMKVPfvsXLq-3DTRLSAj}buS0Cbl` zcw`YSdh6o34F zZ`y1zZj*^m@wBk(3~tKn=~b>fTUCqVZba&d%2BF=iZC=pk6kX^iFh+de)+Rg>(z0jEgN$5}xD{G1Kgp3n%m5ZOP*Wc-RxT)WiuK?$<4Rwx_ zDM|TtMK^ewBYl_J2L;IktCUC1t|!~C8YAT#3-0KL zBhh$$b<4gmS7phJ_d3CM&@$Mo=$qhey4WQla_JAU+WNn}z!D@$Cp$DJ**M&izYW^y z^dM7rC$@$krJcXA??+MGU+t(~8ZEJm>9%~>v}G2ks0k*Ip<SP_KUwbk0*x{@(xBV@D&6W%=i2cdu-a-DoSDdZawl#*W32ne z%2tc#Wf|5*0p%cVW4+s#=LMzWi&b8vp}j7mz3*T`d0Ct zG_DJa+iez2T{KDs?W{o%9&f|rH)P8|SG#+)8=bZto~9Gu%!t+>ey`^0GQFirR>Dq$ z@VKwzj+?P~MAY`8oU;)+e1E%~nU@jrJMF?ckPqOVFfizlByn_ZPy2c4q;@_HkVV0$ zGlTh)-q;>??F-$q%Vlkke6#Cj^(YnNg6PEZ~Mni{Y@7Vv@d$H!_kPrD59n)=9(iR3m$ZBr2>psTk0d ziH+i{|fyFiTUm=(!K=`jgj%>6W7L@t*{?45p*wE*1lnkd-4;nYj zLtEfGj)Pi8-(_0-452ScTx58h@4|2uexL5y2XfU3Gk;q+oxTn86M#Ifr|gY#>~^0; zHJyKZ?9+)4qg#&oFf54ydml#LQ~aTSM*LQLVj)Ph`*9Hm)Szs?gWN6;)aFILer8R= zGzPq0PB@Nw8JR7}hi>QU=BZQ6y-<`(q=qEFAnwA@Ib=ubq{5g zXn0B&6b|IbUtUM3>9%y>rm~B~@t;F}+8E-YtipxBvg`YM8SkaMQ|t5m0Cxq!XJTxh z&zgf={9piMt=~#yM?C{&_CR4?)M|b1&FvHk>&%;OsCzUqk7hQX zdN)n6jr|5vOtsX5EFQtkQfj7?0YNN3$SA{Xp@Tdr?B6RBE_29<5cQ(C%Py06rXPyK7Cwl)er{t*i@newX_d}SPW5nh+lZ~5nXGlc==A38 z*;TfY1466L0mFr?84TnhzWqL$H7w=6P#x1LdKVgOD*1?A=g^K8$Z21Uyeps}tdcTZ zOi%qRdUQ+`rhBe<_{Z1C?r>J&BvjGOz<;28Y~yRgNM5@9d-a^~AboJY+w%q8t`Cj2 zWopj*W?5gTzN(9ZnK_|cDkI{D2qt?b3e9N#0v#{py?(ggcMVKx4jCm(IlmNjJum z#9h>Zl$}*HDYvdlo4(&=YwqU-Clnj&@jW&Te#rpVB&6r*t&0;L$zGY0Hy!j5QM9BH zHF%;F03oRPnE!IslxGMhrYYx`)AYq@)>eya?d1YJ<$xB=RV8-{&`5m5wEJs9^&1IT zdQ@#KVWf(gtr-TdE=)*vM=^JMT|>r7~tN}U$CFZ!MY0WszW`QEteP{ z;ZHR_TEDr>@-!88!9s!x%gPX&Cl8EZaozVDv9bA=BIT`lFts=GY|j>fkxhqLURh+c zPVAe}v>m@GVU;AQk|pHvzWu0ac+y-LXNgD$SYZo(W4uyLE&Q}))U+8f#0zDh#!{+; zX_|#yR`fQ5y1r7Ar2PPFbk1y>*pa29RS7u1L0a;I=%TS|&w{rn*>KFTYPGV~;`w=r zR56>1?8-Pl?UnBOUb639o;tnDa7|$3?_RXZ`+V_wH<8z#5C#PDE#5!c6=U^U zzMPy$w50n*UuXy`xY#lCS^J}+m>0RAie0h)-1DNBkGGi?>S>lQpKmv4qLsTXwFg`4%JqgDH2;TFBs*eUw zVYG^plchwaYgaPn$nV01IrjRSOS6P6oZmMFFrgi5QDc3~P;@c!nfgdL(<-Ec>-1XW zt2INP8@(x#aVy_hy{Htg3&*N06R6z#_NacS2E&nVCQj0H;kP`6$Fq$!MOh9kq(CkE zrANQDU%XktRBewfG(f@!YYyzElzv>E(D2(~jpo5BD8>DL+?%WqsJo3?B#!ORF~UUJ zX*_`~c>MO_OW5orHPAnW1NWy{=Q}O&{=E`Oib2I$@*9wHC|f1-!S92l*W%z|y(!ej zvkfqtxTc11Bg@I>zmc6irS5G-5n4bNYwc5h1_DsY@nd*-V1**=o*%@k%ymD0dnC&xL%wz_=`?KRw-3q|<#Yr3^_=-A+6;pOJ1`zW$r%kK~Z!E@SRxn8G|#rbJ2v%>;m15pCTSzsR=HiV2|5y8xV z0Tb_bn^DWqJsG4vSQ%xs8uF7133Vm%yYCVn*nE&NkfC|93|UhI#+jy5h@rTQJmL0|9S3xC(gw&9a-V7zqskhua6>JlHob(6e+PC|md z$Nk`fS$ppN_7j7R-5)TR{&z5FCCC&90-;1-mw#b2Tr=3z0Wjg;P11BdlPzN1V+SMR_%bV zC~q83^06D9n{jMsV=it_9e1gJE0a z7&D~}29g|PB;yN+pCY;<$_&FA3(6dRXDUPp8TxE&wVLvUlGt$?tF2eU_!P3Q4aD=Z zvIy%;@$@Hh)Lc4yq0v}bqaQ`i7;5Wiz=3*ISU!08)sHwz7DXjj&kX)@h(QvtZGH}@ zWqXFFE5Flb|53}9EjtpTB)-*hxV%z@kVU4fd`}7K)aj$WTR=eE&Y-3Y}hX=@r0Y^7C9w=ew zGkd8r={t=^o5G4SNjA*2o-Hl8pKyqr@gz}sjnlQIUpMMQ<|b21Wx#Uyuv5XVMIs-N zdI)s9;())a(AP<=^QjV|9H&G0SrX|o3M)CL(Rj)`IYN

X+(`OvQFaG_BWv9I?BK zKLw%*tXxhuXwK^*&DP zJAY~}YJ-z()a@7_d2J0@%PSGTX5K7ocFzBz&4L8v!*iART8g6c*559#3N%(nm}I+c zX8p~cyEg2bt)YpOtkc}*9aD7FHzw)xS7$m_0}pqHLR_fgq$ukor3)`p%V(@l-4up{ zx0Fu`0|p5;h`~gvD4cGURYUi8<6P{i2%safEVtF)$ZKL&(dHV20D;W|(l(=u%Pz+X zVg9+yoAc+qrfdeMWnew_5IKQ8Gxq@_YnADs?dHWgWhla>W}e~>=ECO&?g9LKDP!!e zrG?#3XP#o1BtC@?r&;8Yr?22G{jQjlraXV;H;?|BxW~1DiT)Ve!B)VW)X=cOLT6oiK_o&r3k=!PH zy;xn~atVj=6XhoSD&l59v!O-QjT^`r46S|MQQB83)D|>Dr{nevBt~=}i?VVLD3gHz zMu7;7u91dOII3GbbtuKO&vDAw6U5o$n3V93^(1dyx|oBUz?wPaWNxAd1NvZE2F8px z7;vEMm`MEY-u^O6j-|QI;D#a*ZmAlMw@wf=)}Q|~!5=06iPV7&v5_gW!&=^5Gf;%X73 z_!#e%2;q(@_gpqJI;_zDQMbRDIcC|g+Cmy6%V%=O0EbFl7TC!bv~oaPP@NLU|1u4J zPB&nR#z8BLN&+k%HQ9H}TF-~Z@!ga3aCPk5*9|i*l734W9sR}g?9HuNx>CFb=vT@p zn})qs&BM;d3l_I(B@^e)!vP5dqPZ>j?A13W`o?kWo|<|l6UM53RdrSG1(ZDC^gw)i z%1a*=zp?a7url&xh=WWwVxyOMhVQhFsUOH*>3Wb_+%ka*-KuVmks_lvo6_~1q5Jb^RS*l}U{ z_Ja3Z=qwKevJtjA}SJb(o?ZkZf&}lScGhzHFPi zKsG6-F^LYa?U~_TePUVHZN_@Y#sRVLwnX3rCDBivM#&k61H1`%?(1IKHe59)Z40Nx zldZ8yX$g_}GApsMmt*nob}`~8%QcPd*LqVeiQiMem7WpdZQ!J>0sCle5Y+(0?n4!_ z5*1Fj*6nMjmKl>gtW&v1%uL*WM12MOzvJXdRtx@2FI!_daUBGEW8#8sQE$(Q{y@K1 zw#LCS_%gY8+F=n^w|YVFul+yU`02#x!kiR`8Ma+U6;w!j*qOk;wh$ccn(iCQ+n8#f z-8fy1+)Tc^4xO@{=W#kVaHf{d{v)3KkC;va3)sPnu z6(ECBdF1B#Mqgn0l#{39ZAvcyV?!VU!vPhbyOgbOJ|`7r;Vg6XWr#D#{be3{uvigZ zNO&)BI&tG{?B28ByweiLou)oyM%&-A-$S#+=}m5RCo@Q9v3T5&;=q^-K$5 z!Fsi0*>bI2Y@IoV7PJlF$Z6&8gk4>yVrs;Bxl5*Tc(QJ?*k_}+g0DR^elw`QL1TIr zw^X6)&0JlZaGC^VBl1TAdglqC)l(N>B2fekZ^G)Y3Mc$m5Wl3c;gXM7Dl3`wr<#v$ zcN(3;yTSK3l&+zj78OFGWLgxq?W8a~42eCM4>V7lb}8~-i390KG5#F~cH;b3;6U4t z^kj@<0{yU4lhMzt+1-&ML;|lWFpFk6rCK-w^1gEj6ABRq!a{i7@t}(}l>bh&gFHNe zy+VTR)3C8>N4|&kR!E{TP13NXA#5Wml$D?SyXV68I)CF(u?AqyQoG^ z*@GAQRR@6WaJJP`>ZaBg_NLFuviF&!g0y#%t&Wj{m_jo)x9;`$xB**M>dj=BQqNEm zv8&w=FMfWr)ljqR6QjLWRZFwXO0OB%9&`{0t#=0&fmZSt>NhFh(r$ena8Y;6ydMoa z+WMx7IcQ8g<8iq+`~VupCQil0rB|yxSlpv z{oBkbbD8t72hzA@Y>Yc|;4jG=Byn{X!9nWa`IDaAQsc*Yi%r}r%>=zfj1_+GO^siZ z&CNaoR0Yctw9o|pJy^zB;quMWJaH#3JdMUBDkm2LGZku(n1l7t<3@y`0z{P8D*prw zs;>M~FnDe`N|x3FRJ6Ny6ne?uP#ro^zNbh}dnD+b`gLAT0q3KWaPzz0^l^fP7&u+c z=vmsFq)|3|*T#2w8;0qkSj?a5h*4eG6+7RQ?NL;%Mnh(E9l_R7e!6~e;xd4z zerGTu-RYwHg{%Qadg4C>0C6S$764>+@C-?n%FVHF8SN6MM)`je48qhu4G7zK*S`kD zQ-Ll1O*`L*ji1`F$P{{>tjoBf2L(T(h+kbyRJW+m{VJ3J>S!Ny;*dv?w~bAJK=@M> zS!uq8WbruD4@e}xSINu7PlcTi+QAoNB&bFl1LP};&)<~9d}!t_an@g(49tWBVuo$rUN7?Dl1Yhr0@4{ DmvHvY literal 0 HcmV?d00001 diff --git a/tutorials/images/tutorial_tracking.png b/tutorials/images/tutorial_tracking.png new file mode 100644 index 0000000000000000000000000000000000000000..16714ac1c94131a2d042e7e6ac8e6c1e13bc8512 GIT binary patch literal 199116 zcmaI7b9`k@7w3CoqvNEb?sRNh9ox2T+qToOZ5tiiwr%rFp7(k0+?o5CxqsE?oLzNl z*FJ02UhDT=6(%b!f&hyH3jhER#6$(<0RV6t000yU8uaU%D&fQOuLjKFx0oU{H1yhz z%=XtuY)2tgM+F;WM;ASNBY=sujg=9#gMqz~k+p-VjpG$qHxB?n2oMwGS9Hxd&vem5 z8(Qnhre2B>5JU!7R20k?&JSZYKSx0Ii0FJj=dSIyhEG=2kEwMrm|r#!t5E$W2Tm@c zz~|n&_iE(^WE%x>8ME`H@4EZAhN^iR=bB=?_>=iZ>wHabE0)Wj5Sot=85$ha@1G`+ zSQP^+xG1uLUd1RB+T?))zE3n>L>|p*dJb^jUHRkRUjKCVjMeqsV;do|6@eOGN(qJU z!yveGa6X_=&LCg&YU*56A9772kf!M{1W=v15 z-u)Fqu(2sTCUWXQBYBi^v0_>KqSKk;TBS8Q6cosx^5Q%P#pb%zMzTO7KO;4iq0nH2Q}p)a@>x-=!y_6g zcMoMdB2z!PfRlMp^`pt5)dgE~jj;!Q&9YJ5{W~{e2s6mD#Y&4xb!Im%d?^L@&MZBw zT-oiD9l3hv%H?I({9aiP4uPZ9)8SOd$fH!bV{py=l`2~9Q{|HdOE4|V#d98xZ-te<$awRjqgn7SNX!qJ#L9nMqwF| z@P%EXi1J~`J-r1z@gI8dS{sA&qlpoGzpibQXAaZAq{~a&Hs0>XBRO0m3gJ8WU!-+^ zEet4?d+fr9{ZZeBk(l!v9~~cGFzC9}#}meQR}qOoAF&B!_#wo(e6h)pOCOITRHSU8 z3jmN7{LIoo535CCNn@bmKU;p)@^FquYPHRFMq5#rB(O+QuJ2f_LV=~5<6TH3BPGsF zj)+AO9m|IJ_kjrp_0>^G!U|Xfwva44xNYCf%1gurHaY^ zDZiX8OqkKlFk{FcltOAu~cUt#Whx| zzM^Z^Q#$S<7IuQ;51yu{nw|s>AVYz!t9WRMHG&aJ&OM3mtUtqi>Ar0O-V>=OfU^04 zSdqv*lFg~p+(%F+_=GvyJCliKK_mygBPG>RDQ|;=DjdK-c9_OrX-s)t@XSgOe`-n^M@OcS~fc8}` z9Le5dbN=azuJRsOrdqqKDoJ3Kq}}Gi0$h$vLK;vSK+`qPS0%D;{Fsk#$v(^wlas?J z4rMX*HB5+%Nk-PtCyc0lRW&qZ%~E;sHb_A=X&DZJ}wCz;#h=>ee(n1qs}c6 zaJs42>{O*@H;zGVv>Rj`Y98Gv$CRw0b#SzrX^qIa3oC(VZ}HzoN}Xm z`R3LL06;HQlSrGTJK66M*nB%tU zf(j{9gDuo9XPkux#BycjD;CU{KDZNsr3#L_l>cPWg@hu1c^XVo5!0i_Ed923kQ%lP zuGR@Vf-0^C08okanL03#V*vUJ^|Q+JRdobSbSr&CTCe3-w=^EP#wK;Ldzj278T`cj z(iSp$WyyL#>G;U(8#$6@*X64kK`C2(SvKTIazIRjQ_4pdN)*xHuukHO!E}`hD#W0w z%@+tcZL*RwEkwsAZ0+{L3Zj)63ZcX3?uA3U%fYKv(gph z5P0}QIp`Vp-O+gKPb#kP?&*h^Q)4m+d|$=$^lvj9dVgxU2tz~$9Oy#z;xQ#0Qw+Ml zmEp)a;p7%kgRzApWa=^%NfRRKg?CqE&ZHWyGIl@%P`?*1_}G>ONVq{V7Uj*pgx-ap4us;8Nh}t zXI2(1 z1_gM%zc^7&mZy1gdI*lGUq*w%^L;#?6n1a5Hd`#sE(w9BH6u-4u-*H{j@CIG^Q0p_ zMr_ep=tRcZT5~nX3T9(?-}U#Ve}mPe8e7z@J0x0+ejS$z1W7`5x?0al@GD510*$L? zcnWxbw@5>47Z1}_~yKqu?**YE@M#jmg@%2dxBCT~W`>FTSkIOxH|%g}ok z#(y>d6K&dA>{08=3R1_-0ct&<8pna1^zifGfF&E{>~}~2;Z6UplMAC8%Ge)Rx744z z$~kRr<(CME@3-QkCS;LQ=CzAj=6&f2NQ{I~N0FGXA@9u!LL3pRQSKFam3OuiaCTopErUO8yjJgvh>xSiV%X@hSDFk!i*q(gAm8S z=OIiogvA{ksNU)!vZ;|tg)wPGV3rGguli+STB}n0!{A+g(c!0>)o34Bx-+j42;aQ^ zZj*pgIqbw)Sil3!!jMLxRAZ7J7KVZ9=sRREvBWFTS&{^<3WC*$;$|?w#CvVEJ(!5V zcSOqbVd@X+((n2KL`3*B*&qLjXiC6umx{)Bal`Y>6VUSKQdw+Y*hG_kR&*aeLUXP6 zugK?-ExM3dS!Ap5Yw1c!g5W@c(h2Id{d`!}VN z6Ve0Z4anG{0>obS+cnoMw*3paA6OBsUZ~@)Pw4H(T^N<_mbAzEJ9vTfj7O(U+_@`+ z&ax(q75({gAE#zVtXHA(a9kXbug=S^O4l!poRdcSSrWn9$N!`zH#;1Vc=qdYFnj^fXE@Xkiss9lor2ocUGu(KGSi5 z)b}^l@blg;tddN^+mDqzJ3&<2op-`x9d`An^vZ%h46)+ z%+!t#>A*d}P;A5yYoL*Tem#>ITn`k0h5C8?PYO9?NHDhu{A4*PM`cnTz1#L)#Vi{? zAR$q&%(B%}1axeQdrcg#tB6t-8I0&~rN7yIu&}aQxKy7XY&mN|``Oq}Xr&MyBo<)x(*P!|++Wui$8zTo*dsj9ue3Co5&gbhsmNqlZ6Nh8E) zInSwgwpgF$h65ZO=Ji0Ls)6rQ*Vr~tOJ@EfZ_yu}Pjm~!Yc$)P5{t~)F7kiF#xQW* z#Gv-_Trh(qp#OoR_ab@mX-Cg!11k31ug{7uT@=GZKJv~glAtcHk{U0_wI?N&X>MG zD5C5W{hBEl@2$1^SveH7E+mvq+)@9r)a@k$8vM0 zRrhvz;_Wqfqut?SFcWj6l>y2m_`cy#pz>jsszeAp7GBOGHCtpbiGcMpj?fMnXK(Kp zS9}j0V44`58#cOEDE^wen0JkNQc;FZ@1*+qZMn>GVrLBzf!2Kn87!yRO<8>X}Jj98EMuS2p`D${=XTtpRU3`-8u;(s?4Q>1=UW8zn3<+^L9kdiXh0N37&0lOvi;iNj(=GD(-R1r7`U*lrXf z>CaWgZ@qPY8G_oq?wNv>%C83c%A$cUPdCOmZJgVYCo^oZY?RwOXlOLwV!_9*3xdz@ zHB02Aev3y{gc~wAz;B^YMq_U?z;P>7voIm^S%rn6`(~pJahg?i$X_BY5m{urE5l|B!m!uiV7FDXs zb0|L*FdZCJ&@OI^7i04%AN#Wu{e7}e6+fEZS1nr{1ORQDNq;eulxjnAZwm7S)U!LX z)@j}6;UQzK1J&C}zrh|X6KY}L+D2e0bHY347pz=tR0KIXkos6%MCF2hGFONR<;0f0 zHVcPXJpG2RPGaaFFiDH$v-x(%lF8|kR`1Mry3zR=0!IHdiQ%Al=1?HjZl73Gicw1T zt%d3S(4sH9+rh5q{uh6&E|q*E)_<0dF^@Wy?MFE}q+B>>ZMmxDDjMT>#bqPz0GMX< zZB=E70%++m7z@L^q$V5d@VG(cXY}YR&YO5b zszL(x)h#zTZ$oI!z5EZ{eYD4T>AcMlMnw!c+@gm}$v}_(^xJ_dP$bEh_TQU0Dej%)q>j>$~(b)Ku~gE5K|)~dl_!N6c@W!PluzYrbUP-1&f4Uf*UP1exW zF5F$T$Bgw_)KE@igMa%SXdQ$+vx?A!OiKZRTwgm*Z*EUF(2~<>uHhy@JJ?FJF_y@B zSWmNEgG$Q5O6_ZENJ*O-aNR$kPjv&j7u0gh0N3`h zRpti=mC||hqmU>oWy+h@>@XGl5CA^?Cv?8s+x{0WZE!qEA7CdA(D zZOj2dvTzD=Rps%&)X5>WmTg>Nm#0eUDPFXGXtD6f@D{enp>Qhds=6!jb_FXsLPUZQ zV+;d=SQxfX!T7PZ*D)G1=D%%*BPVkC)ye#Kum*g4+>cGNaH7HZcZGWZwrPzuaWH-K z$wt@`$sDk5Xu|4aMX4d!$%S{jmifpgN+)tQQ5!f-_oG}Gq{wGjO~Zm!bS^ng!pNh6 z>R`h0@F4E-q`Nd6-;n03t2QTIay7Q5>dQQTgt0qO1`*>19=_^gsn&;*#u`Fw`Y`UM zYiE|Oc9d|}uH1UW^#eIvAP7#uJExHmh5#P%WmP8S}M--`C1NIn#H2u%%LEq(WH zScGC+CSrj^RTsNUTZxl2da(?|SJ`-p1qZ7$+Q_u$nhoJoR7$ka%|gKw|4%|@rM(>n zbW2y>SE?+WKQXDyCOUutvDRRvATJ)5pdeqvbxp@@5y|64v^S((kAXGy@xUM?z~SD; zDEFkjU*qP1z4DHV2k{48=dQL0YAmf18_kU@8q8QSLK>`F`-8J!J$fuxP@CZ|8k#`` zivj{-c7xez7Ebz?HgZOqHjYN|TrL_qRtIn^WpDIhW;BG_3dQ3vv;BUN zFk#1J9oq61&gx2q!2RL%+(Z=m}*gaCpnujQ@PKWX!iM=lx9ymyPyhOKc4F~<=rxtq`A8u}YHOdHhu>ukXTzux>0pr|#8XFM zRRskj98n~+>5;4J2BF3!Vf+<{_uJT}yycES9!(jF-@a*_eQH!1_kJ<(nwf}6GMP@xxEu3UmNJ}p1#Zv(68&C z`|Dx#G0@Z7{RWvz(=`?@y6`t@Y`S*IDfp@Ves$)pi1^VobbaNX0BE~kV)bc7RooTx zs>QQ#>t#^pLZNoom=Tn0@1O(V8_ySQeYj=s?ei0P9}9v43P-|x3i@FniE2qntGwAe zhx+-aOl*))MO`suF4E({#+hu$;RPd3!fqxMJgjEqBaKvRJehcDF#)zG3?6ov^^|hy zB%hYZSg4aWnq^pYWmD5v9ycIZR>r?=3*trmb7jqx33o$qxojO4LwoCw3@SJtt1o(U zPkbGGz?0E$-Tpk$fFowz1l>Ni%5sMW5lirs{H0PCtZ@$(;p)6~Kd)GwvK|z5O%*2a z`DkrAz??||L;sa+vtPkMH5MDmATr;vv}~;e0ni-|N8)Tgn4f4?hpMeHjHY+-C;W&m zoTZXqQcZ@)A^!RE^Zs?ARY2qc_r*&Gl+0*XS8I zgcjX#6oWYD8hbOM8Pi6p3rHV;FnQNzB9X%NH%PXQe5|pmj0}<=AHaAf%d9$1+eTDU zvLB{|ueZ+k;It=a#$D;a%ohL%CT?^mDpXK_2k8Dns=g$g_Lt2chD5>rg`#jh1iJOk zt1h0WP_$s%-xvrDm{K~6Lc1VAJ*MaHwQ`jE1}V6j;n)R04gJL=Vfv*2jufVH!3}^) zQlQLX73DrBQlOIBiIk=qwEr55$5E>C>(#`AIE;`GdZ3C=n~5*vpj05g({vov50BNB zE`TIbBV2F~Uo0aJh5+CW75+ws9vFaUo&MR$F~&CoNEL+Ej|<#M6+1969B9j6A`))n zynT47)~8g4#Tc73j2k7SE2%Rdro$tLB(z^p5AeIG_-#%fPpJX`OwV|Vmowo=8H4a6 zEA{)v{luu3*HFzGm@T05u2lyoc63JeHG1tH+a7bF5mGAtyAQgNj8pk~6 z$hU98zwP?4`N{k6B^a1_v_wO|58(x2>5vsvQuX}&H!Mj+4c1#V>F8~9I+4A_5t@Mv z$VJzg6V55`W9875q=^{9a*c8PTP#c;GxepsijgPeZ0aV44#-25ivH@i^Vc)|lEX)p z%$RU^vQ>8cp}}{7>{Qo{>T=nQ|C#k}30j`2$%-TVzljhpd|$(qr^SoXIJjSgpudUm zZJ799x*|M2tmr*(Ke!<9V7*0_pWnb~Fm4_oJ4vJzBxQf?s{|8*`aSy~9<4F`7bj3a z%wfY;NEAN;n@GL@gB*?Ow#5Q$hVH=c2D+gCOttIPLpPqXqP$r2HDs4JNc$HCsBdF+ z$-j{{pCVP!l1JQed-DH-C%%4!L~@R-f#u)f|9Qto^ z+e#lS+6s^te>5XhX2ehz)Dbh8I~qA(dP!9MN3S8fKTp?sM+NWtM&yePW#Sv**3K9%{m`{xBzLl z-j?VkEPG9AB({aQm4@9Q_NOj%I}a7OZvcRr#b)DAdGi;Y&nU?RT*=+N=9A+CN4FY| z-NnAjJq~3`+#`o8FO_1e<~FPD&&S}l3LAn3b4(gD7H1Rt`4zWKq2J$UisAAnm_0ih zlAr;AKxQb~=YyMkzD6!pyxXNMUIf#hz2Uz^hj}g--L_`x?W+AznwyhXZAa9#M8HOMQs!vT!ow`PiB@@6WPFZgn5d(wmn&=lB#A z-K=fZ+FwYMZnx7r@#w$b){W7e;ix}xiTFR7K_8S`65}1sdgXI*(WX?06i-ndUn-DH zrLYUwS!JIFj<)H+D9KUg*kHI665GpRXJ`AGH8}~v zp3r!xiKv|Y{ZNY?bOr7zTStu#woI;6 zhD6P;c;$7vxz~{w(}L=0+AFH_z5l%5Jk%(^K}lrgvhQhQoIXrui+ZTqcsO9;);9&} z=<%se@4~N~>_Yt7z!w~_nDd2xrgALN=(|3g{%-RY;u|=>GmwvTADv>tE^sRC7>R8e zC9FYKAjqm=ojo8e-QOa~9g!yD+kgZ97M^u&`JCf88BQ*9+7wO{QKvgSgw|a2Y|wt` z;uZXHX^4PbcxnaVHLBGChmVS<_f|%e20O@5N)q1)Lwy$eli>qabSgm2V1_Cl03gdm zF4^7SG;{lFv{0=(sXjSVPK4>srxF4HkX+XtjLsbEB#O>p<8n~({4F0z!pk2mv3NTh zd~wQn-#}PxeA@|Cxz5Sw_EP8%NvP?8%hgr05wSIhh%{U>W44lZur#11b+k2M*iztI z!G5r$HD=Cxlif|MxM;UBo8%K$noaGUVIV;j9F{J#VrSh@?zTRVl%nNqXJ)!_hYPb> z{3EfvPR&LZy}-KV}R?_`%WTpV_=w0|T26+%&^Gx>~?GysT} zw1Xg=P-Q%?mIhmbd!>Qkr*gNd`d+&L1w>?3PSd|a7uf#>+~`B1$y_^pdU>iJ=1@>U zuyb!QAGtUeC&%OTkSp&)a3L_leki{X*&CX~Vayra=oDiDgnmcJye#jcJ5cvDl8od9 zPXK|xA$@((!c6@n%xHVBndtuPte@eK{vmx{A3+JZ4NF0h{KQ@4dw|s=O+LvsYA)_s z%yIe72NZJvbJ{iU+L8o%Po3brR^5GyRzC+%e$!7v49Oqe?|WJsr&l}EiLQQ(c($6Y z;e?qjnp39XYLdAV+TyNm#Z<1qEX;)QhF`wHjbSbr5(yFRCq46({}n7e+Ltg7krbsI z!b|)m%c-sHTF#e^*&V-WY9gB=1r9ltR^3j zhh9K?9af~zusjT32e~K_)1c^+=Ca%vsV0i`)hs(!mL}xIOILlK6e|GNTYR3Ls~)~< z2beJ0KqYvm-j5AvVCc86J!bIuTn&uH{MPQ8c!C@vK69fl>pz;(;evI)Av+$ZA9qi9 zZRJ|4F_maR1h`o7Ruq$YzU*=zWp%c>*bTV?>54ZEJe2y_3;FIxu3IOVe8zRoeQq{` z3@k!y!ksTzOJgFaA!1ann$BZjR+IKvc$nX4MYNq)21;|CrW}5mW(ODkZhPW+BqY1L z?QlkHT9Q&4KU?DGmzl&lX$X8JFE`4(bS+_c0QF7tWp2`b^278?*&KTulIY3 zhjD46^G%i-NqGzmwW6Rhh?e<1NFZ2_y?dhPJk z+EHl(`Y@T0lk*@iuSd4IO@PXy0SiAcqmgcEW^{8^QkbD=3WfvbYEHf)sefw$7Is*# ztg$xhY|TO``6=c7Ws0w0kYJR@2!ipoJAwNTmM;mRUIytYx2CggtY5H8Iz1*U%KKYE zGE_Oy71sv+rNkO0qp6a7G7F`cnkCO|msC?;F!Qg<_k;tas)wZC7vxjg>G(I7=O?kn zxfW}+oR9c$Uazu0zSb3h{Tzu~6PvH^ps@HjP$sZg z*#+W#XELAS>eZ>szY)q@UPY1$f$PkyI<~wLp-y1k@Vk;C|CCDcxZ0B9_3 zl2`@booIbttHZk7s0HSWBAP=rrg0n_G3?#|n2B(d)gr)1LI_SDitrI0(TR=_ZV z;M+^840?ZEm&;-`Yo>b9U1)~KA+uACE zxeoqD>&cbjUDw_g-HJaBuIX=<<|}slQ!nmcnYi;Vx)Iu78u#j6yfz_#sl9T&y;anu z=4u=sXZb05#-aE7w>wP*uzW^;+KLR;#<89mZWH`SOS;qJCXmK3d8Ylcwev=aM=I+-9X=B_wL&DR2NpGl%WDz#2&^x*jylA;b(hu4*gGuxlXOVG=XLwT zs~d*AIq=MqABRlrbAMNDG*w;{alH1;ioo6#`ZJ_i0)10OM&gDs5-5Xy8ia?1e^m)J z^#dNo>>>{fd$AfId!Q?(55pN(nvlm(a7os7`kt1@dt<+44!1p>UJ?xeY}MvyJ8N0} zs;Mui>LtVSsBHX!N~#zX-VwB!&K5(o3DT8V3c%Cc-KB!g$AZy2@1@POOYRpvnjO`4 ziV`9PdpHhJ0cS->#fP#{sA)8r98g^~ivw|v;f7MfW>nU9x@qALhvzq=w@+zW*Lkr; zY?t!|q%J`0$JD8fj|^SZ8p;+;cESoP?bQYzai6>p>M#6BPk1Ix^o)DlcD<^nffb_5gK5NM8}hgmFXyDPT%#$6GC3NA%3SX*tM%af z#nJTcffT!XG@6Q;immWC?eMj9ZF3O7(>bF@-dtuJ7_0WUJ|K%XEXBEl-Az9s%7vh; zkhbqFR{m@PF#>waxfn*=6E5X&DAn-=sVx-z&4^%{1idV zyaP!|^@7Q70=wY~^3S&|dO(bh${Dwzaj7$kwpWpt2DNAJG=WQ3ApoCS)DDK5$=iF5 zF#!x=5p_Qn^dGhZ$pcr3(swV4#aVZ;Z%eJq~ z;4&)=1mGLHWTVyoq`ltd_pIni6B1lHxma#m>b^SHb?idA^!fRbozH20g}Cuuy8`~g zye6=pf4q+#pi8b*wb}z%-ulO&-M$PunNAo_r~PcLkFx7c`1G~%?1MmsTRF|-nm)~P zcBT+GTIkI_)NbWnMV01>E!DI|6CGEgm{6%ZbJry2DLInAOW`X;?+YOwM`6Tt1fJ5u zjB~ruU*tHPk2inYw-c-j2+ z+sb`dua#^pZrdkQoQ-Y-XZP{b(_-+DoSXJT>pcFYm7IdL^d97~Qy+SZvDX9%u(Lg9 z+>;jNK!cm34!=wgr=nFF=&;r3E!THcpLKUc-Q7O1?EZQHj^kqMg3iBAKw7;u2I5;1 zM5%tyxo#o&p*1BCxk!5=F$M?d*NMc|q}>}utEX;HQ)w5mDs}R_{9IlE0QkW8b~Os! zhOPK1kRIyIv^=Wmii$*ESGQr;JCFR8HeCiKy>c5kBvr@9@Y}`brt^-hM5m<@Dh(uC zn_R}2zgsiqzucJg7Hy%}ysw*#e858j0-e_8fBce?=7C}8R=S}1+q?bZhDu7ZKb_ft z!pMb4&OAgXX~MPswCq}L5W-kZCRTz1h@Y$n(g$LI9S(w9USb6{xF6~mtL)GKZ1e%L zCs>6z+VDDmWPoVlD5lW2o^Xf|D*gQ#;Y!ThP#=D%C-a8#>U<@OdLLOb5UQ*MY|BzB zSXhqBX;|nL;e1PtKIyl%IdsVx-mkapETR6gAm!=6Dh+qL<6fgr$>ThH)=l&?5+3mc z5SNqNjYaD+oscVU#oHgv+zW#|?JXjCb$u6Z<*K*}x1}|(x)SiR@$!Y|cRyCVZ1}WW zQa{gAP9%_s|BNVVW;Xxmr+^6=d3-?zY#J~Q4P&eM3LUxigS3-EWi8F=X*9-sBd^h<6ARm=2vnb z&Fge(Z^$s+)k2U{P|ATsUoJdX{2*nA;oCkrfIl_)16j2g#p#4Iw^@sm;d7|+JXPs} z!Xb74!6Q16o6GH-RFz9S<-k$Kg`-Tj0~bQo2{DoU(R4mnK zaS+Kuoeq+rr>5I0Kh^g`>3lHnt5N`niy-^4YE$xb!~Gz9pBzZrj%-6l%>Uy{@@BJ^ zfwxgBY5AN$*r%hf4eYd#GX5&IY~+fsvg8r5nWS{~-Nr#ZLX=8c-pc2R=Px+`~u z`gW4!P#6m}#E@iR2=dM^v2Jzl?-iutQqHSuj!qEp3yWMj=AlX`hzXd3YkPg3N}Cdl zL%7|Vwx+)>wyb6zSKcKx{NI(wyO?x^1W(qKse}6u#IC#HgOvtX(Ez?btbt8E zYP?7o-;n=$k>zTP$o^X95xv(m*l?6gT)DgDhVm}-Zu<#xo)ziS|ccGomlOccEF zcX8{Vjuq;K&BVf`-S877AMu|{&quw8;R;mV5F1ZKfmrn#!>8PXh&GvTPm8?29d23R zk2L?VwkY+U*qNPi7axB6P7>LPR&_8s#?x*&UDNaUdn%jZ zwd5dTgYqbwpy{*`pAYkm4d1=Vbo||uzHJ$W?c>r-6>-K*(j$d3CBlktKXx>L-t?Z( zF&WKb!E!M_znBp*^81F+otVYpJ!vW1frVH}qT@=^;U7w}G@}vu>e}Fd^#Nm}3b%aymm0|`zQ9c@9D(~;1QFVf zTtJP>rW&y|d8yusQes416K#iiHiUxuFFYF;n%ktl4Jl}#3Yv2;nG;bqSY2p#Io~I<$b-`n26iJ`S;J9_|2EFFindE zyInDhQCC98>b<$tV)1B+VJ1)#D+Y_(qm}BPTV*xo51i83YvGu!XX5eS0K=zvM~Kco zcdt@qh}Fu~8}n||Zr?a*h;cypzS|u(m*|bDP-hoz_-rkkK9(UGPPgsVLS9PXx`6-y zQ{@vTldm;rwL&7en)^yy#nuyTmEE`L3@xqOy+ziXKgSOvRNYsMtq^QzJPwQXsOn>gs@T-->t1ICgFy!4#Zn*=yIFj{bbV#f@Dk zp^ad(rBEF4r!bv59nxa8VRtXO*-7xTsU!1NdMd+irdb!?i)Y|B66zZN5j_69W%^jU zI-unC_CBEq3*bX-yHkCCX6OBY#`Xx|9;fw;20sa;Y>%E;zS)b*Cf1nb6^F={!L_1G zkZ$QXdv3U}c%m6<`oyFCusr?EyD~wGgB`fWh2BDLmUQ{a-bG|pYP9|H)b1+_?k8WCoduj*(AA2kBvpVapcqN;; z7aKBCGM&|yV#ofG|EhmrI+UlUt-rBFbR z8FjQbZC@Qr;vwls-XFX5P83YW3FzLo!9f5Cs6f}Th_U8bQyOyAG|ckkcWvO%w|1Y8 zuUg9I;_V1l1u4u(xniGAb|y`VFPYsM6K-+j|2(5y6 zefkJuDzhX1VN89p%>`vqy??dkX)TA%9Hz*Zy&e25W2J~k8ru&SAnJsQOdolw|jovyIh&gX%^?pFg_nNXE_PE!m zg4BTjSB3=GI_o&!&isjNZ@gH52TN^X*45wf2}pT3ccn-=l+X9S*u@QNk*Z<}k0!5h zI-m@zJ5*XV{mh!*&Pzl->ugI2fK?Q@Gap*oGSD!dY-Lgf)s^(}@^}e!Dpr6aph^7K z%wXYsqqq~Dw(G6DRtfgpMHZoapU0w>suot{eXg?ykoMIC=Pj2ufPq?}NU;pcEdOF- z=>8$eYCRo|cixYE7ZdL1Vq7GzLNusR+1FYfw>t~~nw!+`S8Y>N;37HRM{RiAAr{r|muqvyxE z_Q0e{&HACKw&4r3p;W|GTk3o{g(#nTsODcLA$gs?`0eStthT~~d|l@Ky_!7WQL<{F z{J0>@oH}F@XLGevo;OgVRxz0M`9Wn1Q5pY~u)GG1l7qJEsE63&x4-}V?e=+(1Z%QW z#phO8-@laUsRsn`vnle{>g)W2s<_;?6tEy`r6HNvGZeQ#%EKRxHV`ni*PJQp-`h{L13Dh>_+{7nnMe7}8`%lQ&B z5ns-(vLTt`&^~-wf4ntJ?R$w#4R*qcuWzcG_YqsTiK)MkjzzFju<53fll?W43clce zijn^s*Y15*{26u2TR%Y#5$G@`)cyH~3Q4)U%gtkg6+w{2t9PS}wFRZ2>__vF#7t~o z=OZyRprvBtJwe>P~wxf6fHM@u_y=?$Ma6>Ovti)@{i} zka99<4_TaLS&NqzaR{0StvR;XU1m(c+>@g-jc7mx^O1ec>pI<)y<{Zi zIt^gbdIbe^3tMjhs?=AYa={}6`F_Lx-8`5}l^V&_ z&DPqddX_*Hb-^RM?TM}WnCKFmK%H*3*+0Y7jH$UQL}6`)(s~_Hb|hdScj>B%;PsDy zo{RjU`JIkw&HBxcJbywEUuH5!g;_?+51NFVi)vIzAo&AU{a%Wg*eAD2w`|E~DJ-qT zD^2=3i>{UL=x?kXpO&H&pHL3o+W5K1p3w{E=^wES;9PD z-9!*Yz-ck=i{tV{G6NvAW^!z+e*K$hapNo#N!d#iojZXO{EYhXUIi!VgDkD(y?m$x z+*~oWc3GAPN*~7tQ>03wv$YN4b{5sETkOWwxxlY=1GP|Eh zYmJ!1&cmUFQx4EtIP9L*ZQT_R4AL7S;#rKvC&0t`mR$iR9*2cPjwB?S)Z@A$g5_&8|E{o2A9HQ477WUUPVT@5H3#g>`#j+4_!~QgJj;f|AYa^A8Zp&%vBxIFmX(y0z@f zqu${FtT%qtWaV8SL_B49Jf3b2;O%|%Ww^&&C?Omrg3gfk9kI;4)BDr{2RtyNEAhI> zR~xqqcxVbSJD3r^vXsIfAxEuD``5W%FkhPeLOb=Ffxq)XOO%YngFkkG$CUw+KLhQQ z#gVSZhT=enHy+yk{<!j7CaywsN1I5x?4Wlv=MJe#`+4Hsj`naKxUKN;ag~ON>lWY0 zdBecw$q%MSZoZ9}4ZrE|XjAyLd)x0kBO_^45NmQ+vAf+^sn(ppTux*|GN+&~GW}0j z^gjX70(AB4`5M@fwei=6a=V>zq*5*YKt7$)C#PIW$xxJ+)mK_U8Uohs=VXao zqpP8+PQz^rtUWfLk*_G#)tFQz-)oH*7QpMtda9Jou)jRYn!MZ~Tq#nHv{`4~yG_@V z2nMh{*=cfL{e!pR)mx8DNjZUXlV;r_Q4nf+Vs8E3-v9vtf_3)x{WqIf8HajcdCE%f_l|Tm~ zz;{gD^8n$S&&JsJnG*91Yqe46s^iV!CbAxB+meL4vkmYgPJ^5{J8zqznW8|N(#a`V zT?2&Js4G)MvZC6@mi*V+{qf8}IdQXM#H7MDWEmdBS5_N2LipbinI-~P>fqe>u!oO8!-)-AG~I7Ih<~%5&}dP}H6dE}Zn-|bsNOgUaoK~} zx^$B8%JyYOU`N@XpDz2y18#G*zC2*6e#;wZymUnUPOYv}6yoKdrsHfk5Y%yKzFzR$dqF9vNGxJ~9rQaf%sIeI=hA#L7V_U7F@v+Tc+_x^ZgGF@VGk&Z^f#lgFudj0c4S@pqa(cC1 z+z+lWYghcC_qv{yIHiHJ#>Z0IQcT?~I`e+3O1T{e3dfwV8SYLWKuJRwry76z%230d zYyil!ZJ8QNBOI-s+b!5cJ{=>DnNG%1P$nAf{1;>SoU9+2mdZQBr&8(egVtA^o?fzj zT_35a0wkX}TjqzfTP<+_fTQqrP|{tIGd5e>(Re@{f-v3&OAd=%c>dR}74%ix{+2~l zytyPWJHqb;)pX2UBUHWcbk_uO&DDj&QpIiO^;WiHK>C2o=rAtR%{#@s;AMehzhb14 zyD#@B-2Z>$Pf3T%OG@?9B zkEV?S{&xn&z8s>J_>ve3LhO1hfk~ z44RHty96dQ!&ODcj1}}=>Ynu3)C8f$Abmp@9U!1Ap0mDqHkvI(H#pVdR(wxuSjtj# z+q_!UnCm3v9Vf=MP=RnV6u0JYHXn{2^)1s@dI1z#+Iw%pn}fso-J;n<7reC@>q)B)8#F0NpTerWBk9XK$&9UgSHgY7CJN|98lyYJI| zU$Pi;z*{Pu{Yo&ApW)SJAl@tvM^xNokW2P^dJH|UJLDz^u3)5xj2h3_;C#{Iu!_;t z7UsU8RnKCJ*dXOHo{-4?GW757`xE0AT>n&C^h3pe9Y_6!OT|Bfr-76|`F}%FnvW@h zAD(M12q%?EtUeL6dps1Hs`+Z&=tP}p&8(gCpn%I2lSjc~P9iAlj?@7Fmk$cI~%gaXU56szcntlf{xltE6@oh#m;xFFUNngdgL^@wlbv>$*@*J=>o_0W$wzz*dp3 z($G3LDi{Fpqk5~&`Kq(U3+$%!Srbvjto5!AvV0;mdd8KEeA+~CsDD&qaXO=B&ZLT$ zyo)hRLV(h_kYi1WjO5%*@V-64!Uy;{HG|ja5^{+^t1Ro>DE@nw@NfqUP?JcbVx zzo2L>6u&y6){Erma$afLOl%Ws1tl#rPrp$Q{r?h?DGwSZ|#-Ld){#;N6{^FO@ z>rMd!D8i~Y9=ZQo3VUhK4#lX_pG^VEYgji1^Dn*MNtEu)uw42R6&nT3^IUxHerGlS zKrRTub=9o5O*27K=*voDb*DOpvNDMebsu)}*G56%Qw<5=@QdwkJsHL2veh8zF^f@I zpW+-tCyH|E!LC(}E$v_^2O`5)y5rh8hxCyd1Aw$>s~j53!ud=x{HE5_{sk)N@K820 zHCEVtR_gmt;Rx#t_^fM(E#uuh-z@8Mek58uwyuOA@6TWcUiUzS_F!_7tncxP*|_I2 z2MwpaGA-X^E3UIm7c5m_QRFwI8F7tG{t2?IqDI9d-!FA_nlI0n2>mj7TP_Fm5tZR= zIAxkKjh#feBq})7daOS+LLlIvqD(0uuR5Tr3%y?JP7mRZW^>!3Mr4;bLCa9IG@zK> z6MqtFi7J+dke*ZN=Pl2L{pi}@o(Jb8wqndzUFfbh|7MBhMnYlhdNni2SNxTyZY|>( zmxAe;##w!YP}Pdx9zyo0tq467Pv>Cj2i=L|u5Mjd4<5c+uI~PEvSSL}mhE}*i|f;c zIB5zK-%&m|HKV{YOJl@f05Se6l>kIwByT4#c=+epFP!c9NvMidPnSZsXTM%lM!K^0NrqwkI?3rsrI28<53aVUbqD z6)BH>#*BA|%ZtX{$QN-mZ9=xJ461sl6t#{K$nf?IFa!_mfhW293c9IVf08q#ETR-~LF%HjRWflZXA2dwqXh zerJOP-jrKvS2 zYuJsYax4P#G?&y6+J1mMtL_5wmodu^ygllC-h zkK#DtYgj+pK9`80XuB9)AMWu#*>5ZwLz-4h5IAHFFdzXHvG0>`vdnO)?9^S4E#`w?w>T}6VuNcTaK-?vkc>Iq7J?%)qK0?WJq6O^j*IR<$QL|xdE5PcM6&q zGExaIC8&)ECzdh_TkEEswx0j!rrxdG`9u+TrxP1*>{dk4?u2l6<{a+4Nhy(1(BRWQNy55y( zwiy1y!Pu~#%EnzNhAMnQS6%jg{$0VyCN&uw9nnscdS&`&zwS*>qu@X%_lB~O4)6U% zVo6)E9XW;>`hbpAhP+d5w(%!;Tq%6`02eFzKi&+wR zrtX>l+CGuR|9a!L7AJos^?{Bw9U)W&FG{cgDzBk%nHh!cbY^A_Q*T$y9h0?=)%mdp z-y;T$6J>soFB)p*5$%?q@)09}~o{DDdOWSgZea~MS)}gM;&2}*luFiuvGEOh8 zmh*5D!^`h8SKu|(|AH5J;1<7P!UUz(p(sf~A8mEaS0Z7G?%84qH?ziu(}{$Ehw{Qi zKr@zJn^v$%&1Ru7TkV7CN+grqB-jJAoMi35-qTF9HLYIpx8u!n}|Ks#AlEC7MR>1nzP91VIV0(8t&uN5GoBx53F zdAU-5L9u4QbYY|W?Yr;T=!dviW<&ZsP$=x-rXn}Y&ainF@aYG*F4 z1WWIjBkgRx6G1gaI8} z0J%qX?pKQq;%_?8<{z}N_}2Rtm8oYQOl8P`FA?46?wK!~Ty$ln*`zhRx9Fs~s`E_K ztf-Yx`RrY26QY;Sy;hMEH;9B~MH47m{Er}|R_>YI1)d2Z-p6VMVO(J*zIr|uY|p_y z4pLuhGxXXal0@ulnOn_VtD=5Z382=>CQ&E_9(Y8BS=BF}3uPrE$4#?wHpvkWeIAi7 zppZfxNpe9Tu^LpEWo%0^Obey2fbuq{6{ zV725|E%R**gemaNC5&m5OL^SJw(&LI|F(#O>@IP8Ysq7&5ffid(>J<^{x6M)H!xQC4)V)h(#m6?$w_?9% z%z^rB*|==At6g4P%W#E&&h)aV=1V}QA2JfvkL)zVx@w69mhufsf`amSu!ieUssu#Je$P9@x_{+qS>e^9gPK;#zFu9}v5@d^ zpW+%=0f~i8oX2?8##dnE!`W;Wu6-z9>8J|7+l=Q7^XUO4I0)r13aaJHeYw%7d4^n) z>OQWo8XlJ8zJ7Z~nlc>wJoXO7*EhNAB<_N3ckm=6a%0O>BMG(fL~o-s-<6pg)_Vv` z(}TRA!1=3XUcwMJ1bcUz|K1=10|+W9it086Ls!x-ur}%?^P!L=%_ow4A()dFo9FH8 zT&2s@lVIny)j`spdtG9Men!ZrT@W&nAQeO&}Thw>1{B?}` zKOcjO6WDbo|Jj7X@lUN2H8IQgDTM5AC-sj{aoY|YPb;Vh2+@GB(cSTAj*OVZizbK% z-w#CD-@SjeXFvba%lBxZ0;kXHUx+DhHE1VMJ2c&D_Y{p@(vV-gaT(ClHto>m=)sN6 zPf3wpv2woakU3qi1=_YWM{(*QJmnIXZeu ztMPItOTXlB46tMh#5Pz|w)L)wO2@sD?pM7!;D7-zuc2E6C6*KB807T?oWRWL>yg|c zG!+=yQ`NgPc;=U;!Do7VH~2IrucO4^3cYC&p9}tcT@lXr`$K8xi;L;w*wx`Ew{hDV z!^&F`OaLGjuW^0b#YTqbr&L}M&+FsWtfCXHexRHZ4zJ%>QEvNlS@@ti`3S7zmomE6 zaJ-^C6q^F~gx~CQTT=*1+IyIvEJ>4u3dBhD>-6&%+>B^?=#Y64H%@JI3Cbrq1t<0v zlyJW~4H-sPJ7f=O<((O9e2|D{8A?5&9cEuchAxZ;CX<;>b!c>mFA%`9@jAJ_PrK+3 zJs)JqWO@f~?JxOk#c(F!*r5rH!8BqGWchu8>E==_Lk?(2^eTNc&JYE8l21BfX7k(o zofT80^7K)5(_~iPykQJ;o}DH)m5K5BNCqZxyi(|%908L`61hQT;|4trq5zt|{B*z= ztX{PoIC$f?2UX4O?&%yJn&+jY+g}pW-0uXd(<~Ft zg|g5?zQ`_)&vYYU>C-DEEh-2Lh*dGyZF6-{lgr(Bxf1etucB*~2P-N`eIl6y0dPdM z-M|21s|q7u>^QpIBujs0waocuOqihgzsZ4$V2WzWHQ!n-)p8*K9JH)FYJQs456_~- zOmeg)GpOF9x39FV=b0XRnKC$f^CguUPAVjgaE=_Ti-(B`j<^I^Mih z{~>YhSzI{D#NJ(WACqvZ0U&8=RS(21A=A~d$5Z9}gP0;*omanL>?WpCH&f`(Gkg=+ zGWLffCM(-Af>|eXBRg(v=mPmoj!VQo_XR1EJ$6G{A=8Cxd4uD0$E@Ls=$TP_1E)sU z>diL59#Ys}7lQ|J>X%hmW{VBubYX_Dqavw@@B zPZ+YP)tu_7`Uu*-7Mt3_M$5GTgKMZoO<2l$-9V_9^^yA1491i5(jAnTd%AzKgmnMQkHGg7RVp?em60NdDx5Y)^hdwkcz(l;VcCmoB z)?07-EBWuvUK4;=@BQHKJf(F+lKnKVPM(m?){M0uR6k(Y+NYfWjs6sRU9K`9fWR}3 zG3Up{^6sv%mymbDD?d;{GrXUdbIc!tWyi zmkWmMJYGh&eoDjX9oK2FZa=9_jgtZL(*x4-WQyPMw!BDf{O^9&f2~KTWamQhIA_Mz zgfa1DY+17Ju&o=~mF0!XXEqTdKVRqhoNxa#1#0#MSP)N08Nh;|X5O3994-0~fBzgY z0GM2Gu{l4lP!^!lnW;EVpY`o|1jMo)K&*3GsC@01UcWs@Cww*Q4~>c%-~#5?UpNf< zGKwO9{~GGF1P8<_WSCsqnDdI);D;;Te9RCoDGRRrTo;0#O}}MZey0+0;HS z?`q0gSRtYLGIBaPL_S-fp>(oz*5eE0F+fUNPq^?Iw2v6Xf;KR1&+Ko6+ILp$KCm=` zA{Q2lX?ty~G8x9g@$$cHag2mZ`<*M}Z8tc*E<9Q+A;fip2q?YoUM8@?io-9)5`(tW z@t&O^q*N#hnf<8@iMR4}mGmh|JJ-&L%7sL6`pWB6gGmVr&>%C>00q?M%lbC>en0@i ztdtkq>{9PvQwg<3nM?p?E3mf^a`M)k0F!gmp&X8>={RE0X+DvyweH7tep0vqtb7+6 z7ZF^29Ia8sNAv?eZd>myeaz!O3@oS9%_XAeCAHg^m z8UayAh`<9d7W->(0{{S|*D1GFTS50V2cv6R#JrjpB8j{w1wdu`n~W3|Ji)ncz#6_*F8Ub{?Ba9A729ibb?*+)RQWgxGs6Y_CT%IWe)LCH^{N!4wG zVADYWVfCX=WTJA8 z6>W@2#Mp;fLP8n|xCtiAZp_Bb3h&iBh;(FYMhq_z_AB^VcC`SI77#U@AI!qeQ%6h8 zX`8j^S3At@r>&*nVO1k^U%nq|5GP3bZ5(<3?k|h%%IQ;LXPDpF;3MJhvk0*nOgMa& zEwzfBH+$9JY8N6}pZV=p^vZusE5sRD$}>T|H}C)=8ER9R!p)yQ;qs-u!!wm67d?zd z^n%|k%4~B5;$R5HPp>xBXTxPKI52!oj$TRJ7GPozh}{eQ;Ix#uhgVO4XRAOAsWV^M zn=KfefKkD!e>>mkl{2n__az^k11tGqiw*nIc(Aq=S5;qDQNWP z(hM6;BF`K#wPwram)%-hf6L}=A9F?gO^{Tw=bu$L);urimMP0L#HUyGp zPowYMb2YdKBX;T!G3HJgLRJl((c^YsR!?!1m-t%HW=zIG>XPULr6>}-ejqRgM?P@@ zck26bVC0ARK8+iV?wk=kwE`jSdY?C4i|GQ1B=LhSW6-?bf$|&wfb|VK&H)8wvO`!r z%I8rSkeg0#E1XN%x7NGumgoE@hxUGYkCk)rHlEef>yt}}$;y%5 zEu2t8Pk&v4;>0P87E)6vOi3`;_cN3McutO0wCmEnYhSyTCGeQ^H_dl?0u*j%eHN;S z?ADX#GM=eh$WTm!xpf^E=-eo8hJRL!%v&;$_(>Z`(=L@uGF+8F4FW=+j-(auX@$M4^fjXgzC~D z0Rvx(p8g*@?-fladO0%1Kn-#Jc#s|4u8@`EsWb!Yh@p+Jy5F$(7Kf@f2r)r&(V(A)MIx3 z{O#6M*@l+)jlT}Wi1}rLd4p_PE`IT?s^Z0ztCHh;S1dHrZLaD6_X+I!u#i*Z0$Hq+V=SjTtN*#kek657iHAVc-iUh^Ccc)zAoJM-@;w!3Yv-oiSzaW11_ag^9n+=-wADxj!HqEW;gQw_;;Lk`==&%5MEs$eS0TZMv8$EiGF*x+ED%NyH!4snMTnI=D-5i%Ofya~bQ!_R5Lz|=7D}K_K`x<@-*s6BmPI`bF!g6Wor@6z&6>xblD@tIQ;R1IRt%^V{MSAK8C&%r6 z8C-mwb6voZZs|2c7mDqJYdb{V##Yus)`lXm!r;Q0hSoPvQlalF%NL-u;Uk&4j@&7V zM1wA=$^w&G9SN(Mf{inBEi#w+FzeSbhzJfVrMyP$KCcnS-nM<3T$36mSwTAogO=o-q}rL>#&HoEn4L(Dn-y3w38Sfq6rhx@MI|6z zYV?I$n8wWk~MSyv7rW{X~-)lk9YlFg>kfQLHsmL@L zapgnx+)Jk!Qx{3Dq@_Vga2Vu9-2)yHvIS)v82`DUD(r3yL=zM4Z*N}blM49&p(m9RzrEA`r-GA zfkY&a%ZG^=I-MT1br!Uasn9W_$6EKjAj?a#yx&);5WPg*F_f<%DqaDcs*MVz)XjD5*5b={DcyAB z?F|#fV+&_6Rh9eNGqby8DJ6X~VE%WENs7t-LDL7CccnQ{o-|g|q(IZyv|!v$ zuNezlP-BEn2`h@6tBis~(PBsw^O8;aK=d!~jF#F^B?DzW8xRYuaV&~i)r{f}cYHzT z8@NqgKJcPAzbK-`PWdt`L24w?6KddQGBVS(UgWb2HsJPQDVwJC7;%efJSa|`(NMf$ zQ!T8i$lJj zS)muUf%r|q{;-#^6xG4?*L^h^x(WYX+`-?VED0zZqBYC1dE{xUc7-Nhh@jvzSwh<{ z-rqaC=1oG;&aqd8;~abmA@j>HjE*-7S4eRH-b4^XWP%9F%6Ut>-vr<-38*cj=jW=d zpAvOvEs3FCZ%-q8Sp(GGts&5s;=K<0b|=KAvYSXfg3(7~Hcr~aPWwr3TX^rrwY2c zPCsKX@y9a4-hI=pnv4TQ7F)#!X#oOLZO)8CW{OrUMUPb0gv6LAMx3p$aF! z&rP>9^i#x){K=hX>wIx4!EtD6(; z$oxS~Q>HtMYSYWoWB+Ix0PxfDum;Vhk=q-I>U}(48ymk!KyBvhr8V0j0^|qnp$C64 zj*FinN}r6{jPd24D)X49R+Py%Z36zq(HRZKm0J@fVgLbp7!fIXL;`ov5xnDUyUaJ@ ze+5J+BqYBg^9fF#;-5Y4^H%oIA9^Wed+a>Vzp0>f_D=4lFElZ+HG?Ylutny}Bmw+6 zrrd*ol?iQ|pnS^W^cLf*gv+Ir^omrzY zXWmHAWixAU`f2z3zRRB5FKWZ?X~v#ZIg*LT6?~q(2(W9uD1b(JM?>=ieArPF;P}}z z(X}{rW!2)56y#9aQRaxUzq{s^?gtZJX8kgqvqNZs{vX3!({7HIo_#iZD`CDLO6UN9 z1OiqSg6R}27pI_A>TZ%hJj?|W?Harqbr5okcy^mA24`ZO zngQ*#UU=|b(J0^4EQhz;AJ?0mvL0-VzvH&kxeY0ez40z4KZLSNgR!WS^7G-L#H&q# zT2Qt^G?JJoIOY#)n&Ta=GR$kBZ@VQ(iJbqf|=5Y%2` zhBeV#NF*meY`bOi$wLhzTA)ShB$V?^8QCe|d^~~iB9&jG?Tt(#0i@ogzYVa1s$)R7 zD<)!zV(E*Z8NViRkrG<#JK1+z%E8|GG|c#1YIU{`F&|^Vh(OKJM6juX5=<^{{0U`F z`&Ys=E}gI0VSY{Vdmbk;Zu6)Rs;XXX_vSQ z&OiE!=P9=O$*+e>e=Nbcia93hS9qeXc9MdDcOj%k%GkHSmY@gLHQb|w`TUgUsgb|i z$fup9b`K7ix9@||zLmt{eIe4hp8dKRi*xXiu7uB^t7tbEizl>XXau1B-^-X;+w8>6Gk&$6-P*!4{Il|1K<`?KrTV}lH7 zsCMvlJ!loAqd2?ZwmLZ#E0II86QZl5jWTIO;vdb%uTHy@LrPTMpDNE&p^0x?PXlF$)jZv^)_?zgfu zHOCEoltARZAJ`M|4ZzbxY@~q@5E1vm2m2=NwH@{a6KEC{BX{NES3x>~J%azFM^K zbtvfhRYac82^>?B@r?lK8KI!M0~BCFeSB68k>9sO2i;V6>$Ym&kX8vAyCvyQQ9v;^ z;-+_wr8Wctkdvmp{CO_(O|xxh29taVrMUdVh+R8{yOG8x2JQm;3v_+I?PQkw!U#-< zuWN?8pyEhqO^vuH=MNQh-VLvh2qel)ir9J0gM*gF4@W0lSpPz{N2%J~`NGK4i2^F9 zw{53kR+VPY@yReMwsh23C{4X9H%y$vx;bW9$B@W|HD;&hWnSD(^>^Vp(=3&uunGmiX`m1qu9LcJb5Bg^f?* zZU#eO(oxroATuwQ_xJL`v4+N08>83Gi6;f7`M1|fO`L^p!l2c4W;Ad0yC3Y!Khap& zs@fFcvI@jc;%BkgQxzO0-bcIBI*&zrHvHpokG73{2UmP=sY}u1?{xd1TDWZoJP#m zm!*+5))WMYj(Lmgc{|-3beVV2x{4mJ%(HCj3wkg^2^bwQRRk+JvaL;mcNd9-=+)K2 zP%Y{vl17 z%W4XG7GenaZDUG^d(9*A?&Z2eV~myJVYNF0oW8Wuxd~stK1wo%|MdZ_%5SSzneMPY z!rTDuUutGxMv-vbHuR_`bdnKz$mUr{J*90w9}`9e!PK3)cFMlF**dhlodLBJotiVQ zs@>tyRsJVL{05ujr;FIDiGWM zz@LF%UMYy0;J#{E4Hhz|qm4gSNuX*n@Ea&ttaK)651TyeZBHeD?9+n#Gc2rFk&?yA zduC2}OpD!yPy)G0Z8KMq@;>}=i_gcQ?%jzVXg*2qjl;UTU7I(B9QU3~q;rP98Ud_f zFx@ndov-%1NkY;dNH$yw7}k>Ie&090Yoy9;SN{pY)nk*Zn`oKUVn)>URS+whX6h%3 z&XBigw-Pxk=svmWthJ&F7Au+xvm;Zb<+baRc@fx_WbFBxgu|h z{$@XSGYHt?!yo`f)9i_Oka@u4aI=b(O2VK$x)tyWn$wZp5B@+z3rarE);P3xKa(`g z(5bPLO2o+(7l6a@?^OgfDjHU@aMb*}^JuNEUA4cud6|!5**rDL!YM=j!9P+I7*nd{ zIN`>q-LRm?*+za0f&O2_gGwh1@$bY#wOP5Eiv7@`WOgHidk2qh8 z+I(L`^qy~ztgRzGf@hXgt3H1-hngMU+V_>BD5U+a^j{ed3R$AC(1NIn<{uN@yuET; z2SH{4Kv7K-VHtiOUPru+dQMp?JctY~Q6!0|EC#!#SEfCqsOwQsW;>X(@+b^6els%< zG>6>3IPafLfcpUQEIAn%j!{}vB%Ou1sn7_75wSxRGqqzB@3)Aq<^k?v#bK6?ux;!O z`B+b`_1CQuSRDYRpyCM?VyRP18P!3DPo$E%E=-a_V6++l9(+Ay_k4!;^xb}&jq`=i@qjMcXayIy}F2lb)TW^V1WkPGm zDncE(YtB*&(A_Z?ww|re+c1kW)PCu8Vd{_YMhZBi5)E$x2u2X!oo8cDu&c?iZPf7L zjHl{5oh{lTYUc=eIgj2({G``hIh;NjjahCd=@|HvpKb#O&rXXo=ull#cwEAt;>qBdxZ?w2lNqQ8AUGrvAokn{cnp91g6W2AGdw`NO@}2lmVv`LJ z9?+d(%RmsE&1=x*+pyhcdy25-`5DYj6U!pf0ILkVAbgPOsP%IkJxaRXhxxX6ze>F$ z>W-f}1g>-{uHe}ufVCwe-Fl-hFT}l0nU~cxGGj}`V|F=xUfx-U3fHgQgCWa)>((vJ zll>ArZ{~%Ywt>{R#93VZ&Z%)}H>%dQ2jGDLoc)ad|D_^~#snWGQvgghU7xb|m5y6}vZrF6QCCw^(@OF<|)ULm1T5{$({mn!XbrAsNKX!WYi zVp3EIsil-tmxHzjP{o5=h~UZ$W5u&B;kPV#{PNk)&`JgkWD&G`OBS9CQhLxHY7D_) zNr=M=*1Va%`Ljn}y);`A61)h$}Wmz``lHK{82Zgm0! zJ}M%|ATN=RHH+n5K1^u{0FjC3HFnC-8aB@B+I09UzG?wqvE^jh0yzarUOB^F`t$30P<1@xY$?Q=R3Zl$DoD`MOd4~ zY5 z2-)-|paUJW%CfM_znsUjXs>^QL+=MfC?us_o#;xj!urQkM2%2j5qJfa7z(;P-BMtQ zkb2|r@Xii66uNx>q2LVP@U-wVmu`!Rs($zD?2EU-RMl`)^h;@y_3lkWIY}Z@fbc7l z;~_ArRcL}*K9SZkWbo^3B9NXUI=^5k82mp&)Wh_@K@?e@Wtf3_D@?K2cAzOz9p46r zll3FNwfQu$+LNi96@^SeJV^-wwIB%q5V~>~{M!J`APZ-@2z=`H&0++aZ>RI*`k7Tpeu;~nf+-p zaIi7Jlz(!%_b-Xb=74xGD7n^kvE!X~-_!}V?GQdcB(EPN>&jJ4@?L^Cqm*Ot;Hj%i3NIYD`m(`q-F-$=M#ut1jl0xt^e-~bvEc^_}R z=>h?OC|J2%hfiwX>&G{rxFj3ksy!}`FOqiiKYtB8@E2JQBL(C=pHi5*NeMh1(s80k zpsuoEtC`*vEhqaA`dPi|PbMvFJ%xfUdFk?;uOmiK#f7jCONV6`}~{^?FP7 zMS)%rCbJU0o?tg!U&G*ZwX9KI`MoPvAu+(-JU?`H{rz@&UunB9an1cwx9x+bEvol8 zWJG9ADP0xh<~?!XYMCD)0}Px9iNl5rJFEjjy*{M(#n?^S9O1HN_(N%?5PT2Pl5eSZ zm0M~URaWQAd~Jp9hBYcpkc5`~h-Cty0&ZT@*Xf|?HRjHRTNp3gNMw)ROO$}LZXHvk$-(ex5S7wd9C7WxaPz$1&u5BonB5ZX{k#2PzH=r=gs6nZ=AaSp4ioVkTrP@)aeVFEE^ z6YSExQZ;zB8>YPW6$mF&i6)8t5Qo?ef1W&7ermDki2pX~= zXo4;MZ15%;ASnzQz+m$fZfzEY4W4H3M^5&@(_6R#m_($}PKp@&&o zjvQ~R`+a8iU2}L2UlCKYzwp9S*n|mJHcLOCYfLm{hV)oP51kw-4E)I(xWE5>X0zU8 zv0t?zSR9aApq?h2D3r2%m#>N2UrZHL`hy3lT>^dlv^eGI=Jo|agara-aS)*VCC)A; zt=K}r&YPVGP>1qLAXeYsy!ZM@Vb$r^Zu_jfj(WS*p!V6Eez0LesC-=pVwNDyYt{2F`G1?E4R z#P2)s+E-*^T>UmCpjxNrHrQ;g;|KtNifvB zJK2xUFs1UPCcW%aMW<;7va`Lt9|MY{R4ea8N-% z8uakMOnhC-6iQlbKYvSW7g3Zxp@qv){+9LD*#ON`GQa@Aa#cc z(M?y;PD{=gZ%dgnZXPK%A{UjyCYcDU)4j*7q|@OClyI?NtjYr3yuNR42uo}di}=a$ zBCGc(-Erek(EIcK;GcAXijSti2@g04z`$KlFx&`;!@y}~`p3y9V zVzORg^*`PSM4@9BG4i>U^7B}_OUog?+!WZfylEw*>n;l%vD<_+y^Dm~T#}OlDeHp2 z-?#PmP*lvm?0_%7Y||>EAkpc1!Ok~8uK7l5s_}tm&qDGA{tA=PYryf|KtZnu+?_Cm zD{v9zkHx(@s)^&gEWBdr#2Kt&ZkOq4$!=_II(+i`hrKgr&GSjlXXzPcyG%JP-?M?d z%%GMz)MD<-*>`Wh(*(CEk|gYI-kuo=WV7jA*_f8i?VtIE!2i;Qx}j(lJ)kfiamCaH z0Wkd2b(1yV!)0s3s!9KD9+-|UD!($O%nGt%QYv8hKP7sK3Z&{3SWu7PQGrnvj^(6n zbDf<_uQpm}9S`Q55h_pbhx($au2Vj%!^@7`#lRhZ!wAh3`{D)XT*8?pUbjWcsa$U2 zn$56JjfupwikX(1g&_5unZjQT6%7g2lErL(Rr?(UW#tRqUHEE~-~bC5Zoevnf{pDU zg=6z?8&-5u0hRgWn@cv6xNvXUlefNCg7HAj`TH{hWH^sL@<|%&lpwV$n;#@85}!;9 z`jr;m#?0d_019`@+}}@Eh<&SnFn@j5i(j4AAXx*UcS(pX7R<1ZT z5~nosQK`LA%CZ-Id*~``2{FcGF$tvR%a$7!H~{cJbhE^4D~ta(*sMD4U$fcbe~-=J z0{=Ce>FG@W2R5UW5dM&`ih8d?EXBY_uy23R^IEXkTomE50#2XKrh3|K+XWu7wTqAK z1GGk&_1d*?;3>@ur1Q!shOsHGToY?+rG!7a+7FwPP8-d!`%jl$>$sD(4le7O8~Hml zv2t6fp0BTCV;eoc2}sWjc8^n4+PKke_znue`0HvTou=JAEtr2xM@{)%2=;0R&;4um zu&?}JcDX+>)Np?tjFyuSy{|HQa*Z2sO1r-h${6n5-Raal8_E@!p)~h4|=_y>=Bk!{84xCz2?34l) zW{IK*w#Yx58@TPiFgKNOqF~!^Xko)-k!y5~rJ-LGeInxcKn&*6N@Z=glyu@Q=VdstO|twv zGmS|-HvJRb_xI3IH3O6O@Z)RpGPVhTK!U2gw4#|I;J&CWWN~a(Jg_i6Jsupyv0jm8>L1?$^<@hV3L*yN-*7Y# zPaY5#dD#YZ=6nh#I6C~*KJW=nyt)gfOV_)}FZxM8t%JD=IL2yJd11~s<3T|6p~gjv zTmCxb-sKff=z*@^OREnb84$&uylH&&P$%zrVC6r3k>EW{TBQ*$gqO{sludOq^BX zWA7$@HrYj~`?u>3V9o%G^`tlt<}m_Y&~&q+a%pqd6aW}r<<54G%~#Cvi29SghqUMN zQy!AHI#*MM%2_=_6mZQe1ka6ffl_W~#nf~bH zYqaz5hkuEhz;AUtG^RxB@+v2|NYrH0#Nc~JI*S~ z2PGRZYJthn1$74eC={ynzD@0`P;)$)#J*RNTIL}|raGk}oeurq{Ot!){}-bO(n6N} zf*+6DEqDjRBPcKyvf*Vt_#ppZWu~eb|I5tOZ91?5Mu?=wE9#Q^v}#rokEj~ zF5`NAd`JY{eoeIAR&!|vEY;ZE(os-7U)|rAQiR5yQ_m)w0b>E)m!2<+$m*5)Q-QC@SI|L67L4&)yySqzpcZZPR?k>Ia-g`&Yt*U=@ zjjry|#W-L1a@fFH`>Z{m`TQmk*^|Xb;{BE?KIBQoX+q&7e?iVry*D2AZ6 zPdoaq=gM73Ap`p!IvxxgY6%N3MA|_hCc*sd_6qxM&(03544G#6L>M05LMrIn<02Cj z=tJEfx~UDFatdv%KeR!(UMMngs)TtYIOnx1{9RH_*_))t8(kz2Y38RbdL(cDKsy*L z^neoS1SkQ^)GzptNuQjS&;Hqq5A)wxz*`Wx#U`e{?@mF8vXd_l;l|Y zuJrDU%7R8}cgCI6L&$83-Yl9>gbt}?yxG|NLoM1(7DE|0Id6-IiyIlOcaDY7feVyR zYOxmGK4txPFwHjn3#27bS&b40%BUsixNKbqhq4P#nGiA^5q5;a#i9DkvV`6Am8;v@@;vVt_(c+xvD|I+ ziR|e>SAPbj+EhWGo89gyd?4Ao9{%C4c>bTl3P(8BQ94 z*YJoOo0NfPPBbgQV}nlu0}@SiXP1FigjoNyCJ*Vu8Snp>kCA^QqJgGgEy5T6) zg^(@RlzcK7s+=90Ww;kG;!sZw$YQ3`pRrVx-6xoEvDFYDWQ?KrDhREq&4#Quj=f;M z>V#BY6$xlPWIQ>X=a2i?Cx~8Zi?_0=B_*37>!QgTDzOr6dD80h&rZ8Vh7GYK5me{ShRXpq2#TD&h{Y zq;xWRlc4-N2Nr@{sZjFh&!F|^xihoUb8lpoZ-$7p+GMeB{{EWdTvzVA9pvHrYK1kHQTkrYn86pYO ziG#>fl>H8NnJ<&)PYg^2mnX|lSJ~aUdQ6>4EZfa`jsv#B;2@d-2Ja51irA5YZaZ|> zswRdfA2^wf9>s9C=a`od`8ahL3R(Lcxn)Ai>8HNl=Wsv1O5m*}p1l_|e`p->`~TXH z+K+ngGvT+&nf@0@3lZ#JAuU49!~_^So(i+H3bu7ua?gh};_AWxDR5TNd^W}|SLkIpOE+(!b z)B5`ef!DS5^S7Oyb7#$;dv3Tfx&+WWl{n}xq?7chyj=~{>QV4UvxY?~; zes()z!VN-Z+qd5;!0%e!`Ppy9-t*i7{)l6!!yd_vf+81BWWRgKLv6FfJqMG`qrWT> zZ?xz;S_&iO>XLjCsE2b+9K73Qv)6+*4-P&2+645S&p!9AOq4*eTTeBoFs2(>A8x<@ zKtN8PvCleW_jiqJ*t6GLV4O1?=)De-^-F0sEwco}bBk)NC(rWNB@ROef$~Xt_(>|K zVD8q##t%xOwOiR41j?m_sYfSGOzgi}GK3=f5{d!v=FM6WhpFBXNY!$ux=YzO}fxP_ZkPVA=S?_q>vP@%vP zwZ8f~wTg2Sis6%*xr#jJM?OM5ER75c>M;bmJeih38!2K+eF#W_kH|lgGJbv9EU!A- zYLwKsP1N4$g{ZwfrF}q=+dC?0`#G`F!v5{9^!}D09Bak|D0V<1`cr)BS-S3<;VQa7 zHh=*UTUQC#RbPL79_47HgUW?RBMxGE0Ghl1Yg@{o%R|?T0zT2`5^TW42I%hu}#m34I z+MK1LLjo>xy`(gHlHhkSrN=59o0l7C_UVqNL}JI)nj{38${$#!Cy70HpHku8*Ot6 zSn>v0J}wf~>u@`L^A)>G4x=C^=8$x230+bXiO@@cNxCGj6C zwlEuuFyN{^ub(bM%!d~7ze212nUOu!DMxu;(RI0tNSRGKl?N`ART~S`^p0M>4q#v* zxu(snV`X#8p$Qa>2&!hb9*>^{!|(Ak>0!0jI^)^68Y19J=6DjK07?u-tqbVCVuYj_ zG;j%hdm{gUsW#3308Kcl&gL@*Nhv0r)L15Jgs~9m}vnICASf?rm}`7}_(HpBWAMIQu*0r zAxb*h;KYTch2RZ=G{H6b?e)P_6dbTs;njMfXBfin{7|R~MO=^-X71yz+|RMF8W2-- zT$$gz-tQ!2?#-DLk5FfcNaGGIj$Yty^cdPA7^I4?+Bp3M$$IwN_tLBO8*UxhU!4%} zLTwOXID72(gkq0w`lED47Lo0W!o(gsNnuPfz zt%Y{~8k5`i3JLX=l*_=Qb40XIDr9|s+TPAV;p8n}z1=i91p?;ZbeKbEuLWY7_u5Ip zQlfQ*&vwtdsTX+y?1!iFqPj3x!f^3OD-LIPwttTBtogCjr+*@s#qu(K9yo#v8;OF_ z^ja<(1)Qnx@#N?aML##FFP@>tRHy>|W6#eqsvFH7CH>uWYL3zR;lH%ZEO}y?_@?nS z8>p<8zho`%QSypraeFZnBBu9)k)}$5etC_IQ9+!x=C?G*{7Yx5S@`RJ=S=17P!7;| zW@}0l8Zv9gda6Vv_1^SWoL~{Hz6P%Qo>8>F(u&^+oqarI6|I%|sz>G8h_k#0Jfp;^ zhP)O?GRjx~md74vmKH`SIVihm1E&SU@0u!}**n3hX`eS;o1e`p{*|6e zB8f&AMn)&BUuhpS0dD~4(CAEJwaWCjO3n=+9SE5CpMfPqq<;fT4@92kgh;!00vA(s zcl19#B(@#+tf}5NF*dJ>TQbh*ABh)~SO}3@wkG0<#i9OaSjVJyM2jV7y|WFZBWaJQ z9lv@u7H@LTN_CH@Iy-mo{u{Ig#H;N)B~5Ydb4^`ajHgvI%&VpEz1(LD8n5D?0cKVZ zlhY9Du|R=(bFOJ9>1|{%WjaOqsVC$7KW0|an`zyL*!eVe=&SX~M*;a^X*q=-lO>0j z@maW6_IVZ`*1AI>l9$uuXb@^VQ?Bpoj%iadl3k;Y904;6ajarW_S-uJ#haY$%i8?a zUA;jbj+iIu@V8+I_WV>ZI&nOt=C^xU3dwgX%kEhGwk5XMduc6BHc{i`ul^89SXo*7 z@KY(XQ6;#b^0U;5Rq9~zb%8(OBOuFt*?oh9n-5)Crm&<7QJ?uu7O?gU_c3>_b)|n) zOf=I5^A4a+nizKU2At1KK&8;ZE)fK#c)vCigTVR$L#v9{=HQE#3!4-%twqGlLY4hX zhRW(GG0gE;x;0p%&tAasgXvO|+q>29B+J>EI$3il=?ZK+0f(hehuu|Gbk?I(j4}?p zu#&86Ne8xMS>!a~r$tS5McoZ($dy|4cArwYF={KakF%-9hJ0dlLw~d^@jx*!Q?>f# zchuJ^Vk{2R3M}Kc6yc@@KH9U;pqrEDCC5kt1y1c5@4QvYT?LMBoRw0gJiSjp?ieES^&aRx+pbgL=B17o({1ABwPMKxM@(HhkT+3a zMOCa236>%gb$OlNDbbJYUmqNpUIrECLk6f}IE;{N#~xoM`Wy$qVUPbtzQ;4mk~sfX zrrY`+rVVo?;=EID4_U}jlgl(RMs4>drt$u4YzIZ*Rc089q>87B@y7WApN774m6nmf z9T&Sxl)iFqIZA_IPZ*>IB)_N4R6*#2ao?YCv2u?%)WV68N5}p zfwFj45CXBJ4v-LnwQneR@}M%js!;Ltu1_lR58MhnqJfCb0Y&RmM0`7-XerHh%VLty z4-j4TcqQ+yM)z8p(i^1-Ac0EuD1UbU$RoCSk9%^@zXrdeJ@%V7`@+`Eb!LEDZ@YE0 zw%0tSwahFEwni0(Y6k*2WSm32^TiJYS9Z0C(J$?foA1UNCva`mrjNp3tz}m*REz+% zA_V*cihGm|Be=AylrM`|`wPC$WYv!teyUGQ#TjpvwAVE7a%CL7SWqZU?mjAXxpI5Q zA~vCuCJiH~(ppq%BOLwj4A|-_Mj{hlX9T!#AkdM7ehBD#LqD?891uPA?l}ulD2t!BC$6L(tC_KK|`N2reR5gU)(9IDAZ8J-RQ* zh0tYDI#$M3Y?2@S?zs3*X5;GLv?@U$QEIWu!$I|=e&{&A*G4k-o4mJdAoiJFM?jx- zgVtqsaB}S&ecDl9Pygs^G*1HwWo`l#2=rTIs8slItj|t9X1cchuwAZ-g5$Qc`c%A` z5{FICl^(eOTTEkuen*~QbN`59tU~_VSFc*9WH;*u^iKHdd5)6Eu+ozh>paU)Bj)V7 zZ`PrE`m#9eg?jp~KpTPi)?6bq$QC2j9$#(>QlsV}VE`#B3KiW<>mnNoaf`(*x5y|tt=v2mg&El!6{{BIE=>!RmH3SGiDrw6S$di~KlyHg;z+_&s|9a@sSXV& z!lRNpbdD=9bSqt2lI8s#z)4D)qOlh^Ni3hWv91)S482=a2!)W}aBVzyF z*1;dZM4@A}r8Lbe2lwrv@VS_>nOvakHB^a6UZ()3yHnZRVnhLCCkfn<^HnlUppsO26Nm z=7?)o%S7ue6g{4h5Rkpf6a&&*WrqQ_LzPp89-58&zxGe zSj^amLGQhd;6PB!kpR85az#3(G;jLDx`O{GF)cwfU)c&RtIIKkg?^$A?33k zr?>PESt1h>1Sd4sIeDa3}(~dD9mvv=TB-3xbjK zUnl>g7XV1so81x7cxU*hDr%pR936*xfN++=`jcv4D5T>Eo=xO?#GUez-@ckETqJI$ zZjpMl9No zE0#MLc13E#aEu3YN#%^L$K`U4nMmM2#m9Pe(gy3O7lM|He{1ZlNp~CciOdA_rI}qd zSwkK6Nx!Hmue`|mJxOiL@v%Cykl{&w4bwjc%dH5Z$o{^+n6UnDyhQD<1ogUT13l!z=1a8xxt1n zS#}aIw`TL{7!4feNAKF5tfM6i9S(==0dq@Am?k`HyVgXn2C^9|)Vh-Eth0=StS}2! zP+7~FrN>VEsoRSB zO}@vtf(!^wDU2Zq(lnsLLER~S!}w*A;%!^(APRhhZ48~-8Q4F$lxmpKW|y6a8UOKL z1~roG=mMp8QtjQ~NDgOSXLg$}uMho~x8AHc<_X{Iv{Cq4nBrGwIiOw?Z-O{9WRu1x;dW z{!R+x3m%P9A+j+XY6Gj=dtarxjyl4R8wOKwzncRW%(jLhGe&qO#)#)0hJ@*0QS0qY zjNn|<3?#AvcZqdf=S}`$5jPlhQ9EX{$ehzfeAorkq;$-X4g)AwzhN18D$&vk zVGbFZIS(*+3rxEvI!8Be&A#7=){h}^lz&(j_}QqQRgW!q`#eY1DQ|Y;Xnrh$q~kQi zsb~Sx#J~OItZ4(RsE;E&TOtJ^Wajzmh>*mdFH6q4zO@toEYkRTw;8$hGcc z(*l1ZeI|Zj75JHB}S8p%tgpoZMpap_yo6p6i-& zf?lV#t^uEON|M@AYO&KzK`CK|@CD7QZ4pNs<-aeZTLm5sD#|P#Kz#owsG4e8!I-%F zZTZ;HXmyP;xw+khiec00b0{EfDZjJSE?T!Wzt@b#H%HrNv$w_+*BR}jn!aH$b_8n{ zD&hy}8dy+7KX`W;rB2~wcgNSEehNU$kTZ!);ZITl#x{*0)vf+sJC7?9u`&BV1p-Y! zFtM;uQ@?E^n5%R%j>0EL+i#^}s-#*SW8P4w3+E5+Z#HgK&~DU5la;2NmyMHaosa{G99wgFh_WxPWAQH$Jk$wvYf5om z^TeaC_LWNkzPKgm+DCstpIn40$f>7X5WJKVgtkw91!rorD0Sr*N?A=hbzQb(0AMIc zEQ=*|-C-e=Q_#LYGQ^M#xLZn>K3}}Fw%&1gE8z!$>Nr4>G)|090>d)$d4P$P5qh88 zJc0hg4O3s+5Uj7VI&E1>$~4(WOAB1|V8NE-73{~#!a;L`E$-O%U1`FmJtOX7IxFWR z`t-!3-`_dma_Lx2idqtswmNlb;QJ>~S-9G}HEwoW5S3E9ZtLz(Z|<3H|GA22?)Gn> zw%`L-!xD6cK37t9`rC*(+Ry9urJwR!#}{2qny!EB4`dcmr+ARt*B~SwD2FmZ#Wt-A z-c#N78PaMOHi#axZR z@wJV{6NU4$KQ<>QAYZZg-?j}=N+Xn3!p)5v3Q`o|&2U^+<7qM?lPrQC=Qsa;K9#3S z+x;zgis`g{9=D>)Cfew1adBw(EKck(^F_u5Gd_;PDs zM|+P!ru;=tyOgg*P%Dg^>P`|1MIANCYRYqambpZsJ(5m)O0Plnh)+Su_qvH_yJ|2o z>4$YR(sh!_79&?}-PK#Ub601UR`lk_N{`L?)~YKsgHylJEVb-aylmBxcI8tP;~;6m zOB!xs26kq3)WL%2fpfN{7|s_qbyi3GfwECa`cH_N6%0`{V#=AEQjxK5#5%Xbf0pyg z;ZvDngUB|5K0Wd)fC7TC3#aje)D1#$n$&j_YZg9YT8*KCLa+XqTcPlio4B@XuIAG` zk}^5(@nYl^oK@hAVxJKiaj-S`r4(QT6;xu5!xO!!fFmOLlvIXQ_dDv9>ACw~Hj@Y9 zgmoi)RLfRg3r=ox8<=Bmg#5qXgO$fb6O9ssPO`t$cpMS=i*1BgM!P4Bs%92ek92xV zx;FIUAC8(c!lx-M5SP+jv^tq&Y6fN&E_f7ov#dgLHwwn#aouB0OmQI6uNl>Ddo|2o z+=-24?cy7?ZI2hX(i!+QqmS65fp2&9x` zQYC5WO7?7~zc{MCpVyFv<=~(r1EyVRaAw(%DMp0bXy57<#1FJBOO28{H4l<^27*dt`N)Q36M4{Y- z+M-m3CRUC7D7;)qTu&+kBv+CN`*&9;5(Fs&yMkFdJ0&yYZv4`9FrsF9RjGWaSjWC4 zYt!LZxSQHl&|RY`(YI+X7G;dj7VP9Ykool?T4Hu^KRw8*H{vLI`@SH`OS}$CI*EgP2rLgs6Jo}C^_HM#eA77zv5>v z<@lUaNONw?-)IhBIrgE82zTq%1T`)AgR2^qVHrB2CO68p)33vJnDHAo*`OVz0VE9TT*ei>ep){%ttCY29y*5YLW)r$$%ZG(dWO1kC{<69akH zWM(ah-{{)EpyR5g(@?MHdpHqp8|GGbIcg0wViqo(_FqGR%#pL?r}47U{iQS?QKTmVtnWE)*{m`Bx5JR_wfR~$vY91Xsw?%f3oU56+tTTE;8 zhyI9I;W;Y9ch`XgpO)yYeak$|FtuK7FKnf+*LS$-dR8fY89|`WU^xXPxlT5FBm+T7 zEuL?`jcqY@nPtSb5en))|IL?;Ih&M0$ZH5rY7-qf9wS)^V`+eeD7Mq*y6X)J#64sD zrd|jVYfS9EarLI|LE>RzB985QtlnA3mWdKqs|5)3yGxza{Nh737K#9O<_cqVxf1aFh==m;q3tXTh{uwu_7P&*~F+Y?@iO zjdfaJ!;x{kRRJ!p2|3oDD7_l}S+2KL$~DfUQX4__A;R!7REZFKxWgfvP84^bf>SPQdjee2GO0^n(1r}H$j+am$`KqcJn!D57# zxKGg1kaJn~!`x=7^3q2y(U0kCj&e2T@J*VffDcRco4WvyelpJ3)!BBRKb=m}0=$)LBOC@}&&xwwf2%0$l9xc4DhK*fqBbxV< z{X}S;+S!yRy;bxO3z&}u7J&G!GJKR4iRGUdF3>`9+7sQbL~PfzY^(P7mzLq{2ncL; zrdVHzjAzsh;>4+?^2x+CtP~mTbn+i(8)HT+OhLnlN#sHVXdrFc@UmZSa!|~Iw7^2! zsuOgLI3yjIg+ZduypPjDs3mNd(AQAZNTg(+2|0)NFpR-en;jYAEx=|Yzs<>Em(1AE z)=-Bd&dn`_Z1{PkE;K}x%leaa0CQML@?tn9=kwg6+ow6xUXpu-k1e}ymb(U0`%$Of zZAY5yOBx+z%F`h=AEc5pW4$>KxOAPcHPVE3*&V?BCH)wYWL?)sPAzuno|3gOk+p2t zYy6j}LP!@*L-Yjdtn{BHIP~>u+lJ&nyy9^<0i}?kbiXYX-yc_=gui1 z2A(Y6ICpysbmQ0C?AAqEBX%=y;dxv|N4~ks+4#$egDpT}hC>M=kGPv-#*Y{Y?c0%8 zHE#DJz$a?hwNL%Tm?js;=7vfkm3DKPcN0cN@LVPjlSYBA-L_tT!$$SCxyI3Jj`@>R z|0iSf=1Pd+CgRVUt9uv<$ZzGLG-2(w79sJw6iH-AXpPk$d;Jjuv-g!DgJs(7Wma@y zxaUwg)s&-?24FP77T5qP>f(3Nz8f*@v-ifUdA1!^Nz`9y{ODS1q z7R_XfOA`gWY`NjGf0JSw6Cg{Bm8d49oNA?(a9TXs9?#Gq;&~0^{WcTjJ+v5!=u*0 z@35>z6H2@MN7{zt>$N|hkV+R$7sl-#<6NhX=dZ-zZ|xiDxJ~#p^oiq@1TVyiW-d(T zOd7p2+doNK$>Bk`+wH#)QJNGM6^okB6T`YW&bx_$5Ik2G%B4}-&`@9)YT43NalhPu z-aj>6(qN`#IK^MsP163@8K;$ z%Dz-O$M%}2WynJV`csZLk^44^D}BUwPBm)LU%x6z48B1lqVIZ!e8qu7G4$*yW1N(k zq95LGO+b}KP~TulZ&djh+2T8h6%RH$nL61$eJB*(!9s?l<9WBKURQibgqWu#4JPP& zR?`U_^}u>vx6p-j-Iu3(>yE7A1l6ap^UL+N9=M7d)^Ly(lR1{atzO4rmM+Jt=+EC4 zVlvIwH!3CVfSMATE05jm%eRdkJt97dG~z;Lo4~x36GeBX7*)JnKJkj$iky}e%XDF+<7p7ZBxaO(aHPZo{FS$E!|{|hp~;|ZS7A%cyC?3H6!y6?=w z`&){RKWw%Y_HT#HR`x=)+R6X5N1 zrHjA>9YQ5~?C$3_qXK2#(MRP!H?t%tICRFWLxLb54Wd^j9#GM;b=P|m2-wek;RMSo zti_gMx(P!!AM_j0eTN~g^^&Xwpo-sY%&g{mnsWB&rz?luM67BSV*K7OHRosPqo_S`ToYd|pzTSMd`^T%A?x#`?mQ=PtY2x@`iB;dlS^c&~={`{n zDwvJt+9gn!*vZTthkS;JKb(r@FHw5Tt^!C`gBq4MO@93&_Yp9}^lEYJDF3PN5H5Hj zVOfzS+cP8>9OU;DyF}9C)vRHBycTRHkZ% z(4CIQC*b~(35A%+E?S}GQgAY4L*x7;7(66M919*>wA8=sPtt0NHUcU{j&~GNd&5qJ zuR1MIv5;1>ZmUh)t??)O;!FPnp|j+DpWuvbb}<@D?p`{xq4xTY2dW`MBRQFS{ZEv~ zuoM;WRO9zB?NFxpR#%gbM&^8C_hc7eJ|gFRZrwg}DkUzLY>Ny@Ek2{>1mCI>a^KoE z!d#9R#FLvHXdy8O|Z$!hhm$uCM(*i3DDfSqiyuYYnYzz@q_x{AQO&vO? zlJq(<|1k9z9A?jjbKvtHZydZpJWIsBM}RM5%ARaUz7iz^F^tbns& z0IGi$k;~k{!2;0x2P$V@waT=;m7*Pzkts}NOEAa6$)VI>`(AJa2+w|`Anr(x`J@y`x86{edDqh>434C~CXRkwF zNKOE-^kHTB>naLS?H})hsP)t9h`gtjPi9XzE&2aAOkaJdK1L*8zGR_bNkW6Zw{*mn zIpRU27+70bzS=xVB5NorA%F6lC#E)>`fzXE{`HBZ)8fB!sgOt@KoNC!Q?<~3Q&>q= z&L`#yk1^@q{9D&pXCbWHCeQVHoUbvPtnB|jgbF|7uYOhF`_%lO^{e8XjGKNW*6m;a z%tJ%x2=<6iy5al&d+x};A+C48zH;v3bjT%n=A}V+P^Uw9&sDy$*D^=;v z#f;co-hZ^pK+#sn?<3o6g~qc|ub4|eL?XZ~<`0Oy$tN)wzt8@@IN>0SF97VTej9z) z*gPeJmWVw%#}CY_!B{UMG{C?p*Kgy6wocG4KOd{@ks?yMzUdjAuOh|^iA zG3rRPY~hl+Dj8Wnc3feY@rq6j%&Nj~TfD1oS%w74#WLQPQ>ALgrfpr2nPdWXBUQ(5 zNN}@p((A>ea4~_ZN#p3r%vKx{N_ml7z^tklP2=;BYCNDyEN<~onwVeMYLz1mCS`e* zTke|-)Og2hI3~v=q+ly27~GT2V};>TNrg79w+}8t zdSF#EPb&$Lqe6l31={QZgOnW^}9{&;}piqD=1mod1|S+a<#Rl%0m0Ke7ivV@X; zKh_hFqw;5@L!Z$7I3MAg-V=K=+YR=?3@1T94+V9)x`Hzr`2S7r1d zvNZlip*fGr9Ve!N>v{^7OUvTCVG%=s+8cA*I_jjS@0lAh^w{*Cn=77@fT9+i%Z!^e z(7Cg|97|U}Z@6@GFgFv)Yve5xQSUEf^$f4RN&~+J@+;tdf7*z@c6znhB zoiw$*n1MiFK99sDDlif_(wR~nS903ze$7s*+>aY^2h=N%gxy`*DD4#=H@nkIDmsSO zhf_ekl9Du?Vc|`xfKU3>BtV%%A+tc59 z5>|px6ZxrqruM(V&J28xNif;SSSb-H(KlV&9u+XVlds>1|7Yy%^b5WiN(f`aB{Hmb zTD$MIdO3Z0u&75eGccUsh8tdQ)wn)6$h-FQ84?9V1LmfdAvR6#qo8tz+s_HH{nLOB zGgT7Rnw21W$scLw1S)=RtV2{m+|k10Qo0U-Y2Ut&$sY%r9SXIL(Ia|5Az7x{J5?*+ z5D=J#4G^JA!0z^+uT8*Ssl3B|WghQpn&ZsVbbUGd|i}ur|pu*kB(SDK+MypzmP#=WAB^Ow-fv2z)E<`|6s!AOvD| z$H+(KAK%9KlEF8X@`UZv(w>to?75lsQuL5}W9K*B1|2dEUEJ ze1OKUR;<=8#d*OcT&RoBhbKrf$2VJ;y6@D((nP^UuIx>CiV{FJ|gwE@d54f?W!sDyTSMu_M}B%<`7<6r9@Zr$OkK85|)9& zh^Mn%Wi4#Gq?D1B-<^4kLko(gPm5!l&2w8r^D5LpDlh-h$#1ZXy5assUDv&m8Zit`)E_)JaU|$T{Jg=EfM?AmiU)o zET{))@A=X^uh@zf9Gxh#grA{&UVna4Ulw&(Swmsm0Ive%&;dX?v;hoA-TS*Iev9yb zwuY~xIy^ilCB)}Dh$ZKwi?B%ne;lV7AgQnLQW?&KHv|%N_13NLats+T(0(|0wr+DcEWtejZr6+x1n^Uml|= zwY+X9n1-sI$#7To-L44m+1};T7!`G20NXKZs|bsuo5fJ8>o_|`j?%4ZY|O8UlBdh9sZ%q#?rrwj|no%O|fodp5wSRvR5m)1-7M%ebG zYPa!1zrcA3d7^XpHYg9eEg1Y8A=r;xmiau@Rn#lf#h0UPtv;6`yqKzhUX^@4gg zKBO{VPD8Uci~W^i6A^{2fO@V^i0;D__c>q6FV&_tI~CAochXsis|6I)_3Tf^x)`CjCaE81zD-)7 z4Qq)Gq}uiF-y=%7HZ^EkzbCLyv7Zcz6F3M?A!~*4etY>A>2+U7VIJ?J-}c=F;9d)T z)ShqJRbkp-{{#?5y?7smrU?!$tkH2~eKekEZae4Ik(xG)$@=ZP+b3X}x%Ru;kQoUW zO(osQDdU^(t_q(3U8U9L5!ZVp1ud_%js|XY)Qw}GE(Yf!U|8o;{FcP0Bfs%_kvMms zqLwf;WIMiJxmnS@Z#G#X_hwff9RFYux>)l_;`MH%*4esqq3?2jn6Do~nf%CUFm_(o zbD|e=`f*SRoo&4#fSK^lPYuoGM7rtd$$RjKtW@bZ`c=H!n})MkWfN$U@M{OUhnp2%&a zsSd0(t5MWR0(3nh0hRCzYLfV+5$4UClF?1G2Z&EkpSs2wx0Byjahz?!C!My=EbE~4 zF;vgqZ@$7;>MS$Q*|cUU;S82@*Ekp4K9JEupU-oSXaG;z@pYEKD$x(@*>@DlmQ{}5KeKQN|^&nUU?I(YWC z`9Wa`usToZOUBo(k$c7bhF6$^7r#&G6LUrY3Hn(~Lhvhx@}qjIX!vkN0}0yp3EPS6PPEa9H|;ttBc6v+X*!J=z4*@jJ@vuyEcE zZh8^oPZq(?1^Ve3(+&k*i*=OupNp^!WFBFb&!w%Cl1rPgKvMFat2F!9&xBiFWVLtW zCv2-CeuuymQ6SA^<#cZiGR;=nmWfF+#Zwg*kwQV;gNtk}f(ce_)JoCX;Z!VLKE$jB zXUz9i11kKR%h+mmSyrkGcimdTUh9a9reCANn?7*D1s9Z364|HbK%!=7__=Y7MPyx0 zm8?bMM+?jm8i^?>viB6GH41lkgfRLlG#gXw2{nyAz_2Oh#TPBB^C)A#lnnk-gN6oy zN}cg8t^eA(W1)%x4)``(bB;kbw=PM>8YH>L!KB^J~RP*M=M4(V^VL<~% zU)zS!=vE(_XfHkK{ZqJsaOVOz{%}^P&O}jIp{#YVGL>571oS7ZeL9H zf0;rJ2mCKlD9yc#4$}wI;bOACXbCKd;LCi379A!icWFQKIdvpYP}jOY01uOZ7}ButwZx&*dm+WL;dfC6QKl6Xu^KD(^-a zNCMCWzIkRb0!xJPS7|WuOa~>nq~R3_?WSeBnwN;mX>y))+6Q5_xcx`@zbm9pj|7vb zsr*W>jZ4U|sPbIAXzaVlSvL09vGdu{?zl;UwP)vrTAQ~ab$9t6p7GmA@&^^HA4 z^u0$@jml(_V(;Ytz$UtnX0&{rIwRnq!)#1C+X3xc5_Qw;@>{26;OY)hnG#^Pq!QYZ~xFWiNu@{vy#pW^bWuh7Qd zSe2g+PJt(n;vMn(f-B=b_7b zERLA_&POf!DVs(4N7t#=6V+;ByjiZfN`?A^e*#CK(Aza%z!fC_+M_>AT73st9Hst}BYaIavbwM*OmX?F4#^*)a{9vwl_U&_Q^Kh&He zuJrbSneggA$dd8YOSd_*(36JDbL5WVrzO!%TGQ=$&LLD&fSJr72 zvM?!P`lSjbgsQMKpU?4NxU?H5tumA9@~rRs*h=PNMn~a6s=qIJHJ>MN=Gy6WZe6*9 zY3Sx%eXW?A6Emeay=`QP3E{ed%y&AS<7aJ;VX0u8EPqd`?%2}+DIX4HT-i^J|EVMi z^He&57eh!O^U0D3_Uqw%x+_Rb{26IIB(O`o>a)%mrSaw@(M`Wt* zctZ^u{QpPjQp{dppx>NZ@Nb?J;Rrh34&mBWQ>jy7 zD(x!J`DdP$tj|n_IZ*EUJHP6~8gDms(lo{OEeX4*IrASUFWn!NBSD|6?_d;Zeugk^ zwR@||Ts?L~?Pk?%_}l+q?7d}FTrg@dhYx3e^G!|E|m&GV7h2~R z*eyD^CN@6)p5wd|=7yxj$s1rNbSX`L(sr(fH&Pc(gQ+f(!_G0iD4Dv7eeKs-*RTfQ zx01c2ZI)fhV5ZEgoKSz)MeF{7s8daV@rGyyBMGZl>=7`iS%|3#Bzzq#;e0vYf>uhc z@o;D(j3ASB#*53PEe9nFxLZJm`c%b{A@A|X9&S$~?RO>q~c!}|MuUpVT?o`h8%c9bF7ci<$H*srU|EP98y(@*Z; zZUmAnE1%|G?_%+fcj19{9_M*lVE;SBSzW!9`zn3E29@*|ZTjnHxo24(@Y^k~e2S6l z{IY)NW?KpLzx~nDFWv<^XKDP|*3W5dVW=;4@AtzWT~F+<$g2aW0wUkMi`hT1U%M3e z#9ZqRZk4fimw+Iq+2kJ-#BMsC(RWZRnfLQ*FT_$vLd#J=y=M<0_m@L$bFVd;oys~^ zQG|2uN7Au^*m>XlGMsJr=Zg7Hf1Y+Y0@BOoJLQ61%<<)0;(QBEiTA5A2q1{uanhc;^`e1h52qhP1GKV?`)~DYCAB_T-&Z1(8FjRt!;jHsg)UE188jf7RX0i^<#x|)*-d{M zc7JUO5k=H6eNa+20|!c*a$9eACVy5iXlSiUMdR1$&)B^{y)_miJ(e?gE6PtP@hw>5 zLrrov`B-;~7>bO0am7vN3<8h>oQSn-l(LA*ox0W9WWj!@z<}UK8Xk!$Tyq z4A~BJD&*TaKNAK%VV6SF_6y3_ZawJ+;}%&tbz~;ze-@bHipc$+2BtoLeYfe(CYURH zKcsY+{W1I%_Vb5Qi1tc0qly$>-fQfs;cet*mT+bFcK|~u6eDf!H=B>@ZEkAB!TMMB z9LiibF)6L{pZySlM=mKVcmvv_Y%D){SvOAj(eK;!P;#RzEeB4%`;j*`I^o;Stc5Ln zks-jDO2Qwy?IB~RRqigw343JyE0=>e6cKNX=bUL1Q&^Bub3{}$Th|NXjvRKT@gh3b z$0JrWBZ8xS<!V@$F{jHzh6{|DL8p2dRYg4Q-Fdw+*@-I?pEyLh^WQ0%!<#MSPKIM)r4W z-{OWRc+i@@MnnHg&QTQ?fdw#PPGsy1X5W;9`a40vqQ&wv|L}lee}rOu57yS!h>shg zs3THTSx_wBWYzBTJn@5DPa%s6qr0=F7~LXRP;@CI_-)oL`PaVZC%@=lTuHzS z&@#-Qa6NlyK)CH^g+J?uIv;67(_Gc@N!}Zn{$)K0Ob!`dfO6VBZV&F25>AB(jOT{N zF`B>w)FUY9AH3_=p_$I!B&1Hm42}EPCaB?D!s3lHtZZum9b$O7YK#Pm9;zi4WDv{~_`5S$P{rS+oZWFyP|-8&w$BMp z2kz-@LC>}Tgh9Wit8Rrs0+MKzF3#rkbDAkxtc zzOr)E>*P;M#-5y(=PwQ;!LZ zE*WS77YNTBhMTMxpXN;xfYJ{HIeIuPNd79b`GhTD3e>A1q{dUCZcsN@$^yVy@}7n) zy?s>G#P#~B86e;ZJtekmT>-ZrAi?!ZD2NXKfl21x_`AakX!j_k(xfH>cK@w zEBpXCZcmNQWkuQpUk+#vEQq}?s0x7sMvTod{KeOZ%*b>nWJg$Az&oGf*%^`s%)X0! z<4AYZTr^JdE>t>)Tv!DxR+w_g#sdhp9{l)*O>WijAmli7wNf1ZE4$$RAL1~kmAgm$ z2;W7^)l3Q&M_($ecawbN_T8>i-4v$?XUd9D4G>4k2p|#LSIH-hksv8zp$Cw@edj|b z<$BWi?UN0~RheV>{UKKXUJhcF%Z4|TX~f}Ja^t%a9#2>({5hx9r}*6S0morNd&!|~ zsNM3G0y>;uC|6!E_Hy@k6JtpphiV^Z;ok?I$GA^;A7WS(HDsIoJ0KcG64cINyC`_> zP=R{t7;q`=4?6z|(K}?T@}5*BN1|HaX=!EVWYpN{hOs8T>Z;(M0U|QV{|kU9jm)!{ zQ{0~%>s&@aQqM0UM6)1lsiqlyIVSAbK9jWOpGBycE9qT)e14B6UdRVVH&%Tk*Q@sk z{O_SrHunDu&}erOT+DoPQHzmhg|*r&q|5(eOm-l`-=%B@9Rfr^Icy8Z-R2-#S(V$R z`jB7kRI9_nyl*)ldwKhL1`(5S@kQ?=Yk##CxlpJ%6D5Bb8=H%aMHJpA?$*=JF*FZ`f5~QstgNI*7pI+x&^_-T>md$+E zRDvbFzCpfOIr^{glOE__;ir+mWLCMBD6Q`*elDw9JC-%xT*{Pn#tgWolx;bvXkV8q z+5h=akhZg~KqyL0R#46TJh=H#6q6%d!gG!NbX~ZbB7MXw8YA?oc6-N5828pZAA|88 zzapaKq#5#HMPW`lf{hn{g4EIyd0qxMqEO5Bq9{Tums~0mL_*{G>llF^4H28g%}q@$ z97u#{42Vj~Gm>C_8Rbq43OT8^%@wkYL%YV*~428=@$H0&d8P5FITjtXBJUM4ze zs_na6Nh#p*p{rBQ%U1lSrso$aF$>tf;&`5{fx(y0iGC0K=X8md{6EvBNZS7=bSWD- zw9?m?VO=#@>fJ^&d7R+g8gVR%C$-SW4Dl!^6LMZRRZ@qkYT{lAD&c`sq(7~wD0rWU2lBiomJ z?X{5?>?3rh3jaP?>|sL)oK^{jk-8WzaQ|%Za^6Ie)BaAOUkSm*!TcOV zKi=ET>Wpu*3}!)lsC)8MpE1%$s6Fck`9i|3p^d&vj6Lkm&@%=Gg-|MpwwW|~JVI3c zR{Y;UDWX7%p92DRin_NClUN@?q+-Z1GK{>}kV>5$KLQiR7z3pr8C~rsO`hnZQKG=Z zm_nmZd0+5WY8AIhNb-P5 z#`*lTWN?H;=-^d$lTZ8?|P(Z{@ZCpTWbsKTfY&3wtdQ`DCT>&v* zpuk)pn97MVGpYhcD23hvINieVNw(s8jt~yO(bXSEM{90@9HA#8RC`XQwk;Bl`X^Rc zr+FVCShfyWXc=L<>M<|ejl{wS*;aQd0i&ijKiD$(A``0z=G=|;=|g5!nJ;ynM^`w^ z$`0T}kndLsHU2q~>RJBRMC#>#N~DAoJ+NJq$2nOV5aG(N`&QsUAW0B8g~={XvXiJ) zCh2in+pV&iP{W`sm^x5Gt?J*4g&LXr53wBr#P_}SXOcwXra+D`wz(B2x`b6A`IF`T zcAOr*x@f`OHQZYBnDk$;iXR%({@YU!cBd^`$%B>+OQ8!K)E6}&9I4+8*-d8mOd%x| z3|)fN7OJ41doS#|N58`##n17r^S`H6Eo@`MKc(Sw%h4sVctoiyzWt8X`HFg3n_`1a z+{FDPg*9Ng&PrP0n^)^U+evGY&Z#73V>3ZFHO!$ z6w2&TImaDy0-1iKOvX>KUUd9LO|}T|ANr*mKDZdb>>#GOI&gJjYoMpkLP9Oey7oA| zNg5xSqYay+nW#U!33E+uQ2!~#T&|ME^_sRHJvaQt=k#rY_byW9oTP<|# z?~hei30EIcVN^sXmK~cTgPKjnRDe-eGUmFc+N)p90MdsVh|UOy0hPoFDV#Rtfq%$& z&sOMXp+dmXZ5yS#=MxY+?9x~4uN<*NTt-z;)c-DdxAW$0%Pr6KFlXA&ON7-CjYBn5 zlxWzY>KVxghR@$)uLG}T-$i9*y%ig0h?9-V5mc>~3_(v6)Q8b{u=fMX*whmaXxn&> zT3$ZHWt)up^(;4Ev^0SUE%6}c41!P?AzB z14y$9|0c~Ud6i~8mv59E?$3b9AS5J|Oe0?6wSLQ#%-h%i_xFS)Wy3)PMa?e7OaV2A z^SE2Q1>pi;E>@l<24p1S=~U|W+o?h{2t{7hF(MawQRem0zDj9V&4GOJ*iHst8xDMuG<3EOMw4@voFJcBFJ%M|lo0N+CI1NV z?3{^W@j$Y9Yp-A0akEoX0uXRlMo1TT456*<;$x-AvBN{Lms-4%aFW2`et-;gCc{bg zClbvRgaT`#$m&2-O1Qh^SkORidKs4o-7ahN(Lo_k#yv8jL9euriSP!MgMUG-+)%Go z?wMklcBLrJfH{C~g^pn(=)Zm#THZN>yzZh&PR%k^yWw6EL%KirJ(BiVgNDni`w9&~ zyfQlom3U<$^G<+bCmbm~vXA^9G85X=_fA7T|JxLj{; zhVRc#eGounW;?kHatW%WpsNMRe+<`6(BImwc}8>nX$V&B`W&e#fz@J_XPr>^w}wM8 z(nRSQQPwGXFuu5?WR^jdHal33^?9!4E#6qzbwJ8ous-goybNf?K9cN&`Hf5KdJGB5g1 zBsEJ%`M~w(7u>fEc=_OXJ%)KXq$0UW#4vR>K$r^}p=o}qL>k2j73G1h@^iW}s?p1* zha;gIC5C}v3+%DAC{_5XXoUonmuD&4#pK=kItqglAk0M*M?_6QPVa|=^X=U`V1Sz2 z{Qb}-UY&&R=rox3Wtk%4K`&v`;=5am0FRVXvjhn3iLV5%5KzJAO9IufGDO9^vvxua z#%y;^u643Rg@l6Jo?i)726i`FfU)-~9^8dm+0muTj1%eE<4cV2Q|(?x==FY8AE^GH zMPlG8e0s5I(i)vRhtbl8oU>ZX>M+G;b(qRj1G4+%bXsr8n>k~UE^$vNBuCY*;N zl%!U!#$9q?WGPhz-gg13T!>fB{MS?&U4+~_Aq5)VNZju&PYFqrhaHd|pryHZ=9sQZ zuJpKSU<-BC44b&-%ZK#-Z%32xc>Bj7P_u?W~?!=RoF4>tXnG9T&F3Qn_nP>&w# znZ<Sh(Gdx<_p*KcI|y8@_}Y77Kz#`n}4KP~fmm1X<-Xnb&A zrhkrVy0Cs>ayU;c&RT_=8EipZI+ty*eR*Glz6k}?S7`6V9I- zA!b|DK>ofmIL&Ffy3uj+h3>n*ZMV0qxxA@?qc}2Dsf9C9n+My!(juuC{AcSX@ z_DDM}M)(6O%J7RE0mpL3@>lM;CrMdi5b~x6ml@BKgsr-)43~tW>F@{;<|;7AFeO(; z60~roOA6uM^zO2!%8uYG%pC#>46h&xOq2jemfIgkmYiU!pe#>`O{$2y!Mh*hZw~WV zhQUb3k{!yLjjgIe!%FzkKGDYY%6d;bg$9~fM=bcE;(kS*P<67;Rt-N18tLy8rm%U5 zm{5*SpShQ+Ze5HcXXCXPr?AYRh=A3d_faK`MpN}YLL{2+LXBl3kSG7VtaCzge<6VM zQ^9>&4oE=7|LpjZYb)(A?vqwk)FVRIlyLuQ&$5@(^%-(IIl_krnhc?|pdb#GXv3r| z4mh4Za7|2*O?2={X}cBEmDT zx|>Gqbx5&rWlk51-7jPRR#B381$w1&^`jRd(vbQL0AG_0o}Z8`E~&nc@w}*E{kU2D ztX1cDBl-bF80uA+6IPUDxG2y_^V2{=2(VETxxFon0KZRZFNkL(y z>H#L1L;gZ!Apt%U0v~M*YZ<-$F470+V-5!%rf4uDiV?>ReS4yUlqD`EWE@hG;_-|& zJe+#NHO7su_)~U!jp8HNi${p~ZRVa@paWlt6e=ASR=fyUT+uY{CUQDDOh$q=W`;;W zvo&ukj>UfIXek@Xat_3V<1`kz*oMt))ePlU^pJnyA82?>!^W2&KqEak(6Ak~SPLdn z7^(3v>>PJwC^B$le*6#wl2T9^>oe$>8`@|2{*qWD{%Xpy+Ym^I+5Kb6I+(Io5GhF= zri=dun6gq;Ry#NVQ&uDaLQ2ESpfD*aXfz~d1?Q7PL?+zm*H1vyP?~XPS^0bRs(A~S zWuiAGC`L0T{kHb$y=!auz8uzhE=MZSJP8ryhxy_$TA2CMqz8F@o20gz1sYl?mR&B^ zII*6ugzU5N;`$VP2Y|zkxgr0EKLjxlSt0*JC^5*43%{o3$b%yMzUm~ls(kJWS4wyQ z%sDRH%f}~+6D!adDMKNU+z(x+iSG*{XcM+;s{3UgDHcA$uPzn2xJ9SZQiQ05W6!I= zBx7tMyYA2X(pSoTYNp$TI?1W(vPrY{{fE5|`9KTeeyQoD!w%WwEfLf3=k?bXL?ohh zZNQ)9x;uSCsAf|;NFRQvSN3C1@8A7dnV&wXbhHr=2Ev2hSUHg@Y@vTFZ&jQby;uHw zd<#S&1H`wCf%q1|66Qa|w*n%;K*FtD^dBlU zSluFz;r}7N#RI*O6Y%n%7@y2PV|*vCjPDJ=__VDTf7!}{K~y*)1|mO&0IoVZ;S9G_O~ElEqV8H8Mkrh#WRiB{YU9_ zcSZmX(r+l6NoKZ~t+pd8G1IaKv{_p9VVmYaaEsmF5Zs#zNKYv$U)~K>K~?7hwTQ>K?BAEmjU}dAvx4rI zJzi@OH<&djhn%#FmI#4bM7{I{%}(WjzCX2yv%SaaW|Ew*l&|@AXEu0@0hh;H8qgIP zJxqB*-4zCPVdV9~%J@#k59-&+nvem(Ey?;<%2ypU(m4avW6^Mt9L}CcjdL=6&GpP- zG=AA?lK{4)g?F)Ma*1<%Z@rs%n?RoAJZ>XL&XlCKnc!u@(d*R+0a`6VCV=nDm=J|b zDI$RwHk(j4U%ME2Ovb3+!J^y_7#DnDWQxgGwv!xnYr13aaKV%C85gjHjNYuVdw+}7ejC{Io4_y*QBUF$}#Z9v}DR|uJAU`6+n zgA_sUQ)Rk%*lBvvtb_p0f-In6~nv~iSibMSYaf#W2&Wb#aCn@{pLu%Kt*9cW1kOrZ=YaFtc z`h`&}27$5cggtO@Uu+qizQo>wXHC>*6kZIaD?6r|Odftu|B*WWxdR0TF%rzPv!IN! zr~vJ{Ns`7dVJP$&Xhd{8TdYN8aZAW)^dCX^-o+4tTlXb|9dD|g48bVep2i6SCLyJEoC?sZx9d#CDS@dO2o$w zE@qCBJW8-l2h`U}M4L+7X*R!UE0E`eZ1N0{4Uj}vsa)T?dy*!V+_D--DZxFNsO)Yq zu;jrPi^S8hJByC7kAEq_=HP-07Uy<<;G`5skyX329T6(>A#tqYRdGMXJx%g+)Wp0ih`};b>StHON!Ff#bPI zCOOg)mYFN^K|XU}%0~5?D64?9X>sPnb4=#bK{sAt(Lt_$ippV)yUJv{KfH;}3FE22 z81}L@i{j{P^?vus*^~hFcQGSrOn&nEJ?p1*Nj|OBCq8ZchbE^)O^5PCXNNEPOil$| zD0*GH!~x5bm*N=OYJclSoP+~=n_SFNiix%+*8vO*MitRq8AS|fp=&Q=-gs+(XF>2_ zzO9S@;4fVo0NECJiGTMqe+~7hK*iB@aQ5;lRY^ zfQMwe`@)2jv{?#zdu}yQAZBL~u+S7`RKxtR>oT6397LV3n`_T9XeFcLs4|CMNwxT! zS4-~ItA&hR+pilWm@+kd;dMeDML07=4IXSaji2)IHxoem_7Ayrm`WB`Cb_dRB?$kJ zzQ235a9anX7ifFJmz9}vR#a03H`S0t52T@ua06u)E39zW0*5w z^1f!f(xtw4Gc7OJv>yT4E|!Sov_1uu+V4@78Q~%dc%H15X&YRh8!xseP8MM3t)JY} zbt>=1H}X+X9Gb%qLv)HB8RA_y;e`ZZrGLp2CS?OxhR`bC*M=N|6n@oCZ296RBjA5# zKz+A?r)k4<@sh>qu{S$SHK9u>cgT6{+MhLAV8!Nu%e-5&#Qh5T=ADR$h>~7G-DOc32j-(L5|JYK5x#Y#4zM1#M!B${nL zt)@EzpzoY@R9OQP0DWyuEAFyCq}McmA#l~2c)Ko$#!RMcI3HPk0I(f=7^?w$;ZZ3{ z#Y%n644%K@pIp{;=fw^>`^u$|6&m;-_`3~Cr6Q3ChF5uQtuoS)caJ6hV!fz0I}9$xkf21ZD=;~JV5#?)hGbc*H!uH zHz%Qw%hgSEE6xZZtt z#kK~F3A1wu1J+#U%>^1s-o}dOP{88*7wPM3a9e|M3tftjVgT{Vs~Xj~B2SHwR?@_w zPHm>uN$}dPBIP$E^}_)*iI8RUEDggBH+_b2->uymsbs7@HNogDL69PuukE5a{?GJE z6_YoQeKC*@x=SPSbKR37pwY#R~dp`bNsU|$=TA0R$3Tw!uqsq-29uww4 z_KM026}Sgn2Ny_G2aQx@{YBTrEMo==vHDTwW6@hz&&pK_b$3e>u~^5sB3mnnC9+!u zKR81qG7MU!uB$ZIek6R#M1z?^moYwb9}pvDDTaVc0s{q(2Q##rlUuB^2Wupz$%^A} zifP~|1n02pWMO?i;)~z^)kE)>uv3*q3@hq<5dh}3Z-V)F|cH;mQiOYj~{g`R^>x|PZK7Xr7 zJloVLbKA!c|B*~HYkv+@Bo0`tP#^CL<5fR*q!Jud#EsDXI4W0fJZk^t$r6i&{u8Z< z(Q(AlCr<9US!1?gu5nj{f_f_PKB>7UKwkuFFuv6BnxPFw0U^4db43kGDa3C+Wv;nG~C5CM`T#)tP+IFf1IH=9IDW7a85t@QGG0p$@}I8{eMw z(^ShJIC{5NK~{RmRM7Ua;~!QPR#$4@XiwG}-4w!WgGTfxEr$4@*FUFbR zpJwW|VizA>K0v_5wmP2ZA-;ehcivv1$8=6h&CHc}JF#wXsMf7UhatJ_WL`-50pzJ5 z=5%OgN^iIY`II_SB~pxZs!Z=o(k|2cJ#*}bwSC?*dr0p$@`e_Zv;H7RDl)8k!Sisi zz`~brl}X+51S`bVnVbUF1TiIoacxzCH4Mmi+cwwI@ z0`&{FaPWeayNqx(LqJmFflGPixL>hx6VxIZ(EdwEUnEmVnOZiqe^EC)>6a_63OGo{ z{Sf|pNB%9mdr#C??a#aL0QURtuY(Etk;P^$>(wXY=FxF2>amv5$+b6ARo?2W!C7}S zycX6t^2DA1aJ~dNrIFN+6#}S~G7|Czu0$h8>A5)rPIY&VtQ5 zk{!GsVY?z2E&w)a?_pr zH;CWg;FXP<ePYBoQsy9-Fuxj;cy)U@81x&v zt6hh-v~jgY5#$xnA}J)o=$y#?Q~|{b>PQNYf#$F|5#X{qwS>nADAy(;Ridb_M8y0> zplhZ-g>;%j+1_ah3)#E!tF}cPzI~rKCX>!+Q-b3miyk2R(b5Q?`1rLSF*cMx?hX!V z5Qoq$f0ZgYdw2Ic;jc`kZFe*IGDChFgX11flNl7%WIS6QlG2Ml5=I1+LrSHNNecCH zNuueUg`Sh+2bWGW=iesjgVMNu#){GUn>k&9Z$PV`l3T|y%|OKxq>Ztwc4_!DY+gNF zGs~>a4u!@2s&T#9BDx0)R0LUlTz|0k8!@MbDj%KitIbvT`y9+Gbxo*|)*wkNSdpFf zUl2aoZ$y-30JGV8oFP1IjlD9ZQT zvOs8I3P#ZLeEQpf1%7(h*=y z?6hsy*zHqHn8co?5O_$QrM)F%MB%cx@hr=j2;&8VcH9=M^;EO_Ri6|aL=qr{D<1v9 zjf1x0DSdo0C$N3=)}We*ql@lQA|VA%2=?d)LJ`BgiCM@>B~P_$*_L?3!g&+U)Qy$% zXJ@}p`dN^%i@`;Q!$J1;3jEN1To&uIV7f3<0%WFqXQ_1ti#?cZcE%R6bN=tT$%DFB zYA1VeEL|RcpP8&h$GRZlX|`MuHHQA$^Y7!IkWEqmtAs#vUaj%KVTOVhB(R*7WJY$v zQ13JO%#ym;qB|Vub$(d(UJ91iJaW?pzqlpaS8~i5)(gwNrpP7L+W=K;e<+;^Gigrt z-Hhb%3sKI-kTLxGe(6>`8)K9kn6zfN4fryIsb1lf6%B5#)asI7#S zz`mxcK9zBa4Bd-|ov*BM+WmSfAP|PFa@RbgTs`?dUp82d0!HRN)?`((l5wjooi_ak zNzj~EB}st+7$`fd9QAoro&e%gWJuE6+P9V2gXrY(oQ|T#9yEy>_!|v+vkGtR6r6O4 z-FlBX=-_3ELl*9SM4(kQ)+3@#LI&Dk*5s0cP_dH4c_j*TGfH`I1h;}J+bmKFKY{Q_ zF>9ah?oP8->h_N$a=<_pD;C$>5iI3&=5vQ=8VhXGr!{c6@b8J(f(uA^@6yO7mS+j! zyV*3YaO9$;w-El;nOL{nZ;ZWVcAtR7j68>fXz95^33MjzA#ptSm%8I3Pgy$6nH=$+ zteK+s>$7vyYC{)%jqY3nAqOo1or&9)8B0KC;y&voyxU9?>hVsqu}d+W;) zJFtc@oXkI+iOk6eyt`2s!)E9qL;lwj;_5C(KBn=MWt{dYfkXKc@JzNai~_O8y9Fn{ zpRnvJipbc7(0=K${ba9ndlrM72y+0OzzU7zyjW;wF1516m1+$O}Y$T*`0?ts4~{#FM6OJ+;d}e5Ow;GEq?j4EpMIoBfs1k(FyFx6 z90}{wWXIevN3{$-+iup00_jH3HS8U$xaT>z-QGUA*J#MaIRklw{V|fv>}K;0*)eH< zUh^#Y*F@G}jp(@KnR~g@!nC)e=XV0mG{%?RiTxURh{0$`%-IzmNaFO_HHg>bd)~ZJ zFfm{LWcV~qaTsWNLUa*e~oB!Kaw3m`VG(^l*Yg zE<3bM=M-2+ob<%#c$_%RFp|Y#nU(j1jE5#lb?ic$VuFWly~D1$Vi`}JhjkcBT7A?U zZQlh0L`>)h#T7M#A0Jr8tSquNmh)n3($ap_%EJ;~4WVuR=zv133W72F28Ul4{0+br zr2Iw)ARy~T6=1g+sc{VRSl7uTtyDVzR&Gp=-0B4(bazas>PKR*w03^Eeo1+39;hNL zMh;GjORD4jwyBhyg@%kL;zUuLgvmE(`;iI|-D~Ik|K#oOA5WqT@VC3rv(0 zziMC?2Ne0?q}&1Z=`Is$ijwD`5D3yqD6HknF1r*XAMzigg}x_Z5BAGzCb(r6XPu2( z+rizyZ{VQ2(Xt^+@1ulmwH#VJ7^R_$lep26G39fQEOni(;V{0!F%rGB4@z~J=30F& zz^>ciQTW{TP;^xW?}BsvRw@{-ik+h&Uf=9$2XgqeMe!+FBy&p=L3Bv}z7;{JtnDEQi2@q!6{@3cI(k}C&mc$ z747gt{YHlsK3T_|2dsXN+AMZISyQ^0$s3UOV_CpazDH2F1m#b|K9iw46)>asHSo3w zZx6h7!%l>3#sbvKXUz>R>B(!VRU|L+-9ZXR{dXKc>5O|5%~9enw`BOj%Z=U>iP7`)bfGUKrm@wVd?CnHckLb5 zP!nb(OC3HsK3Es3mat^p(IQlpC2W^j=_0N)iC zzSyCOk-4Sh8(%~6FR+x`isCxGI z{)v}6&y^eJCAg6%tSh%>+%e=+T6TlFYM&3lbV1c4R+&2(sqnq}fS3-*!{sL`s~KOB zf$f-DN%pEdwV9tCM=@}xF)fhVO-?WOykL%2YH6q+I!4s(6JlgmzdFQxdJ6dG2E3&K zhgeP9ah*yjJK0tXuyGtgwl{@K>q8()4@ak_+z%9pFDwbfE4+Vccgi#kK*C_eXoV{p zWhn>>Ej3Co&6@QKt)IWudhm)~t2nK7IjLchL_ZeI$u4VD;? z_6+*(MzXg7ZaSG_R>qR-*1M(0V@#R}Gt3Fyc-fpVG&|_kn{PA_Ygp;&c9KM_7a(zR z`R$K54iswBacSzB8cxW-85InK$P!=-S&CMwpA4rdQFfi8X2Os(q_ZGE<)&H1N(&0O zHTLXn%1H`RPWIot;7$rKW%#`rEw`UPW5E(8>mkP{;^G4(5QoBH8w)yM7qFue37Odq7$|9P1;F%_EfD-V} zps=N>)&=TXk>--B48pDS@m;zk@gW@0{)&tt`FZuBKEDm(`*$DNC$FoTM*r!aaS`u& z?_h6CupCIyAZOwFFF*?+)Lyst-(_ZPJ~u6eD9m7U%z%$8ay^ zRDp4>)eJ)#KZnET9~5Rt9jt(N`ak-}+|Yi3ApWC>pPGyhc(c+Vw+O(_Z+&8|y0--)7 z5xj>Mj`s#`SvU42crTRr#_c&%(|K}}&W8f^T$(x<|A^lzpl?$8W+#znl%0AxNa>@5 zb0>fExNWhztVS?3Tm6at-IKgIZYiX`xpJP^Mo6wbCQ%4fVhTiZaFsHa0CINg>{gLh z1YuZqB3eN%Js}y@pQsPQb_9W{!^-%h0mRpwU0u|o6p*v)IhEwKd<*Q%!iI3SIbD0! zvc6m$Eoc6DRQ)5Wq=J? z?+F0n^@n(bmtfLNoDuJm+|h^BY9TmArY9-8>I4@f3yFU3leDMGwYNqi?e|T-L*5ce zzU6e)05TTi0v+Kr_!L8O5DKuO;xX4+&rPv_P{+5`N`swWJdmy)t{M&yrA*u`mgdXy zV^CI4i$;#A9OB(JM+4io+0kVS)H7%pdHiN+BC-4v$YTMcEx)GUW}QDyOiHGiPto(; z9Bm&!pEyw?h$D@C5RIOhR%kzAy$NSwE&hgH%}DRE)4ARPbSVa&ona^Y=ejJ=F)TG& zw<)bYJT~G#Fy*fkQ+pe!Jfr(Gn6d(0icj(;zAx%snpjV>N;2+ikZxVu5re)G6|t}< zJh81clGF3Jl9^nLW5=msXKfY?p1x@c&W45LZ4~3PB^}=q+HpXHg}XAXE|P0Z3rwN9 zfNf2{Jra_(`GPrq=1OG^ji<@ZnLkkH4GkBvFxHq%$HS@17aKk{Y^~8oR5`zww?MQ` zXHqFnK_2!&BQL&V;G3|=z)y>2M{~8Hn;VAROJRyVOLd;zFsi!fPzcaWT|fv_m6 z%2PfrD>DiXBH3zCI>Ad#-e_}?bId%f#|@tzc_Pg(xfIWX00GL~t@j`T4Ka)>H9glO zRJjjrmJvhJMTO#^yVN&?U9CS;McxOdNtZ+vJ%lb~Db1m77?GwN(_oB^cZXH%- zakDmrzXc>@mRzIm&f{@Xc`|W6?hdwguu-LWO=MZYVL-U<*LDIIZouz`Bdael=|{V( zkKXFs&%6NYg&HBSDZdiU>!c;PrL@tR#M?F{qV*Ax(wTeptLk0+Ui@y%)NmO z1U5s#P|HL+l8}X?&yq5q-o#Jrm#s29T^Rv>n+|0DUs4GNFZ!_etS3m|#0x7!1DB0H zLz7J|L`8i9G~t+3!uV{Ld3j3CP#cuNnC7F3W+X<17~rtXDi-SWIA;I!H8Z@@xe21w7}nF&VhRceUFU=)lKEjNi#)4Gs2QtSBfXPd z;clq!qS3Hg`{)BEC{Gc2KR5YJeWQg7YB8Ga0C2)0n&vy& z3d&jg#*|aNsx>`fVO`zDPSetF&swoNbhr!7H{&pF$Ftgi0V~LTkJy%TM0u(9l&VzkQz(N5WOhzj^SF{#61#Xi+ z6#GX5*N$Rt`A@w!%pdp=Nc2B8#mNFbF={x0!FLSx366Ao180o#iM4xKBSY0UV|IUh zVj-Lj<@j|pmD4|~jMYVCvSrO@X_YWAgau-~!omwKLIfn(*3Mz!Z^rE zN;;ieWqQY{);_z|rZ3z@W+6gZNugu3v7)|7@|WO%qs-YB1T-mT08NTmLozy3n})LE zup3Y;F?xCzQlgc2YS%cpY zL|c?a5@IV7M_qQ)lT^|;bdr`gX$cIj^|#@w=Jw0bJE14=4!9;C8a7#fvLFtUC6QMX z%K} zjRc326YLG)e_T}o-oAX2dWmHV^~h=uR1HH%biwqLHX&>#kQa9PFd#tn30P***FR&i za;=8Zrimo*kA7vvC;AV-Y}nco>mZp=QZ}@yCN|meymW^93Q1&e2;Ge1F4k;!tIh)5 zp^Fen)niRM@@lq!2V>A)nRdy3Rl6Nq905)tSOcrsu=!U%g~u}O;i8$wWj0#;zNDMf z@`gYqF~T0QalLvuiQ~xaY)T2Ib;z1f>>|6oj!hT+5_|`;sZU3l58Au9;rh5pJNv_YaF)( zed69Bs1rGnz4<-q@p+Cj2F-dca4+xsJ+^~6r~OT*(s8Jcf-D}#g6g131E0sv)gj6O z1g9cAAkD&=P>sR<*)WljV~@A>nL&Ftgz-Uk{nC^of@ zF`>ffS(l9x=2`AF0K=C!yG>MGWJz#v$$W+&FF~WKh8@Z7G`x%-p}zuFtdg>~%=pK0 zshZT*kR(U&&kWpPnjFm+QaiEj(jV+-W0+29^Ut59kg6t^@t)#xKIQO?Rt~hfs}X!) zVv8Hqs%m59)!Tt}1|dQfYV}#4Us|6xtChjS@QygS>7{Q>c~G`$?2{lZxqiONzynP- z+pDE z^6A-@doQ;yP=*%hs2ohrX0%w@dBAwEoFWFC&dBJEm6imr9Vn)`%ML-_A}bMaaM(Uf zkL43*8CSleS#&4%J6|$V{#gddgj3r?TaEbDfPjBH&e+;Uo2D_9zGqN z!EeIK*Ypfr|RB*&)q(2h7_(<6B+1?J2V+oSFVlhxz z=RTA7okC|$V|}xlJ@WKe*(?RRPX05y`la@7?8*xp@ksCYQv}du9xYSA;IZbFNSt$m z<|;H+t`6fA2s`<1;8EAD)$Q@PwT)#kPo(&|?{G5U$46>0VQJM+Q4k2RYL6=H7i4>L zFt}>{+L%F?a6T#7Y5mSTcEAm7oPtUbs?(*YncD;8bI3;bIfeUP%LPLV=>Y^ub557Z@gK*aoWgavW5 z(Lrb!({*1O{`Uw=gBV&yRX|N6>-MT^mAY$>-S=6JnHv9TRnnCSJD1;U8F(>bpNX=J z$bFHbjQ_$}1w2pPzU^;dZ?w9~o>gthE29xW(VcmSqbv3FuM0XZZ(41;b@$mXXU?1g;N7uI+KOf@D~E8aegNoV~%ND+L8& zYfg(Q3C(knU~cWBrV;`@q70t$c0$hbql!;vA`O$((B?B8|4;TotiQu5`qaO}s$f`% z^WZQ+y?K}bvZ6AM#)^q+I>)Pq35K(D#t(u0HrHwCGnR9cRCxzN=G2{#$r_?j&{Vr= zBEA-q#<@L^AXQ8u;S4lp{OFwr!L#wMU|*YfM0e67eP{DQJ#i$URd!ndbQ?Z_LvQ#_ znV4Tmw+!e@RMO<>EDX9nyGO0}aFWjFSXtc3V+Z;Yr`&#m{pm|QJ$~&=MD*OB-1j)r zF`ia3iG4xbDTJfN1o{$t`*$=@%nSb)b8j6~N87J!E+i0~;BLV+xVyUq*AO&laF^ij z?oMzE?(P!Y-Q8WL^S=8#`#tA;d(WAff2M2IN)=TrNv(Ri>Hb~Mecd#2`DleoC^^(D zKTX&xCfyHoJH9d{fvO<@U*a%0NK90p>^Zwg0O|`7CM%o;oS}F!odT`PdDP^q4`VZ5 zpIv`t3G89ox< z6L#Jj)|BUyPTK{lRVNF{!Vxy!(L9K6KTp5AxO%#xI~6buQ^JUTQWTej_x_D7F);v1O@Da0@~Jp7YpzR^o5Ch;mmoLrnK1uW%HYRhYr@>WmYmU{)<#N$uw z>(O9KX2+xxKhiTt^5P3KPO6}iWWiMF?q3v2cd12RZfpGW{D<2+XUtm#>TQhCw35^K z7>Z}5)wsJ?)P4E%vcqJ}0Z1aszw=%$QYvsPz=a3!DCQnzmS$f6@hA!b9>wsCeCy<8 z-@j8{h(OBA>nk`ipShaTLu@$?EJ2QG5LbK93+6(yJS|Mx>nCoNv6q?4t-bnpvV1FS zqg68Mf6=Be`nS+;=;-i6T#-Z#G&uYz6iHEKc-uuF0`b zun0-V+7^3J!FQcMQ08S(1kux$)6_0|Q-lEU<~0Wis)_vwwhw&$QC# zmZUw}oZ7?yWtptB#~5td_Y9_-;w~`R&P8i%_n`i8fxjk+tNY8Bc<7wJdmYsh@s}^L zgxTV}k_zx8;>t!jI~lL`mO8r0y((RYE$zjG$z?c>a=J3eS|xPrrZYr3@|fQ_DkcXv zKOZA(n+t5k{A(|OJ{#}qy|VdYV2(TR-L0_e|5XMR6S-hykJz!-F#nZ%iWyq%1ST&o z6iK7Wd^l(~Z>rILWL4mTCj>1dz{foZN>3aHx|!*@#o+m))85Xj`RO*ZhG-{dd9oXR z(@wta!7Gg!-2l>L{5Y^Tt}FurA$XO(%5J;~dYRB+%kjC;tiai;_BCEVvb!xy(gxV= z@_&%;GT+Np9-wyJb(uQcRD5eUTqf*|^97<=LP-GOx`ki1*=UGF-FW7ISG`4djIa~C zGET}04zl&9RAS2EXk-pr-Ish!803}scM!?P4-!ccO(b3K|0cIpS(Zb&0R=*yd$2lR zW7d!{-&qJZ<7}hgqd~&$U8=MD3mvVM(iacT|5>s=GN)u*y=W{ujGaPoxj~lMlG%^Q z+`JsS?+T!EQfMav=l3~dlPNiIrL-t@s4BbO=>NZDv=rs|g8X`t(%baOUmDww8{EyI zx4FmI`BKM8rEb*lYvyN1T)nYCCwAKV526$hOxQpRHc$}%jeJ&B^F^}bK@$(vR`sny ztK}&nEYf7uQ4+tl_U?io>en$a7~o#rqO%+jr39W8yzkc;ixqCGvtogQt&@r;%Y>3K zNtZK|`mrrZSBJn7jQ2_-UBeg&w*835j(1T;D!u&Qb@vxHmT*S>&$_6u5zI((X%=@< zC>@EX{ynuYF}Q^a*?aeZ3aaU8?J$%aT9OhyYkIYgFU zG_}+Zv7p5O&9AHvAc|0Vu`j~Ru4`8 z85!csr1>T4+GTU%GFYcDTE1xXE~et(gmJi|Lv%7p}NiOREbh{QleU`jcBG^>RtT?fAQ z29^J#xayfu2nvLyj~ZnO0Rn6xx~J3qt1ZOrNA?+W3@v&}qOm8#e_~Bd%=3S%5P|pC zH=?juf>-M!@4xWO-)~dmf_w)~Ncpi^8X|o|bQM`nY5gfJdOgPBF*5uLhgn zfP~aeFMq#kSi-?Qn03r^lIT(e6wiRXEN$B-QPm)lyt=<;hTNPXC`MhQ?m?HivhDU?YN=X^4`Nc)P-?rk8zXA9Y1rLb1AS5prn_%zp_f{{U0%t~i63C6u+|^su zW{CcaT-EMBa#fpvKXE}mU+jKdxxQZotjh7xUl*Ar5{HC=42BlKre zB-vkXCI-)EsqjSECh@Bp)I-)GERH3W3uK?51%gF*`Xs>8N-MQ)POWj;yEX&uDNKm*%V4~J+#0!=aWhj;Dwi(~~%o*M+I>8hXO zL6_Vx$obp(oC}CYX+lRFppI`vJ04Z(gCx?bJiP5|MSev*R>?KBTOOLT9QE+0nD1dG zKbF$#+D?vLwmTRUng}Wm_FHF)i&6=hg=U;KnmR;5S{sI#SJ>WaC=#Y=_k$A^(KZm6 z^79@Hkx%^`5^U#g;_{bJi(Elf>=lazzx;AFoDm_sxqRDDI5_TT|J_rNp3p0+`wsTO z=N~buLPN+0sy%QW_?mJHW*CMT{O0b3*WH;uJxn)~PYSFe2f(k%-%TjKmlI{3eb7~& zX1)WQa<~zG%-g^EaJWwRu@~E|j(;>X=}Pq__v#)ciXvDHWU<}JLGYusZXh@sybG5t zv3gEy7YPzYfEk4me*cbLr~EB;A+hblG6L4ZtCeoS9KJ=t>I$lcEPSyKsGyT z>m)apnqm(ttOKuzcY-T%)|c3uK6GCacPVuc5wC4+KEX-V!?4dP5XE~J3-)hfR92|Q zHJ=v!6Ckogb24_^`q2c!;??sMt|)s_de8%lgZrB;Yl5v~2(s#@Z8M!FvUVHm?x0}&rtrv2gdrMf7*+2Hy}dWM2m%!qqf!%86c!;znl^t~m>I*IEPXNf z&9oMqn6AO@cV_h~znqdcHKp%~iqd))6ojB1m(JDS$l(@v9lQEv?59f1s(gqoZNioSUiS#`Q&{Jlw#nt zT7M|{En_ri-**S*CH4Gy`4w+0B~VeMEuLj800GzJZ#fL{2lgFL`a*|G6qxl5`84#) zhM&BHsNX5^r!Iz>x76=>FU8hJS`)DI#+FoDERh%q;zt(qfNa)z`rVA}_eKlX>QQ5G z9{aU>mDW((yeN#xMV1%bn11luFPd_KHw6HRy8<35wXaILM25Bg>}zDI@0R2eQ9Ui# z+(!l^WWwB>M`uRfLNA~54f37e{qLzM9ms!|n$qnM{ohhkaP|L4O*KUPcd01}UozIc z23Gizq`QziC^>%o#f8$p8&$4PhW?!9xAKwzamIxK(zr zTJVN$lnnmUjfMaEy19$pwKnpFHBNb|MEa2XQv^(S6lUQnmM*pSEj;>UOl1V;L9yV<57~(OW@ZWquIg zgFxP_s(|n1UIA2^@+>2zx!8OT9eC?vEH%FTES;)7o*b6&6(&y9F%ED*17`r|zs>-? ztU`Iw?>JL(gprfac6TU0hEe6g9)jDy3D1Vsmo2^ZEl(uID}CNGmClCynoG46_4=Ir z^xQqvbQ%YU4qpaj{}vr`7aO{?^3Ph#SbE;E5TJx9U$rMs%V2$-bx>nE`Bu3T!QuQipg3dip)tBAEiM= zLy_s(viE42zYpk*Ob`^g-l@23m-iI32#`XJC*=yoO{a3|V0UXE${Bbt2T1}|=%Dwu zsPd~fi-oTnL5&MOmK2#W2(8bzqnqU%+k!_7%P`dhS`W`Y3y8z{ONe;z&ca3d*-}-~ zzIS2l>YO{{OaAGpWucyNT}tUi6@zZ>5{`MD76&0F3|FZNGekgmr`6$mt$IUi{0&ZG z`;?X+mmv^M-}qqfI+sPNMkD<(u<#eBWA@zaK?sDa|A5l=4}*TQZ5?$BSEh@?-r@QB zuzFqkq?W5?C6#GJK-vb9bet#r9H6@9sM)w+w(?uyR{Q9wye7_12kKxDEOG4l^P*?R z3oiMUB7}cmTn+QhoQ4RS@ZgC`sG1y$I_K{WvKS{J0ht%}*imLlV$6sntHpwLo4q~* zCw})GIXG3aovNC$-n4k!YbV`tf-1fagI?qq5W;V$IwFxwz2hPFJ^ZzjQ!dYer;a=& zy*U~ee72;O)XJ02hLD_qRMn>Pz=8iN)Kv1+Zep7%M192*F>d~zV;}kR+^g!3AaaA+ zBU~L@P`1n|I#&-GJuf>5RM{uhsifmU$zlPO4hD&mJ-VC0tkHlLN(giboo_g$?RM>0 zP}(01ovPk%bsao>Y%68Z#~in8wsX!swQCewKwJso- zhVV|Aqc=apu-U2$TTRm&V9oC2(^Y&xu+6O}usLt<9Ay9gHsPmA`jZX>g2CVFwtLUu zxGJ}!(_)a&*PnCtn)SiRJC{m+cHVwS>}jx^)!JOc7XQCWx*TDBYBmj;qymoCMq4j$>V5$>celA zgSVY^0)HbG`nXn01^m+UDalc!XoYekhaN;e~JR{D4&II;#HJ+;Q!E%B5 z_Vv~o>d%w_1PTi|zW4j(Nw@$<&6JzV_ia~`^EHnaF`tqmHoCPlzmbUR*$53G2ZawI z8NE@-E6&i_Pr)3ahU3_=qutt8jdfyug2s-Yt$2<(yOHV6fS~qhy-XIVi4bM(p#vfC zmT~hhLE#{!a&r55$H<3CC)l~cjslmOE-Xx%)kYy8{~tiLLYbW$d;=D?`;u&Aauv@)q ztMD1So+&peBh)dG(LG7*28y;~pq~o!;U|-SwvW$J4f*nolKk=uR+~_W{n6Fz)U`Sd z0aU&G9;C6xv6#4V%@h-tGuu(a01do08LbQ)78>J69J3X=S=$og7;dRmVuC2yo$EQ1Q zGV5Gs=AZUZ%$I5fXOaD_b9wak(HY!V^xji2Q&9#3g~r!AdeV_1YBeAM*PiPQ$i^xs zlo;;UxEx|%=#*UsgLsW^uhE&!>Cs}*IawUB8u)H>8K>=+ciEnES4I>TnS}zkZgC4C z8N~3Zr7%YIsKx#OFyeJTRG>ug{M-riw19y9;efVVa!Z*M#XOo>B-ZQ+A+;9@kKnrn zhVMJ)w1xmDQV$A)6Wv%B+5>eY>hmk!uz6gWoA!4Qg(QvrCoxu?N|Gl#Y?vg&^WX^z1yJ zW;3*L@rWB?RT}0Ss^@vgB=a0a4x#Jt`WgzCTAt+G@36Lwk-rdRj5&@aFz>_ded;3O zJVs?1R0g&#nnLp+6}&6FNwS7z)u0}4-`UmKUg{fmzt{pIR&`R4!59q$og*}Jz9k{R z_!Xn^cAw#CSMYcS=wKcly>RZY7q`%>wQ=6bI&f)?Slp{a+u|I;IM#VgO^gK7_I z-xfwEM;Nw~yjRAiFx_x)%vMLJwol(r;Yv+O<{#wcB~i;>K3JO9>Na39VzWSbKMS~k z1BJlesw&zD?dDV;z)S}u%iM>-9~cWlZq790RzAFuth%D`KQ6kmp#mn z(z_=U+~*k_!((0_rz|%F$0Okzu)o{P_-`|d-|=a9uoTKlW;haG(#6Z4rq_DZwMKWF zC#^fr*l25zColEbaPT1Vt+4~oj1{f%H9s?t)V)or7CNAGKO%)FClWfo4itN!V@=r` z?YN#0Wk%yB3>b0qQRiF?Dx{1WL#$uq^!&4S>jx!w$4~4Ub=u#j1n7BTZzF~_L`5(C zFGm<=47`q+Aq;s^2<-MSOec@2R)2c8di{DTYyZF^&ZdXB4Dp{eJ88~|K?JLj@}u^v zb;DZV(4dimNTcNo^G>do!hGm9&%qV>R(wHY6KxLEnXTmM zL$0cuA!Y@Zz(k?bg?IhlLzkW00T|B=ATnf9gC!!1LDGPsUn)bvNj>7jR8w?azhH~v z8E5Y~L<||c73B?LZ)M?nOy)nW4N@Zv%cnnpqxa)%h1n$kbT{&1X@YoCQ5GYC?C2HHZDUmb@hN zv)JKa>DjQ)?l>z0P&u>5oZU%{R)k#7ejMK~RAayCy|y~D=Vov-eWV#Tb1`eSI-J8D z-YI;5TtXR3vhs+Leb@DUB|2ofYXnD5-bgtrM(Rs-Ld}#m^of-=!iNzT4Ecwes#g28G5C6GC(2|mYY0&=i5333rRSn1-t42 z`Ep=4(>fW74dTdWyz1M;&B&jb$VLa+5sE5!b1p6ls3O5Y71WhX6067z9>a!=BxSrF z@Y~#JFz(mUVBSx8I!h-ME3DgVBEOOAyf&T~YME2DF<7nyt(ttEhE*sSPT`YX>xA_% zvb&jZt5MdB9G+D36yx}XA_6TdvFYHyFz)l*j(G9J+Elk|a#@fDU^h}+=u*KI1~?xd zB12q*Rx|eC#yRs5Y*<06yl;)wZW=xkwZvga8VF<$*e>tkkgIAR*m|RcX*Xnyf4ibt zyN6oIDePd@z%1ZH4xIP<(M@`M=8&Ap7KR!^nvH_WiP^>CO%EuLZ#2>YKoOs~HbODn zCqngc25#5aR+?;Xc^6mB4?HBHI~1pmi+ML2DT7P8K(UsbnC1R=BbW!`5EP;^Ms1TY zkT4J7S}igPL-e{xf6B5u5pntA~x#Li`MR zYIc{3_SPRHBl+Yw>EGa<6ymHY2d(d^OMl+H^H#VeuJ;*&x{pKFGc&P0Jzw+?%##|_ zr@6HvoJp}|dpnx=0ch6pv#29!$zm?uHx4K}zo>}o+RM1_pSDnc5&ll>tATRpvNG~C zU};@De5V_8Bxn;={&nnTJxq*^h3u)Jhk@gaz}b3alslNv96RQP^--gj0p5Ahmf z=Y^#P!^KYn^M$;IbehJreos=5V!78Vbeke&375K{DO36z6lfb>F>l+?##Rlvl~@j- zLtpc1w>|ih&Z@QVh)G*pRD_Ozh!N|v-#xn`8c;6H#BXV@BjNrHHEtHXG~xYTNA@AYqD}VSF8Lu0gVGG$ZC<%}P zADN$?wky}CR49;lqT+0ZzJ(FzFMhCjJ*lm(v7$Qx8gxE(^Z(Z9P`7LU@VULo#)lc!@UuH0Sn+yHgUPnY?Hz(3;j|bM8`q`cJ9&&4W zULg-`oXIGDWMJBoEk93pwHy%?ozy@`1(ZJ4tD0N#b7~&j+VKZLn-&cQ%a*MJaU%LY zvsRr^8=AtTDP&lYL1C(R#MoE1>yiDHn0+-EW|5ixC#& z!h@DhIA+-L2=5ES;f;@J;P}f++IBh z{xbvuAMq@^0|V?=WnaA!a(k!s)Qw0us}ir1n_vQIlQkhXF;zkV$Jqr;hJfay@~6Th z1Q(v@yO+^uPSa@jQTq#jy9l%Y8uq0rWj4g!-`99_my3^sM5e`h8HW zveM_6jvpf+Z2dFzvnfaYYeCnE`A`2kUe`KoGKCn2$Un_Nf%ww3>V}FUd0m9{#}>fP z^cn~!{r~WxKcAWW$7kL;WTWsO^p3oL{O9poT#)MkTGFWsLKf>Ehfp_Ehw5kG2ksp- z@=SaOUzo%m+f^YU{yuW8e`K!TM2HaEy=F9p#XMJ_ABJp#ud&@o#6g!peE_<(4vzl( z>mn8w9+2){-8Bq2u^x^H@yJfIeqf(xwUT9~_Gd6RLK0Wc1M{Czpyq=(~d^01@?j#IA<Aq>k;MS2wPHTv>qRg6 z%3aP;5%LdE1_?#L%&Ki@Uvw4Gx}>9SuxbD&BFFTtC!>KRbCbW2r1`mV`RDV}%wJiIUB@SPmE}1#OA{q59>^V(;TGcOx z_a9aR<^n_@NfAM1z?hGuVd6y0M;|Rjt~iX1;oSZU3tLaE{{iW-ATWS2; zB{(T@JQ@2;S=w^1Vjh-(oPwVkp84_9y2{67kwJJjkFPWPb#oTEQec8cL!C5laj}wd zrRVSG&~ptTJ$<l zvv^?cs-*;lqOfL!cVB}wS%kPhZ?#e*f5wF~T!D)Bo5e~;2|bte*zRK?8~t|13JHEE zFN4&N>TY`|6tr50_)3~TT0XX#c$jMpv9lKSmOY~n0ods+jSeCOkuOTI_~wYN(5*BU z_idR*)SN>+ele(D`241tZD8B+NMm!sF(~hpP%;0i-%10te5v-F8Ol3X%|mlMLBeIi zl5x;|i@ZSn)(TL+r4fm#@npAUf}Uw6cW= zUK{0^JVWb-Gn&+^Io$QD?bo{jFj*we>>!1RM?Nmvulqs7d_ka&0@hh&WfizbU2@k8 z^eKn80i;#igRU_qK*1LW+dH7KgA0QTvXA;VGfr>u7MxN+o;J-T-n zJ-9QrsD@*Cw^-ph6dS1W;AWYpqK&^i7TE_nWEIb&bCE-FnK+p*9C%D&M|H$ ze^_pj6Rh6)^n#k2>goLE<|n13gpne1YeG3v^d_5w*~p7AN-}imbFOR78l3&6_(Mw4IijZULLx;?R40Jww5PT&)#R6cR(Z z@&2@AMXiTny{5JudgRzQwz+Bzi+Jt=!?;@#Irfy+F$?+7sWV*uUO>vDR4Q%r7n~q{ z0H>N0j(EaAZ2-X82NP%S}nl}an*Uh$Pv2HS8N+EtR3}S zKYT~Z+JS0tNnQS4nf!X!wy(MQ{mMXWsH#6gWco%5J%~*?M~ZliNs^gu*U{5!7+*+xOyE2atfMHK7 zh&YRTAmL+>+4mq5l2}|+eNz#Az~&U)q3bZE933DtNmOi8g^i7QiD>Mu=37y(<*IoPJ-;goI{LB4u>hX*N#X^*T*L-6y?u+hl*6jyt&TXW0#BrNJX5!qUY7Q$ z)6iMw_Ho|N^_Rj}^=^}}ouF)0ST3McrGAxs&Tnx{85!u{@)#JBl9O}(zB0qIUUQg( zzP037KsH^l-~#D2LaaCdAg?+a+mEzhXyCO`QN-R|kU0#jj8DMrN(5JOYi1iYQCSN+=R~j{A9_%f6Vsdn$9Ad^!X9qNI|uxnWct7V1CFn z2VCYc3yMEps?AjInVdR4C-L6mtmHDC+U7*<9y5ngw85m+VmS^i)!!vtR>fMJ4=15U zm!C#xsX~DgE)BgON6590>BrL7qCAi{g@4ua3#Kv?-HGt>nX@fw{?LD zc%pUK`IWG=5I$hTds~_(oJ68ju^nzIOxA?9ndbAJ_bg)1;E<#FBzFe{s;KUSV0Okh~P>m_6Fq9)G<5@NJMQr``1ShxZ)%ij(4b z$l*&6ow5rnx(iUYB_i6o#(q3u>G4Eb76FuPJuXGp9$K(&6~aiy9kUm`)|m%O#{5)*ypfD$#lpU`n?~Xf zp=qlQ!p2n*nb2bK8NY&5h!>}Z(+LqRtd~uLG_q9T$^ThdKt~-jp?$E&Mm#e6YUW9E z_9ZuUPq8>gHC=CL_LF+v$4H0{nuyH&@Ta7tnI4R3ddR$hk(7#n#MxBd&nkXTf%Bu` zWkkeuof=cX7TuTnyC0ork;%#Qt1gc)zbBU7I`GC6r15?YGIR8px!*9$Ppx3kI1+H- zVF?x+t+w< zR*}5c{28c3FQx{0P^9vn>(d>+sOix6jSXYL#iuwBNPxs55vbO$9O~7g-RXRDzy8XHx-l zt2UZ7qqbWY-)F%~+{*2gA@QM#ihd-Hzi6#ycYc75Ags_>ZyedSzmy+Vt+v8FX;5Nu z823j%6aj&ZSr4LX${wCsQ*Z8;2k>jDCJb&qffI@oC;E%oEj}zf;*REOWgm|%8kv*h zmL^-Qql~s*(lFk$Z&}vB=x6lH)SXVRRhtY4x376^T$7L@{60o0Qfhd=7OXz=0TX|% z=#1B;XKy0TmVd6~T{=b*?@>Jd2jE^L5#>wT8B__|`nFAP&I8{SK}>ye0r zRiGnL9&jp@P~=jAkf$+R)3oQ&oac$lv$t?ct<{WhS4?tN^QU?`1x>}X{dsdFvPUX? zx^oo2d4F7AL_p03JCDS3jt|2M3EKY2x2FFN4xiCA zKQAJ+dn;_Kn^;AE^3P%^-R{{pR2@Goe?~P6}G^>5{37)P{817ISorCYZf$#VTz8a^xjc+jcGmp363~_jDJPmy7J)T(Qpa$ZieY>FIX9$3t+#Ic}H;5HFf2!9UoTRZ`@zV@6Z&_$;?w~HJx&S&E};&Y>KWf3`u#$ zTbEvxGK=L|D*=>mIUfk3suHaHoI$pskB0?0kLCk~TjEyQcDFWkaO)mI(a+20e+sw4 zL-GgY*_@ujk=wjNf9H;;|6RDnzr*T7T2i+J6mB^z=W-MbFFyE=$Ap>^-5oV?z6=pU z?bPKM&vV%q9VjiZ&@i*N%hP(_mx4)${VCiszi3WUt3nG3kEH)R)bO>*`q`s~G-Y;j z#S4C*PRr}rmJx#J)Y9K9;O*99>+D3zqEC_%N!2gqIB)K3(kvO2XDIl$p-&qj^y^2x z9t9%ugRM%=-{#l-65?VoEVG}a^wwaGZ|TaY*%_&F*Pv%Ni;w4%A~hcpBKV7>gg7DQ zA|vuna<3linWJ_^ibozb&B}2StuaJ}L^MD8!9c0MFa3oK zz=F5{bJ_*ro{Qi(9M{23|7h-$+Ca%mHipNuy1Rk+J3khUXU7{uw0Ay-)F#l~k6HeE zYwV8nZPsdJStBA{=9E}E6o~XB9I%|nA4Fk|0?^@G(jHB7U%302r%FG!yVC)UTlXS} z&-(-+LHj@3R`uV(0Ox=V15aM4EY0=HQSFWk^9#kBqvWCU8rqgL_FLm!s?hK) zpzQ_1^p?wlPAHv!9bX_0%=C>%d>89FjZgQ!|I;ibp>n|G{^nQo}pk5|`OuTLVr ziCZzse-puKa&aNh@%XP;m4?r}KYZ(^f5j8rYx~haUKT0JUi)OC7acE(&M4rL{xB7Y zy4|-bDRFxLIV1p{z%&J@+%nF85cfPaCJ8}XWW+UgIIeYWdK+2`eAF3FOt19F0ADy$ zG^TM4_+(K{9=9U*^K`J&OjTA1E4cRiOr_o;PNVu zV~c7F&&lZv^qducWLZ{~+n4H&e}OA3f~S7tDzHFkywu(=U>VIDQqxJTH@|KUA9A6n ztJ{=oDZ#2FQ~Dh$BO*{fiJ)S-vmRTijZ=%p$&vnVC`(89KT#I6{C}dX`2D{dx0vNP zd33$He}~80e7_i$*XaXSbf*++c4Z3LRM|UgZ>T&733k%Hlg9RFq85xx4yp(UI#1(R zL@omh`p|=&P(f-FZ4J+UULw`>Wn*1$w$rz3p_koOAn}wSMBGFQY$pMe3v{0WaoRbh7a?r56OsR8Xi z0)Ve3?Uj^d;>jPL>uNO_mP3=^aUcXdvv|M`lR*L{)a3zdwQ)fp7GSxx8U1+1n(7@g zx+9F@Iwh;Y*=li&Y$#w+*ZHs}gKv!gyiCN~^vgHWMS{^x8dpHlz?(ExRZka+D8DEl zJT4Ch=kUIJw}L0K`d)J5>Bac$$&~qM^43zW>Snn-Of93{sBRMEoMbq!``SAYH}Y}>Ep3vP`z>6i-XEHmpK0B=qgMqpW*l$j$?)bkUXwsPiCpzbIG%1dWPeG- z))3R+GI>PzhRyjy+hD|!%Sl<9=nJqHktcK%itRilULmjPx$;U}^`xXDsep!N&K&w7 zY`Ic|e(6H-L%4jvqy-x;DDv#!6djQ5A&PS%R~vk01~2t;Wi);$-oc$CaQ)WCete&a z3vrdY0G=8KUJOHv0SBT;xEiA+kL~q|SdmhCihP=*o7Qzb=0n$$h{v(oM==bcTvcrH3(`-^>{&LqkbMVrSUjrt;Y*9) zQooB8!U6nzGi1vR+Lg;2v3gmRYF(mJ3h$}FjG-aVrKYrXFcf{A8cFYfcpB)utVC%b z`Ms!c8?d4t-%~Qvt{K75bQ(3Q2pQO|>}^tqWR0x{gQ6j-X)6@+#IJV{X#{}#Rw&m4 zJ{HaFO!1uA0tbV80t^#Ya&e4KO5ch*`hf`T24?~3uA{D1j$H~4=W;F{a6C5P>*VSzBT!pk>gce#qZT=EMBX}R$)ZC^)gO#D|O=x&tkF42~T;S_J?AVKqkD_IRO&4rGLg^-9vSL&~jx+&%ygm`cX z57u`savNZ&zq>#fzGK~GUCFeL%_8`s|KedM4)U9=c(0ztN|pawLke+c*j+|JOx>6M zGYT=8(Q4`)c2s0>I6fkXEzBbCMO`J<0uMI&mfilqd0W z3#TTosp?CIv5{u?f=UD(z;+>y9*o4t+nvbl_o(FMX?(;DtDbvS-p%8Ey)4QC$8klG z(g0?e*{mKpQs&0$iGc^3M!)PG#Ne?RPuPWP9AfiUGqjwk3cFKc>(N+`#{APl+j}_5~-1)@VDwhlHYIQuiypU~d+ppK8qj z?H-`YX)U-n;EZ2Th*>*lg%d4f0QprTHKHrC74Jot#9UAjw@r_2FK^U7`AEdabgLe( z@D;P}Sn#QUnkUx(e+0!WN~e!?cAKBb(50VSR;+5xHf})0U<@FdrE*6zVQA?@hLge098o}C;3u%@2wOvuGkf)Dd71=;JU9q=ihNN{7IL; z)O@i7Dj}8W61#=r<#53amOhi3-ZLm0c|(%DAZj$b4KSOdoN+VQoLq1E%x>0Klw2bm<`|T4^#Hl5 z?6^OpQ^t!q&#bS`B-Jm~?k}=iWX-X^&2UDq22>W(Jik4Fr9BZGQ56E@@8oU)}VhnYCYWG*Q`PUpBmfZi=F`2lK-&)F&z77X+=zvx5Y$nw@t zcb09W9QL*kWe@CgOO%aTC$O4Dq+lIcv*_gQ2MxaCQ;Hr^!Wq|jN`6No&gjCa2#ZF< zsd_e6V-}NYNDPA_fN@kcTDy&|h##BAvSTny$mWa*mP`lOaRXLO z?u%AT?(6cpRDr3Zhj6SS@VK3K)zc}aNPy7Oh%&*1_ATH9Y|{cXfSnUS;*Liq#yWxQ z7Py1T^)=|-vg+I75h`!OSeweLY`vww*gvrwzUTjf-F^{sy7xC%;=3&E;ffmczn|#9 z^ZyHjUFhh4X-V6=JI-qs0d+`H7ym4o#O`=j(h@%~*!U=?Bq=Ki4$TB%=*RnU8Hj1^ z`(9`L1L6@1L4vS=raE&VrZq;VwR25Zt_%00E3M|;YWsKoJUEJ_#J@h1_m9uK{YWL^ zzHFZb`wyJ<=a1Y-AKOVJ?g_vDL~}ogVdu?YAs~E_oOdMqDDY+aB<>dApZMMa$qoKu zh|m1q{|$z_@WB5Bo!n-HDMl#L(>E*LamUW{l*71SGB-icYMY4pFA|5m6#Bh4L!TWm z@WnLIf5;Pi;|$4pA3ARMdpc@b+pdR#juRMm&XDoB9B??T-_5iz{skc)DV+gb%blz% zGe$&G)dh=&w>YarguT0{84}l^-k!rVQ7#cIC%L+wzg;g}VfD6yoZp-wkeb|7Si(%t zquk!J%H<5jOG}H`XzZAv2Bx%ET(_HbjS!1_4-D3~NSRgNd%||STJqjM@#%>)pWC9= z>C%rkTbHa*{ffpm$y`(Hb`C58n(~Nv4bxZr?;Av5lSL%mUeAJO40gEMA=9%stPaY} zf84=M#Y*!Q4#GwGDJLu|*W21+ibsD9@o1J&SjZ=&Ckqo*BMW4$r6A z({%p}FTleWmtkbAR`iFqb;7n52O)wWXWq@d^0g5$bhw%WH$r|Z5vt?hc_yV7a{1sO;I27d1w^DJi+;QE zo#!M*A+^CUbCh8CfEwhl19{FAQhlr)7%sPgU;+9vbp)pgWG6aFrPO#EohORIvbps0 zYvQ+frN$uZX~&K}+EnM#GUzx?j=?l|*hQ)-N-hLeREUd83Q>oq9Msx-1fkU%NtsnR z-0G}gr7U(p0^`-T4~G2AJBO;VNr!@0csl7_hUWcep~Zke70f1R0iB^=AI9ownHg=5 zi;IJwLRF4u`oQQrkDwBPD1zjPiV3Y)EW|6*;Lk+d)~=b|bqLK>EOC@~tit~daWi$y zPNt37%NGBCkKHuj!?(0bi1S&$VU_PE42OHwJhZ0WasNobUEj5|?d~*wTzkqf5AGg~ z#HQ*e;6_oLqpAJ4Ng2Yil7*z#lAY%Ug<)B{SnUezW5PxS8H!ibPvr72xhYQL!fmyE zVFH!y-%53Vq8fwtxqR;a!!%7L>;|XVM8JKh)xpBvy%}jXf63$pIv4YLfU~1KZAILK4@LyNIkPUO%eOcSHhWTx@e*j zT3I^T(UC3FBn<`89eAa%YHoT8ImmWbY<%=>hesIe0r zqFeJ?rQNbjB;*YafxYE(B#Owt9dSsC0RQIk!?tmas@*H5CN{_CE>rF+LMEds zSfCZARE#OGn@`bTu&jQNHM@=(9nv~gmaw`yCKi=I+ldw7zO>1-_rC7v3yRs)F^>=b zZWQIVUrRea+fl8x&qf|=;wdLOI=VD*Eai4jj7hoq65IC=dFPtArwRjkecOT7nY>Ml zHd`2lEr)&FQrEANde(D_X)fIHahB{-DUmqN{+V+R%Ww73GC6s?uuM3#S)G%bS2`8^ z#YC}`3mb|iG6lc%aD;}D1*Oc={N){Sf`uYR8xA&|C`u#JqUNcps4|Fi=AJL(pS z{V(d4cr#G{m%VShpea6ftxcUAse2@*nnSB4@dmvCr+9SUb?{ELuX!GdDOiY{RU}h) zGV(Kq&HmyQHlFx@;39Sb*W6zh>8d`OnXPXTyLVU)3E|upmvqG}=XVnmCR`?2<&dR|Q zNc${MiU8>Q&LJ?lR$248tht}c_mn94wjpZDKc&V+U$9-iMnmW>RM*tMOwv>E#s2<^ z+g3dgfifGoR+suwT+ft9Ek6kR^?lHjGGsI7*6|=#8Gl*g)&IrbTL#6|E$X_By9Nmm zG`I!{4#C|CZXvk4I|O%kch}&O1b24}?(Tjk`PSNNoqg8Yckg@Z*8Ov5bu~Yz>e&>d zN6$H)@w_j7Mk73>%(FC}ZAOQQ#xvVaU`J6xGOvyXw3Zx;dQHSGLy8B{ZwKLdFF=NPFS4-A3XG)Y%zh~^eRf{346LD}1 zshpZ~ya5bdLELg3Jhdql=*J-SAXsT}P4EV#@_!4swVn12Z0MDD!i#w|bVA)8q8^R?nrf6}buj9)O8Dh8 zcAXwhU4zBkBukO#U-T!SY_YUm5=8sv+x!$X>F8!SxU+{E5IWlBRnW(nfh0fVcb~Lt zf7m7W?`>u#lT1{TCUG-=cA*8MnC3p@%6%B9@5pM)Ohn?X{xxEvqk*vBgihk2tfV!?io zcQq3nwS?^Q;!NH^lUF~svH7duM<=ok5|(t-jNAe=h^68-Ugk(M_W3ZdHB=W7it?_P2u+RCF&ki%Mb`wFAKG`ybEJ3H9MetH&buT|fKu1a7-CKY~e?uE_h&64T}J2j*;fy5@FbnEOMh~0Sq2A1t|4?ET(&=m(}i29zd=q)Cfn1rvX zgnr|u^-m;V(cKykS4TqIQ78s^&uTV11=?=*d^94QtpTl2VDyh7t$x=#oG(%hdDORS zScP4CXn4zWzobUTLM5_M*eVjGKkXPQqdIL9xt>ICwu8beNuT4hRC%y{N#pf4ZZRZ9 z_h2l)K+<5cY-s6`w;Hrw3r)+o&^asP`|sgc9dvq>n40am`H~o&&dkh9er6kG#n79j`baFbf|0liBlF zcNVw@HQxXWNE0<7(^zyIEN*e;*5lY1NHj`OsgycA!h1UZnT1Vd1GDviW?|eR;0yMh zPzL%NP&^E~d9#FUk;gj3mDhplmuGrs;rIx*XwuueMa={AKdX3+*Y0k@(`&IO^v90` zLcsVyK)TvsUm}9qwu>aoOvf!%^6-75yd*q4y8y5rfobwUq7bhL@%4c{{ zcO`93dChw+K%wXhZ;OpuIxECL!r>lc@xmz`lDLR`T(a;FBoXFM4oIG^o?Qo$kh}=@ zop^K{e_gx4>vxDIm+#{Is_IXXbL7fa54ywWbG@C)mcxB4@O^U)?A0cjPz#9dDHbE0 zAu$3H|E}>^Ly_3If6viEBb>6^;NxW_?tJ!n1d)vsKHMxP)3OVN&uhqPRAziK%_2FF zR0>5$P0i!d>N=>%4w8-wrF@c9w;E3)9vg^BZq+q?+0p%&?ivn@Ga%cB=Hx=P!ub@IwR_S6>3{->p#3mL=fAm|AKp|{l0$Oh3Em42LbYdcyn2BjI zh^#muV4-CmSb;3{Ik`z~JINg`lU!`z=$>J|GZIrwG1%#d-m5>&+7X3bLTqf@7dTJO zb;~T{O_@xfkhLNr&!!%oz4%JLxYD=wQOde?pS^-McF1C#{T%^J=1J;dWBTmMfZEik z1MQF6IrA?NmC-Q5C4(qjUi#DR@L?v+HMVVzQKNlGlAAU7gqY*E`jo?lwP2^t@?V`- zm>!un712Zc^{e^f@V`ujsnKGADtdR)ACmgl`TiBxTDW3cX2EC-4uK2SHRE}Hhhb-b zLB$g(XEexhMvunRN|>3l*J_d20ErArk|rE%%=If5E(n|2^{(_}`dUw&Hor zSLIe&dWr~bW|?R^#fZOzE{0F`w{SMU*YRgWXCwD!SKi*zL}o$T>^4t2HK4aizu24W zNMsv{$xY)Ii_s02tzBCE9c(RBVrMz~sVGEpM?#~Bp82b*%S8#hHtu{$no!>H_+(Qb zpbozt%4c!@R#{EPlYdcXyjO%A^fdV}JF;AzGRF#u^~T||LUkNVk%{5(U56B8wDr}f^*OQCmmBG z=C*24Pku{miAy>I<*ki&p9@&g z5ygxQWyr|BuXn*M>8vImjfUs-i5YjnvGRDFnrZ@`K{=3OW{9&m@5euDt11Y>q&=#Z zYIRKI?_ja5LGO-yuS%wlKDeq2Lk4yE*jdb&xDVZ{&ifL6uq|jh!U#^2l$F>6@eMaQ zeH@+JONzyuW=P?6J*npC+EnC+V!0%Zs{uCH2$*;O*XBAGmuqK9~d+h7L%t99UUp!P*rE zix@3fZU9Tu(nw9g$Pa~bnfOgQrPs9?z}4=US;(gZ#d%5`PoS{lJ2Quq^HDpILjGnI zrdva#sWeCGi^C88Q|OTX95(`_j0ki@Wrt1S-mbvoky3D0NNlDgvh0l6;nv8dYvmUA z6S5`(446IYZB3LBV|_uznn=k<--~0Po1UfC*xTv^;(481ud4&m%1^oCHeaT;3ufMg z(Y`DVd5X#_nT0vO)$Rv@j7J*XOO0Euf;Z%j%-$_3-%;W)NoKe%*R-; zxw7MTM?dI5C@?XoL00Fv4Me zrOSxPPv?^CkClTGVtn)e99;cMb4P_QwsCvZ#=F^ZpYzzdwxqPz)VFVs@=4sQV`BuzBuT!7jryGo4--ZZvl8oQ;L6}I1y za<)3!>f6qVTy?}0*>SJ!F@inCg59Ax^fFNs-#gYiq_bHWj?z1pMIw8Xzo$FWq2|5q zRvDthka<@FgaI1OkghmsuP^K^8R}CO$qlZI|O}{KNL_FRM1 zRCb@^d=ob|o0)8^@GeC$0{>3q<`(*d#;Y!&H_VX8TWY3ylGF10?;ehP z{ZUFUGp6N76r!P8md7w>Ai9qn)y0^PhlbPLs^tx(9F|-5Hp#TL373~kU$Kv~8R7uX z&=oR=txJ5BNzJ`(dsWjachmAajd6YqB*;%)CFwC>_G($?)GCLP41T)flsbSFuWnF) zwPStBb20_(_l050;M%b3&8WVja33l@;D2rIL4)K(S<&v+q?BacKO0LbwrZwyyD*rw`*5lg0hV`CbSc z;cDK$nBo6jB76OLPbo(6r24=4Upe081;B4_y;U;w-6wwPhuLQiSDjpV88iKP`#moZ zw{Y4gVi-(2C&h!5{V(d-6_oU+7K)KVE>)(etFvHsQU6i_!+c0RhlMC8YhX$)Ag%`# zFrH3Jz!o8O&>|5Ff40LAM#IYN&nYG@ZrTo#RkvmGmnxBTKcBEU{&7<3@)z~Gls^T5 zIF3^<4PS+=4U-yBq-oTK6u-n28rf&2?XXTKPS8pu{XYj>Y9PK*ZD9CYb zi`=|TGs9_Bxkb_VJ@W`}M{d9wvZ4X-)#BR6*@AFp6O8ey7(A}NDeWC_@bqEhw^^Fd zngu_>E}%$sm5IeBf-9zNDz@C(q>mu!errcU*t)K&w+d5<+fOQCICt=-RAkV0nlB#Q zcOcGB<(Y~imQrmEt%63R|J3WDu?UC6G-zKiEp3G9Cd+7AAMgrdT{{iq6G**2!VWOA z5_;gEO$w3AGyTeusmv@IyOW?fQ5Tu1G72xpbDkD9>Yvw4H`@?6o~N5Y`*FcTDd(6p z!snY)UxDt}-Q?8z)3Bb&XXV#!I(Fzy3GO#t5eh3y{OCQsjw$`#6u%Yz6L`G#lioCm z2qu*5O~@pawM)yiUkot)n?>GG18r0H!f%C}PH}_AU{qK7q?_N#mYm;dZJG6VWzS@j z4nXJ~t*E_yxgm!T+fy@ij1M`>B&TUs$^rKALG!^hfiALgaMv3}SlsLY9}LDA8P42k*n8SCSu+1@=WmE~aEl=i`4OEV+O zcON)DISu#seV&E`)8*uh(|+3=KxSb7OvEa-Ql~&H_&RDWjdnyQ`qFii5#@*jkQpdb zmgZbE`2gSY9=HU>&ACM_WIqy!3e_E%PVb2(JKu2PT3l_Oc|2gsq{U6ajaeuiQ4J%9 zc{GTTXJB*nFCG2~Q`gEEK?-k5muoVY+tULP?1}3aCD;c)p;uj zht!4<#w^jsRvv~k7bk3aln&lb1AybQZEE;Xg~dn0j$k>AkN>OfCHi06UPnPJAvuUb z#t^jVarUD>a>|u8lu<&?>GZ(84|lJyT;oIy8A4q3beFKDptCTSwN2iVci-{JWq8eX zO5Y4WJz_-(~p)#zx%7B5=4oPbzQCLgiX1kmvvU}u%IK-(@W}~F+7foX4 zNVxc{{JX(2qxj1a%ukeqJ92XaVchv_;^cTA>zCh={cU84e)HgFEia+`^uDmD73wWg zK2Fo-A=AKYPfwnH$NLKI2Aj8|)0A!5q|AwFKc8qy%ncyK!c@)LHK~8vj&^4?R(DbEYDXq8efgS?4*F$*PSMA%3WiG~G`Si&9D`NGLGewqY5fEy}TlrV^RQPkck+ ztJ4-10e{ZvL5{#eVN7Fv+1WqJxoH`Bk&$gxJ$hqftf_8llgcI+6E*ntV|=?;CVFBT z@QC@$Y`Y^doyQEbT&n>(HLVT5GN?&MzT*~?@VdC2aBPs;BGW*E{w<%+w{7$$6>iw+ z2H)20aeKTxmVD=YTKQPBWT0?ecmP#e5QA{w-}0o2e}|zMsk_ugrlSb|?`$uFM!5eU zG*Jcpw?NZt9>OHjKwkjjzp=Rf-vdo<=mc5p5~_rriW)PNudP|bqnh|idgzFVu;pr+Q_I{H<NX_Cr+BcHi*l7;JELIF-+N}Vwq8d}rdTB4MF!Sl zsV>{4=aTGx5R*n~bw6G`k0{^&|9~_VL=PePsqupSa<^Tnv`t=yIu z+m|fy@_BOFrozQcas^`QmIkDS(Szek?KSH9%7bXLtF7Ma!_6BY>LmaWbAV}QXo#`- z{(0nK3xzq;C1do0d#9Fr$BuU=%`am1rTo5mN}QnnO8Fkm161U;SMz*=e%wk|_~``O zR!b-;QbkHP_E*wTFFv@XEj-flYC{$#TnPe*Phxg+j{8^bveSf1sMFASSC?(hS$p`K zjW#MJq3-O?&w1Xog5+5e(GOk&y=Cj|$iuLrYDI5J_}xyb zugs^XdV#=frXqY%^IL9ZZlwdhhVw}><`Wgo@??LYARAq zc_fu=SQSHqVNKJkpsD^om-kAi8srMw#(Fimlu7q25* z8knPffUZ_}khgq%YEs)qI;?IH-pFizsfpg~ z+FTX9u!M*(bkj23g!bk)x2r8n%ZM!Om-~+>!+vFzuuHvc<^ff7r(gosVv$MNf)P8pzfJ$amFO55$qn|aiRh$&i*RBS zYe~7iIyD>kBn zEtm4f_=@Q7P03~**Y9(*p=#m=$X?-%x0*dE1X+z?bOEcCsR;2N#NIsV4}|&HmPwl* z;60w*4LpAS`hC`+6~eg!BpWJ_JNrIWe5h#~c4z|=gKwTxZpv7E7>ndEiMK+oY+{l; zCQM3U5_9tX`RpMhPhg=~{!2nt2nxyJkM8yONB6={ty?cxSoP%rfqsB{PptPuP_YqG5!B^rU0@TMl>)jKwS<(AB4wXI zJ0m2~fayMB0=0(=2d$_}0Dbn$lr&B6w+z{`CuOo49HH*LnM8u4n3n3vrCPqzi7Zq` zp@Q=DrpO1oY|s1nV199oV}N5lYud6jryzkQIt!8B_lGzA;aDt4I3yncj+Hwk^UAS? z$uX#K2UvzmBH9R6w>#FIEOa{D=g$_mspUKf4eN7gzGcUiJe^uz!+5J2H4yH;; z*TFWclF5~?%ALKOQIl_r_#juVl*A2ql!~M)pGGYc3_Y@YAP;Rb>UU$JqhC#~l@MzU zfM4aaq{qDStF|hK@EN-s60F#tkWqw0vc9fZpbvlJS4<#?rXr;;T11}~+@o#Pc0D9| zq4XT}(snA=X5*nzK9jOe1|B1M8YU5FEfDv(=Oum5N6N~}rta6B`a8d(D-Iz3e1fHv zO@wgQBWJQr{DMT=0CkRe)jg+oX= zwyE};w}OnZ7Dnr*@I74GcJDM2#J4`$fcuDfk7gS#TJ3n4ZJFQiaI&J#zeBe6UhVTE zncfOa|5Rh91Kq=-rB$s=(dX9H+-*A_ffD)_97DqHAEi}M0$?Aj)qw21sxnY6wPEc% z=o`U_)3F|XD1>4c;&odGb$pF5e4Lq%{joaRbbHC-EQJh?hD(tU%Dg) zODJk-VNLisH3K4+d@0X)=;|Zc;bhD0k5A{|Yg~nwpmsyl_#MlP{5*J+n6UPz^RN2- zOGo!Gv1qeD{iA+i2s-)>vZj9P*=`=~R;nWqYQ@j%(-T9H)2yfYh2H6?*e=ON0Xxzj z^)qSYX>>voZq|9>LS_n5FUo~N&XN^cvCCF( zKTrNT)*xmN3z%4E2zf*M%p!mH`^{~IVBsc3cgd@_rQPaUwjR4Hf*keTaF}3Vz~NzR zjballv_47t>HMU-1?MVV)X*GWo^}&kFeYUMFokptks7?1X(+|XK8ULbgM0hnBGuHN zCAVnwX=^mF_pk=B zW`RhX)^Bb|pN$4`l8FgAIEQq2yuCJ|emTjQ0Lg*gS}*#UXK|IXQPG+E_^pxlGwy?W zQ_o~!pSg0nqLyFXtiTVlp#Z|d3y2{I+GI*4c4xVrKf`Zs`h6(bbxic_*NfT*eOyTK zk4MB1n=oc#5NhIfb?ugdlZ8t)^mrU|nL0WMB?wjT>W1D-?*LZLeh^N=1G(g;rl;ltH0UzTZT4I$J%Vd~%p-SE zC=B%C@N?+?KPtU?6Ip)SqE~D zkO$fT#<4)*DrtLAxIyL`|5gGB4e*8BV=%Z%)f!<*2 zSN94o!BOPZy;20+D>dSfxHL-sWB9Ku06?%+3#&_L9fcW8pXvE0hV@=d%o<==z(~57 zgr0@k#IAp3Se7nFub!2|$-YKH1NGb-Mvk`whA=@82vxM6;Iw0>=G*l?Lh8qJcUdn5 zJl+(ig%OhqN?K#Dn&u*Uy$b|`XY@^5hH(QKerAF4D{HrYD#Pt>)1s5hZZ%YbxUP^%!QKc|;H>C#+_~UJ=ji=$Z7l zJ5@MB$CuL`ixmgSo#xVk0m#6-@OEu_~*D+j=_-;An;$X<7mPb3oC zn_oU%E%{?!y^KLeiUJTz8Gu+x-70kD7%~Ja2gk&tCE|z<+J}FKSV}l=XI>#z|3_h! zAah~~#MDU!1}-t{)wY}J>UVq^1~X<97n8*C=Jw2_AITpVP(FvrhNy9EIW_-B#5&5-9F{cTtgqCh1heII`mhkGFCl>lh_}Im5%hvu)yl#H6J?b1}0oz zN_g0Y@?CZXsgUN01PXSJEUk6t8U9*GrWqsjc9cA z{ng^3cTSYn%Z%Z0yKICq*YeU)@ZT7g@1x;t_gopzXS-iLd+Q2n%5+=(cf$0o(mIqt z0j?|L--h5HhGkZ|X<5r`><=)kSnXGawHkjV18bQ>`7vawBZyk0{=j}ffVFLN>n|4M6n+|YZCa(gx+xx<9!tRM5fu5?Mxqm91N@Qfw>bY@qoX}zdp^{=M zL6>}I^tsBfkC^G55cSQAX^w#e)BkKB)TYuZ``|wbv&XO3`5y&YUa&ZzFL@SUD(FD& zoE`T0iiB?G0lyCIptL(qdGkWa7Zaa=^Ihgu|DzY{#qWc*W0#i&1oA%)8A2$7Lc;cJ zIGBGr5N_u&kdY&R*2Oo{vK&d_3D1>Ce?Re_25PTcd+u1#QU?Y7d$JcZzvdkF)xu?N z_@n0me$urr{rhGeb`R9B@bXB$Lo54Z7rmMr84Ea@Qu1OMZ8JSqrCb%AZ#3Gj?{Q;X z=_{$ipKCF@3*?s^#7!%B_tO*7q;eJZ(Fr@O)0ltvns&1PIX)2xy&6;D_mkL&neA(c zNh2|*D8f)*sP&SqzLsh3H9n9Cw)KDHtcORmxPnn|@BQ_)JAqELGoeFUtXR zTZK3uHM{49{cecVQwlQH4g5_rGUrtoEfK6*Hl-~RHL0~va9NikkuCpfN>xn7V3uPC?hn~u$Ky0NutIjymo?)6A$x0^P$Nl|}ssz!j3>mnWFV*A1h&90ViXXF#D zVt;f3aa|f{ka)=_CF?YlCmt8`gHBUo3VT2{x)!{R48MTodc3nl{LKlqjziSP+J-5coy#OeMrrp6Z-83~Hn6C-aeYPsxZIqu zH)Ss6V86rMZ;bIDU?3R{o|Et+DJ-?-{WD>=LZ*U+Tg(yGh#O;$jpdp~D${rwoG$+2c#c!TK(lPZ9L z&>^Cq)4lbOI>oi^4B1`m1=aL+OLI{dSB>P8Wn%4e`N41p{ng0VtYqTi+Viq$O4A>i zhOfbf2`vi?t45pQj(KCCa{5bSz|TD6&&li|vdx$**oa1iI8yl1C zXRnW1_;)%}=>6!thd`@yZAj(Lwg;U7HS z(SSH*;Mn=oabfi#*Q~#jHZqm6m*CTVbA<{rSi#@Mk8gq}Rh4n*@V1g)j{5*mfyHH7 z9?yG}-F-naMA6gs8+%|X05W&?8a~&W>KG>Gy!AbSrK^>|#dxO=W_3$g3Pez%b`ty8 z1OcJ~r6Malr1+LDZcMNxm-!nFeWj~J4g5=FoGDJP)#Z|mE5r6TJWNH&e!D*RXq;ug zyAVYYzo@Qn0Jpg3%(fu|8s77ADbbR{^tm29l(g#CT<0Mdcmd~H#l~io{X_YNr_UkO z8XO?>&RJFZSc$3?55`?OGS0_S{Z;jTc-I}TOwLTwKnxw`q%>p3=*Q>p zE+4^aPa>6FKXAi` zN=njMMnX%V*=ijYOx&C(uE)GSVoXI2RkIW9XI6MxpuCHC2dDVR7x$`ep7Ji)BI&K{ z20v@JcFV;B-B(PXQs*PA+FM?#7IWE9tkRjdGArA^_M(3TgCU3&U_k&bLD;|eY-rgv zU(DE@a83a_=gr-~R(qkxi};942t2Pfc`%Rp{aYyTW}GnhmnLTE25pyHc53RmgWI3% z_4f=LoaVxUMF@&4jZq)5R$Wsy-_%os3RHDE|t6yo#KaNhH=t2QgZA1{K8SCAm()+I+X9rKmqEiY~z?q(( zCJPgqb&iDLFu?o9ftg~o4fSnGW(@FsWZV>eLT{B$_2_`Ctf)rUR$o@#SsXH@N^^3^ z0yJ#B#ueVkIOBgL-nmZ*ZY5KxxlTdAS!ym~G-10be@9Ctm4&)5AZQt)!EtqTk$?VS zii9e(<=(BE&j%az3b-+RSo#xJm_Jq&7qH75`jD*=bc`L~_e*d}rYk!?-O&Y1UJ^)*#y2oyPwe958_W;p_s->x@6?89*PAX84O4$zI%oSM*c}Frz2k> zr=as1!z^h8}Q^a+@$#7A4lCF>?l!$wmrNWoS4ie0goBZ?nsV7o( z@Sl$h3u}nZ7DaJ292{A=A7o>cLh^nQiUe2R_9m0_=;(x(8nW*4ZQSTL8DV##7CDG) z8~ipX=TpSK$A;hMa$WGm(!}v;-R1jGoeSqK9?6G^7>B7ZYh`|5mDJ6ZIjER0*Y6v~ zwx*Rfqv^+EFt5CH8nh~}jyCEzk0){$tVCxKH;Ynv#l>fJ58(d)-bOor;OXzb3 z6x>St4cIJvL)5`QK{W%mKP*ek*P%nS(vy{C-Z8mUk(OYX{O%IR9SR#u^ARQJ!PL>} z3kjzt*<*M|e|Z5ZBuDu}0B#tw-EyPzW?pO1>L^M6L&=3C2W|j@!xkJ!sN06w0haJh zZL{X$p(!+|YH?w~=xa<(1a7qQXVu9JL*l9FTw^h$WDePM%JNTU0k{DVf$V<;7V-la zgHnp~qG9$YkXWdZ#IRtq%{bpT`10HQSWc3l?o7ctXt;5|FmcF9jc(QER_wQ#1U`aN zh!#P;m+#tsvDXsSvATuep&!f44>f4@)>q7hGZJ0ydfr+EHH{c^55Br6IwK*ppte|M zcSlhxU8IFT>c3{^HGaQo)L~vbeQ(FeG#J@_u2x6`22_t_?4j9Oj%Hz~n9=A3_SU%s zl035R+N1^?HcrkWzhzx{(3{-mAYYv2yn~`pwi_iG1NVouWdVtucY0-VmI3fm@HDO?epq6vL1}fk4BpmsKkVnbn$1CJ@{*j*dvwDg2QLCJ3e5` zP-)8fm`mnX>vSrj<7yv%6XTd3kpJS%M?Cu)S?I3@jYs<@vM?pTlme$BLw^^2xJB+Y zvT(AzR%|UXBGqDEx60*aJJze?<<}9G7*@`m|6bN9YTKLYQXL(8cQ)(M;@p)$io}Oz zZJJ$s-}zeYd9>G$LmcXcJKNm%@!pC}M9qd-`w!xVo6UM1<5ua2{YPWSLiTEpp4l=M z0&nx$e{4+o7W{bss$z})yuZ#iFVsLD8?;YhZwz`zSyu-W8Yib%Pc(>zq z3n(uSyv?v{2uv~S-aQbL-l1!cYQ3X8?donCxB!79Tr9hp>M%=g&2}P-zxnhOA3riO z$3U8&{p6FNakh0(HBdBI8t|*{=r^_32On}Naqhdw5C+RP>gIBhwQ=QD z+Fs!s6KK&E?H@(4RKC3foEX~PL)(r@l|mnlE2bo-&#U!9ck-y^K*WTI?tRW#F@SnW2+ zQUfr#7=Ig_ZtzXxQ(D@PaCZVhzofiKK_k&h*0*%{IAl|*owObf6jh52VI@mld10P} zbD(%8r*Y z!BXG18Gv{}O&!zK@iK2}I}6OFiyLE++$t6O?qym3oCsFUJWjiR`28t$dn|Y6Uf+pB zF3FWlT!vrS7YHUruH8Zi{|WtrlRZlkj$r3*JOSH&!0u^S4<=!-v{EIK*M_^jIv0%O zZ(jubQB%sCTyLjg=o(MktL?5l9^}9kkiGi_)^<5+pJ9b>hQRc)?p*^h$$|0D*mfF4kDNQUGpaI!O^ZnIvY21A;h{Lh zVBov6asvN;aZz&?&pR)R%Od`usSV{RDOUMz`*h(`?dG#jF_oV^#oNQx9U%0Gb(*^D zoABo`xx_#9S*x%0Se#wQ8UT4+yKz&wzPL~i1uwaM&5fK@GHh9TAd1B6k`+tD4 zyj$LVQ&*AA8CO1A>V0a01qXd#qzwM`RC(E*DH$Q6QVRx%RCT(fO^knaY84O*LIwbx zT5YmDHV(t%~b&;r%%J0%xq}E*6^gnj4 zo3uvj6voN|6Rj7O&jvU6Fis&pL3!KSZqG=S&gHsdVl_w-v3nPLpp4=}HhIY~m$eQ5 zq!M#w<8dO>{be@fw|7}aSR}uk){S8_AW+}?7MhdxA$WXs4%Shc&{0NyHbBgJuKW95 z0DKb46deJnOXG=U=0Jk6Lawq8#qVWC_u@qf?DoHUwDQ8tR}LLah&2KCnhQ|_rhlrp zATWb|v>;OzmleYQsowIKDr1;R^41!e#L{A7nrKZ{>~jkf{y*Sd-}V3Jyld+AeTe`m zLNK)*+o*zqKa9A@YMf3OZE}m&%Wt>yA;D)nRZE0J1`qvT!``7ZFA}_N=A#=*y|!=r z41uYmdezF27lo~w!D?|ILt_*VFKD38A^(yRSGBL6*~S@a1HY0Zf^IPHJcZqdkMzfm zTA%@_b$X+GO4vD2xaO zpU?3Q85BJ?IZeYF2!UU3OH{Nm#teS_eCd8!6FypemkPc&E91T8YX*c16cI}&8_dkH7xDJOxq2rYMH5q>1_ zfV$xP$Vj<8S1@@`pgS^CyP>6h0|XadO6`<$wUNStewYHmg?RSWNb$eKiNh~~st$n0 zE-KaS(|$I&DVnu8S`7Y>_fu0nC^-|KRTBL#f2Y&;^LQCkgWOL9`x#(R?J4gxC{f$r zh!Xl_ky;Okd`tgbGfbXc-E?ecgDE}tI-Yk7=_6xC!#`%RChFpK`R-Abl6J*0Q}1xWF*W;H5ikckt~rrlg}Uon^Y46xtHB z{@sGy3H^ymx%*+$_Pl6X53}jvsO}E~^Ek`ylkZzis-5A?(ss+o~U>)TrMvW2r3LzHiRO34JuS3l^X_u{?5dp=oa!*Q1Pl(2iRSP9uB9>dlB&G#ssz~IJzVx8K(=x{!yH!m` zFXD#v^@!+n%i``a8Z{)f;1lg$^417x=UCQ#uaWpg zf2Zb*-*%MmxwV2|%0r1fp*VDgFk-yPr&!Y<`S^$c=w2eLe{?UZKe|_GU?nf0d+E*q zx>u}J*~?s)i>RWamHQJ>P7EAqEX`(1dAz=jLYD7)q=|V;3njc7nJl-Jnhr18X<^!f zU!%m>lbX1(QNH0(-O@BevFiGcMWAvq=Dn6wHW;6HlF?X&WTAT+EcOdsOy(C8qr9Yj zPu_eS5Nt>XL2c?82P<)YUNl)H&xsLPmeMry7#)T=%vY9n>~gY`i=VcI-_HW0F3*+W z$}{i5rtB$q2#ebFiFI7<<%EuefZ{J}Ej~|OJfQgNFkyDY$Dmr{rlQ@zrPMcE8pt>c zkiekg-{2Mza!@<;%$BmC6f>@DuTpzIdUHwfeJyvoan&Z}wft)p$Sy=7lRzFzwNGXr z3loK6JmOahBJIXtG0+nd>KG$;W$_P6h7kRd)gG#|Zq??iAo{M_d(B+pYmonm)&nsJ z^x?K|@WYq3<=mz%X}!eE@md~_8ajLy$bCHz&+6gN_i?q|`KhV-97xG%8G~t0&BuG_ zcnW$>5A94xqfb=_`$t-GyNzR;0ze+lq}T7c{D&cn&txFuOmq@@dX6_qz`R8?KzSg= z_Pu)MSQdOFaiZ}Q0orS2TWiwLz41%C=yn$`SEhF?-=K$$OYw%*N>QNZUwjuChYOWD z1KR=4H!fot>81Ry)-M!`Q|CCfMH3uI{tz|y=?RIo&9$~;g7dPJF1elVigazwG4;o5 zrFb7*EqimNL`_9|e{kAOS-bl!0~omDmK$Ey1PJ5OA=e{)PfnotYwqVNqIfu5$2A0I zZfx{w#l`F@i&iTQ&i6go5NP;5A9QeKm%hyGz!P=OVfT8v8lPp<4y$gHmz!BZGr|81 z+CIz!ve2PnF#Z1dSQ25(pnI# zZm3uJDr6*Ct!2E|tbs;!bh^v&-G%P4YtM^)TW2H#(*{qjCv1oHJrM~jYnmfzpoJH9 zJCD^OcdW5H9vH53mi3>*lM+!n@$4xh-98Z!1Su{Y?_+8q^~IyOJol>lGMcD3uY!~x zgrkHbe*=4C^7?8##^!(FDB$@81t1Y&bx1?sp}b{x5-aTQ2~;YD`E;+Fz$>|9bjjz4d^g1J6@(--_ zyx`Rx<4rr^{VQDG-7W{TJfl8SRDNenEjjbh{zilKKcjH(-jRU#A|6DZ_7DPOSFHo6 zyK-?!McLc)+$A}Sbqd|riDHRxKa$V!`MY(8X4Tv(jhKy!1B*fWM;@bG;^RdCHn)+r zg|%%K*@5UR0T9|q>0GGBPLZc1SbHnS2lIR1waLVCFa9@I9_>M%Xj?s2O$r&<&9a4x zu9VC(^c}hWfIkLcJwDfo?k?EQ~)Kc`i{$h?n7uT~8%jLzfsn5@RG)Jp;0xQO#q^7l6w3zeQBZLr;l zVQWY7dI!+*7Hb@)td$`PjZtoaSo`p3cLbj)xjs9A#N|b0;Q*Yi+50&aS$r z?uXmeAE*MFf*Q;ob3DKId5_*=W6g9E3en2!bqJ$ZwVDRCo;59MV@;g_gpcZZQ6xY+ z04G?Sa6JU8;5w!|6)Tlqt35rd9m3xWYJMzrQ=i9BodUkX10su4#O$$?PHBPZ1M!BS%~}y?64lJ$p*XVVJ5?dPqcUZdMxt67CF=s9TQljnKTMc}k{J2~)VW z)HRUwU!tLCki0&Oa$j*qqP+^^UiF}fcyWR%@qMGfqF8kLjg5!uyV7`q!H5q2YG2Tp-pyS!d9Y`-?ljFD2M)BO0o@w-Ki?x28=m zx3s7L5hP)LS^ny2;HA^PLJRDGHeEOucn~AfS{JB+^PzTq7M0InK9;Q7Q!ZWS*V00s zog2@!O{MvTAT(!G;9X+C-X5QgLzKl9 z{uG84t<$o8N~YaIZ03gvT>`PwSK%VnPQI)VYD*IsyDo`v-rSAPItDdpH&+vdfo&;{eb z9FRD=CIlE}Eg~&;W2mb>Z-0hv5r(Q6S#_x^GHJmkh86&4Ekxl}@XYVZ!U|U;{w48W z5V&K+|91%7Oz-~(2%IReuR?*Qv2C`Hb6Iga(T1iJYkgfx%+oCA@xTMh!_eq)?0Y~+c*KVf2nhk2HPs!JUuLmD5BE_5wPt2HQ;{<45Aq71 z=eN>LdwN0F?J$?>J%|r&D;GH&o6b~Zk7E*MV8$ruUTil=&vlVfnYp|OOxQG`b)+>7 zCoTl&CQ9|x^{C{tGAd6q6FD_I4G+8}8A_(}sEQ`TpS+vQMUL3LT2`NfG^qT=a;Mt7 zAEuOUi(4qZ3xPOsK&00VnBc;f%298Za`ubm?NVm{wvi5Vs^Z+)I96v4)kqwR?bK8; zVD5q0y76uWwmkdOmewj$WZjn3jE)1bpC%^jr{kU0SU)mgq{4`gYT{ znzWReO5wnO-FgCVjR|7ejw$NM2&*JGM2ey1zU@fW zO1_H|xQ;~%ac-`l>_$bj>x-UDu{%)-ogs9OhjlFo3Xb-g{GMWBWBx7M+`+5+(mc`Z z(s7JkL@$Tzu%M$;9U4MM)lpZJm1{{Q96ua%StTNw?h}Oi# zT$;jRc%dh$LOId?Gnyp_Vg0j&8AowHURcYIA2 z_ob;05YC#Kk4F+pGm0b=!EhE|T2y`*Kn0w^iJA8gxgLm^J*zWMF)ZYk&Tx5jB`wCn3s`9rOwho%#|LPJ4*Hu3F zQlNBnQStl%K~4U7Q_gPI9M^y_=Qq>{)7Zu`A1VKU?Jvve=v{x>0^^7&%)1r7%FiDs zMiz`y2l*4NgpM_cC=t>hLuSbNAB~brXVOC=)xEA_N4d0Nfw{j6neYe)cPJoarisnX zlQ+zbwq7R~zWB|kFSXUVz2ba@Fqv(XalUot4?V~4BzKJO7!)EA*o zpKWSZY(M()uI{8ATB7R*3c8uE#a_O~xnObkL-dAC(g3#9Bbf_%X|)QQWXm=U7Nc9; zLFg!8sC+smaO9C@w{*p@;!*6RKkPd}aX=I#BwPa>OVT9W5YwC<_A;E2%M6V+?;qQ1 zQsH>h6;`dE9c_u$siJUgj!TwOT`GlSTKF!WW1Dwjpf!qBM zda8@9;%jSsn*Fu*HTgR2!G$)O{i-bI;w8VWa$+9)(LaZ!nt$wXZDH8|XbbacABMnM zvyI@wR~L-bk<_t$^hX8TbEUT-aBP0DnVwZuxTq+tn+V^75LlLuzxIx|&3EK{c5RC| z{MhNyYyg*x)@#Xsf?^x3Y`XW-`mR($K^p{8YW&oiv+esrYLqm>py2!z} zlB^`Eg2yEz3fIqM2wsHN(3ba}B}eUdtRs|kaRjs!Ys{3-k{-GwI14=UgQGHxz|4~U z%;(+lG$)$_bvPJ*xr_Eqyaps>-+|W#~Wa!-FY!O`n3l;#TA6 zq{{=1?TQY6(vAlraX+WKs|-SYOIIM}CpXx=VcZ2~EH0vHmc2+s@#ZWq&K!1A!A+Hh zdgWcii2jrvI~(_x{c^|ZvsY)fIpZ`(h1l|9O&9JF6#VzOtvF!IB7|<+G}4dgpy8CuN&isxOQFC58`4^jOvX9T zmp~~;$_@xr{)G!)IoGl_*Q0iO*X!$paq?e%?9MC#B7b`e_yiNRAY}rb{gCkvbA{cx ztks54N?-ttL7f5*=mR6b0{2h3(Tg;QM2U+^{$2mm_^1&T7Z=1UU&vc2jQZsZ6RO6S*A*R5dq_GA;E_3Kuau`LER&Ap8} z)Y8U5+XfWnds3}hwtK^O^;J$|JGsl^btvi)Ixi1lB2}-#J6${=VMOYI+yqYRV4k1XI=ewfJC z27HLXm5{+LA7&YWW*uEdv&Vt(cDM7D0HkN2@ZSGXcRz$b9xtrS7{cf3%&beo{_6=T zsml|ktZ)Df!mw^HMb+dJ3BSu=gF?<&?R-Vi*Ydu)`|>;O#aVh?=cn2RIF;2vz;_6z zzeg%d(UhvN9F2c`l$2u&=iZTHSM*i{mS-w#c9slxVilSa5IVbWnf>#tD(U;=MVw8f zrWV(&Z!O={7na8!XKnaHO7(2r)+)!UV*vqTb5Yb=5tzP%j{qci;IJV?WZjz7OhV1} z(2DA%7?OgaccHl=xP3HB`k@{^1esy*Cpt)tx#jXSd^DO=2@UV{BS485mso8r^=h)t zn%W2j<$s}U-L0+O+2WVKHt~(5O^!SrIMsVm0*C$xnZzu|&7RrRGGx(mn)^K zgEXj^mMOi*?=(5Un7RAG;@z$Hg-|+{&W2j-ReY?Uw|XE<@J>8RAxsjBee3t{t&{p~ z`9djjR|6#BoKC;_bkhBf)OMWAa+V(RxQ_P?Sv^W1IK#ffiL6=aN2|;z`!8HAydLqH z&tRI%wA1aHh0tMRo2?8{Zt?bJm1eS}DkaHD1{Y4`=*%^W9X7b5hWyb3??;Xx7vzNp zVX5{^pEbq3$M*RS0Nx6^2tun?i3XZ0zT8a>rY6P_huO13DL-hc_sRRhw^01dGJqEm zbD5Pt78*P66qc5S^fkW z2#`VB>X8S5wSn$R?KEX=>tw;l-jCmn^;pkRqe8-MFgfdWM%Rq{mpe&zh{Tif?LE z>e;`qZ1UXSu~1)(PH-n^A{F8~6{WY++Uw_LMv(7+nm6-^fajfbJ(Qydc1RUTd~xSu z?<|FLZIvV-P(L0u{=ij(i{tdTKt#Ki;$VXpjo5%;tvUBAV40paBIf;;FKs_cm;?t} zeN?y@1cStvdclBuTS($W6vI4QZQr+R+g~QcKfMVhFUq&7`fhl1oM^0~s=+LUY2Rzb zr?jr~^d#lW!#CNat^r#6kiml*nYV};3f^5=S4D?>uKD)~EjFNL*&I*}N${qG)Ss-WEXf|La9KEne0L zv}+<~lR1N@V$#$Xp=jTo^7-ymb3(X=H-5(9bwT*O?x`W`?!8v+CD(T7X@8&P55=yD zIlnlfiZ)<`hLSZd&BC|9q5jpT?*wLoYf?Vvh#562fG>iak6#= zVyuvar_);p7)0QFCnQ@{nEV$}2LL_%WT4LJqBLFgJ`Ca@YnMV;2dQ}QU z9^^=9o9+RoaFXV3Bxw7&iL6Ui#Q#8+KN4yF1+57u;Q6!(#du^xKlQ2V>azaZEI_RZ zoLx8Q|A%a6JH-*eB;D%Sb#&GYCP-;Ma0!kJ8npF^11~|w+l{6A^RtPk6JRkcrhNG# zw;R+1>={GX(IM?KAUn%`HSZK<)dBlu=>HO&2!&>}JFne{=f&F$`hISCEZ*vi_R_fPjjxNM3G3+r|7 zEb>RHL=b2gTg@8XYSH}yQsptBx0cWY&A%jyJgu&TJ{{&xdE{A8i)`a$E9MeeMYl47 zo|lUv%lTtsI$J#*QCkI~lm(dcpv7)`c#_aRk9!+@euob-rRm;PoV#cSy4grHC zC`K_(dC3c3EN;ocb^+1i-8(;io69mYW% z5QsD|6dwkCG^7zyP-^rf;PtcrLUXmtOCZ}fo`I6%Y6M@R9-3Bjvs~MYGaVOX*Uz#B z1(yc1a;Mm)v|f)z1ML-bT(w2gWj`}eu>TpMwfqgCCDPq|L}O+MP(%5@O3{uX@kEK6 zUP_0PJk#+?of{h#KY(eN+Z!lT|F}$^wrPC6zovq86TCu<&Q??21A&ejv65>7&E@7e zw6&-Pi*k85+xq?MR6{AqL~$4fU!IK7--E`am30YgZNszSD-;-l#_#0be2f1+tCqJ3 z$G0kQO$mQL5$*R;gZyI=)_mC{CH(wVl)Lv=3o)PDWGgyxw*A1g;k>U3K}fYgJDt>+ zzz@_&ZHziy(<*|G-QOn>`#ykbbwlT0jx~d`J5tu9Fxc8!vj*TfHhBKuXr;V1>OqI-| zyxx36+M{>rWiEH;qQ=c8Q^@O>a&OgG0h7PBDvnP(>vpY@P2Ml}5im~nwL|#-MY1l1 z^-UW?Pl0kUcS8`71XU4&ip5v(LqO748lD>tDM{u;1`FO_Fc8!zUjN_6+a_=8-Dtt# zsz%YjJ$F7v&?Q;w-oWQ0Pek_y{DYfaz9M&in@4@ELHsvL2Yld(7L)3A7w`%1pB^-8 zCd$C4z=^2jS$Mbg*fbhPsg53>_#LtT0&~0G1i%(#lXq3oROMv#Lwsb^YmKb7V#?{H zHG#jg_cqb@a)_Oele2FDJ3UKFPe=prY==?Y=oT0A+r8MPC!)Ux-GnXaJJFjut*^vb zNUybYlyRO-s0{#1VwVGlVLf1Xc8L`HQk#?pWnV zohCX$N|HOolRY?82>&CdMxhu#UzH!K#0ChNZw5w@8vosbd7dtFz`%&FQ9v!S<*tx< zq_7M|DvHlb_7v=JD&p5=ZX~D)f64Eq2#vukAuKDmyu`#axoG`!{$~0{=gq+Ab@XOn ztVYP(hWvuGeq-(1Nq?hauF~$Ytz-U-1^9^P0?JSNWt-p27hb#o`o&?x;}(6i1yAMF z6;8&NQ*EffFd7y5Cci31liJ+V`vi!LAzg#brcugfb99rVwn>Rx5t`5MGb>M&z`yn* zPx$n7*lf540{X=bZ&SZk6ay?lY2+V~VhAy3j87}eDMa~AQ@nd-tg%Aby*Vot+J$5T zHPBvO`h@IWh8zM=Af)Wyd09mobGJ-2=(?=zFXCQjJA>ZG6b{U`e>oYiO21eaZjS6T z<{Kp44PBT1E(@?WJEs3)R!n6M0g769I`mFYNXM*jkp|kp?zDfg$wTDim)}SM$3nJP ze{TcByk55Tc#cv?ulUw>Y<+0S#_5NdOyaDZQ@U#Gkh|usV}}w1H6y6@{ejHyBz4p_SiD9+cSK zs83_XEwqCZ71B4N8nTmYFJM#wZD0=gKpU8mMc;9Fk$$!$m}^jvs(fE2&<3^)w1IH| zZD1s7avU^k%T}gvir~QND0*8RUw+5}A?LSlFXZ>nEKre`DQx)Rh7_jZ%=VT1AI97C zm)3s-=t%V@=IY?8bt9M#WYyltz2iq~K}B?SKo65Gwt5L)B@XXF_!oAz{ok-NM~1Mh zFM;%sru*^WA+>XsI;<1}`Jq5cFndO0f096hhyDPNK(($hf&PG zEW0nbxf%H+YO5&M2}PAuvb3R->_s=M?bjVWMO*^>DTjmXH!mu?+ck?%@sZSU)E zLcYB}P)2rz^d8C_D}Z(N=C+)8t%VVbn9-_ybW~BH2?N5mAEeV7%gl7!MI%0%mo^D! zE8#>FHhVstY4rJP`d$p+o|=wBfAVV47Psp?R*|~NjGO=;BBFY-Ji>plA&C`|cE>Vg z`XUjS`yZ$n%a6Rb>aLPl7iS!Qv9P!5E_d?gUr7-To`WJ_($W7uf%e+BlGrC)(}w(% z*wadenyHlOzNm5wn9JP z@h>x)QL=;a4wm*c_h~%;8RzJwYuc_y+^)mOZc6lr`V?9hjudo80qo79*;ZQbr2Dx!LsGe2r}pUd*w!g3WU9jW{=JUyI|y|lNy zq(^ctAw-t zvx6B(gS(4D3K(6&j}s;=ZaVyB0L+xt_}&(m3I}p9x+rvt$zYYSv9dsk z^jI<5X>R|vvgVdIl)8~4`U9@21XCKP!jZ}PBDDxJ!L*T~KLz=_V-I}=3LOO0h(m6( zBn-usZx>R5<|BuMW5-u0& zZZDDPNeA58xslas7u_*xDOzaNU`>q1uQ~G@cHYZ0=DM`BH-c2+?v;hDYv;t<#Ky|# z)ag9*rb4WKIjmi;y{$$}k#f#AgUhdfOff8?!4y5C)cOmpJe80Z=joihWYTN7p9Z8z z)CJT4H{%Jf!4I96hKA35(cXzoKJHxxn?0SsHDA-p!`#5%*qIW+-EKV?E4wykd6lLs zMGE)w%gH(=&IXcS=&c~8+^gnHqv|sz9Xun1fA17?w5-~K2y^DuPE}Tz##NWo1g6)n_=`mv2JTsXO+P2J9ySl+uF{`;w#1t5_s-JV zQJrhs&|W55{O_YCrEW)e?L!1Ln45o%n8GaV;)z>$77GZ)bMq1d6UW{54brB}`Dc+j zK$sX*sg(a%J!c}FAjNdKbl##rS=Dn$bv=?XbXWBNrr@H(T!Qw_WYN2T*4PIt%G`Vm1g?fsDcG=p8&iF^nOSc zN_%-;){ImAF*0)htn^Fnb}Egu(H{{iJLb{jlr zDyq0Lo`v2`7p1!qRt#kRx|ZMJpL)t(V>FQ~my(d?Ve6<)^zr&U|FA48PYGdAJlpKY z5Evo*IwTapB|h(1CS)g=+Z?aI{)9(KpSP&(`5fsLb+v1$K2B|MTPchgJO{F~8DO1+ zm^sC=b8+|x4;XdOfNUfaIU^;|e{xbXP%@Vg{^06N*Je5(ggr1~2qew)F?!zwiNb&& z@kKccGZ`s1JoLRqiGIAu62il&_K7JJ4v(1XN}$-X8yiFM1>cr3H`_{MXhf4f>@oY& z*&bomi5Fn1m>T+6npkx!M^N&u_zXVSA04M(RwXC(%LC@_K@8s4obuFKf(5$%tdc!0Kzi_wmdS|^|52I3ajqyOF-r2gcH511~ zo9rDSc9YA-HEffW={i;V%)!(|6#rciQNSP!Ojz@`>U3pDiE=Pd#Pv*?EyK5JtNTN) zU%_(&A`-;C3J5_`3&J$c)_5I~%P%j3bwSdjMkV`T!Gm)Kch8NS71D(2ggCF=*KWPt zXB7(_A>ujQCG{zE7ayUsbW>$HybT-IzDp7mx1SpRSjM)P?0c=HHh*41dz3ERgS~0$ z9JpB4+k+QSV#I6PJ1aa!F0T-$zZk_}QFA_jPTf>`!1~3qyuOFCJ4 z*H|9W=xgr+g=a!zhH-SE*Ks!mH0+2&su29{ai6<74Gn~BN~;L*hlZufI(qn$;IS2zf8 zv3)vWO$>pr334x-A1rcW3VnaeG@ zI*WCQQm5DdQXBrwf@|poI}AozT93XLDK4^?a)Dk5$Pj<+pZGyVT39L_koEhDO6i9X zyXNVJ5^0ynJS@&|W>m+9UM=wCU4eRxEEyqvfc}%8!ER8E_GI*b#Chw z?)e`q#<=payd=Gs_D)b54Ori`7l&P6-s3f!=vy~&uRiVOEgaGAjPcF*M*XUVLxsFm zGnx)_6O`2$_P(iL*@b8QWE--0r@lKhd|hUQ2~!5cJ}EUpL1q?{lOV-=kmw|RmF|vV zKS#snV{c>he##EyqpGg*&ikM^66{OAs7$2O_lq&aswwHy<^1Yay`j?Z%N3@x%A~Sd zs^5|0-jAgw#%AMWr3N%2!P?3~5Ui;>l{}xd)hT^a(psU$qKniGuB|hTiEzT-Bj$a9 zVaI!<_cXB~Y#C}`% zVL2Zo^k+im8#t$`O)qvy?iXzlyx_W0wWcVSdC_DW9ViCQAEF9MLQ9;pP8 z1?bA&(=DfDu$j5EOa1B#<=y40T-R8e_xC1G=cqV7&w`kz;C50Rv6oT{!{rBQUopvl z{@$jR_53Fnj#NUFKT0zlPaUS#Seb=jwQLLAXCni<%8ivw1kJIBjsKh&j){gC8##P% z6D(4O6m-_QWfIrbsopi^A#GkSpm1<2O?Zc=G#;u!+DJ$CwaTn$`ZgWIaS5*D>$p^K zYr(H-KC{g84*ET-VmV5gVC5IOhEN{&bK7b1@oOHUL;19c^ytm=%xU7Sm8uzyu*Zwj zdG38DD{*5q<{#Mf3r2QmQjl!^6pSJeoC^I6QWuxZX8xMDp_1ozi|6eZdY?XIQ1Z8; z$cQ6vr+LK8o}_W@PBw*dO{80VvfzWYYP$X)D+P+5?uT?m%yn)_Qu~03rsQO_d|(#V z_G?p&a~V}@PFS&@K8Z(rmYh}hDYKdK^;nz%pI>#6yEF(!tCRBKIX?Wb6mHX!a%Z55v0McNl(Wlnoqq9}u{fI&j583tT6PxY)uuxgz zs|Vc&v{#ee<|sVl^+ZyST$)7eiSuGrq%qhZ;yR>4yD{Yw#bCCFX&iL;kH?5i1DhT; zoKbR?Umme)ynm8hqe~j}=c4cC?tUDaRI<3#MHH4qCbdr-e9w>5d31-goRVY4A`z~48@T3@%p&5q?iQRkhLYVH=sH|o-_BD z&EA&3tr1NN*L1Q;E~as(xd~I49iQ7}By9^_J%`6Wx^RFF8)T>{#rlf{y%-bm+E_ev(1IR+(iOb zjEbjP*@%J+8$*tY({{VIWKDW}vfG`j(98MKnUv04tVH%#Id!+Esr4mcmkHH8j#HMW zC%wVw&o-E91XAzO$6G+iRen;d`{XGu5tt^woea@(fj}DqoT+-xU|MIkl51f;-R6d((*XrCm1(nWv39ygxeDajp9xasy*bUpy)L0ppw$K9Iplvu^rbc6JZ&ro2BiZD3icWdu z^I5<_l|pEgWRkv11l^_*(I?xLX!;m!gAmEX&eHrpa$*^cuDtib6lkR+fORT3@sfKs zIMBu1PmkxTob0oBH9%Xy;=Fv*Giy~A@9>*a1niI^*y^rxWOTPurme?hW^e0(@G*ze zwm@%w#Da#t|MkJx3Ak6?0q#|a2Da(4mQ#F<_;SgpwkFAF zw$TswQHQ3FHK}^Xk+`kX{GFBLui>VSll*!p&9| zomLv2V`p~$E2ISeWW3X#YIw4m{b zPs@Ww`yE3~wL^l#lU@#I;H=mnw(MG>`wLo1YJ5k>Qu0&i5-A^bSpn1B+mKi*FP zi3EF(ZY__k)4jKHFm%t(MP0QJn}1t#^1Dom?!JkzV0xSL31PIax%CNhEvg-Y%)$e2 z62p&LCrk??lstx;O)!%GkQgfdO=76TlFfMh)T|9TTDnL`uL^Ej*6*?1xc)^#bZ|rb z;Q4UZzk)4eXF#HyGrByxg`^lagJXZ{auqhC^4HLP`ccx_TIuhcexU){i4Y~W&uQv1`0jWS0TM~BtI>t0u&~|G4EeAhk98Y zd;czFmF!zTNq zD-I*H0z`+h_uYIL9ggNhw91Gt`1HQLM?ptwE7?H9NB=Wk zdR=6ea=I(RI=wxNRKQNYpAdB+nwzu8(Y%wgdrb~VSLYOuLBF>h_VROchV;XTn@C%b z)F%u2nC%q@7Sm_~Dg>7S3oHHR%P&B?Uc_mWh~78sK~T_oY$@Hj56g_XhjeSe4xiO9%~U= z1WWHx!<{^Ktk5Wex6`*5y?5ifgyM=pI`KiKL?Q%#ghGMIYw{Alvkg@lh*%+cv#b)wB~qCXTE_I0E~KebH0PkRm9w&1loekJthTD>Ud*>+HB0me)|8O zdIlH3-}NUpv5X)0>iz|bl^-;oD~Cg07}Jj@VD32I{hi_7AmV*01dQL5`%UTWx$kBb z2_;yQ8jdt&P^YnjA-6~_^!s;3+)iIWKb2|l_64Cp1jVh5&6QG1r%bGv+DjEzghtD( zyRR!M2l@wTLKb&ZV@f3~vqqOc60#W)g(g78NBYd+Di3O+vHrs#fr%8a`pt}@0!eCSO7JU3qLLf9;b!jxPaV)$Mzgcfh^Kq{&(f-BMC8V%j1c4M?`eyWJ>@q+5!J@ph|Wm~_GYE3GOFqP zT1ZU+lry1osH(%F(ct#FhaoF;&mVZ4zvUInIoUb8iZ$;8} z8wZqhbbhE6F8EGfI&l~iFvNdUvCBv8QULG&QYz-VL2-C_t7cIn&B{GK_k(CsI3JmF z*6F%KB2KCeb*IezSKw_<*j%!}VU}Tv_C}Stpv-B23{{l{)m`RZu&FIB^}d#y?B?xV z8FyUc)|L1*Ihu}3+k?$#mj@JEa=mRxx4SRePR>}~?&6M!u0F$p@Yi#GkGj*&e<<5o zRI;RrM<^x6CP&_(m(}Q270AcvQbL2!0%@vP^Z2X1bb?&j# zmC|cR2fOyJTX?Q)^+XTovUflex$vKm0Ogb)nj4Z2q~K>ypI??)eV+omKlSMJURt@_ z2VCjPxil-!H>`v*B$IqkB9I^`IGNOE%>BYK0ntUqM^IeJK+oG$Q35+x9d(6g{+aSw z(`Id~Y9$IYMQ2`jZ>G^$!%hr|Rr^f&OUD*iKZ2G4vpijg_2K*)d(2)%F|MVr6oT4u zGEpxp6hc3)HNP=?=Et!C%A!nRVo62qG{p-(l6V_^F)uQ|)rGlS_T_NAhU*JaN0o}( z^ACv`CI%Uub>SI2X65-GI!t^EkCEEMGwljbLt4cka$y?itcCwHxlr2ud3#Du`?1lE z$#DJdV=jjEDPWzSP$3?4DnEVBsh$lVDZlMkNN<@b!9-PsL-VS!XE1B70_JBu*1|vFP!xTtoj)UHX6EEve~InF1?RUIN#Wl(j5Wh9 zwQFjz_8iI^D}-&ROI5?A_EMILm`$#_{sK^;RH;nm4z-Y+^outj2Z;~!QY>(Zn$^Z5{J$I$yU zqjm_>*a^{%6zTQ4e7fXZfn@ze^ON&DHLxh}(=*vEBN6}VKX zLigLN!mxFAcL0on-dt@O-YKw+@$peI`AU17kv5~{$)qoyNOHnvh}n77tn2R;vPzy}4T z6xL$&QCr>{7f6up0a>kwyCZ@JR68g?&r9KKDr6BxKL7O)khod>&_J zcEv33l*`fHrda;c#O83`?lg#pt~bphD}sZvdM%s$Jqy52#%UA7bLga3>8A=2VF{`N zs1kqx)s1$g1ctK0`iAKgJ2^68P~bA@*=(i~D#2R`1m|k>q@%ds5<` zY1a>)KARh@zCU1dB}y8Da2#&ueo?j<6KeHCf{3V!sKM$ov%V8jSgVSeWB)$I(pFcY zjJhcp=Q_G_pI>+cEQQ)Be}0Bhkz$YHQQSO2E>Me53prpjUTmmS{KN(=?d+6Cvq&xr zL`%@q6ucyT|FcJXcFO?k;Mf?`7qd4JsWJFkn;teevhg_mc{!H2OwVY*fVzW4mX^fsgeC1@)uWm zc|?Vm^drvs_B!{y2Q_N+>`zfit}aH0Yq-*$2AAF~;bP#@WBgivxb?6Ces+HF#n|w; z@xsP55U<=p&_Um-Dd3kB$%r@<%4WPCGMtQM8<(MIX)rw57&itmQG+=AN$xMv!L)jO-NNFpliOwPyrI{#+$T2p zp^@u>nZL49-B`Qa?f(T4D#Dl8tGs#^N?qt?kgy1t9mhr#d`#IiEuGa{epKNUOzHDa3`iO0|C9kSwiscwgaO*YKtMaF zRC5)A>l|8dlG;6yUS%X&Ua~xhq)lM}(cMBhD}(%{?Q8e)@Xs)y5<^?HU_>hTTe3zM zSO#gxCR6ac{&AEqU$AiRc><6aB?%wpf9hCrsqisLmHZCSes9NI(B-Wj%lT7spO??p zMAf*b*JEn5%HdvA8Dn6sJ=;5|@ezRGO3WeE#v?1-t`!@lo%9sn4Kil^A;T48Z!;C^ z(h!G=nvw6Pe$iIbk!)Fi5qkW)b};k%e$E-79pp&2CTM9nOrKW9Rvdh)Tu7ymX^G0o z$)XSjsvc@kQ)zv;b*UgKpQ z{G6+Dwe+a1Z**_XaP^L;5bKw&babZW8@Ymvwz#YET2Jfl5rtq3DWu+trTuFMB{z3d#}ZmsMsNi_F_XuFE=tz zsNM4pbpL%5IwB@uSw_OzlR{hkI}AxIm;S$nplttJL{!Agz0fc%sgHIN zI!@yDhjbbNYY|z>x`l3+zqda-w@qp@DIBMaIC^eQi?D8X^O_`nQ1nvibg9YvzPD=5 z9;5sNU5M=8nNf77#p^dM0+b+uHM@B&A~?GGD5p>5yse(&)g3LW4Z2jxK(3L9ev9wR zp}^0?EJ^rC4Ckw22l98)>9S1 znpym)OgA9GBSGn>>Q>E>ixUG4p`$fgME0&cYu_vWz={?vf46$wnrTJ|Hmk4KOBAd) z&DgGrt<)mGs1%`y***UT5-~6#L|D7{HfBx@?aM_#!fX2ofVdG&4x8<$7JAECfBXjv zBLy82dCPc30jKYS+u$fUm8*$^>$VMJjhcV{GrWY7y9jl_P5jFr|0$|hG7>WJMY{Rr z;DdwSHRIQE1@0wzGyp(DtG%`-MOXmZ%KOp5w6i7IsFdh-42YTE%48R{8y;ymW;m&?_n6H*E=IEW9l@X?~JoF z3%f?bQCq6lcv7V}osV|!+iOZ+RxDcV%)Vwy_1K*)H9&{-g%i;7pS10C%<_B_z zs>_SE7c{SuT@Z`6TfCw;POWjJabTI>$LneS&mNgPWLvVB!4wkHX6IoiU95URwwx>1yen_~{5OoGZGJu5 z+ws*)u4&WV@TDX%Z#JRohT|!dDsGU1NF+O?z`NQ!bmV4c8FdS>7ulbu{DUC!hbpDX z)jq>1BG@`0Ss{u5&;2l682!kQ$DeQyVgV43NO-qR z4c8Nj_BL{(9O=vE!<1UVk*=4gF}Z#6_#?cIhzbLjr~H^F}fKA(aXS%mQXPmm`d!`H!d5rqAXjz@g*tv?$>q7M_M3!SSMg z(St5XBA3v9K(xg~TIByeRI)HtM6(Z0|E62V?M-o(6SeDC56AGNDr;%7{mG_weuAV> zVrTZc3DXQii!)gW+Gj)Ibd7fR*F(emkr&MZo{8Q+TGuVR`!Ql5qJo!GpULjg->{TD z*Ld4rlU}M2Zbta<%R=MML}Hun9W-9?Kt1bmoEMBF_1A&D*9nM>M%9Kh0Vi^J{|R6< zn~^Ks8Evm)Z($;J6w0<+xou;p;51o3ZXB}B4mP}XYXO3i$oH&(YfULW_XP8RBRuF| zDb%M|@8;eM-=}i=nUj(HxAcBShWPCg~Q`M(`bKxt%P+IU^I0&$%YgLWu7pNcb%ul-@s%X1wq; zsJB%^!m1noOry|7L31%h%sgr8?f~M~Ugh~8me~ejHuoUb> z!PHiM6Y5m+=$1UUVB7!+g2HiH2wN?l$hFbcg~F}`<)V3@mT%nX7A?}Oy2*1?Es_Wo@ z!%XdMG$Sp|hE23Xx2Bp|AW`ZbSknB3fV7`q-l82SC6w;fK-EOAQE$4T6nhWU$xofh`S&6E9TV>J&%aU$DjFFwE5qC&Ts2MzZ$FI_fkK!Cbg?yA?> zcNrUcW{5b+CFoUfe7bbMzwgoXtn>~W(Q`idd{1q51K`SNVgT8g;bnvq^Q zRGiJp#x<%@1z45HM2@+fCy$u0h(X$MZJzauD-01|d-$h;8szxT)F_7&st11X`EqJh zaU-b^{q&$Bo%5=-EJpp?A8)>xV>i5;izn;%<;)#UgrVMiU)h1RSD!)_NTVcnR9*4N zj<^;@swYcIMglQsgfA~$X@!Iy&8eZ`n0vU3Bu?9U(dM7^bqmnr!S4-YNPcZW1s5o zfdcuIl>{^xGGMc6nVKH0Q@axnm6#L{Bk^V@`sBI#wbldQ7bV5W{BPq>+Pmi;rzd#F zk0ZdGk96Syt^F&WQzZ%S|CSo{KW6?xx-kL9DWVTKPvoPy6G{U6t>r!ElkWnF|5AqD zcz78vJ$_`%Kk`VgL65#ILe+~nv}`J0lixhUJqNwue8cxYKgW<_fzZ=CAw_ac$#l`o zJZ){(D&%ga`XpCLKYCg|a3p#r&?Kk4qCV|6D*y zHd`FG(lDPnb7~5?*1*WeLXk=1-}i4Pz)%c7rG2yNhil2Z7!$z?aTLruP)w!_UfBf5Ybk^gsYeT7yg?#mC4 z-vSD_hDT2C23&yt^f8pR#yTjc>l1+AG6`F@yUhF!Xk3_Y$A4bBVRhZQaRK$rj>|Vw z2^efQ9eXZCfV)*w$|Hx34w<4BgrmzDCEpf`gc=b$lF&N=vQ~amm?mW1r8Gsgwi;oD zpgE7BQQonfO3E>Plk2@;b&_QKg+mIRlDhPM8OUCh#CL3EbF;GIjoBe(SH?`cv5WH3 z;B}|h`CGxUO7bHY$5a8G=O?nFmxe&`aM-kp4WV-US#nrVPa*cSo`Oi6utrcJ;GHPG zEH||6Jj+IXa{u95q59?ho)&xvbJd_OG32ijwN7R35j+Nl6a!m)wSIugS6_nSv{qIq z*JD&FCW9Fh=jTm$o8f-q(6%*aBqI00v64~g_JSa=0 zKk8<5oc}du8jH;}uve+|5(@-*1`z~X64Hiq5MQy)hzI(UasrY0XlOTd6(2cyZbM^W zmO^b^>(u;XlKFCI&$A&Si*@Pz1yb4fv;BBrDRi5CVS)pSStu**mO_!IEw2wLKE4hd)mi-3pMuPhQ_^fK$9rz(KE0an=`)Bh zX+K{~J7GCFga&B;502P;4r`m;=f9T|nN@|+sUnwle%rs=?!NziGOUq7BgDv74Z_hx zO_c2kRl+zHI}+4G@sU7G=iXCaoQEb-rF<1mYCUJe+lXb>wfayV8e`)aJXr!s-;Vvg zc&y?tQj035+oCMb?uaS;{gP#`I_Ya6PYF-_>2Q?lW}SwzndF^v2q1CA-s`dD)eZm*BR#mq*`OmX);!>V1X66Wi@&!-I;@E!ue2(2yMq(yz!^Bpa>jz9iA3jhi4IxBB(%dvZqFTleWj<1Ey#i~Sbl&iAw=v}}KmVwb4`$P_WMyI+P(U`X|( zYAKZZ&F8o6nQ?bd(~q}!n8&q?DYt|<;@&-#N(iLkPL8LyziytkZ*!Fjuj|mwQ*tSG z`lvqr=MEECFbzP-3h^J>7P7-6X)|`n&Oo&vVy~_26stgRNGl@rST%o$N={Bovwk1h zhWE~7GMd28CLoWR#%f$WSr{~jO;3q(U3IRv85R2G)3%XTKA4lEdjv>DDJm~Fe_|>z ztdaAAo<^-^isPR4psg~v+vc8nX!zW>=NoSh({nqxDstH`2VBJ$&bzM&#|TPZTITLI zI&T$Vxo&l;{40_WMo*+U-1c<-%`s zPgDN8{rX%%^%TJfD3I7mBm>|5m0S#PDO_Y%XO9lCeVxhOCgkNhb8!oeYLRYMiNJ<{ z-=s_g^LG5Yd1Pvnog&sV_}-^Dq>KMQQ=48|hF%lW#15cCuwq@tZL%xMSkZGB&FzWL zv^ZUk>F+VLJ9;NX#XL98*THKM@!fu|nd%PC>G=Bsk;%!HQv>9JDRx#Fu6UKD%{Tu}c ze$QKnXE3w$=#?1%XRedmXV753J0zS~9AWh_q3PJV9!J4Vio5k!6u@^>Q~|LT5CYX5 zlTArfAGYKaRzY2YD&{(8jO+N+Zhq#DxEn${vDYVz787QKfO<*ISxQ;ySE$E4E0YXR zrEuwoz5dYC*Lnw*$h5Vrs0Dr2WK5Lp4OK~0k^4Awo6aa1N^ZsJoI@JWj?*^aLOL`w ziUb0Eq|A-nyj#wHKF_)hP)&{CAx(XTI8Eun?-_DeN^eEe<;gidYKB)cKd@S9r8`8+ zPw=Jer-56ipE18|>a;|!uS`IHCWz1FT2|2d^AL4~R9hSpFP(wGn4Q8mld|opxA{F; zl#Jtf|NLE_F|>Xd0OJi)?aeiCQv{xwC$jStNU!30801G&XHf|z5Z>d_^V7Yrsh92! zcaCXvwd+)0>TWNUdrmG2bAkOe-%%jG*sXb`q*jD3E|+tnPNZ9U-v2>`w+ZAMc+P?= ze5Wzva(wy!z++^CDwJ;7;qx8O(Mt`*eT%>0?&>U|h1kD)6!B%E$%B}>49_A)aPn zvf^0YJ2hXZ38FsIa09N4OF3$tEC|?tj7B2EH-cVU%7xF1h+#L454Qh5aTF1WN9rVU z*Kjkw1)to81#j!r`(i|jI;q&Or3Y6;5lLy_QVYV+rHmGB3zhxAp&&lIXj@1x!coTe zD3<9NmlJ&CCWS*Nn=5Q*f6V{`3AVGXGM9){sJk7@!eeY{@MmAm{Tas&Ob-dkr;2R2 zd`L&_unX_+owTqz%@wOY;n`pCrEV+`a0G^Cf$%*Wt?!cesP$2h;_qtg`6A1{TR5a8 z{Dz%u*uTjOR@7V{Ja<0y8QrB=R4e9X62G#kDcy{$w4YA-6EgFzrP_|)c-?XcudSyI z@hb%pLV~(V#>6DVFD|_~O21Pv|IYQuNFSw3sgVh&VZda=a!d06o4I!gWbReJ#~t<; z2<#K(_FiB`;J?S^UYm_r;@aRAkFotsS^UdgGx+HNY1Bd5Qx)p7K1$$&dV7U zvhGM2)blGy(9ZIY>;>8)!f9G%Sv^11(^U7v(*oK{811#iociH!b4?7+-LclEhGPGk1&T879RYPXSP}MSgH>C`(CnAM#cu9LeS651SDZQH6{l%&^XJJyZx-%{$L%Wlz zjCvD3paVpV)_WO>kh${q2iEn5@ZFrx&H!U`lZ`e%a$9s3H=;sTb9~oaAe2oI4VMOz zyvdH?)BzW?$Bz4@eJf?zmgvH%cpPws$U1;|?Yu8g<0{qj|CV)Uw>+dqQk<|g^ZF%8xby&M4)~j-=BQt z%nU_tQwoEX%K76-IEJrOu!hZWR5dS#YKPsKudZ0^M~ zL8Yi04@oOo8oe9`gL^wY@FbC*)_=vPRCo`>l(6@o@~p#)+Yl{^(e{9j!vEHQAGhYB zF(LizTz8{vqJAyg%cTF=42bR*bLR>e+z0di2!WS44oS#InW_THYNl@e9OqiB<9W7; zcu)h39Nr(pr1O58TM zl_`2A%s`q0x0ntz*HzHRboma#dMMsG`gQjy0^4v&@pcH+Z_E_YQASVwA7}bU@;WWj z!Nt}3HC!w-!%$0!$Z4Gju{O(7L&t9X2m-Wb@L5`TG_Ia7H7&|ACl9u`;Oth{r}lYR z<_$-w1MjNQvm(GjWg|J15As^!pSt(~QL+p!F3>V5U(@A+ zJO36^&l1=gBzPyz+t(`whljnbT5&P_2&FYa)B7rSn(`T|=;$V9zxsGY9Bl9AhRG{K zVVvI+#(yPm9gK<%kKr!uc__fl+X&+=-EF632T+U;cCb zC?|QMvH#23QTC_*743*H0Y|ebjNG5lbjOxeomM+JOBT(pSslb*c+cU)keKgX)*a%i zY+kSV%YqGEt1Ajy`y8(=`;{J-8nrc89Oge4hBdM(xs@qqytYb@>r*a1EB+@dc8 zk%2?jW+)Y!LzxFJ!#tuhseAlKceE(;1GtWv!%g+eT+P>&KhNT{ddMio{#U$5)ndT` zsaqWz+}Rz~cXqNQ?I_6auyT7s1uD3FHp|6TDANzz>o_E{0?Wmrwh8hrrfUyihdGJP zHGh?(Gih2y0zS&8=(VT4A^s|+)SSx)M-mJWD)e~Ld@04(oGhw_$6!R+C>@yLU;nLs zgg${)@LNr;7t%+rQ|qbgAS%Rgj&Rz60y9-ozP#hTE^AlmBVMSI+>MY!-mMs1IHCui zm70UNj$GQ6)3Cwba%f;FcW}i4n5ySh+*=w>Bw{(j*ZYk61=F=e&&dt3N|dlMV#!>- zk}#hzQ;$r&MERHyox1FRPawd+s;sX;?g0Y_JY{lvsmf?!q(YGVAjFBoVqRV(er_*t z>B+gRIdWEUCJjRvk3`Zz%uWk5li}~ztM%J(w~rPPy*3-x{EnS!P~(}-gRoW&mxx-F zF} z?fHplCZj-!1snyi)y_3C%e))UCy9V~=TKL_GR8Oj3G!{f3rQ#?8s$m zK4Tkyol}3cn__QIulteu=3m|pVb2#)ctc?ok5y7pg(;TrI7?1jO`GH8i4ifbb}j>t zr%Gm0+j3!Jsh)+@Tpq{P=h+-bl=5j#SRNi#`(mYyp_Jhp=v(>)u=1F}=wuKk_|NkE zZo`(Pv(E{q9}5(Q?lLVtD{|W=PL)F=N2wmR<_Jvyw3W%yvXJ8ggKejDp0vD z@uJe3a8^89OSz-dXT(UseVUSX??4RK+NpHCF~d}Uti|=QQX3q^SfJIU+2rvYEg-XR zg!z2ymqosZ%5&La>GUSEB}Os{ZG)!$P@3|^(l$h(-M2A~N)(&SZvH-_ zP#y~m1e9xB3^AW2qAp{e*uAZ4$hXkVeeZF@)_i>anUSRLPn|cQB6Jesmf#!$llT8C z?Z*TaGVTcQxDP%`{kd+Yp0&D6W@2xC8{{@Yz@b!WxW*cVyXx#v)sRc9e)MM+3$|_! zHD)Qy!iRxc(2o=wuPLL{(km$zm)-8y$&_j**1)2GZI`19#S1oz$MMB4nLi zM7)#EHXaqDxZP6$|Dr+--QiZi?@z+5Lh?-v9hr8q$EU2#H3H-JE`U|R#BTlrUxHjrN=sO2ccMI*+T00NJ{f@PP2Y7_M z@(zxt&$hB2c4m5~iDwnu`WG&a6@-NWS9>?qPTd7`sQ%<~=^yB^X7XH{skxGz7Zccu zoL8(6G_y#-yA0>hi96AqQIr9tePj1_e*R;m#mAE+w*57>`jiZ zO*gB>2&)JZx#T1E;GiHq1+s@Dby8F5Zwy~S=A78I)%%^O7_-HVl&r>vqRVu3V&ZR)pQ8Fg&uaaMZMb zg~Un$!E;@+#z#D7_(LcmKEY1^1kbSu_WXy?HwHaJHtEB6w&43A5O0*?{M3TEA^5=$ zNt*UlAZ1RKiG~UD1Nn_y)Q#$;*)M?%FHQnUDnw#Dyx4@7jP@!KJ4gYNw`g^vQmvMaB#!mS+ zr0MUu%B!*fI0^D9;2Sv4Et?j-cv^h?M^QmQkYe$H{_hkW=KrYZMD?M_AD;g;M*$Qk z%MaCskHrVK!yT#5!=h?T#fwP>cS^hVEjI#9Gx=0GU(NR3Lgetj2`QRlYUcx07w|kZ`hy5#+Zn-L=`FD|4Y&LlprxNE+H@W$zp`; zuKHtvyq;yU>7R>V$c%;}`khyJWz#}lf0%G+-~|HC6G_y zwwd4h9ufH?4{!?28NK7FGD;MmiA;%=^d6XZ;Mi9Z&@}I@u^P~aL>sp407=> z5*`Y|5`@~D*7q7#qgoD_Zpfi=o-?=CuUoH za;s1g=!Rllzm@dzzb2qj)bN|51KXqTS3oN(y=m8wEB-ULTDfF$)le>U$$vE%`B47b zV5GE1uUxdWS;ZnY-z5s)xx2y1}Z=FtK%9t(|Cqdhc*wIKVmB&>}TAHT_*|1a_Ui%hId z`>1CN#QdoXH7t8w9cqV8kc<(R&OfRSzN_Ac0SaCF;@E*7lq3@p#JDZy|6rU%v!!!I zqg*CCZrL@h-5iNYwC~0BC?Jt3pph&CpZw;bHQPc=vg8hrbYuq;!xc<0rHCz=d4vOn zB*v`sp#N{`I%42S|L8hLT4;*sz2H?@$2Wlzyx;p z=;b+|L8zr)Vmu^Oi?qJ~Br>|NUNU9T1kcJ!2dtxt(TTflGfZg%;2=%A^sUe{a|G3n ztIK7sihOg)SV+q|TBoCBQoQ6BI;792(5va4TYwGj*Y1kaMbFL*;wE=wh@77S22ro; zL=6%fpL`;d%Fge`BJLZmaB$w46bGgy6Wx*gdL?>A_cv>{Q>+3N23-*aCJaf~A@_1R zm)0BUKTF%m73}l<%V(I)x_g?)oAN|O5zib;>zvOsq@zQ+`^ai*X%$+QFPrL{66h&F z$pC&NEN73Pe~BTb8Z$wt&UL&FCDkx|1%XodwiPGGzR}e29ziwb`PrqQOin3ZOlZ&C&>E;XE}9fpr0kEO}mfI#NWvh$m-TT)#k zFgJgyTaHh^z1>9|VqJk!ebJArq3=6O&SK=fO#X$UiOTw)iaSWxJxy>g{K+d(+Grap z+IXac@4k857MY2G(|`#v_5T+|LX+N8a0?@go&glM*vDR2Cr2 ze~P&vFqOu=o#j~{s#*=hNmZWG*_&xFl(P~ArqDi6lxbgq^r2|0lgSdb8*k13V2j%? z&BHVEkpz_9Nh0lHfkW-VH{#c(${-u>qs~udN97gKPLexkMvpdrBkGLlw(2;YNj(>d zSabQCJ-77y5G*mpKrgesDk76nw>TTT#n3(H7`T}`)iif6q?PL}=ckU*n7y~&8rQV< z_sBcuOGP&(O<&qgo`>L_OEEVoiP~>jy!Vh>IT1Nnbk#4K)HGWN4WfjE?fl7>#JI5x zV7#YK0v98HrcccNtTKrx2tuj+wl#TlZ16Vt@-7ApaJST7|N89I<)=dlq2RAVBUk}P za|HtZ6W=Bu55%`Mhr0hD9(60YE zn#A7V09KXX5g2k|yT2c7uUWS{-!UD#ciN!y+_D4u49*#oSDXiS+z0AAUCk3t<%fgJ znXZenuJ)69MPHF>7JO2zb~s!D zJo_>L5vr{-jrmKx6*{uM1Nu29E-tRfUr1IS%jpxx&#{inO+07043`sdl2x0gG7wXcI8X9(z$=i92~<~riZPrXjhK7F;F(B& zGU_>kW#4f8Zv3i9O4+%2qgNmr;3VQ8d^$abIdcjRdL5{MZ^D=Tkv~-w_jEs*vHZnt z7Nb{|Jj)dvc)p+TTdR1O!UC~;`@-$5byHL^TTd(E}6s%jT6wuIw<;tw|@ayEbvfZAA3Wa>@V`mF( zeRf?I3_d^#r%0uJTp#;|vB>-PDgu%i;GT5Mf-Dlhr1uESiS=dYr#rgC7`mQ)LbJ!< zU`H6W;dm>{6G$OkDBFun`ax2FYAV6!pX{`Hg6v+mn}7@pEHY}^jpj&9Q%nWGN;9uN zyy}m+GPPB=Am^O@t~b9G|4hdGaKU|D*P>A&?Ue5&N^Bzo4jr^jK2|64sTj{s)=@); znS^N9LSZTTbz}KzmgRlT(pLo>L;}ql7>& zg~7vhr!4p%aFss&CXx6e#9uF@pk_bi$iEE#9F?O4WY@Kod?1jFmux%nIUcLC-PwX! znMsl(9={y;Sr%4>Gv1518(KN0Hz;xtU*-jR3zhvw)h8w*G5#-m-ZMvH`^?H{+mgDk-A2};9K@c+hS}}*uDVx42KGx;@7cYuJ zmEx}lYWQJHi~G5L6Th(`rSoh|uO?Y~>kV@)KY`P@UHK6AnSOqaJ`j447 zF19=@g=dXZ+EIvD=O*p>in+j=FJr@RdlZe0U4alH38N8ZE_c}_pJFI6y^8np-qO4r zgr((5n^%rlin(IQn3*b7o)ZrQ)}~*%XDfEqwm%{SpUUZ@fbC3))ODMk^G0$W>UF5i2GzIX(|zfl zw9~}kpsG>|#7MTKG0p03{e#=J?GsV>{3w&!{`y4BU!tXD?@`!% zGKah=fHLyBUV(1k(sjCAb{h2S2T4O5(uo^O)Jjrrq8;PnX~P`pFua!Cjq=lYtdlKA z7&x+ILYoFZP1P4gv$0!Frbdc~DtR}7L9?ok^>~Xvp@QvVgbb%X_2f&RcJFl z8`)~~q3~ob^^oSvszq`@u5Y2HxU^YyQ+}R92YH2g_fIeT9dK9`UOT#}?2C!*3)%(V z?xMI+C<^X>6`0req81_57LR^DDdH7yLCeXhq$w3%h%+HC27|OONrJMFnCyh!>@U(yyo&WKtxMg=Gg@`M?+R-~1?NBryq`D=|C z-B5WV#jJ*?>XdHqm-=6s+%25HWg-J_5@2xDj<6;cW|yr?$~KHaKY}RahnsZkog|VR zz6&^QN7RGY;3}s#sgHdK@>I*tKyEU)NOE0`O@WasSs9UuO~-kpEl+^w6+<4-{{%nP z-aT7IPJ1jw4X+!^1K_7?d-U_n73yTn;7b{=9IYGQzn9p?#xOj&3;tF%80`0$8E>?E zlhwc)QSHih59_!`27zX3LYRKjurj(gxfxF@e-fFlUgh@{sGN9TDqA1&SvY=)gq%Ak zs^h+%X#dk!K^9xZC|F%8Cka$P;RLa+XNUW7<*TPvl31kXe&Tw5ZeL0~F(ipI1tA!S zwJf2M5$XfMxm+*}$*=SSXa>5yxce1sk$W21Ih9gmyPaSBdLod5jH*|TFtuGd{Bl~3 zW5Z?K`se=l;pwRts~Rvx(V{r;{<&sbTVDfmr)D$o#DbB9f!VsEEVdrq%?0|?x^?^x z4>JM%)+sv>Fc|X1%E=BZ&2f&oBLZBP?1#H&4{U7G_Dzx|V3!J%J-ipmTZc4@9elT^ zIDS||Juyq(S_14+`p-WxA3j9IeIliE;%I!<0ge7@_C&CHsTDuJNR4A3(oP%JgibV; z{!P3}Mq-{5lMsM|y3vmNR)7b(Lcn3tbm_GZ&%S?VBy|CBQ4Jv8x5V(@JPJJZ=hk)g zZ0kntfto{j?>@j-c^8z|%+5eWb#f#s;?JuHHn@oIR8*+wF#Df!+9Em{B#ugdNZTqD zVj(?AuT+^UEIsC}SlwQg%1FRN*7a{*|0InVyv=1^$zyiZ(Ei4rkM;xJ`x}+!gL50w z+cgNZD-c7mwkfXlR{cj*f(Z!u=_N%Zp$Kb9Pnx;RWu##v{ATZgmmiV`DeQifV5cLh zgIlYkJgD(Q8;bT-a*~HY%i}abRUA;clFOISdXV&R$y?)9)? z&!&Q1WU!tJe4f7$6@J}yVAo~#s7q0hW2mKni+WBKnOF?LC|rkc^*md+Zi0m>geHZ9 zujMR+MTIUB-KzJ*@dJk-L}L922S#Ys8(+rcKAXHgYJ`Yi6y{cLDhp;COP%?wjf?x2 z9z_9Ry0l)A;Sj9f7^2XW%#z#oc`oyKhveA_8FzUy3s5l#=UhT1G&>qRbaGANz}9RMo=o zIx$Y2JI>G0Y7kXeg?dyDN+)thzZbWCl_Efb`9orUyP)QLmWz|^SuEfcWX;+I=Ftr! zP%;Y5@g6+a0UKe_Qez+Q5p;oQhEA@}!9%V4u}CJNcN>Hh%(dRm&x&(s9S5Gzj=)7^ zd>=_COsm=OYkfq3&ce|@^TA!i+JiyFIF`PP5sVKB2_y<%0d^2@cLBZt-M9I5dRO}^!e>@g{!-Dm*+B(z=LJ^J@T%@@R4j*^W3Mn=2VfUpI zRJ_3<5bBcRs@|-Ge!;WkrL|Z-{j9v{sQ7iGYI`P;tPCj_GXml;|6uBi|67Jw%gMM1 zEGKmYV}T%AxAm;mB<;}qH>WqRgubDk4c6aeoPrtbZl7@wdbUA-L-?#a(DfC)HeO`c zppRi-U3d_D=#Jtg#t6GDD83|5C{;M$l~p~z+9Bj-*EN-CF76=0)kkJ`U$9eSzvL~U zUC56N6Dfr${pOC#*x`l_{>sIUa{^nZ}0Q&(&>Fuu&chrW23UEl3%I)^zA@I3!3eCVYJ8``r`1 z+mxvhXRpz%Ld$YdG7wk;MA0>AFFp;KInv?gpx+1g$+vm3*oCD|sqA0mIFSH?)KCe9 z{qkRe6!d2C!g`y|-BWpN)S*{v+Zk^dtQzd+5MHAvoHM-jdRfLaW}m+VsZqZKAE!)S zqbmu?jnWE5;R!4u^Iw@tvkO#d3v@?L?$Wf$Jd=CECojIPh7@oH-=WAi4oR@^%QLg; zTX(ggRbPjRzHVNd|LM&;tqVh}POdlZ!NmaxQvAK=j<-eff*FE+Z*aKf;iLQrYm@GF z!@K!CGoh;iPA+*$VXDKHL*g#??6j8->N}}*Aq}$(J2Za@QVft>1%JGIO?AL}bgyhm zjY)s3(IWG!k$t@CTw*IH3cR=y{q4#2vUxOuz~=SqpE~N2=`adX%vRAsH6b6K9HOG$ za-|@N!BSxZIr{5!T{AebM7x)HI9YbaeTaqv;Xj@GS;!-C(f1zF<5ZtZBInKDLLn;5 zEyO_9giMGM`34kBHXCS6{36iO)PgUDtHD&ED`Gc%Yp0TKNWZ(PA#)Z+ql#GFuF<^T zt)I7YJ>r^yV1sYZE|ClIjnC&*GArs9EiSm~iNPWTrel|_-kWK;8k>T@by*jjWdzGL zZ%B_Ofq3y)?IN2O3d^M9Y5Kr;B|-2fvA&vUB^U z*|O((d29Gh1IcQlM^bo&3n`cz`vxt7Y#IW-I=%qKd46ogt!-@e+Kz7DzUlWKozP^< zt5L~gvYn+f*|{P4xb=$BpZ)HLLfj3p674psKVHS($MVQj)AqTx$Dh)YWR9DjUbf?1 z1<2!P1QJeHzPB;ms&i}b`tKMA&7%h#V2fV?`ES`}&uCr>cl3=u6WuqQ39gXcld}9i z3L+ZzQZ8FI=BiUEQ~c@3TgYx! zd*Q2MnWm~Uuk}yLBHUpwJ|z8i1{UXmE;0V=7uc*9#>ZIUmH2`RH6Tz51MMdDO3m{g zOwnC!nAwS280<2Mbi37x20QXipwFQ1gZQ@xF(G3;g959@|QxhMKHgvVkwO=wd6)or&nl8bDTrdfVaXJQytYkuyh7Y>Ro9Iz_QY~^G?SXD~E(C>an53Jo0;)mgl)Vt{D z+ZvCfdUHKEZ2Ez!I=Mdb{*zgR=AO0z4==3O9UJ}5P7g!(@+V;bo>uaP`ooo@{f&6b zjV2tiQ~PR=W`mw_U=U8Jbx(>F=MNk^Ox;>yB0AgVe!0t`&=(8f_4HO< zIccH4PqF?WW&9`+{etY*>Dud(I+&Mg^6g6h@lCq8Ag{l!NzgQU!U28PA?ha)7@x{q zKYtC6gUBiYCkyoguFcQ$UW~-7)Qz;9`eyA1d(5g{3n_@w6C2I3(?d|&3F@!wH6sI- z7grjK<@%tgryPjLIkIT2B^5dK6!}Q}$I(B1SeaC2YNIGpa(F@tws1+#P8EVnX&I>) zTaVf9X#GV<#hzxJGuySbXO2#hzJgu}DQQiJXg$m0=PdhMkM*ViK5EP%lt@|b2)Ls) z%3di4Q&8?`F))T}%_yWNC!O|j(TGNdqM)RBetG0#!GI3)@ip;l?t%*8rewYW#rYQ> zrBW}_-|OKzB!@-;LT|75wl6t|>(&u*ERS`SPnJ%&LQGhae5RVK*?y z)zE~up^fUuoJuR~zZ6ujpeqXV^Ppc)KbFKIF$*$*PH>!}Ko16_MmJz-@lMyjtZ!&c zqQ=?Ukvps_oRcxjW^Mf~Ztw%s8CV%?b$;Kc+%KZGpe$wba;Eb{k1RvS?x{%Cc+)&yn=+h%;b{{sXnydl=3_a5Tl9L#I-0E5Qv z5in^9@tO=Yf5^;q_RI?~|4@k74Mq@g>miaY+sq@a5%}YM zmEA$eIYKMd1$E`sz!$;;_ZvoYhvi>-)>!v~2*Di-$9)cczf-GbWQT1cejXT#(sE@+ z-mQDbM`gmB0G2#>4J~;ra3k^`Wx`^OB;~a`K~_J-fgWh_50{r2=igoL3ttAh|9&1X z{tA1SDprgJ=T#IZ6EgmQuy=zvQAvIVc(l}p$Pj8iX3OdcNX|7mwS6>&Bec_W#UA|| z(2k>NACn`S*&4Z}xrc=MX>0m@V1{gJlwDD&vEjd#%-BTyt*$wdQjS>9Om( z>=_|t*t&f)C*2rdr@RX}%M-7M2s}y}=?HM+pK99;@}TU*8UwA}vqv7X#7Mcr7XTWy zKMmKY1&2T-Ax&|cl1DCx{8J4UWqq_*14k&heved0a9{Rsav+l&Mcvq+q1aL3q3gM> zxDPQae!j|Yw1slUs>qe=37-;CcCgpHv$U&*i1t+f;V5}Dbr>aEHd4vuT+OvNVi(5+ zK~lD1(c=iorPpj9jxJV90#`!B`7~ByBQDr&p`$=vB`@QGnOj8W3vi}xodM2NTSrlN zr`@DYhPO-xMl0XrS153?k*5I42i${=OQ^v05hz2rQl}1;wgZdk0F|_sY7>=$3vd6@ z#tPO$l&gxW?ao(P`J-)SCu24~X5Z%PxU8FNK1wEb;|Nnac$?}3U`sZa!?;24gl4kCLt=uFIN;-i5|m z8$$3hPY?%`=MBfdN&KgUn=It>Vbg>tztm|)i1v|pbVv}l`O}OaB<~sBB~>3X`gZ{L z6wZXEIN#$zhf@0x692dvvVsltzRJhe`Jkyh6G3s396{>fZa3}62ee?^<{yg$Rg8<|zWhscaBZc;uMee%( zhq&IFPrIw*ilh=a`6(f9oP5H;9(%c6u<;fM6sS7+oMMHZO09PLu)~-5J>h97fABQ@ zV%m0~#mJ_!A%cKs?R>@n<25Zyjm6OgBR#G8spw z_NQ#kwrgL(HpKu*=*B3hRCQwBB0-iUM9&e2!}|K?HC?D%ZHGp}=ei(8udG0a*zXY@L=x3FQd#Uo_(3*4k4=WE@HA=9_j!G#78hG5$Ww ze`F7!G8!Lgb_=DRve4qAo+%GNfgX`d&BKim%e7F0-F4RB9CiGd8NUcMCZza}TE7z% zPjH_eSw4_b;Jm@9j)Tca1^_Z&DZ+e=lU3_G!9I$;XHC4HKt3 z#-W&Lo^hRz9vuW8@XGa=71V1!F< zJ7zfhfnzG0TOx8Pjy)T%Er$L+$I8uIvP%>EkkvMCS-%bRnZJZ7Q#bLyhwV7xYC;KF zCf8x~`Ul>*Buf**#53EWdk@>ERFTAnCZiJCC4F|UAPPuZp7ITbhR5>_f%C`>&NgS$ z+ef$X{8jW4xWiw~*`4FEH1|Ab?@r>5w)Te|48ucH6uEI7w=gza>Ibb#H+rd)?I+|w z`3QS#m6;@@(($)LO*81S+ z@Q@V?fXI=?bK0pbJ8HuTg%q{^W)2rOk#PQVx7=Hb+vo~YGFs7@+kcAveilu(U);zo zQ-d2g3M=DVbQ9ZbwZs$t_W`XFFyoOE^uPO|#iOZ}@n^5$=}? zA3*CP%9*UlnDPLE2(3<6yq=Nk75=V3p6{p0;oU6m^f>+>T3A4$Shchef%}C8Q$?sh zE$3Q)q!z+>X8NuxDE+9UF*~&`CS+JyVBrV{$ae;7*0-Iwnj(^8%?&1;R-^G{jaU3o zjWnj_EAW8^D>FT;u=zC9sH824@|zthc^?JJVr!dPI};`2ej!XJ)f~laj)ytf!2i7p zlOVR*Ec}LmCCA`t3QoavL7bl}CX0#M4T}>pd`{K5yHz-iyOZMVc@(O0W#v=U^@}9D)pzCt zk+!0QR8BSgXI{UgI(=OFWEOW%8GWI9hHycHagROpmYjeT!WEjIH8s;#W(`;k9qwsL zgX=B|@3%wZk`V#>vwiwM?@|%H5vZW9Ka++LX0H&I(6AeGWS<7Oi^@^~x!szIU{M7l zq!qbQ|4-z&)mLGP^!>yM5HOl*5QR8Wt8LwO^yqPqiOc~MmWO%u%x>~!ci z7fdtIM_$7}b<0?Ss<}t<^Zh_X;q2NHtXz#81PJ64bD7-fc4yYfV`;(Uxtctv&yd;m z%Fy(K#(B!6a*E?luO!o1^{h&x=4@(vYcY0VnuIO^*Qb??BLR=YzEhzG6$qhTl?=CbhUk9~Llep(|gKW|i-gnKz!@dk2!y z)s&kd{74n;DhaD_{9*qVe@L%KDr4PU!)VC35>vuaqF7R#{ShuuzK=~UpDAL6lYpAEYf8DuDDw5CaJ>%>Dbb5 zw{KKVC0Qmx28k+wW_=^(r_kAP_#$PuSWMIrNE-LtszGyT@4Z~Bx{Q38AZ||ab>Y#H zpq^fY?!dTW*`io72D{_;VdYIK*~OmY7ihv1YUkE(0;x!_CjU{MLv6EiGQj>4U8H=7 z%GwlkN`9Gx*P?(34Z`r_GXi-F8nZ}*ff2BxZ7+TorzAA2nPVZP7WNEQ`x;>^`c`dw zmpJsp(-MxWW%`e*_TqOT`Au=k3!rOM{&v??NgV(6)jL7$@^-amq-eA>;H~8~9}HrH z105Uz+F~X;KJF-fuenh(1=%a({&>LS!0cVYeHD@faovsKwF((D*KVuvtPI1FNA+d= zEmC00PjMrDg>e)5=5Yc9oZBo73F; zbP3ZDN11aKm2LW+H-QM{TmI0igF@EVc39cz#RNqnvk}I)IWM1v6h^QVdL?|NWug<5 z*vyu-u{11XO%}KQq%bbCN(1Xj0RO_AzMlJTyqLmrYfi##xpz|J_z`wsbv+HL5Vt=3 zK$xhk0YV|@r{Bh?iqO*3hN~qvFxp4IV;UWFP!v?-J3!0TBGtHk`-o@{A~>dAt5;+) zT@SH~G)4Bh4;BhxAZoC}b)aRBC@?nPeWRk#-4qTD)MC#>?TXQ5@|ZA#Fv)9Jt!B<+ zf79Vyb=WsQvzsG?B7f24&eeMKjapM0gH^jl|49=kUEAn*{~iV+)`wTou9g=yQw!bf z?+D4|Q|FgR79T(>ZP)85i^Xh#b1K7)I%_)a+t)?seOZOQ4eO$D9b8+@n3IT-n^y`* zIo%s_GO0HQ!tlP4>KS{T!)F8t*~rrAnjodVm<)v_p^*|9Gw}i8Oz);W67ZHKD3;M%b!Q*-?hAx==(2`HtfOP$ zxH!BG8lDNG*C`!%QfE2hXWu3}o%@qHawYrae+|)yH`R53#jqhoe!f1F_dI)d?Uiu3 zq3k@R#U)uNBc>o9{(%ew>e8uq%cn;I*(3sYK=%nJPm=T3!nVZ?))uSaoPnR=NhpIT zSR9lDIm0oHa13=YK6xFdNwKQ#Lu+ss*c>dIjjf*{0-2E+Q6nn6eFOhl3$n#-je)fQ z>HlEvt%KWIzjRF*Vmo$BiJ2j0W@ct)=9rn89VcdHX6Be3Gcz+Y$;=+*obH~}GrykO zbL&>!>r&|t+1}bxEp6@nJ?nWFDzljS=?Z5^M&onOf~|F!Rg#~wFp`cEGDBQJ2ZI5a z{Ik>xti5m!y6$wJ0m{=WvbpQ;55h##zIOzIN4eP$FvWQFA6<(=qI8?p`9<4_v1h}F~b}T zU=SgVJ3gQO*u_wCAZogPH>_*&(LJ6r77gRJAPpBoQN4(Ian63>bF#mb@60vgU=n_- zN#f_ZcLP%@mtgu{b?9Lm64m=%VJ^iu99e;VtSC%^1TidI&|)G1KtfnRS)0o#7cV}f zqhyn}f6#o;Eh92H0>6SZVRqE&C*SVde#~{lcAvRx&$(XfEq7(W?<4;q!5->~67W7S z%Fk|R_|RJbkhO-;E$BD6Vn<>rv*BcVf3?&DO-Za*rm5_=`gP=hS6xi(BPiSu)*s8I zsmv?`#DZg4QrV2?>xmrtElKZu@pNa*Ey5IXwtG*2N$3t)n-rH=mS~el+e)(qpQR)> zIimy}`^}5Q$||{9i7}xMI$u^zXpja%Ki9(%AAj@`jVb2!+~{kTQB!^Hb@i=nk#i*p z!?dYp5e~N9{3g@}M!?{~2pGJ6F?9c~r*f6mDC=*6%T1oD1FnQ@W$se~gU%2lvyoE0 zQ74!#doxTG#o=u4!>cEVKs$2cFc9;+s$9gBaT+4$oSj`zA`H2X%xbRE116uQ`&`8% zHufeN0l#c-b>&6J#FT-}5!|+*PLC})Lji(wyNi^#$H8M%&U$VrH5#AL{I>Z;KF`*H z`6;Mq!*?E)MuTA-id2BFfcM3yUaO3BpDS^mlMqJ$*SSJ;l&0pDNm*w?PZ7LrQt_0Q ze-C)&t2Y$DXXmo;r}h-n(LqE{O{qX=I>19blb}$};6Nxra0Uk zRt}6r?Nf{`v+I}uxW!p5-yi-B#}!S=jDBs#41 zQbGoXz$f{7cl%7h+CNN7P2@1ZzVgI5Eu=-ExT)iqOMj;f*ecw})QNsKIDY}7`5qJ8 zZa*sL7RK%T@Rc1Ws0WNFMH~QHJ{~Luv_IzkLY)1Aa^r&osW(lPk}MLiqDaq}QK5Z( zs$p=?b$}x(WNxp~UfG9_W`QphxZ$kM`XEt5wO$k-CsvM8G3re&=KA!L@N_i^pUW$V z+wN_CO-wD~bYY7n=QxCqd`61N^4AD%SwO5dxCNAjqTm0U$GP*`vK?=d0|-u1vYK1J zpBmk^IzB%IFD3fH2Ghi1{GUSUSn=5_^rkPKGPN0fGlwGPAEEC@714%`KgqXENip+k z@(EbF4jjSMKE;U%b{s5ihDt1%W8xb!SxyCUu^+b*1%<4g9V--taeohcMd#GSP722P zmG!(IJ0KNYfZhauaU))VQ5U-wop5swLUbp;dfCiTtwVKsLDV<;$rRQ@dJ7_St{Xh4 zZ+Ay^N*aVWh=Lkrk#>D+95uxdHuhph-yI%0XA+2lu>YpLe^ENsoL?Yt0r*dxt~;OT zg-TdTL>L3$^^innH9^@M126p zD!!-fp*;)<@EC6|b5Eol&^bMNV;DtljhrATN=Km3*GD&~2L%)=w!{sTG?<3Cx~I@8 z$SzFkFK!yd`LNWn;?rHF%NZ( zrNp>^<<>9##B?NqX67#ER>w<58qZnD>+80+jwD%d6HU_E_{mm=CrR$0G6a4jD8acC zJbIXSUv-irITHN8phFne1}Y$g=Rs$L_R%jZF9@)nRdfdq5^tPAY_;WEC(|J=bI$ZSti->H}S*zAa+w6?_6#Ev*m47q!-5H2dQwl zGS+(`o}upZd-!x$X6K0h1wf0H#fxY8kFmxqzfc#Z2mvQI<1s{5MpKmzIz!DC< z(%YszZv!R(X1EiFhyGSd+t5OSSWCh7PL7hltkg{3l3X28+186rQ)>MnaLk44I?8o= zM61Bb_Y_)wCMUf!?j+fnoZokSv=3O5UL54aHQ@+os-iw5^;xgCZx@b@!3wv* zG9X!&^u~U!AOG>a_z!jdIT_*~za9>U-Ej3H=c|g(s+jT2C+jF;Ah6<^d%IWJ`-!bx zEUC-CfSVLN7f&*{SaBO3;2-u49h(^ScPSDJ>J|(R>qZ|f=;BG$_cl_8Jp*~iLeiqT z;e9PI5DdWod|5`;<UD1qO=?MLpuFA2Dt?dISk#S< z7mfcY;=&$u(u>(X!#7>acOQkTW^?8zc;JqP4yz&D{Fa)B&Y`}97!987E&KD=uS;n= zkcQz$UR280H@z-f#rKh2Pim)!F8Rg&hwG;ZATVH#w)qPJ^haMw{CFD@vj<`Uf{ki!zn~q?N&DcDysmME6($^|>>)g&VtPoZm4_R3 ziABO-0PUCaQ>Op?c2kTBX`wTNy~}KQHGsaVX}e1er+1NJ*G-RI zeEs|{y(j@xm8)AeYV=d_9HaVR1wz%L?0ZJj7{CLkr268X>l+N0(?Y+=@->YD zytq(6kHbl~P~*I(tWDg9ZxxT1yQdjkn4pFT)1kQynlh`?JK7EBHAyHy37zDnxcBGB z;0Thw0*>2Lcw+}b{e#`|(DOPy258gAkyt;>L;bwgW`8wx z&+=H!$G(~wZ+Byu?U{VJsFZsEirAF9-uQOYrt^k{1;Q7>ALVFm1lx|SFs=|4MztFj zM*S~>bV!VVu1lWZ&7OeG>qn6h?T&#pOJw;}`^v5ZvvvHV+@U*@R=Xzx9?XAucNYXm z{lo8x`9l7H3O$PnrL1HMJm%j#k0fgs(iACwEQSoPWsCV9P_^JP9 z!My{(?aS}EU?YZK-H$o7pEl-;sfHb2mS^)O&*`wgUY__h58gWe*#$#{Mqcom&ZTDb z2#SuCTaTNB))xZ!sZK?0-Gr7WZ&?Z$>_TeUyJML&xLNX@RdIka zQW7}|6wVS+dYltD4;xtP?0@}uqYwf3BL_S{=}w_C8m=Lfy=7SWzIHw$=5m}R8{3@r z(IPMrSlAZ1{p~v<@>)nK*UKyF2mrtGgUj4Fl!&KQZ^(O4oT9$I3-5yjYJ%X%_n)o5 z-1q(N*xzr*I&zfu5z=bi&ZJU{L2-%=KZ@yHX7;Yy=%HU_OCnYeAs%sAr0r74p#gx} zz%kr+=`gum1&aFmgZFf8Udf#6r0lqOF}hVB8uoH}o`PA+*jywKjG>TrqAPN-MC^PK}J9*jN2aewF~fhTYj{rdoOf0#40V$9|G* zSI3~o_nD<=y2tu_(gAdG;g|#$Fg*cXGJBZKQQFS@)Tb!|=J!4v(r$PyX7I8HDVcC# zYq6n8dUEC?n6uV2dyxURkK65QlH_iM48e|nAW`V>l-^?bfp;hp z`a1>g^`QH6{Gw8gjF+LeWqMkP zr{)TJIel3;sMkm_%kix0i{n**i)}ciDo$(9(wj!~X*?<~sHYpWX(1C-z@XZU$m_mo zhl_;yPpxX#3E9>m3qY_AWSGP7Rl0VOGc7Va4hZd?z-fZkv-?O#RCzkwCJTNR@VXo^ zcpiAxr`McotX4&R9Yh56nkuL{Nd=IP!1<(e+sVzi z*c_A`Pob-ffWnaax7xZ!;$i{c^6_FdjGA8SiQmsZ+hWF1&XZ4n>+b|A^Hm7!awowL z#NpWPU%~px>7_6rv;9DOb$8l`?{6HBr#=Eb@OxY2Sj+Zw?Qcv`Bm3yNE^? zgU4J03c-l5=~TVP(HxGrzZ26t1g?6k>bWj6Jyx|dH0y zXU}sWxR!n8n_^I;{vDQSdwK9I>-akbFOj}e7tL|);X(+>2tTT)m~wbxkb=?{OjXES zl$NFS=bd$Rjrr2WpwvVacK7{N;*xx9iqzQVD~d{^10X-7qF#eK?pxEf;h>hJ^n){1 z+NNUQZD>(gEgTVdEmW)AicHBTO>csh5-marU6n-LCqkyEG6Pcq)C?|gb(1C?xy(=A zw~VBmz0add)RUNHRlRdj+3aW017HCYC|_3EeWEgZi@eEguAxMcJ+#D?j-KyJfE0gj zLo9q&TBVs@ciCbtZ~z6PmV)ovjU$8`&qGJHcsk45nI$dyaYq26LX^SRdXI_4{Z>!J zW7)3Dk^@yfc~ZN!CN7#$@nKu6~ClWY@XR+5e{rbYVv*33{>8o41GZPcy~ro zUfvFHyGzR!lfchbQNC9!V9X_x~3P z9Nc26@I5Gz(P%z+v-)Kg1q2R9B0OBpubH=OO{>#}Esh#YB6KRnI+}*aEwXdyr`pq> z?)r#CFbp%&`_{JGt#W&32=_+=d{!F=|5EF4MIvNcx2mPJ zG%?^ApjcUR$LSDg&gxI3=vOSwinCi6r|i`uSAb?DxZthoUlRGYD{?WYu=~R!5ST6+ z7l@y}4bTvyfQ*L5E}JC+i)>42&)h3MGe$d2%aXRBt^ef6@wB7P88e)9!>}a-%h35F zCXl#He7Ll~6)>qP!mGrF65nE@GlIHIg&F-8O zt0xb~GAq)o=c{g4Rrh+$Od&cl?rx*MP4B|tNx7;H5cKd*o4sHp{6f?rw2*Qq=<=U# zMGjn3TV-*9Jj^+(8)p^*MR22;GK-O6&EbZXR@P2BH8uPeMv=PXQ`&VaifLcjyvC;V zj@abZhtA~h-!q5K{xeL|`T(MAl{y=Tcs4-{%^;$t^h?|Z0MLhe!jk~PEeQtDAASNQ zGM=$YjT>(%Qu~OrZahTJX!93_f`t$9Wa_;eeD&>3dL_A<&RP+SvSIc@TWpY?nr(_5 ze$K!%FYDwvr;;!c_s!l@^?GgOXFR?t&FQr9HTT=EL=^{sm|Ax9zhr9I54$;OwuSht z;C?M?m6q?6Tm9A_@|O7GPKYue9(&PPDI%6VRw)jliY8}wyx~-1K;jR;_!D*HI4Spr zJ6A@N`v9e!BqdoYS2=#xrc?*#1G*&>aMd{;9bkO8rl3Zo1Aj`RWl_*H{8rC1;5l1am;doux`DGs~)oMnl!b(xyp^9Iw>&hSqm8NCHC3F7O{2;AdZtXjf}o_#1ahza;(8 z003>NW|_d7PH`P=JwHRV3x1*i07O-66dgo6qXu6}Pk$}SwLH3v^OZ^oar6%vJK5Tq z(}e%bb!4<-N%vg+GiTqdhl98Wf$qUEZb* zkeJoVQ=s90&9e1sGLK9-GVrr-klSDI&CqqzkL>{k-4jor2Q&=r__m-pd)b8FHb~p~ zy;joKdRKh%0uz^nic4zESb3%QGih7p3uV*RAi2Mnk;FBoA2+TFl&U9lj6I9{%&H(E zC4>Nbv5w%Yga~klj>MvCH)!dfeD=or(q610uLU4@9}&IAFU`_)Wv^XHKd)OCqBD;2 z{Y?w{Ktk}F+ZzqUgBHF2o9>!sP_fCjn>L?Co{WXj!jQj8&=LHn-XjzzmX4CVe~MH= z>+;5`ZI{<>gr`N#|9@cF3KUuh3Ow05_*WFx55MbXgWTZ5o(gs_nuMJQ&@wr z8ie>Y$#S$KtCrJ$SJ%?+9I+U6i-=8k#L6T{=5p1-NapS^5xT*^kzsIxf&noEF+$XU zu74w9+nsk8d}g(m(G7*RoOPa$r&|ySF;yxwl>9caXHH+LT0;yG6!5l3=``}(nV^KI zh|Jnd4c`y8GMc>miskLMZy!eBnxl?T+#*=u4xNA$$CQ*9H>lVV`#)!7qf~WVUBnm> z#(f`~M;L*8=8Q;lW*4pOO-I8PSr6x}``e$efv4NpHp14wAQm&lf^DVEg$yD1!{~>h z{S~(#qyO^MXjT8sQxgz%FwzY}DdTF7`>Tplj|^r>f`(%C*q(UXK^cv*I_X&xNzs8L zS1q4#&K;F9#?k7qdFT8C5(_^gyWOi5sK7(>TYH>!-c>U{Q?amq8>kt&ZXX?Wve`ws zatTWLpSRQ4e*Q1E)2`!9tv068RGwc7CM|-1V0<6Vv=1gA?Ea>h-ulIoR0`buwZQiGf8-O3BYe&AQ;H21ERQfr&}?)()%t4%y3)5$9z57ddum6XRX4fAG{L@G_D_+$@7q zP~pee`+=lr_=qIov}TwE8g+MH@GE>CBC5%M-`$@=)fF<8+Oz}cUC7~4m=tKQh~Be1 zyROOh25~bz!j1VyMZ5D&9*H4o1xQ#4}67EcaQc zE_|@R4VdH6d{ywwUPFVI#X2`#anV?P6i>tNDfV_hP>E9UMVRjbH2#8L+Mwm(zpS*G zV+p3?ncQ<+7Z3pT3jyK^QPM1(c@>CTWb7L?Cu3;a0o%obG3l z5>7#%U$NfNQ|_Y4WaXX3sSf-w{~ zI9q^IPamT|r`5FejNjIysl7*xKN6Mkxqsc|%7FKI`2K0v6c5UpsiSu)ndRehP z{k%IhdpQ~!0X1pX=&A37ali|mi|onZ78>5rOI5sxk`SYd^B|Z9z;^;J=+7ZY5rUr| zL&RJPql8r$NH{GYn-vr4fJ|1yuu+KN5l+%F#52g&F~BS~ag%*!A;}yUoUHd=7ZziV z^si+!1c(2wj0Q?|{NEs>=}x-CeBN_{hYx|rV?9!1vb+W|+D=Tg$Ion~#&x3boZMxV z?3;}@?`8Z-%VF*@&-$GN&6Vlm)><3@tn7j)9Hx)UG`3Gnx~uvBU|yF0nRx*)L@?H) z-HP;!!C-gN?_{$1xIU|v0pmc5AAsI6oG)SK10tJG$Fva$Xti zqEl1QmM^a&-hyHuH`wgfr)F8O^!UPxjllrSX4)MZ^(Oa2U*ylsFc;<@F;HuzGCelx zTb+mw5kEvh0~7Qwr|SO<<=CHScqv{q?k0s)wH?tp%|NTDuh+U^#u;C`RUnhTBC)oFB0rGkZ9 zUN5ID9ok+BMz(=WS(S47PN6>h;{!I;&)mjflHemDV9aJRdc5IxD+jqN_)lNW7)1+1 zK~mKaIOyt_)=*nU0>1IC)6>w0A6F|)X5bYo@PX@yNj<9}Pz*|us( z;dz|gun-YZn;tR>bI~^dF3j;r@R>2s^+`O?7qz)eOV%Pi&99xsD>A!PFp+8QgGnRc;P47IexK!L zbh;1^jMVqFTYv73!HC<)H@U^&8E9nte<)jYMi$M<7w;(&_d}rEM^)7sWwTnp*M`Q( z`GIM%fco%|a1^jzsKM_~EN^$SB-u9O@A!8ef<++r028@&#C0?RvkIXX_YuAX?2rMkJ!XskRY~= z>XOISMreKblsb*UE~J5DFqA@_i8akh75PwDkPnKlYRMm<%P>QDv4ytV3`|;0a29q^IY?f5{IAC2#TA+@_VMgKbdY!{>8J}?nq>2UFY+bMU*jG zj~v`}lLLKeus5i+sgzDO)jQ?@{g7k(NY{;15zc zY{&vg@>4=>bt4(=neZr7;rbt@;z+~c;RuKf(La1ZR)DP0=V&D=3IHV!5a0&*p@5YL z2ojiFKNBlx)=DI9ZoOW;K7?|*GhMH@xnG;Qy0{)y+h*m7CV&Sl|KdS^qa}+g)`+R% zK}SsZvVXF}{^2!v-9WBv=qn}1T@PweK}&{9zT4gqmko2YM9j4c=lo!mxUi*uB@+LQ z!g*?)Gk6v6{a22(6-jHahm1AH+u&O6eW*R?<9ibF6L^J~Rr_;1%W4f8YJFy=_dQUo zKW<9 z01Aj-xe^FQEw(9Oc=Gxyqh1y*-zR>DXyhSPxJWs1p6GwrP{ZW!?;@%^4sd$<2ZBKG^Vz>%x6XCs({YXMuuUD`eV0krF?Or2L{x zR>5_-?QBJyB0Lrr#@p!dGdBC-Ca-7tZr}WzeX?_WL#Son)R*S#fC?7y$BiDai&m zH3PkNjImVRzCNRDX9j6WqVNqL)M9JJSx^fL*ex^9_2En`(pAJV+P|<{-lkW8&#n#x z=*ntjW}MXa)5LZ|0a)`gpZi=$e~@e49-iVgF%~`@lAK3Yx)yWfwb!!a>-P*HIswypwrM8 zmOYO--8%hTK^TT8>kv)^$H?H~eKh$US*i zd({|EC6|48eC=_$ppXv@%Gi4&aeH@QIlZ+>Hc(8mzX&FfrCK%2Jic|;iaYwaU@j{8 zpz&NEMaR60{7Vzh0FkGX=$TBulM>@N^{rm(*G5|-wB`a&tcQ|A1WN)L73Cn!l^Z(W z1zagMW2XUxUR0gyUsrN2a!;am=-CG$ZjV~p_V%f6mSWO0_R(hoOmn{ipY;};M-KJF zbIJW-Xbi6dQ_rzAjgNl$XmlQSF`|JcMQEAZ@_XxFw-s}-_VWms06eB{Nl1|y(|wVY z&CafYSXcWtK1`)Zl#4flBVdz>*ubm21r&arLy^R8L-O?cV*;9^uT?U#5@T21pU_q= zU|}v67(JiQD1mZL@hDPZkyr8>nzl#w&j!2EU(hgbVSCU#InSEKCa}*XbFV7)#N_^v ztW^3cg?=|Ngd`qUt+7eOml1Rmmvx>M_v8;F!5tj- z%LYTbt7vE*g^qH|A~M01e#1f3Ph7iX_j=eLL1&mU@EM3S^B@1lLn8Zb7p`>Y!L{>3 zhPiYBAv&=>T+QOMrd%yFt@RIzwHSZ_MNX^DYT>!^zpt>xjS=eGnTvo8{ z=r~@-dK|Ia7*!6mu!~^Jm5BHGw!+4FpoF>f;+f;M62f;$+0oX$+VSjLA`Dqo zv)_q%Q&aZJjG%`p-H)4JRz7I+D!Q$yuoW9C3Jt$D$>D2Td2XQJjD{UK9=~dP$qtatH5C)ZZ^Bscu!N}) zOx@!v$2*iS2leql}_^ zV^p6dac}Iw`l^MvYS6`mwKFJ{aRFV70*JtmK)uTW=97n zSUNXWB0kyZ+S7iS2tnP4Gth|K!D@N#Osb(E_=qsvD3AE~#ZYM`(xVL!hl?PD;)H&- z&ci-%y*U%h3ddFWaRl2+0fhu9N7(9({>tWoH$P&v-5?npusOHSMSUiQa2IASqx|Mb z3DH`RI4Xm|t9q-~VaZMMZKZ~6uHvYon9^t#js%)t$EF3W!xA=Z4#cdSbI^5QTXWQ% zgO~Du{%lfky}!5`NzAgi^(^z)R>Gv|`%FHfWa8m-IZCmwdVtRz9@%l^Yo`Ws37^RY zLfd^$|Ddd#E-jOv*C$2LWN%IK)oF~fc;Dw{4{PFEXrA6THd%Vi=bF&1)!g@7^mBoDapR>0-2Gw{RqHW^>MSS;K1odlkY7_9V?>_M z$y9-};hWybT#6##Se}E%v||&w-vJHmL*K96&iw%c

SuhL)+Dp*K9wm|0d82GKRyV{P*n8F~+z< zbsCl?zoaTG2)ZdTa=VQ9Cfz*;vd&+#;(7`*0}22 zEZkSbhda2~Y3~7DNrlLbwp5B9g0fbZ>E>pB`vi{=AD6GiBrSZ3fx3ZxltO-v#41qQ zY@OUzAFhH+B3Kw>)g{O3+#5BNnFZVYQ`Fm=d}NgzcQ`>BM+Ea40;I8 zgbp8--s78YOMQh*@YeWqD9&z_^H>@gXyjdt9tD+zj6k<2jPp4KiZjf8Ri%%}9ndt? zY?u`rwQrXd_j(-HKUHKrHapf_5|23ZXw)1+E8%Z7SfdHDL%&7Rz)T&WE51IJpKy&; zh}}V-;;P~8y4Pf{LDgA)X{5o(Bex)U5*-MOfKtSE-1LgvFSXuZhHTC$Lm180;ljyW zDLjAA1YO5XC+|2K%NiZ>Cb>zjfXG$pPnD_*r(v)l#b&K4ieN(TGMCc+gadjZa0=dQ?k$I-*qguM>|oKg#p9|ns~cA zpN|%%LC+()W3ARmPqAmmj=pl8CA6>a|Ehva@Nf4|1<7Hae)$V~Dnhnv>(c-kTq-08 zD^@-+LQ0Am%I}Vqo%FxKXfF2VbSjhHN}kRidIeM$rtdKU{A*HCb4`-$CyfEW%QwC| z$3#KA8o^;Fh+1(Ues)OE`F8r+fmtCAq5uHKCsSzCtxW6Y7*L1Y05u3?4OA_5xL64S zN?@zF?V?jZA?<~+D^nQS;-Y5fs}WLqEZ15H%V0|W4YGE!KbrK@kKiriq(1bXY3}b1 zhPC7r<}s$L>J4vFdkf=^?8tf`HdT5kO(-7g3wDTLRQT5jj^_P@x^0h|1D1Y-k3s(- z%uOAfbjIc}L)zfi?{p>7R(s6|)qQ;m`ja&{!m9v(CP4?1ZB-H92nyMd)zg zQ3tKJ>~t zAZ!2I4(bginE2o^(}vX#ex8plaHp#GL+kBVlaGd^e;Z$$@LZy6OX z8wE$+f|#+cii`Fs*_s#hg5F#~4$hu2qpzjiHwqBB!jlRHkt>LzzGN);q=;}d%6WPz zy)~HEdzJH5c;>}=5V?|BhL`?U@`qfVpSInmY`GGBHpks7#?QO(f&}>0mm5YjU*F5( zQu@{%Qb{6G%{{ahclj8m=#@{fMXoO2-nSgpA13%O;r1iV1d)(~{H`r~K$j`2Z^1M& zU{nER5*#^678x5?RCf`%b50HMRJ**mMw57d@^?^3Bm4`x%KnXlcS-9H3Gc=9nG5V? z5Vsm$yxmTM@I#`!_AlBC&f7`t7V$#xYnjaRqYR#t$GL<}?HP5k!ReD+x!XFq5AQAd z!>tg57*J$?+tn3Gz1KtB0i6S^FMA3(EDA%x^%7bcJAGVQw)`bn+vzWRsX}L1MWf!1 zq6fRkwIZ`zXrQr~rUEKwfiol67yNurD~(ip}#4Ow=T}TQKLRf6~I#Od^H1`?-DO zv9Y)I#mAGx$X}k6C1}4bG0%95(HquT8*+Ab`Kh{%;YU$(2_~;z43xPMZ+vKb5m)G0 zsZ)9%wT^y#fx8<}CI%32xor~!bcbPor?B>woQv&&&^fqAE*00bn@y7C;zpsM9A+FX zjckqYg3-M?@XH=~yvk!6RVISw8MG3pLW06N=3lz)wTKxn96`Y114!C}WUl;IE6M&7 zr(WYzah8&N&9^@z#-8D^4ImH@*;%`V0a0H@2+=^}%@36Q4e?P=t6ravl+o~V=aol{ zRuadsmenvHHRsB~dqtOA*nph(NO?aTelvC&!|%(UAku`TZGZ7U#8GrvN}^ESoLnkXB~Sq^&oftm{a?(BZ?S0b{@Hg0%)bB zoqU&C%q(!n#R~z(SVr zKAb*KF;$jQhKyuD^(b0Si)O+5T&LG?It38!jrvi30@T>7V$bqYQYHwQeNAV9yog4Q z(3DxE>2i-(a`wR}pKyJ`=8^=}TE@idi}hw>+QiQpBgvJ;I!{MdvK`Cr=`<6?0HT$5{V9Lu^ysaU%2U^?aol`X zRs>~A^Hf)JnC(>My?QxNqM!^lw`=0ckaT5fbPx5XOZy>bEp^%0Zceg17wp%bGN(lm=)w^8&oe4;c4JM(w?FRSJV9_I7xfMVL1)kMfv0?+F z24Z`z6Oom3{1TDS-~<38;1QY(0R(_wv{|m_29!S_%-iQ&=~gV;E^D|_<;CMLjkl3a z*MMvp9^~~u!atVyk9fZwqkHPFDL`ZmoFmM9=GJuux_fCBw$7RQQs4lpvG@|~^S~R) zDIvLc+5pily;KKqXw6;-u&B4B9C99Q!)^&5Gw~eF+1NbuonBQy0|kDlAxs7b2R7|} z02Rv-ICrbR+Fs{F;bl8Qq>LoJcL4-!{A-f9&>wt- zEvMw^R0azMc+}e;J()>=D6QuDgRe5v41j}fi!f>MZbW#{U2lKzmDE9m{73Q%5kL|B z=7P^9Nn5PH<{x|ov7-UPSD9!oys*Cul_Y<3QbyHq7!=+y(BJ5!A@xaxs{nZm(%Cnh z@~`5Op;(cei)66}hi{)2_sM!YuBmBAy))?OW|NLcjk*vk679(+q?S^M(*3x-U3Ca)1XC(AF}Uv1JAioUT(wBd+!M5-QX&0-S`- zN(TIz@My^JnQjgZ&_RJ$I6&{X4_IRjF)@g{*ej%R?^O5LJuSQhlGSO|Ieq$)C^97J zku-PY%OIlgJGg$8jTFE-D$}w5)UcAK$o+-ti&GLnjB$?AzSY}6Bly4 zOCxri6$&e9ggxG7eGn@2k5k2;?5xUdOr%CqaSFjcRKnsrNOWc&^!IZ2W+7_k>j z!t$w$BGPX4#Z$+_#-6xxBKqh~cBjDMH8Y+8;J4`7G6P#7r;$aO2K4qxv1;{BR~~N` zEBFM+-dk->HamBj9E(9i>A`5c-DEZ#o~j1t^gx#UW3?1;+5gm(G8Go^MDHCrLYTr| z^}P(jBxR-QA8zAeInb6(;~}%9(43E8Dxr$ZxEbYg;u11X9g%&dyFbgUcL%Ymt$BSj zBa>uVDMqewndjuJFJB~GwbGZHyu>g{6g@V#E3iWv^D{?_?6rc55z7u-{)7URlOB+yyG3_k4un z9ced4zv&AZN&1O(pU$l3xQ6Jp$J~@8Qmko}x!#sRS9N4d*z3>l`xKKUbG$S}zDAZ- zPF+6v7?XSfWK-hY`MRMTBp;`8 zwMaKQelMPleSXR(5^iLbArsH%mL+Ko4){~E6k&$Dk(Ui2>_-}uKVlMN?;rJBmkjy_ zE^n^TDAx2m!DeATe?HA65993I_0iek2z}_Lpsv7--d{M+F|k)&k*-?OE#n8ha_~ZO zSkMv@;GzGK_Hsi>!@}?A=vLERK#Z>p5pR60u`Z1g7OtaRLq|EG<_I)W8%D7??XbEq z+Zpc*b$nlvuhyaBnjtyEQ(HEQlv4s~|F2UVG0&EFn~Hv0C@fHLbTP%7GVQKs&?5nF zf&wE?eB-1t8hhtk*=F@=VgAz!wF#||1>Z&ueFC@ z?TYY;!E6;C#lvF+J&u&sO5LVl2ljU+afzZZ?`^S-CGJFhZU4q>=-Syt7?y! z*^;RR(6Hd+;UgkWeA5S`m!y3&(KR`#Hd>menr8%vdn*LE9`C5>see<%NmWEV?_}AX zqHv%3zJ*R?9W_4GdU~DX?95*RN4 z3q?c$92syKv8c1jSH!667z_M{)74*BgRS+Rv}?iqx+LTR%3%Dv7r>MRt^(U|9*zbY zDchlG%16fF`ofEi&_fGUdiJH%1bv^IY0N7ad~d*6;(8P+%(joKQYV_Ej;7Pm^M=8h zcxoo9-YKoRG@urA@pkI;k6G$njc)RQs9k8es?M#lUVZb(;2Cs83m z_V^qdbzz1kN;0s{thloZ>@FGeO}Jj3kOvu4?E25wE{e)mOjQQyG6=E)8@tMfJCuyy zQ?Dt{%ja%*D=4}a*tno&QkmSQbLZ%ab35uXt90FhrxFiFuFq{2ER*ntBb>%SPW$i> z?kACOmV>V%ZhOf4{`b19(Gs(xVQQgC2+wyM7RnR^#StrxTNe(Xt)V_HI|Ai73_3O= zl_vELaqsF=L93QVeA@P!rBpQ1TIx4~3|0Iipn+NLSCQE8#)`XM2^S`dA+=QF^B>!u zR^xW9Y@jW6dM-{g%jn|w7}&`9~z(O-&zLvPIUg=)53*!nMD5ZJkXPf;9mHTacF_hm3?v&gQZD(CfvzH%oFLBaw9@^X?Cdu! zNiGD^(|G42sXx~ZheH15n&qcnV_{tmz`IYetfuQ`-^rpV=-og@_O{x?D44e+s$IFs z{|MLR+E%SbE}$L;=qhBJRaRDkd)6Tp1%5a|^`)|?;&U}sN=b?lqbvYA8d=tK3oeYs z8AkQ8UWr3!ZgWSpPZw`cmQosmCc${$6=;Q;9t2y}{RDYZ)(6KA%)&0QCGXInZc`@-50ehh8quz$*jZSmz+}GP;>LbJ z)=8Ie74ACb@QjYmY8Eopz$xk_4@>%05R(BODF-@RidX`9WUZrXhfB#(R4|x^(`+OC zQLw45@`$4}_x%29yE7JUtf-aH(g(90e`UG~pI+`JXXv~`NeI!DUuPU>OKFT2wnPPK zvG%4V@5>}L-q>}6G;1?maw4wk5ay-1M6=6<_?0!>TpK@-a=PZ9~cP$;Jg9-xSPOmu^F4A($iaw%-SLy?7~WZ^-(Hv##KhKc`+w6_k5tJ~Lgn-C;u0tA-? z0>Rx~g1dWT!QEXGB)Ge~y99R$?(XjHdS~+Owbr-p+3TKj&z{8}RHbOTsFB%Yj_3Ej zPp@fTQsdq3c3a@ABKl91A7K_Mzl~*Pa+tWF&n4_4;_SanqvYkP+z7sPUpKz$c&Hg% z_Gm0LtxAwaYC|?|&gnh!j}VYj`8r8~pnkYly@StX`IF)YT>N70j)Y3|S%*r->xech zJAcVC^8PYH`hU=*x;Zh3pu`k@4I7i8kOB-i4w~KHIO$;pQUnof(I`S<-5Fa|SNIkr z*Kepe-dyuQqRHYphiIHv{9K!b6gAFIncNGFf3T7f{-KOqoZ=}wA&$>ntBta8%{u9F&X+N^#Z#;Qu5q$W5&Rn*EjSyp zK&~?7CgS|k=Qu+Asq6>(Y7tHlXFEE6D>7I^1M5i^{xH;GY&T(k&tTuUy{*}XSz!Y>QRkCI4@ancXXX}F-OSlqR*_N!9F zL9J+DM@5z4_6(qNq`BFlRKKGx2NB>&HeEGZ9eKlScc~0t`lHHvlW|ZD=(e4t7}Qu! z#aa_mIjiS%v$4IEQdO5=(pA!HUtcABc2AZN-Y*n|93@}JhhigWylL@1Fs^K<(m-Oj zNS@dFp_=lzdtTaEw=Bylcni*=l4?|?#u^ib_ByNKq_#Ss_oUBjCG}f}^fU#%Wi&`- z-6}Wg;-!M({183ZSG1s6)&rN2T!lSgVqBw-Xik_kDB_x?p4594m-W8qDTy!k%0ANm7;mmYr%*l|H|g0A!yn;{>DpEQLqj7Yi7GcstGDP9sQ=s{kRHnE5x z5XJB%^23f61gMP8I3;Q75GxCMudx3eMErXiO7vrAwXkskyJlJhI1Jg(?~)Q7CO3S2 zUy%I0Zj}8_e$y%20f0^!!{w^}!U@hmQ4F;Funtdj;&;+1nde}M30T{(-kSbXn7@oRq5fXL`$$MSGbDiB#gUsbZ+E{L-?Q_xrfr;Ro zcLu?aMJv=veelIY7o&@aCyd&H`r+IP(182OoiPXe==1bO-`m4MS$jP{#1urU@j zPoRC8Kgp^N$aW)PuG=F+Mb~elRU+kM>~h!kS&Ftk7b!m0T0k#=S7rjwS^42_a=OZQ z;?3kf_U%mBpc?LF5CpV|*iL(7)yq5jHWlu=<-Yqnp9+foJD=LfPTps@rkVL_8qXst zkqh{&-!?5(^W1#F6^oEDUzBggZkZq81E3ak9R=`7WY=KKlryvoRe-Ql~jE*_^DMq=QfDpu51lGZ}A3e)b@7UpP{s~xp=P37?5 z6#)lXlU{Je-uG4uyT!9|GV7ZOl|=avyZSI>G9-pnYOSkHXB`F;7FcXspVAX`viDnu zt3UfUP9*$f^3Y+$z8OB3KHQzB3LYFOrv=BTH@zsXlDh+Wlcs&Nw9_c{ha4C7*)l8V zFDW$~=jVwZad%<}>@U})HvBj|OVoLm%r?a823VpB*&1OP18Yh3_MH3X`t<-`_;ia1U@=#}`Y8qe?NjH_L)f^5w;BD8ZGYrd4{f_#%XkP}0_vq|byn5@Gt%m6m>>lV zJTFN8yfFyjwi@kP($_og8p*KPBHQ9|UKr;>D)AkM(=ym;YJ$FDh&Y14Xum z%uAf*9(@z5q56S65HVkmSB%RJub6w?iSrQ-5hoV|%T_wcn*r^Z%fWRlpdCBG1b|kn zsIY=ut|H2ghNq4Xq}uX8QKJS8pdEW6C$$crs=0KB2DD@2dRHYV!;z)hv_sS_)D8r5$UT^H%+7sBV#MdvZ@Z5Ea>fMp0Xam-Lpmu!8~_ zH=6|V3mYMlV&JU0Fcj&YVnASOZ85g2yq}yLB;35oI4f^s>>#D9k*(1>YMp696cN$B zUt(y#m6|(Q*3)sGygD%d!9b(-PPX^_XVh|MNzw9TRdg3^^s9`Pn+kR?Q^v=0-QUfI zrf+HjW001JW3J=iXJ?abx<`Ou@LaZ z7=3wc^G;CiLLijN`$3ik!t7eA?h{?D9@&r7A9E#$H+-%_WgX2U_x>~In*1L1U(JTf zC*vlnplmc91))6%fNi;|pkZ8b#==$nN`saPqGQ6Q22xoH#X7Mq4e#dnJogmqMSo#6 za}!<^R&MC>>}_-Wd@iI$+>+3i=Mh@Dg9ZALRJ*ZlcTQ5+6`l>ol+gsnMim|<-N8+UJmB}=hUmV2ApcHGZxh9JVsfjU;U5{o^)B5 zgvLJu0e5;GRH5z*-jf~vgcA1XKt7YL(kx(*8|hwz8N#nB=3 z+5uY;n@HAh)|$^1XSn|kat)F50yRX|1jQv8-UZ6_{J{zM<8B{QApdIx*O$L=~vZg@jWE5VgBC5&l0F+e0Q)L zpa`3@xAuP4>bRyHIQ<>2y-t|AO34h9B5U+wIsyb?78ggxK*_D3(Zo2r0q zuWvncJEp>`#7DAmdCITGDk0fc5;x`q%v{cxXgminiUu`!6myUlrJ0RO*3A@t4TeBB z%BeZ-5hCQ2)9Ad5Ff(L`Q>LB2$~@?+l%SvKwr1r-YFVtAb>b?U8hAGklo_4^6vu2e zCI&cjyVZH{B&?wk(8HmjR4u?jKOHE%gPSWw4%~f39<5(B2Xb;#)_VL_J~z5e3X`@! zTOAy3-pWnTVzigZG;q^WzJzVPTgH@eCux?UC9G3hq$Do6hUakw(CwJO5B;^(B>`_>F}c9b;(XLtgVaf*57w z3P^40wKE7iZ7>Jnwm8L$>-()o?&bA}{y??ia~~Y>sn3!mO=1oP^xdbuQcXIIRUPZ> zkHm$re%PL#4t&pXY!~;8pIgWeL-jm5zU?^p3;T2m&6>5Lp0R?iXMBp`FljAc?=TIr z`a-l`e*>&z2$O%TW0)gyrOx-&`;PgdgZ9=b*c^;n$i0c7uV!q3_<50zLgW{5dT!aY3nD>| z|LmoSV)<0lV^H}0=LO|p7P^gRI-V53Jhtd^O@>dSief?P>*b&EnxBG-w2yFUrSda> z_qcm+S+aQa5Y!vNbRAY)vVmVTx7T^Q@{sUeXLs%fTsmF%1^X$vNP%b=-2u;*RG@krL>GN84W6HjsAJ!p~<_2GX|Fx>4G^T*w2qvU7KWh8+vbI|3hgmVj zk#OU1yMrb64jpNk3k`O}7c%EUQ=l5If*p7g;wSsdJysusQh) zxu=<#E

}1abcEH=H4l9#x!;KbBm}o`ShNDatP)hX3+DWexfs7<{hR$NS4XhEN1w zaik8I$Aq3!;KNw(uCDAq-F^YgV->dQMGt3@-3t~#!J(9tUfTynvhL@8xerB5BA!1L z^qh4>5h1MtiEvq7z;UVSivb4=UmKbyoC-8rKkFj^{ii9%)%*wY(|P>{ZfRO13l;>Q zV{DIQ$sj>SY>w3135|Gmw%JhKw0`DXtRe9>jKyA|;P2yqna6OmrX#V&*7O^k*p@!t ze|tbqrS0r8=vGOn%iB&KFs|C!q!JuxuqLtZu82x?_O~!3m9(8Jc-d-Mief(bq)5An zeP~vUFkvie&|5F<#J~d-93I!Q)>z(!(#qvrwsotsAef7CB}fZc!Y6@Aw*|>Eqc`PS zl>dmwWPXdsE>Z<41<2ll{r<$dicQDeEpKu@7FnRvs}hH~(=6Pcv>umPKM%v(aFO2N zWG36*83;k*V9USaL@`LaMrvkw+z-i?u94VVR%$r%EjSSjv{nfo8+s{@~$8y!(<%SY1gk z&$2LoB}N^4Z{B&VzwaA2k}C(1zFDCapK=nx%d$B4yUB2tJ&DxwlsjhrHHdYK2Z>es z86_@WZM;nmm-c|=eY(=r#F#7TPXf1+vn(Sr=QQNnBs?WI1Zf(}2tbmC!7G_$v+TDo z%C#vP2Q4@$`swBXdxWhELrTYZ$cwSn0hubOYTm$Q=vocRr-UDk)>n*?jPL9%QDz}< z@+uR{jFt@@p9(IE!LYlmx?f$}Pkzy3QA9&`dmvGh#_uns#MMmi?C_p;R=CaO%71?z z)3FVD^-h)sT@1-fDWd~3E@i_=`evnM>UM}12xwsb7LOU5d0SivTz2d>8*Km|)}ltp zeoN5`o=NEouBKMNxVJ%Iw+SIOHOFcLHE~?DL z4C9s&5BkeHyTgGryFR{^X(#qIsC9ChcB;j1$ zVr2Yo=^TF&HsSBS$V3tf$69wIo)s%#ra96CLJZu<45ka3&}&59lr7q(Wp+*{%$5X# zN|NK6H+QK=EexY_kJpMZ5!RX#8j7Z+bI~3aW7NqvvF2e)q##=IDsZDJ0by5uC zG7$wERB+QNd_=AA&Zg$|-Dm@Z@PFWK-zSo$Ovh8@i>9oqec~w$9%!=1filSkmEM>} zQzW*A6iw2RLSim9rjc*13J5er0=pdcBL!C`uR-ZC9!||OJshbd>Ha=zrXd7h#Gj{P zq{x>;lR9JbMIdO6?S08C=fQ1T#`*YD0;zWTGGCIuI5DB-DZ1#d9e{1{tIU4EzHzE* z*IQx#*4SHRj7k0lMn3;b1PU559bskv`ZT=x)CTmjvdK+4{XYGoL!zh4whH z-6rsPi^5yc&|%&Nv*LMq`i`sVJ?}!9koae*NyAQSF{N3?@uTiC>mEX5&o*J`H#G>; zyg6$BCy}c;Cvcfl`ucB3uH*lWg4|5#M45(p|GDS2ysUh@2}mSkriYA`uS&qwyliQCnzfHQQjyKlO&z?xH4=?7voK?A>^(Xo1jFZUpvDD29~z zb5Zh)haUjfx*!(P>Y_3u)0`1E%xtXS?n(0a36vv5CzF+}4NG!wj5T*!Tjtn|#*^El z&`Uh{-d{c4x?Ocp1lMwEr8)u*wMHOimTl{?fKT!>IPQ1K?3uzLO%&)ij1--$HhjSa zGxKLW36H+%C&DmmL3645-EZjV1N0j{&dXt*C`uh`16D$|&ll|!VYJ9iHbUO$+MtcknCnO@@Bb>D|D8MZtFFZ%;WIclP1+od*&7kta{YWu|d5 z3F|i&xu&(N)KuDx44wxF_S?o0{{yZY`WLPnKKwhbTMi=&d<8n;{lr>nFQjvL_gYS| zEzM*_odjw2I{r(uVd)GP&W5L!J_rlae=t<8q8)X!!W6ixd9#7iwuFiwPnmod%zEwX z#pMXG14kX7hgjY$W{mtGggOE1rH`7kUr1Jbk3P<)=d&MgfTRKUG6R3%;DB8{ieAz; zfzmuKiSYe%qian4vl~4li0?qNmwt(Xg(fWh!H7Y z_g}oB0U9X(my3*KKQ766pE!rk;29~83JG-z1jhlpx)r@OS5IxaNJwS|(q`C)PmD}a z^83du05FyDp9tO#k@f$c;5~@`j|tup^Zy6I3l`j+UPTM5VRN)h5n8}SmZYhMy9=W) zWCCtD|ATCp0RF#a!)nvRE}lP)+6pv1QkDK>m29dZ%8h01yG~CqS!{nQJ800iqZO2m z=KYR8=OiF`gGg0rr_oxhWv7h=%ozKZRI{XWmpg+e@o+X$)9FFYyZ0zjuvo)9u!U9E zcTR}Twk)k!Rce@5zoTK1aDSp}xYFNtlE?d$E9dK4Koy8+en-yNz zZ$yqoY?@=}t^^J1~=r35g1}XD1tvS6^ z9XdBo*OF+oy1oFzg&e6+>{(aQtWTX}Qga7K!53*?zqS&cu5H{_BX_S9d&_mTQe{_M zK0Qp{M*sfWOw?kgl9lFe>E&p|0vOQLq6qbZxn*1P<|PaAi1}&1LW-sFB1{-LlufHD zYluZdvtHRuCkt{ZUIlARS;g0hSN0H)G%UL#bA?-c!rz{yeo2M4)L*F3(;JP$660o(_{_k-6kA3V$KhtAd8foPIR5lsCb*Oe_A>WXbF?*e@n3+T=Jl!M+)Ezu29% z`4dVG8`a@q@iAH;GZOW}qQ02Hs2SETYD%?y%gD|SHwKtah!RV6p?-0IhzkR7-V`Ev z!eqG3%h3c3#sc_fcL8tmCBN$^Q_QKNm69OVv}ej19ceu;@XN2d_g$lo;GN>nWmLp)YuBbUTq-DiCob zcj}N{>2w!%yGuZ!Avq941quy^O#)9@7*s;^YpUlf{g56a2ukSFEKUVG)17)`C~^>jzED2oG^qxMgj3M;_cZ-aB^(`WNg~-DrO*Vl7sz&oVl@% zOThZWnc{{HGdZE2h5W_`$26-gyMXs}g;8@)^(OU)d zTs%(OXtqTc$oPW7E0;V!De%W`-J{bxmw6l#vo_6Mt(Mp*%N3{LS|9XT^s_pDQo1QK z5BknX@DKQQVg9fZO>ozwX0cAm#b(E6#%OrNlE`7N+*cGhtZvyX{C?EFAl5{d|Xyrorm)|04rK8otnGd&FXuO8(-)#Hdp1In?EBC16_p3=iY zJr!AiGlG9B$9npOLNop-$J}15=g0HqUJq6HsSO4taArtT4shg8l$8J7`iLaY5Ru&U$-(?!TI3$fJt$iiCUls0Qt{-}MWX!r5 zRSZJd()mix({p;rRg+{d{yWLXZ;p~1-)VJQYg$-3@q`t5u4-zlw3>`hT1IEG+0hFD z!I)DorryLG&n431SxVw#4{UMU!U*b{vya_6Jri3+shl)sLPyYidQziT?i4wh$#}TR z&W|a--tLD(fb9dNZ-13M$#LNwD*xon9G=H>b{=|b%v%QRYb#FjW!a%x;Hg4$9viIQ z*Z`c(H}gz=m~#3H9_V=*C}KojcFlFP!zOC%p6UR3 z#pNZ20ZMf$8|HYy+%Tb(Vcv$=ad%!OO&{{jE0=)nS)aG=9v`R5MjBcs7G1u2wk=z4 z@ugzG&zsXWGV3h(Fj=Hiv8?Q(&B*}GhDgaHV;VI>8c82m?54c2s!jbnZ5Jk=R^;nz z1h8%0LI;fzmUd92ja`d)zr-|FzXqN5{aZc^wu(CF6ETv&M>}jhtJfMu!|U>@Khc6P z9ua+MF;|*m(hKuK^U&Wld-RqWf+y20(Qk& zx_FAZ~(kcUMR zt;^&DG}|k9MS^|vcZ~-M-!bWv5;LWzmym>fBZ8P@l{l!GCBH)8_(vFvz6pxlrbC^wA$Q*OAf zia%gzoc0N0jBhRM{e(-*3i5zCUrD)s+p7bpbK_8EFkjj`ukXd&7elqMlTqo7Z5H-v zhf5U5DKrMJx_~B&5!mH&y~&gzQM=#6#Soy;BAcj41{e1)+lu7JEWD^=b49LvjLYW*7VpnW&wRO>I4|h&RXVVw&Ox^ve zZMZuSyNF2_2~WbvXrawhR$q!>Dz2e1e$s!4?WrZh{fe+~F^1U75edYfKM0c=ixC=X z3WssV<|T7Lk1Uf@jvWXI=Ch5T8xF}*F<#(ydjdz?Dxi~huY1$_b&z3NT-)uXIka)N zNR=ac%rXiO%#E%V*~9_2>SPO`>QIsff%B|?tvX~Z%aa|g#@!j$7JDFMfQK96m4Y89WwxWHH7a{N_4LT*Zl)3XzSp$(?9j zk_)uSMnJ1!Gvze(w)Mss;aQN%XC4^B;+ZbH&AI;}nMBkmx%X_^4D+20>b)6oih}-I z3RW#y?<``SL9#HE>ggp5NWo-C^;Q8XST!I8OLa}oVpk=YaqVcxAv#VKD-OrsY9Vi@+ z)A}u+PFF}*v_s1HzsJNd%4M?iNe5_)*pKC25jp)zgY==^83);J5!tv0Gx3H!yDq&$cA|nD)eGEMcFU9BzYtjOkFB@xAliQ0Lf(on zxa*ncCp&U@WLeX~tqSu21H_}EV7C$zB?#Rtv&JN+6xV<;!Fufktx9Oyyeoh7FT++- zx631h^IF&4G8yZ)6lXgaR`?TSr+DTz^-J5R>WjSJJiE4q<$Gk~{3*(Qx_rcP-EO{J z{3!AGSrNMFzBt8jhY?(U8g}9~g&VY>JrQJx^ueUloVSis%c+!X4v)Ze6vu+SoUqhDmBT(@oTK$odOJ;TB4ZK>atdh65cqB$%N@k zjem}+)~||>4#%iFcZu=48bf58;CBWxViTe{d)dEzU+2a}TMZ-4K`IjLsJsJh#Q=~Uu$+GTzSgEM6b6o$iE5g)gBiOX<`7%5GfN7BEi(}p9WD~AT_lWg za4y1ir(@-K1&hKMlfYVF=nq+0MbML**zEV>qzbu*NZ`)%#H!vKRMb+xWK9>6ty}Ms zuvol49c_wrQ^cnAe`Uq4M}%Sq7mdm(eEXGYYGt;MV3|$reE&~@*!zB&Z1%_UC&2C% zmr)Ud5nDV74}Ysa<>qTP10!e$*u5&}%s`y@;z%RvLNdOu)c92>UqeuKe*Ya4Tff~0 zBg?DeiX4=*xXyt$e8ZN;zVjyzen1VQJqT^xn-s{L+%i@}gjBm#4j{a87y6C4jz0qJ3ckk(Jf;D0sX3LH5mQO5xaXRo{@k}+uiM%H&Tq|nyS6VhWaKEv6iNQUxBADKLJ8-4ZiFRlqa{ujEW{XN z8e?^z7Pb2rt;Y8u?{5?*rz4><1Bb03-NiO`7Auip*urVbX#A#pXRk{z6!3^%hJAaJ zLhtX{QQR^E-}lbemrOl5{aQC?X}&=HoJXe}UKp+G`A6cF&7)CR@mt~r!P@;UG|98< zx5TUK3X6Ve*|b+#-7$h*%LDs3AbA&k(kwgu1jkGI5U-zzB|x8SM3J!vabnH8DWPb!6cGo}hDLKt0>e^9V|Y zNJOMODD%VqW8{N<$PVs0d|r9A0dJyKqkn9-syRcmfosXDcBPMS@tLIQuL(h`I6IAP zp3?dS5V?6Xrdv>WPsQ9$td0xA7KNmgx7P;tvWh*q7-C2tM7At4I}-sbl0^CIk^#;I z{cMnVGNd<`S4^I&!BWfIK)-!W&>g#PbjuxP~9BwI4%KAvhQaLfoztUNmy1i8toll+USJ^wQUD2(>888hx3sQ4 zBgFHs6yuU-Hi-f!&A#^Qgpb3@J|)p67vsyo$?L`iZB^}(B0RU;;5vNmwV3~n#l^Mk z*QrlS_Gu?`$4f6%-IiL4Pe3PHuqojI_N{0JO9UZlz%JqOyo|Hhj4b%maG#ZDzh-P%YTXffffRonrZT4%XBBBAko`!yy6Kk^WW~wJ zbd!0~X!)lk@i=CnV~AiWW!m}S@Dn7XqG4|{1%@Gu9L_tk?dC&<*-=gOvYJH`m zm?7@T(V<9%w`et%LcR_IAJx11?j2=ypswL1mYcWL1nN?K0p(Mu!`!AZBownuj|aal z-~M`-Xt^@JNJRoJTh%G}sMlC-1EM2w#4gc;Bhb8);=iwD@0P7(RFw!MwpTyD@ANo= zR#So@YCZZ<)M&<_=Pu^I-Gm_7(?54wGv$qT0OS7^L&4TM{$%h>xjZ#u3Q7jw@o;aV zh5HHPY2wpo%2-_^|Kd$Gvis}Tab62HDJaSO@CNM*4$EvaFURt2< zP;nXYsVt-Dqwp(Yb7JF@_b1~H@9g;4Y5(@a1pH7S%vJ2j4LA@%*hu1z_Zex}%d46< zz2{FtusqqKpBG||fM00$wfx=N|GFMuzJ1MoobW7xg!tFRhXJLRM^KUR!|Puc2)Szv z4FbX&voEpJ9I1W|N$#=i{l^b~UAt=GL&Gh(bbCIn!l{s(FQ&fpncT#yK`xBjDb8GE zkw3`n?HgemKCr^5V|Xtv?axl!qrKP**;JM$W^&n71RWVYNdc}dvpodMzMC62(IVu; zbm}T>{iWEZb|0?i0x~iQ_7dj3c7~fDTpq=A61=~!(+xgoP~Wwx1-pYuYsEn5D6x~m zw@2yY5#yCesr#95>0@KO{_I|G-6)F28KLozQ^eDGaXktMG-Y%#p(H19k9y+m^9?sL z@W<3yxPOctHp7G9;x9$in${dpT2|dP9!Jf}?3{QST@EmCQ>gj%JwqddetjJaPMsKX zjNf6OX@QQ<0x2;FBy-qo^soY?&Lr4F67DxwzFoi+ReQW)7j*9%w8!ALz{t*tPR1@F z=K~~69 zY}|AhL@c_z8aj_|0H`<6hAJqoxm~dqc=PBcItV@yA!t6_M2#ugz3rf1pmK;q;d^+bmhK_lNzf8}^xtaM;%IX-(a@%BpZ+q@&MSHnAoSw_<@a`EDN$Mbt*G^>gWMGV_f>OJQ7E zy!B@7a^Apu%@5pCdM;}Mz+NLkhdH57~?5yR!V(#H7}_1-BB0n?Dezk zCa+oq8gIGK7CsOn8iig|UP|eE6y#TiLxRv!$S^E$<0EmJeoZeDGnCcD^J3t$^6F)3R)y_vLD<*~EbY^zfO@lCysb zM_)?M>te#>R18ykQRknXdmI#Y3)zWym}Z3G2e~Uzi3b(Bo}bi*jPhf8hl$=TVF@@A z)3cLd?Zn|5_UN$w)?=zH zL=GoN2LI>muW09yHRF%RkQ-9v@I=)a?bJ=|Gvpe4r{0-t&UIyuFS`rQv&U^ggOWYL zUn+A@U%@ENe-nVCSmE{mR5quq#r?~*#8fV-vUU$Q&-_`3D=E*cMRl%XE*NEKtgWBL z3L&YKL5I!-%h30=oVVTqQkte}yt3$4G!sOeY-Fl{r8OxOr-2fj{qdRpOivnx5y2>1 z@OtocD@^!7-Kcdf|N1`SXG;Y_P<3=zVl~HrV_37vMHA|{lwg#ke@bsI^ujSFzE!qk z5`SQ2E@9E8rjP}Dl|4k=W#SIs+KV+?zr4rG!k|h>^sjZuaE0EZ^EtkA98>Ee^Lann z@5|`pGUwZpKUO{Kxy74y_CFD5oW1Wl=JME;Tfl$<_PN8re8Ok2zek5kNBKN|*<0G|S!cee9w=*8SP<{! z!uA+ySukdybk3GFL>6q?PIrRDG2PTtE|=*_p`NX!lekA@QXvn~?li=}{ODXQcNw=h zD>Kfrp+PR~2jZyNNSZLzk8B}6Vxoc2 z4AbnETC6%>q=`Wmh+K>IQ_Je_Iqk?Q*CIy`p8(+RX*$>5$&Mr~)P0gFxnpVEVVdj;fynZJ>&iawU&JV;QtBxhHGefyw6J0K&L z6I8@`%(og!}H3{p`ug}a^BIbP=Enhi3|gs1gqUtw^Mt2hJevJRCBGur2j*Y0IFhmn89TwU#GwM>T8K)kxgbRM zN*Ui-;Y!ky4%e3v55r5Hi;-*f%N2)XdB&OnR>PD*3Xl zj4WpgMV2>w;)=e1W^ay9OhRpL38bO^>IGn^%3Ogm2al>dg`o>Yd@+xxF*vfrR&|*p zt}e#{%$vmpuS5g{zqQGVC<>Wi)!+1i&*S9)N8tAT;^o4eOXEp5MoLmoP!M@`ywrjJ z6DLG)EiHN1^xJo(S|Hvr#_5j?@bHDcs_%r}A&mslsSayfq}Qq5ZsYA-B<8^R!Zr6w zP7_lkhQ3I`jEDyG+#7_;M-xGS!Y2pA7Ec$Z4~9Ho9`;PbIMdbcpv;rf0rhP9wT8#O zOZ>oSVQ=2y49Adaqp4$`xEd9*JRF(pPyP5UpD|CcscToKVb_x6)?P>*E!r}7Hv6be zrp;DX9+YIfiHuzyGYbzu2aueOIm8qORg@fu7r>kQbMZVeop_JF&jrI~`?gh|Y8uHTEJFbC zTzaUIEAsrJxV}&EfN2L#*!^Z{JG#Ei@N4psO;DvWq_mmXLKr+RSfLNT`V8=jh#X^WEXenbl7WhWwpeIsn$ zIo~4r?;<=u!VBX*FKHc^b5{3y&h%CCmR;PHAklI#Q>gn`7Iei%YNuGj$e~u^EjoFXPs)9cXP!&~~k9{>2T(C?fE zPJVVhx@x9);6XA`&o$Z8;=_0zaasG?M19O4m?iC~y&diO+)!L;YFm`vsN?7isz`#d zYTL<@WG_r)FY;l(+Gn6ZDYr?}THf|pTj?(o<*GR;q%dxjgh;=x-xD1(V{C zrBCw|Bc~oNr{q9|C^6s31dlAzA%d&LzI6VK%S2a{_LkK^ByX%29h9e$( zD?+|~(6s21cWfVMi4*b#L-fE|BB}t|L0B{7#8LxAvsYfAM(ficOG{CxQfO%ys}|`N zH+iM5bXC1;92Pwo-?R4>sIq-9#1xq3pkj4sg@$m7Qpsnh(_Knz@6B9~FWe4YZj~pj zEv;_3DY$w^9E(=>tY^X1N5pi*k1hA!lO}bi-pZy-?~x!7ouDbkFucC1A<%sS44sRI4zh#{JBj zK~Tf%R(XqkkFTf>p}B^-AmUTroH$-#RisvvRLL5|sN5$yECEP6OIRk#;2<~bf$y`M z$nGRvl;xP&m{`PPYMoTh)>PR`b%*`Q*_)RZClPxws@4?*2p7pqp3@Qj^wg&bCs`KF zK&k2EAmNfRgF^^Gx?A%pgI|`)ta(Peq2gAv<)Pw;?{;C+&E4fSQ8hKup^}sCLW-yg zcIK>N2C%YUuO@tH3Y$S%n!O$g{860W4WVkz4mVSrou5xO5FrX`+hKM$sC)-%0ya(2 zxAtJP?%vay~bjt1;OZ#WfZ{eWuD~;h8HQNu#fcJA9SE#2&%#~p>*?1q^AXm!0OX+kV zWFFu>ft5b`26=D23jWoz%bHt9`+9q;d7#=dOZSro`QEbs$!m^*mE|r1uS^4agO-^J z$s1~$p&b|l_+Fm6+u`XkOV>n%s@cjpqW(CB`8^%Fu;SdZqSsI?Wxm2Q5WL5s&D*v# z>ePFl*OKHg&H1Vt>Y((;gML9CMJ}6w!smut=G;4~8#*|9#K9FHhsOybB`dVVN)i-# zqeD`bMz2Scm#Lv2`>BQ3@?an%A|I~XR78p3z-|B8B}V+?e{idE^I)ZGLqEpPl60zP3=Iz?Cz={3$oTqgakny%PD8vRvF zUmG(foeHWbV&LN>^-f2)uI?8ju;QZcYpKyip5RwB+hj>4so6rvO>twvnjbIeSiHuI zekkJ2z421`>^~7+uq{xt6=`}OO79bSFt+8hfO!{u8D|_Yb^1}wMl>Y({ubD^-7L|d z4M{aSKMea8Nw4?MJtD(;9n>Fzc&^V(+#_Z<5FOLS3CeUC_J&8IU989y4 zE8y9aJr7E><8j{Q4Hi?^vfoDA6m&(SG!AEt#(T^jJ+F%&FN@p{?~QQRs=}Y%%J@0x z6gTUZNr&5$SaPw|tRsVdSN!zFs(PG{CI{QW8QJxX<^JihZ_SqS{;16qSE*dmD{l<+udosN6b zC$J?I8|ynx*Cx}0seq)~kf#Fy(+L9?v(r-x-GsENDwf7D^;_;9pH5QIteEVvNIeR~ z-Oox?jBfk#eH)eaph7MMGMQdTkb}PL`$wI8J}B)h45lD+cmaXQ(0*!d5~T(~s-7|n znc9j0B_Hb-PB>m2m+(rJfw$f%&zQ8glSa;8NakZlGJP(=Ez3Z3j4ElF@}RGD8pob6 zCrhz4ORMReKZ1&{Pje)YOXR~qvPStK;UisVKBF=8#N7XGI#2C&A8Z=3+uQfawAu5I zJq+zZrlW3634sWJl}E?sF`i?7KDz7AunHE zOz>6h41sH{W*B-y)?l7B&?9I1;%2`h&`R>YeeLxr>S-7@%>TovjoL39nr8Pg(VK*m z`_4B|l)f!WsTtS#<0W`kDdAr_9UOjT%4hSHj_|MWxb_@tTF*}2ta0zWd6P=R;Ur8& zp|?_K?_u)^w94d0`kuPsHdgFc_9&1~2%ql~H#|3NbVoplxE5pOM$8Fc7e|}_!Z(e1 zw8a);@19~P)=Q8G2U=;Q5ELY|)+AFCr~uZCCPIX2AZGZNktymQS0OcNf#eC1>;j+g zer#u6AU6F%;l+qAU#a4M6=662&0r47yG7J*00R-FQ5Cm9`UmBAh*+%?O_^uoeY>OF zE)1v?Abw@j$8Z1T6RX?z5g7UyiC3$h!y}Y1S$p50!gNRqFrOAtxpNe)XoI@ya&%4D zRGaV5HhivUM()gnL}iUrGOo0y)lSO%n=C5K0wULAT1CmSkTht&Xj;jKuHC+IcLKV( z>u%rF^j8mAmCveij0l4VSNe`{+VK|M*u8q}q~Pke<>xW`by$ zRu6GYuz0W()l20Z)QTLL_oTA?s9qrK?IH>F2aQnJIx)k_!J|mR>KdQy$D*nQdXrnB zw6A0Sojg*?wEa961Eg zyT@MCTD|uueIVQfXi;!)z9aG!_&$(#iWc*$Nr%yGy!^aD7|i+J*4^m5b}zpDdf~?A z68nwS(VBdo25C!#U}5L9D}*ruol4czHQ4uD>PHA+$?Y~xDMPv z(pTJX6onvrd6YjMq&MA!>cbxLJ(ZXlw5IEi1qPsdkNu#c014Y5HG}95M36MvTfFXy zvF`Li-O;F>Wdm*+5>?Kx4$yCGDiRH^J1alo=>dYk$0Qp65)OP`fEon*Hv?|M9AW*7 zoEnW(1wy!2nVvlx5Om^mHc?d-{MH;-`B}U!>D|!b$(0j4eL869ozG^VnaErQH~P8| z_k(TLA!8rD`r#QUyu);-s z_nlqmOpZP}`QYkMunrO0<}Bb1*Q$Ywbew&(^c))J#Qu3`LeAi;XRE@P`Vu9<;-1~% zrL-773CZU1u_snulQS&_ya@Zd_R0hL`^wklnH$A*{*gyfh=kHGPt6zKkaNJqITf)VV~%loG=X;}6%I5>W|;Z(B% zv!*rla`%0)Pk%}zg3gHC6<=#B!_d$l&l=HdrOU`UZk)h7we5E-mfC4BLQ$KTX%3Fc zJdIW{5f#)G+y}Sq*!pFwEaSS@hhlmDCf2gLCLy|LIdq}$6M5S=fiH_lwWY}7UM;i+ zE(@l;kLZ|xVl;#Wn=l)njOhO!lY(9UghA|7p^Itrx_??bx@1Oyoms@qbE?;5?0nT6 zw&DgV!VHQdbQo|SYighcBWm_plZ)F!D0%`4GpZ{~^N4VTJ9HZi5*kWH_s}&rP#z{U zK$GlD|J43G$Si0=k+*R5UY>PNPye`hW2>6pu{;0|kf5d$iMn!$*e)sIM1>?a86_WO zgBn#=s+;gBA)w5azL6=1i*H`Qy>9OmBflZSw8~EPCsKPJs-E;RcLZ9ITzs9LrWFIV zaa&cqDX9+|1#k}Z6u)c3bm0z-lA*UYVO%OXT~v#V2SVJb5|r}*ln8&NiUs9B_1gn7 zHGW3fI>rq{tnK&gSBzGLWU`UAWG09F0-1$(DBtQSEJ=r5HUbqgZf_1c_A}~T?t?@J zj=xT$7-9)wi4Jy&pF=;iTj>W@4CwJKaOa2c8RdrvaR&c|iq-?WCr#`7&$KRF3IT%A z8gr9V8+PCCn)2fpdL|{JTLZwq{e5h0TdW6)l)w*o0AnW`X&(lFpCE&6 zY|BHpE&l%_ekEvmpLW|$1qtc$n=j+4Ge!`JX`P4WfEsVUCqt@BFUc!ROh# zOi^dL;2lUQqPLZ$qF{aw0zvWc@DFvfL$0TXY-*XQD!8F~JqqQ%9@JA(td*d5uEH;4 zsKMG8Z0&Xi@0f2td9;HKV>!h>5?Y>^iy|W1$}bV#meTMs@+ETa=fj>x5rkH*Xn&zN zN3niEVkm&|6D`MI;K@W{ACAjr;;t6iWD;1RWB$I}HLBLMwcpEa zR`)%?$Flapf`*FxCFoADO9)x2=l7v&|1W7UJ$fNN-7XGVT-$u!+b{F%lRx2bzMV9a zwaAEwu*A~p89tTOIz1WbEmOwLBjUN#woF`SmwpcbpnEVZzPbp5P-EnQ`TP%e>(5=( zWd^?TN`%Y~EB=v7&=yo=1>z;ria%!K2Pw~(-Ek!*jI7@!p=fzl%5|pg-GEUV$#YMa z8&sUX$#cd z7lme%oI}&ejzf~~D|MC%lE9Bv%ShCBOb0?r9H$jRy5COmY|q_Bc-L9Ky=`GRttZV5zD{8Sl&8qOvW*SVL$)1kzftnrTx7F0KbDiK*_B_zs$)<#^D;HXB<_$;O>&p*A)!Jx^Dx5#fOE^U}=D2xslY< zu4$C>zyWefRgaV3)h9Y1Uv@}iGA9$S@FnI5I2b~}eJb~cReKX}vC)oS3=f}l6St|u zT~p(lk!gyX8N9xZgfhW8=rJ_#oAde15bh`@WIB#1n{aZ>RU3RX7 z${QGCGH<3q9$aTAkUSLgOJlduDMyL8I!2a-p7?hFFCe* zY#Zzd1$vxY384?GOwa(y!C(0DYg$<}D<9D4{QHzh-A39UFQrzk^kR}@>*V%0t*=my z7I;mrMx+-M9EXR6O0$V&<2lk@rY%16-7_p*bH{ymXw`LDHQYnCFEDH~K7W#Th<@Df z5aBDU9;>JeqE*Ll_F4<4!NT!Q+sU9BV5t}%x>SNMhX4ZF*wd4RMCqXHZ7#J`Cn^Xc7dXig0Oi-l!h1;k`km@{o89OH{f%f_D( z(2Qt(7*JweaGZDhDpq+CUKrr)k8UC-rasUTs{1_v`yr0D3vNAL|BBc3{PD_+Nh!-L z0&nCU6bq2;yBF!qw-%6dQ2P5MLw&hv7)QhLWjmqg z*&xx8-<0O;~A#)6_HU?`F0<_H@!4$t*@&u9LBAobKnAoTj~79>e47Jbki1 zvGrSa&|Y@D*z%?I%C=!yuE+@cVIWa>=(TFd7ckWjXNNC_KRa8%l?bC#`4h>%Y8A1P z^U=Rlo2}QKYr7lWLbq%f$;)MXK>1|z9EkRxv^IcqB*K!=9v-iYzeO7iud~I@R$59Q zE#XCgY-5zB1w~9^U9ewfrnHL3`-r$y?1Jw?{gV|%R;ru}pvrSQ!hz!!;0ZoD7>jcV z>8R%TQ%pjKXZPjnukuzTw36Z&A%6Xun`QtqJv1CM`%>4_)DgUKe6sXp;&I}wyG&fU zm0Xz(P8KpMWB)|M&Yik!Rd8Ap@YR4%5gO31&62uzlMCzC3zAU<_a%k#azN5cWNfWC zZnImW6kpFLi70N*YnV(9ouUU_l&A=XQGEuN7XSdZ2~<{W7i(_IxNn=cl<)C-O6dBt z^9nkGTieW*7HD@aO2k1d3eMy}Q{+u!vE<=Vgk;uH)0rd>lBrAPz~443Y^2&G_MV-iRjp-W9;YFW+7 z7ewVH=m{gFfSr}WWNIH)RaQ7We^ry*_$ZHvW3mV;u?bw8@-exNv@&oQf+m_QS{n<6 zgAZ!G=I^?J;8iip7^nV=nlly$tMu(6^Kdb24xXF!2J7OER zA#gc7uT{s3>~%0|{lNLenxFp3wrZFuA6vSDF14<6+5US|o>}PmaiMO-nzedZ!HcuwC6nqK>O~a}U=E_0t`_ z%Nj1m3EuQbh9KKU_Zql6kLQ0_zi(Glt)9t02@Zq)ui#Vj+nwxd{=ac2ed@?b<5p)+ zvEuugrrKaCNMnvaA&$5Uboeon5&jExlDZLPskM| zxWFruT4mNSr~ct?U(0U^iS1jgu+D1w?+w=MlY^+iiz2^cD${|8a(-c&iM1dTwzZd& z;s_z+g6+kQr~9|Zv%0yv^5ZwoLhGdBJa1^ddx0bWn2YAdG4wG0mG4O^uMbC%1LY%S zzNY~zI}kWa>Yt(RLABq7)l|&X6btk{O~oM9Pp^iSmKmOP9-P)yp30k}>zB|0mKh%O zZA!F1m#Fh&BowVk2w?7eFj)(c^lR4W?wLC}C->yg)T0{f!4H+PrFZh=d<%ATa;}%* zI`Ofp;`+6259jZ^waK*F6b$H~GpUuN5|yV9K!>oENC>H}0(|px_C}(|=FjW5ueHC_AoD-LGL^6sc-J}&u)hZp6O(vuLBRH{v|ZbdyOg`(YNvR~#T_4OK_DHi~kkK>XWI9ORFnWCxL zG!po<%hmE$N`hkYi6>^FjVQB;k^a(x7R@L|;5z9;O{Y<$k#Vf36;i`?PhI5O>h`VW zm;VP~@@x1DFcFuO;az!7m)(JDiX?00@>utlUqHoHV0rb9R|+F|{tTW$8++dLY<1r6 zt@l=!H5Q{o?zfx@Y$T@@6O+>lmxToIHyp6UgaOv|#2`pDtryGY=k4r8P}20=-OgsY zikoGefXK%Rg|-WwZ`lKo_)fbg4mHIHY3`eHo=1mytk@lT_nTPc#C#0c*1+Ho3*hp( z#ot$yG`5~_6GZ1Orb){YRp4FD!RAtR@T%ZZnN`50GDq9fa~<(Q60K4&8Ke}Rm@<>W z-p(wKQ-uns%#{$-V1c|m`GgGH%X`^)N&tiPuUvrW3ms9{6CY@iDZK=JNi2_Os2Sth z2ePVU0md}DU!)m&AI|3x_Rx?qQC_W8rZ3y6PWO~AAZ}a0ZL%9UE?_eYlR}fuoW4%A zh3H;Ad|&9^7^G{jak^egC;vrT|Mm9gEkR@NYRaNR11iq3m*T7wvB>C5jga-?jOmnu9?Ou31l3==glT!_A-vEHHN zbcVPMnwC%$O+cNQumUyUJcp4ouPu$@R6V9Jp8mz7YBR);4iQ=ad z*3LijNA?SDlIXtcCr$cl1ObrOawaRZv|9H*UPCdf-d4QnTf$#p^}h5WIPBjWBuC0* zr>t-OIj1j@DxwOP{*Y(RZ7pnTE*?9a5PJAZ+InMQfQL~W-i+>Tn!nDT_N-#6j-`VS zl5PUOc02}$i31-E8=gWKnmkAjcnSob=1r6CGgz_vxnmmAQy1+bSU!DQ%F zha1eNONbfEKKKs90JPSOp1ijDCZ38)9@6Ef6|}Y=*Z6 z@kqh&kAL=I`sIc?VRj*7B;mMu*(GJy*aT`zAD(PXL11|HdF02m=XJ1~pDm$6aaVFG zY9j5EQ_j&8RYbznER&#mp$6$=KqmXnsR zH7R*+83$EeM|WXKUW0>!>-Nsy&qEmlm7>LIq;kOByKu%8O0~`JrwbzcOdKFoJqndG z!(jo(gW1&gzZCu8JH^3)w1ioRT%A#_<^F_Rw(}mC%l~@(=!M1Veoz#HtL4eA=WUdP zsWRE!N1WTpMus>(J{P}Nb2KOofsTk+=aZy6f>|@0RWH_6te6^*4Wc}lQV=C>7On~h zx1l+yboPKSJ>6Rgj5Qti7fBT*j#;0wUSiX5=m@j_aZ`i|!Q8zEMJP&V@=4j+YyOc$ z`HGjceq(vLr#A~+UneOmddI6Gk}h9Zj6VZKkbG-kLu}}0iK48`AHL*6AqZ3t{R{_} z@pbWIbK*d?;HvAvNr-&&7-)`Ap7IOTb=@Umo$XVKGmbQ`sL2oA4F7iT+t8Jk&B~&) zU!J3AsJsTw=UyQ7-gdR4=WR(qr`5e8wQlNpdA8BVrqK|HBDq#aa_{=3zRnL84ACLE zLn*TVMwsdriCT>DIz&D6X^DZ-upf$Gv>YY}FK`y^I2I0<7!<@Y6|{lPbkH}vocvT5 zpM%m%^iYp*tpqUCn0aEE-~_LD!@;jq1KTzoXK;-TkX&uhG&dy?UJUI9hJ2-HG1@r*}wo1DRh_w5cj+4K5|AJNY-gL^@g4DMR zQIE0x!gkfEnK$d=WRQSC0lBpDmDv02OqTiwDP*lg!=QfGdoThtrcQd-`IefYg?yEd zGJDQYB;=E8bnT#UkFMU;MT@!?A6&F!d~?VXfv{-nzg~k)CYCW1$n|VecEkU9+bM)h zIu^a+Sxy?;sn?h2Fv95YL68kkAPa?|@5wVHL(xOFp$7luVJ(JZ>PWj{IC~M*fGFTk zfPfn)QU>8ne*YJh3hhSXk!ZhJYS<|sc^x+O$$$PKT**lITb~Bof@eM-qA25obK;0n|yGQa2rNVp;NBic&*|3Uwkt;BN>*fJ-1DW_em;N%|*jYOGVJ-X}3Rn2rq7s}3^A z=3~H&V%kBd#sNsKoAX#!?GOQ!bXkAm%jXg+cvCnm^$oS`n!spCjn_roCD*nG7=-8NvVfn+ zq)Z-A;KOD8NGpKTErFH{o?@AnpAebZ3|T?LRMs_7P!HFaAam?=xhDNGloZe@wn|BU!IC%(jTOhC)o~5s0tQ!^pMeSo{|xxtte?I%Xa}%PL)H= zAL}f*#E?i&UeVHYB?fjnY7qmjEK#{A3`G4&Dr*0$~YL8%VJd}|jYYkL(NOi2fh`-r@%kVdL zmu#shm^EdlGfy|@gueh`FwYI~aHmnS=i(+SG zzdEB-n)asK!J-JN`N%CNjP?~qYCP{BW9&`A`o1Y& zG~pURkaw6%ejx`Fu!ZrP0%T~{NcmTtLhj*jfpL#K8C$lv5CCxKQejx6E@P_N_DBDT zSPOcu7})TmRID}>85*m2mggp1pLw*<%|J?+$x(*9j088iJbnixIcvz=gPr!s$wsvl zOxkkO0T~dKd1nrTS_TExh4qzrU`vG=?`l(-_CQV@d$-<+ z^yngeiLJRK@em9h3!3*uuuDV^%8q4sy<}x67i>I0cinVZ;KD`x4(#Ow~0BDki)Nk)Ng{4DyHdQmj z9vpbfmD=2@95vSelat3|P0YfXU(&xj66rg`*JcF%QUMnyKJ-R~8h)itG8(5jTxP49 zwvc)}z!lKw_dt?_aP>SmiIGfhtBRd|RD6Z1^Gz3((5rj1qNE!k>-di1n1dRBzLn(j z{bxpp^tALHFO|mHEG)x6B?T|r0{4X;rn=eX756)~l*g&-l9#9Fgq9K>R>ul0oMs`# zf^{56C!|i+%jNjni(3zKm!3>r>)da>9VSY!;xOaun7+l)*~|S&3KdNNZxOi{e7VJP z_ty;XHkU#CzYC-O{}H5=G-h>(ynY(hQqDXRTWK}XGtndIT;J~~me4f*VtcX3BW~Eq%ZbkJx9rhl0dgpqMF2Z$ zW&`(mLgbQrXM3UDt0Ql$Xg$S|9>aE)K7%fIadj*~x8!}eKHnSk{>7Y9Hs7)!0aE&UG75pepjY>jwN0^P2&FD@nsMw&6(`lB zZ}l(et-%Z{7s@Z}Ut-hx8zCt*pc60`iKhX$cLmMzqJ&DgJ!2KhamJr<2;URQaW9mA z{c{q@zn{dilksYW|1WRr&);UseV&(7RNUmhA3PVtlLO0EKfjl9E$>FAoP6$i)BXtg zkKtPmy>NVNg%d-6@3GA#_}ZafNO!0L*-G;2M8OFO@nksRHfJ7pO| z!0V7PztxBH>)l^N;1lUaUD4N!oqS-yEpE#(oSv@)TmRekYw9iCL9RE_!*=>?7MMsl zA<%VUFhtLWVl6O?CDT9v6vNmBtjT(E1uh6EIs1u<5;gHr+%%=Yo0SH?({$OCo^;^P zx!kSRs#KoB(%P=ERTj-=a~8$anQC}c;ypZSzLi`nTJ(pv#^aDThAD$rqn_1}`nR+X z8NYL<5{ndG`8d5RrH>LaRi*=nbzO+IorSce2Z|<&QPH#N@|Xu(LRWj0YBh0%lttAE zzoOagxq)|1hvB@x*{yamROIx=LI%(Fr|rE`8FX=s)aJ9gW|6B$Yk}9aS$S+1h7I)!EK&Vejkv0(z)8Ps zn`HyP#?57})%B}nw@!;quZRS*b&HVyf~Q11@TQ2hGqK8GE#o0M1LQQ4D*=>kp%%>FS%=ja^q2S=M%H-4h(ENpC5)9<&{vd3 zU$@DoW;@)5yegg4U0$zQ$+Xe&t})~Avx8{VlXlu|z8+`I!+f+5bVyCebD_SH5sUN3 z17z;YHrZ`;#xAeRIfL_POpjLd2w-W#_15pgp#hy{EY#Exf=$8xwG|)G{(HcLyYycI zrcUwy9x#pK|DOYefxSgSFD~YvOg}&e8X`w>53s zyWG3I@rgK=27NEH$={ytT1!u2={v!)oy;HEF43Yu82&_8ee?_)Lvauau=716O*ZKc zFCBA}pYilv3!^YD&T)5%Ls>V*J3`9j7?&sayNLF*z!T)w{$=A~Ji&TL;q}g7ch20( zY%cEq8axe#kC;w;C%_1$g&wOs;6}r2>!_3^k3_~V{>fD#X91~uCwH+B=kIo~;BO+= zX%d^eH(n#1WMBprk#v*HeRp5YPuwv3?Nbjn*R|t@fuR@+pByI?m#BC%Z3X!&jo(Y5Wm zov+{QjTvPNj}dSszlSmHwS;_;EZ%Z{IR5+)R%f?}YWHRcI&8^iSnZ?~wnea@bi3O9 z1Cj1y8wO?s%F;?=K#m0p>SzEhm)0WI=wp^- z6jFjN_|OfNiveG|OZ(1&e)MjuOhpotPM~+&j?_y-$(gy<5-eq~l3(fV5b@j6+bq~K zo%YC@Z6mFU&t@6eTYSkzOkPK{`Q7FJYo;TNRqWS*KGsW=wsSv1>?4#T+BJR^#SwF8~f-) zlk&v;EH{;VER~C!%LYAmx3?!R)or%|^fpoX>&bCoB&8Z01zu+h!Hz*%^B7LG=Zzo+ z;Iq|;UHV)M!8Z04U0n36@xqcn_Tupw{4b*B<{-1S95RxjwTJvP0~`*+P5qOyNf|Q4Srf z-62JSD4@U0<&ifv39OQKxNU{gG$Mut2+rc|;W~c>jy33y%7-iyFjCk?G&YuYWVXZx z67YA-RKLz<(5TDT>etL~ZQkTkcPYJ#&ruY*g8_)utr6xt&FWrhRt~x?e1|g*9-^yw zuN_VASL#A!7XGF)YqYQEfrxJz>1`Q*5*3?aHX>H8UBRWnY58l-;kppq((6A*O`Py; zbhJ1s3ZV^}yPu{I^X4!|wZGUjbuLe`h`XLDmCv2Am-MQ1E1Wdc=~z|S{~Gk;SOsCq zBCsM=9e2-A3Fl^rO3n<$oL1bh6D)3ZSQ%?&&OJP3U zeyOY$U=_USdw>D_YlPooe3AB}#<>4mjXo!KMaYxv#Qqe1BG*nv2Yt!$;xhHV&Ac9g z;PEa5-uZ)hOn7nrXmO@|+v9NXyVB*ogoY-A`-aP-pE8Xf#b4cx{RLIB;0l1_X2QdeAwt1XN~mRQ%h6bK!i%0m<-=0a z@@KaMN%~0`SWjJyV+${4_->S2kQopBhqE4F;ygk-nZ^#ByN4K@Ll6LR2K%pI;(*lE zR-bzHZ*xy1nKQoo;EPsYQn-%1nvgSGJ@ zXYzCGMx=v-ldJKP-T^>1Q)cA25S=aHI1e(|6YCm4;&XI9*lE+*D?Fs13FE31$ZF4n zR8FS#Xkipd;iTlgx^2>$@t5bj$ZvPL0$YF(B$84US;nsPAWNgG)MtXEec)=k^V?Kz>D+wP7{>+ItEBrhg7Mr@#; z@w&<+1^iwKF4vxS2x2uVwyW(98;3EC_Us){P%m@MuP{7z`t}ueKU}+|XmB%B*SZSsbh+ z(z`O^PTr`ikGa(0@M;oz!2&EQcCZSsR4gSSWyt(_y3|a0zss*ES@Q{2ukoa za}T#ru>krvJX*)#c1PN>ue6Smo#@b0tF94dg9wXV-v z!Fbx0{nB;fdV7(&2e(@&N?m4lMS(cXMn0X}$m^nFjQUl^ip0p1Yy^^ihwbpSin=;X zLJh)?h^lo)=}B`ki`wmZX{g5_H3X!LNA%0auk=2aC~EN27XTkUEmdgmPnL=h^ZQ~W zMoW-0Lbp?FGPY}3b-W3o(|zEK;WJ-x20kZyl9I9fBL&(iBWdk>%^&Cu`9C0V9v3e` z&U#u@KEB_xFd1V?7K~;IYwP>9W585kJfLMjea#E>F9k{#@Y&_bQ=+pCqyJ#0gm?3B zu@@)GIjb4#s*AFb?YaDa8A?G@AQrI;e0}){Zc2~3WM^|~w59l#5kIUrVBew9kExPH zoG}LbIflm_2D4ddhW~^628QFKurmS$bS## z3y3tXUc=tF`0!3!p2lq}uYrO4fd5L*n={KNZ+vc$Wtu>(xh|(2E!up3lwQj*n6>{# zYyZh?Y`%>KIpvXmd5@Q<>&gU{aJzeOzQHmr1N?~NibN>wKZMwxr_4-M>qLN&%YHGL z^t@n02qlu+h8nIQLX~@u>d&qe$tLdMCJ)pz*h`wc2+W7Wel2AAMbVO94LyMc8 z>$+pBJXi>Yg{Xve{GH`5&a}7igej19o7iqTwc6v?T!)KDyeND~V6D$OIH-MZ=CDa8 zxTy3*)d#J>k^Mi7sg^?Q5W@t@yI=`-BpyI>&bVRR_MX|~sm(lgxnYCt(3r1EtlYzU z|4b`>II5A+p|?wo`>b@>&WC&QoN#8>9oIDHnJ@=c002%vN>oTy1y)2FuG{7-j2K-U z`<~=I+Xa!KT0n`qtbV&GE2`5){<-64asNLPeqr>Iu0YnSQ#ui_`J6{YmlFUb_fR3= z)0G(H-YubLg_z8mIP4mu{bIs@o+6O9axK7V_Q)DCG&1GVEU%o?q%`{2aS<<5rwuSS z$OMni!be|LjM{+JE?m!OF+$`wPCY8INYt_{O;H$R#2p@(a(J?!-4nr2J#Gh0&=15Y zdAZ6W(Si)k!nL$w!4RK)-(0(mNXVH;BB42%k)m6}mCgu?+paOb7aKD6Pyd)WX9D+A zB|zDp8oJ7=>k8*P{H@kE(BgEuvG}V%zDW^85~3PdcBg4`|LS{EBJUo~DkU{nSdpJ< zY3szLIDKZtELoman%S5PMLN?(e2Jn`vjerHPkj(ew&nU9A&Vg~%j=DvLZFu;P% z>_>xJBK`jkej+dWH~e&jzglR00lre972W?6o`3*~|0ygNZ3lNl@-Vb;|l zYx@V!B4p3P2a6TqP!Fm>8WD-tND*e|FfY^``z95>t?8hS4&0?V%sa?ew^R`j<+x$L zkg*7h`x}*Vs1_ui;>m<_H7KBQ(0Sa_mqk^Kt|elp*4vwDzm0gnzgiIOakQpY7@tzx zvQ2sKHI!06P)fzrn2F9t?7hxloO_0_F2T#*;KYqkzGQoq!}z4 zz6GiN+AU8X&-o1M>v=M6_GYEubH3;{VX>cSaw2!bVD9HpWtI-Y-!q9$wr|+$NnHFC z3uQ(+a#y_ET;IEu_K_fdZ}`M%5jVoN)Ot*BAT>8V0~rmL#+5uuOCeL(nd-ZmG?wIW z2;T&P24$=CM|^hn0h!a}un7ZV1eSf6>Qmt?ybrBTF4F*FVt0q0DA1+?ou^gT#VoRS zeud;np`!N*nKt2?;)nG$2RYsI-qHuY5f=umd@q~?s+|^~RI0dFQ(gbs$mM5JPct|R zApfn*Bn}2O$5>SR$B^zvs-Q*7QFL;J2mXRhh>uaiH;b7}uZCGrD|r2&v)O}RQfPB$ ztwu>a1iA{^wW=6|ACsce1g$j?*dKb2y&R{}yn-(DMMbwczvNQP;1?f`!^y8kE!8s| zmz1=+IzL@DQ9Usnr9VUpWyW5ZHoHr${n$52j^zhUHMM<<(Ga-$1s#x55R5}1Z^^H; zd_S$NvfWndaD9n=B7LfY7S8u@+D10yZQt+4M&3a5n;T(zp0_Iqx(Yz?{`!fXB;O`w>sXTB_Us#s4NAi$Hxh536`izHnHU%A*>>Ox4_y z3***JRBkvr^NdvqKKn^dBY5bLJAvbjo1FSvI8Q;xH=~rb!E0r{k5NSr#`C2+au&dRgM# z>8cZkJ2po30FNqs0xHkw5GmKr>1YVs(R*dr@Fdn?5_nmD?ECEn1ST|rWwo)Pp`idO z7K)<1gN2}9!*J*bP?NLgRl5}H)1n%!U~mhraWwNw>!pn$V^!oUA^e{M0H3yx+*1rUU!dj9!L$cFB11iFIyk_<7Cg@F zw<=Tqc^Ik%TYnZA_}mlO+Oa?9Fh`~7cCe5 H;`=`U|I5MX literal 0 HcmV?d00001 diff --git a/tutorials/images/tutorial_video.png b/tutorials/images/tutorial_video.png new file mode 100644 index 0000000000000000000000000000000000000000..015a4cc5cad67b599523570d19480267656f6804 GIT binary patch literal 198317 zcmb5V1#sTnvZgEBiS3wUW{8;?V#iD|GgHjW%y!Jo%uF#eGcz+YGt+hcJ$v6XHTT?^ z>90y(Nu^rSf^N0mrxheEDGUpR2?YQEtjJFRSpWb_2LMoLNYIZX@boh`AAexBd?NCY zkdVupQX3z;7mc8=OM`hcN@rMW(}t*(u}zJ;xkrQJDLI~M@p10n*v@=mEI zX^!g1{mUI0i>t@|1XFn>fqiRYIwDk+zjSDWgu6m?zdx)o}0vzQ%3!dG2#O}fgRSe_+&PJw&N1KZ*=Ru zZYHTg@x8_cA&r@vA}A@L|6^cGz(h^_)aIwM-7oSi4i-n>173tN@{>6Sc{sJ9gss4##Inh8SSi-5qSukBtM zJ~K%qF^McO4M_l_jUH}=UH{Ov7%)E2^*`+D9V9v1-s{sRe-M0My6!^iZ#T!N;(XD_ zMTC!hZOUXDS5D~uWWjSrObkitd9s_Iymggf2OrkGz}3rSp?JhD1kd02)}LFG{i=+_ zvu160d$)rZRJ=rarxW=~Hm6N~E1eoVUATD(JrFE^|Jxn0QEzY{(;3~LfCrL}2k;{3 zXl?l+VSsN>#J6#>r97cC+!^SkOFe*RvFIWzr`HJH}!ZJF$Jr;FxkTOuWWM z0xc1;Ya*@8NKid2l4I$JrRp-L2F0Lwts?Wj-<1EF2?>*gW0wMYn3XTx$InWSWCNcZ zN_%7POmt(n-3x&a@{1oIE31W&5Q(5n;^fbxfN>**QSY3{UDLtf?Vte#0kSXJd1ZZo z-${zwT3_qK?)5_U)=&h#4AXjzKh=7kG+A!<1Z=o zH?Hsp`!&JVxg3%&rJ|xoc1!?%Xn&{KXHZ!AVMdfNC%83x&JgHoo87p9TRihAqF;A9 z-gQL&iZY-Q)^#zEN?)_@Wj_6#m0?fVWN^$$CVYWuCO#%u5`MMhZ}#>p;sQy12%k1j zP7jW|P)4`konMic(Pok}BCrAPy(^$1+(#rXVd$CaI zo>k)$kv9)MDs-GEO87PkBSS|j{rB&AI;fVG<-r)GpC+qP7ZNZ*0lJmR`k<0;#|pA6 zg7~T>au>TMutkc}O!zSM+uKaSJYWP$lw@JSxkdod76I;hnKC(PEyb&tBf2DHgLV1F->TNbJ|6S-K6Cm}|^03SU-z&iAsZY4f~AYA%AMO;iylw1%D*s`_4BG7`4 zD~tjWRCQBt`=iJ7wP;oqG4vA|7;FPyX|eRQXu@w}Jxm^eXVO=;6rWi%7~D68=ru^Y zy^%rmBdXdj{V@Le`PXnieR`192tGGiwU()fD``-o*Z_|qLW-%}avRG)o~67hB5PY! z5oS;@GL)<^`|`ysWPx`9*%*P9I6kr*AR1jB*J_Q3M3HJNE$72gdv;pg57}jFVh#(5tA&4??3G zuhJsWqxhcZtVXWh)lC;(A;cN?Pt88f4*a?3NDY5K_-q`Xn~btRy|E&wZz83 zd30+N%^MmVw6<~Bvu=En59$%3N!Vsnq$gw?!MOE4Q496a*bY_9Ar85|1_2<|#X<5W zQTO&@)PXee%9 z(vjF@tB1-1CV&QY{^l9ewVr<7Kp#cLLS&%uW7sGM@NZ79YH0z0XssSQ;vYO%Mf z1#I%1W9_zfjU+*c`wbf!;ALgJR!y4`kYGv*^CFzW1V~IXNyNPbfdWexOcqVBVwY3j z$Pi{PO*i&c#YVb8j3lfjZN&A$<;$EsDVhE{p|T00orpT$F+5RD=gjX<$@vd%Z_8TF z>SZ}Oa*|_MYRjs!##uQz+sh58z$Z{#!KAT)5!bSAi~ZFyjOH?;ZsNs~lvftY z6lnDg|pU=ELG8Ue+CABQb)@2Vb!|`o#sxxKqT9Rt7nlJ z6SHXo_}XQvQBi?RTMKLpA@U-Vl?*6|ff{a@HIMQyOhkE!imys*9D0A#9daL!H1oj@ ztZd`#Ep$u?Fy4(CncqAeG7+D28X}U2yu2t*FLhzsfn@0OeiZ;nKmF225v~wmPe-@II zDP1-GSlL$8BN^;ZL#g5yZ5#3LE1XpBMLJkQay75@-ttO3eFTsX^|)SNCQd{U4QXI*AM&~gKzqlRW>^mWFr)H_6Ix4Q<4&j4e`0hbO` z$de6@O-yu4BFIpbXstDP6iX^CV&0TXlC{HRh64g=D|y-V)5RhBBG^eNEM#%P*@As{ zvg0$HI2QNvP`yk!;R$wH#HTS?<&(37Qb*=hdL`Rv>bibVkE@6q5*y6lp$0>iif`!z z6!w^5m|KGshL3r?;R}=5SXn#XS}e~hrQcDJ&{Y4_YZ8DR)U7cvUZu}6r&cc*A)n%F zM9Ka&BZ{TG%LOHwF&QIF%wW`;9qgcYE!XO#rn>On$gVqiX zdzUcPc_wj~hf=I1kx@zaF_lxXmlKeLK;iE|;Y*uTsxN=6OI1z3(U3oTlaO!V>p78@ z?+CCqoy-sE@djq!2zP*#A~m_s%_U`^;9$|l$ZRdaVm>7g=`?<0&#Nkw7R4H^Ae;tG zEGNI-_8pW(0KyR904ON!Of59y{4FN)MEr^+%|IGavFRt~J7jCQFX3SjS}LiUx!@K> zKSG(OCYwUdsXK{W0S(zj`=ck0H+^iA=Qi#<6uA*&&Jlt z$S#J%&kj0qRr#Ac7(W{fjEcm{EgkR}VnvXp18zQ*%*<8aZ>q`h!rPzxtfHp^zpICI z!fWici$061pZo$7oTMLAQHArHNerG6wm_$FHuj&vUrAP|5J%Sv(=E$aY`qqy6cJUk z!Dj?VPQZt>&kD7PVOu!33iiUU`Kf=^VE|J@^ab5JioF!o3VVi4+gc4Ab6Coy^v?d; zhGL7uHn);?hoo0txut9C366#)mRj?nDRHRx=g$5nTy0~oND;*_sW2HiZYj+U zB0BzWP|=hmz9xji(()EuxL5NenG&YpLV7=u5U{#Yoy z05E}^H&tjKI3b-Fk^>oQ{J7)FM(_KtLF5Pd1we{B|G?(&6%@oQRrF*4<@<>@f3$h& zY?&ios;DGSn?d8Nu8njBSLzG}IJ6d#?4ylN}m5gs5UCKUUICFHG=O zJLRE>fBtY=`Q%2^+4=d&+~q4@jcgvjx~tMxcvnXyGdJe9=9yRoE8lOGKMUW#LVd2| zL0pP0v`appu8Ye^3Hzz1+g-oQ+Z!bm8oftBXMv+-$bnUvTNi?}p6s%zr)Y-RYi~KZ z;ysnC|I--hlGW$5p*VKtTUkg(N+$kkEnIi7=DsdX*pb!1d_JuLZlzSoo`;3x9g9ws zId#9#DAt0vkX)gVfhd!qL=1y)u1|$#GwSWCnZP$J5pzSet=F@NTRe-YyKrf4xhnzma$oman#x(9?0#Z3}&eI9#U= zx<6fPe0=!!L5{&6DyA@KU`G`O3<{Vj_N@?3eu7=)GS)%^!)Nv*uWbAbY3D@%r%55) z*p7f64)P7g^;ni@j2HdeSO0^l^0?vOM%3W=_+*$~l%BV2b=r*OeQ7`FflNCS`*2x) zFi;gCSV8vE;Dj7}|zLH5AO z4K|(>skxAuhq1Km-B7+c1Q19w_H&;3$#+g4wa}}3(tu>|neF?I!H(*!4l2a_(Zkqn z%EN^fkjd2Rycjh}FWaRaWKbG3RR0aACAl2rH-8nvl~|hR=P{lsim;U%sY5z`pk+0N z>!RmT@6P#?RE$x3z5LbX@{8~~>aA1Y95PxTckoc*4zx4XUwg;BIg@RliWg!6_|mwK zjjl?N1;2jU+}$19zO-Y<0VbGAxvx?Ct>aWYSBdB5i5fJS8WoGQug9$snekdUz{*guV10SkWcVzfXZ$If=u|kO=wOSibN2fK8 z2t^!}v3HF$g&<@%{YcO71Ktn9zfA!0d!@{OC7bwnfC=59UBFU{NLTgUpWqYQM`WTP zBg?&Y2GNEDy6IpHoj?w|4gaP`MGa@a|2pArJDhn-DYXuqIS2r3qVp)s0d5bWe|uWq zdGNa?fOVRy4*hS>sqkQ4zcxP+|9NV!aNYWkPV+)ZpFGKWVr{yWsqr7#C>|3|0!)Gs z6Xq+8AXs?EiK*T{E&Q`#M&HJtt7zqFj`>GG`P+fvcI2j=6>#9yRIloyC4wCO@4{z5PYukiYEY5i#8tf zCkmFDeTO|>%R@byw)R!S#qa+8a+=d4GX(JJOXKBsHTOYb4<=?>aK&ZM?cMB(brNT5 z@f}7b+CBC7PMjs!4Eidc66R(5c2kvi>S7tJIC?0$8fVnwUsx=|?`jCz zHChGfx9nl6cma$lqmp^9O|sraM!{v^TOTBhvV70n5NovF{J78kX9M^f zvM-C)&64ZX%`S`rsAx2v_Pcjao7CoX!y>5kIb!eh$MthxNKX=Xw-47cl(mP!~FDTO@&~fMF1}mt~A#gGMX1vt>ts_ zO-qqjTIr=m5 zM`D%P;~+z)o_?8CYD9V2b(gW|r1lS!%8ch>t|S4s-+*`z_|e3y`&?UOf;t(g3N+B5 z8^Il3e)QGVYHmTTXbV*?VXVO}a^3i1Y+tn1YU%_VK-i<8bY*WDbg@oVy-VY8b>R_q z^~$xu_{fWY_ETY?I7x_t0j1R9@*sd$IMKuR{dy|Mk%{kh=oM~#Q*u`asHTK*0N~{d z3s(1zd4S}8G2ng35k1X-h)j&8_me>>oreUsG5A1nBnQSb4LR}d{-Oavf0toZJf z=XrCEB)lSu#G29M_O{85Z2tU?S_D!y-T^y}*^l$$yi>v_vt6zi{+i6dl|D(f{8cfgKI3t$DAbdQ_D74Hu50_n4^`)!oo>qeSEM}mc~fhX z#yJ8Vuy!?TG2QLi6>h7}C)3)zQ8cbt#p$}arkk`J2w%40Z`(5{QzP>sq? zf>`I(qe`$6S5Y8uN={E&R?TN2b!FyO`*tlyr)WbDw5oAQWndjncbZ(k3ww20e62az zpFHa?=3_MGJ+5cl1mc1a*D!diXCV~BXrD|cYfz-FAnW_gRg0j+o{KTHMXOgCd>nsS znU8SReMes*i-{?gRiVPec?~rGqQGU8Ft@CZ%=zTWsu)VKfGi=fCP7}1Tv#sRu_@Dh4{jXaxx zNp|97aV6-Lg%iqypFTl9e<)FI|7+`KnQF8*2NEC9zz59*8kgP$F78#%7k`~9v>b8} zy8U!9scNY+HwP36Jpf#;K1;$RvgV4Vu!8~`9xHK++wo~bB%>j` zE^bKJt=R+sFd!9v#(dYgEd1TyMH{9Oow&!03!}w)HaBYY#9H4#pbU(sn3$6;w%3%! z{PqZG)N;2J*j?bL86^4)9{)xs)J;Gx2*k$1hB%m=j8}*8&PLW$; zKzrRdVhXkhyW+ZQ^@^0{YT;HKF-eqx+t}Qye=!h`m922TNG5Kcu7c$jaVDlXk~pzA zEtK%Q^Rk9FkL^j6N0l^1Rm09rL!xB~y1#bpVMe>kXz<#*GL_yL`~E@Hs_33}ubX?v z&)3?V3pRFc@%CUF*lrV1G(`0`8)}Y@a$D#uyYF0W0Iv#&0$B1;*01fCea8U>Y#173 z&W6Wr?ZT!YRLqm2jxKx6`rzjs8%rbi3yJ$1qY?A799#}Pe_Umu8rrrUxL-ixAEj2} zbG5B<#C2LeoayoBgmhIODhU3k!emXt9F%gFH{`9$b``Dfs!9Nf@#-i<_Iq25p%G{B zgK2{8XPo9|$YOpjg`KUnR`z$N3n9hcJha4~Jk%`N;Ixz8JpMO3p#_C9gc#E!9fV zYSDvs5RGzQ^O8pp!scwpZfbr8R>u0j#*mWkV)#>HL>Fh0t>h_~Dy^1GPtt^ptxB!V zhQPF@g+AXF_t(qEH&W>GaeS4oGE3qjjKjM8hIDPV-=~l4vl!c9jaOl49ztom_l{f6 zauku|R}YL|SD#6uua{pJge!Q^FnO7&mUFjV3)dG=l0>}QY&~83zK^|fJ5=%lnNF2O zw&yZ(XT=2D2a#_+YWEl`P2)q&Hgst-92@uYrUhyr4+2HxBJb{fd}tj&#_*<2m(+l1 zytT&sWyV-bO1&lvXohj34Q2WY6`2P)XJRa&QpcZD}=PLzr;e^ipSGlxd!Bi3$nhfTz!{of`2Q! zzj3FB6~koc7ZMVi8_U2S2>KC9(W z6XV4Z1)c;vGy)_$+_h5N_Lbcvi*M5XrFh>9?K3({pJ7g0-+~aCvV_YEj6nVvWyhV} zBsS?+uXVPV>K;_u7a4-}r|pKW*O?VU(_CP+dbX{1Glw`5$Emp~uZ1O}ZKt(>4GTjY z!mpJ+6_$P;U}dedOm{L{OaxE3OOQgkf28IZyHIh~O&-sk&{>&lW*N|}3SM_0NdCQ` zUU({#0-Z_b>3t7Kq`2M?nGp?{W$#Coyg|lR&cnYn+(dZVto3;btXcRfu2}}0vhnz=P*-oyt%*0p%pWz zv%~O|(44*0+1Lz}D%T)4VrzITSzLd+EPj!$EWFK~75kw@mEzFuRmWb082rtodHMH^ zKAisXc3(ZIy3T&i-5qO3={QIF6w;S~r*y39n^XU-2UOb^X zbR=KTbXiC49!>XH9ic>0hM+CMAE!&VS$6Emn(kb$IK~on&Rz{9E1H>2F8bQ9$h`{S zV|q2pC6XuXwoj$MmyU!>pjVj12Hfn?j>n<)Ak?Q< z)nR#@2GDnpwUXas_u%`N9oUc!7mDp`N<=t5&8DPO%#26aL>oN!#Q z8)p9%i2yKpGG~PSyB6R(eMCk}aU73(5)uk#^ww9rikc`wGzNQ~VI+%;54Pon7F8tK z`b2ZGBJD)gi0*jKXkVkdvZd*r5@QFX-jIAgZc;&Bn=-)%$U@nykB0d3;+B3@pvlo( zFJ;=CXEaNdVNb1^>#A3Q3z!Eu6va8SunB442vx3BNEm_LAF$r41r$1WE4?NcgEe^4 z4qwi`o$s@7Gau3eG33dv6yN5IGiEkBP4^uiYaS8tH#tk?_+_aklb^;rX2aeG)0~dLEGc8=+_|3URFUhI^_+}giMz1R&F_!yrcaDh@tNmdK9`4V6 zM$J<0GN*9sux2h#3H^_j?cO5npUs|4i;dQEFF6p0Ia`vYiZQQ9zx@<+!IZ)r31 zny9K36kArlvky=@-KF;=eZ01T^0=7D#Ay+9s=JP>ZQ7cS#2O0ju@ixBVoVrltl`)- z7VBVimd{tx(3rT~Xe(o6seeWvC^0-LQMib)dM&sq;l5XMV@=RO<=BhoZ~%?D?k75uw3tDt+%ihFHudtPkxQ8UX^7 zTL|L~uvuT*_eLJJsx_M26=$RCSsdWO*E~bGZPprEwp8@qXDs)een-nPX!~`Gk@xMT z>9iI9bs>$abgk&5KG;_RN&`_=c_3=eb5tvb{<*HS0tysL~C`pn_Mz6?)hI&4^5F#3i* zeu^t&<9?eFy2}$Ep$nnqJEu)o)WVdaB>6hByqW+4v*$uI)`ZUCxmb$6Ko7gL*4*Ge)Zb4!?=)_=|ivouN3lyPwtg{bgYjY%Ou z0CKUx3J>kCkU#;e67mz3>mkC{w*?;AK# z#(z^osz$607xyP)4SW#GCk@MS-RJ0G7}XT392gyCs*pVJt2^?m(*ToIT!EMx!(-iu zN&XaNbrV4pzg1CxfA=PI2N*Ez*K{rRLfo~V#o@D%b3Pb7^pheJ$P!>ezaYJ6Btu6) z%V|@N9MyQgl?&N#j1HSo>qhTZ33#|SiCxiXh%#WJci>>nB#=!LUfpP9(onvLU@kl_ z9iw%B)#RVgz!p2fes9m)1rzlra&Nj$Kr*1lTFZ@BkoY~~f*CKugu5c1t+lm3*%-o# zVav>`ub{G5B5s;{ScKt++wFmCkYRN)kwXE0DCdW^4`Y7LJ#xXQGtKCgfYo>ZKrCy_ z>m(*GDFai8h)3ijcT6HLWap+cC}k6@05)4Al=YdHT4q;II-it8$Uh^kZ6o+}Vb>Px zk}4?6{go*j!IC|{Iwy%EQ3OUbM;dHhQ@*jlP_7Z3NS>JMC;0ss=Sp#vA8C%Spl6uH zK6{Bc*v_+^8R(@ND>nN*+fi@HKEYSZ{?E*ZUsX2d>Pp=O1zSSmBxIRgRZzP_Sq@&F z10;7`LZ8c?55C|OF1tz@M8?xRND37Z754~}Z>&|8XoFB!nO`}}i9g*4rpv&acEyV0 zYcG2d=LAwR`lQR>q8RXAXYpg2WPA!xyBtCx4|97tFgWN=$$~#`87RIH|6~Iqz9>YCKMofw>?ZQ6tWY?GEki5CO zK2!yyg)*Kv9RxOlJ1~Yg9c#l3%MSQ_OQ9ua=t${fKLY@EL^$>7>{q2BGyELa*9+dK zmZ)|rOa@lAA1TMLw|S2J9))rKhv0}% zo8IW@f%nBufeW{e;Ib6P03|Q6<9R~*at=y-4_$_U==4^e zQj0gpHcz3k=!5a+yyI$~duBO9N{f0jA@IM|#D~WIh@%^bz>f_*D%%IrqiU+-OBIK^@ zSC-0ZZ7oxqwG%H55cw1Eu3HfBP%qlg4}@)m3$jxT%k|abC-i8p5u=UK9I@dR+Kx8H zvoovjt2^(J)Q)3+l~LuNmrSSkb;pW;@FPjKjL6&mz?=mg00RK?F0D>SFjRkPtS;GPLRYIHR56;+7O+@+Jvpy@_?B3j9LSfoip68sx}F9>KAFDvd-owkm*gQ z1*_gh!`y>g@p605V(AdCSK=V}#Y-sPHGNpatix8T&uVpBNy4AnCxidw_C&whORNq* zjcS=Nn=REKs4v}M;IMTac0Q?i8Ym4nkoK3JH<7Q&ICg)lLQYIO_ww?lxr$6N&U244 zma}OgElr!i-|uSZSJ&d!0sswbS=sp1sudQB^~0p|%25{xlKH*~UER9Vc?%r#>;0Se zG>IWXRH{P{m(%=nTG*A#5jr8$sW67`MUIznRCr&KSwbT}%IW~jNd-9b@98o3sp^^Q zbKT~Xx6nLmDTiElk}{3u8o$nve&m5xf!q~W{7DtPEUCjf0 zv$fNd#eF>NYwc~j_^Q1g1rhZrvzc5p9MX(~@to(_0|p#6@OT_BUw5PCNhZoYOIvY$ z$fP6WrDTqMuyymS#B%%g80dil7$LHRWsoZ~8@`?SnDXG-+Pl8zk-`o`jr_|w)W;2I zBJIC7{y{{ht@peogi7W*ev$s_#lmrAu<>9|T15_QG}W1@L7%+NuTZ4<(*B^!KA)i@ z=8t|uvp;IZ`ri7CyaGE)AI?2O0cBUzoG)IjQf;L;p-7)}|8R5FRszfMP9NJVudnIz z_pJs9DBY4qMAqxK#=Kw666Lq7Op&#yiZLr}$Q-gqz!I7Be$xJ`G5izO;{X&(F_lvcbGC=1b@ASW%3`zs@p~p8KwW!mb?%-f@~(-?~s8vh-4Ax0cRgONX;3 z#k9v?5)WD<-h})#;9rWmTp9gGoLlXda%*{^=>P>yy8~NOpBGWl!ftBQP?1hB zv+n@AKCkQo&g-X8n%9wfUGq8`tmeacg3OWNA+Suc*AOQ0qf$hL>I8lI5fgqaSDpD< z@?)32vsIIuK6!hLys9NK$Rv6<&9!0-Z?z}r!Iz7WcDKeUC!N-+Uo>e?H9P=Pov%3A ztLekknnnc1Tz+y>Ld?u#(cqA#DIE5v$O5kRdg@o-7v#S5iVBECFVaX$?5bxIn4B*W^sH)=ZOFctR=qg z#Q+@xu#RJ`CwQ1p4?GV3k9@JoOnhar?_zj(Xt#9mR;S3jMNC)s@%@XoTKjP1A=uF} zBCz!0d+fS5x~%%f#QzUAH1W!ZRr}TgYjq2a_)n?ZKbtrGmkB6Bgbhdn9yZWFO>j&9 zZx#9DN7dicSG7-e%;%=VU0qjgohG#~%2oIs5%-m!A053HYcVgUqoX7iayCp6{>XeZ zw+8LcNi~GKh;LN6Ez|Hr^4->2pZ}~sYV=1mZnIbqbV3G(a{m?vf{TgU-$7L{GgAO7 zIc>kRky)^eY5B9do?f`>(v=9Jkvej^9I*IMbGlyIwnNBWn~dhuIHZ2x8RF^s6_q3c zn%2qf?P#iOtO2Ew%7>!{i%VAzLdmp_!)?CmO-(+Bg+dpZZkkFWUx)w=`*Zn6H3 zQ?`%Lv;C1u`E=o}wPK5DZ)y9Di<9vu1T@W>_K;5iP{K&1jEiRTr+!lpS8x4Z=w=kB z^y9(nJD)nNZ!@_4rn#()XZ1erx zM3PId&#aYBCZw|6pf5drTQ1)ag((Hkl4{e3`1GT}j(co&%WI$Kh}{pYhUWQRZ6GZt zqvE#}ZSYF+YJFfgHC%CHj?<$^ltd{u<6&-~{$0>7Aavq>=jYBcH`#-%#Rr0-*?DYR z1mhItb66>xb{sBSgNf?(8`jcjZ1r#w!y2)P791gis<*8FHJ_36ag_m6Rwd6>Y3X9v zYIZ%uZnsuZ;wU%vdm|b3huXHf0a+Sw9ERfiG)y(Y)$eyp=xF+6-`?MXBmn3NXy;p9F6D92Xd+;P ze$-l6(?;A|xh8!MI(oKbx8tJxpm6t0&tp-9a%!=-1d4Lv#(f3yvmA6z-)!j`0U<3F zzba)eBBlwZuuv(&9A-ghmG6ynXYa-TpR{eVaw+>wjMN_LkzByw8;f*6*;)0S;NWrh zQmP&`uo2Gr#@1FWeA20+`!~-M*I?hC;`J!# zog9MToPtCT>34iWB*3ZGliy$_hXrctCal7P{u|nMtHw*H-R*VS4*n#7_rvDbQ}|9z zsBe8r3gh3&#;D9$zd-uYtD1Pq|xu_Oc3xRelRu0yiV0J`@n^cbH$aZ z1t;cvc=d`mRdeHOKX};vlfx;;a9o5fs*q4QwFc>0ZQibXIJr1y+|m}AtIfFQx1cH2 zjAMS$hxds8G4)v@TnruW!P>+K7W3|tbG5K%so}J%+ohqVISNUK>_DjD`7U9g>JI~c z^!c2ecSmSX&PDrER;^R9Kk=oTpGFn&l$qNO$_1wte+&|?VAdPwQBa-snfQ{AKE+bF zKnO|c!GWW7>`<1-qYguW#JvOnogCOTVx~6H+qRJA`A~LKH%j!@Le|ugSA}#s9ke;& z4r_7pm1rMYz_%d}JTE!Rf!J~<`1XvpT_?ED2)K7kG%q6uf@$HQ4VtjH@#h?-8axGP z5W-`YwXUs(jRNXM{Yv@V5rNe0&Ji@*2Sd#M<5~1wxT`Gn7nQtGqL@Gsw;DPV-s#EA zv;3o^55b_DN-Wju;k4bWVfa0(DFhqWA{{fC=x5+}lh#ee@JhAC_(!>=S0UbqyAlkenFMUwN50A0?QEd|3vVp$%a~d6GusXSj&=`s**U%MnVVd z$-ckDgZNiDjpmzkauuZ&@FXEWjq_VP^O~FJudh9hj(|z+G69>+dfmOm8tww0Uq*WryQYF2@gwQ3pkCI8Rn7o1JBD)hR1hEiA>XEE2Vp6a$QQL$Be zqSX^eFAa%qtzS}I%bzP-?Zy*t(QL)=yd)Y~KBQ&n94)SPwU?K((-cQ2NzHfdHLno4 zh*sx!!+INaReO6`&BS``XU^{c&w|giKXPA6;JVZHZMR%%C{1ijwf*{fPAw3hY?SxR zf6bL=@VA^xUc&{?j>!vp-38V7tS2rHRVsh)nh!IYFAU)spK7 z2unQ$br)|Db(60Yc?*M@W)`9ekq_>dqrTuruKQZZ2d<|579jx*6Ox29TyEbYny%g6 zQ#;fB4-x%|N`|^lo@o>3Xtp~-H}u@)a|Xkt3N)T?u22X8@u?R^yx1$YDLQsZ42z#Y z$Eh1Oy|ayMx^`p?K@n7NmxgMs!)z-%&S}-b%Il0q>%heFV1rhg*Nm;+TH0-`)_3G}nk^ z8zoo_;eZ>w55BfB*9zt#RXQW$)`tjMW!(DqFow69UY7XdZ8+$79O;eY{(Yer90WkH z7qaAV&=I;`5nJw)O1r!5@e6@lg`vgA=>1h(6{PO2xE7}-jqKywAUDn_j0(HIl8i^U zof79MWK^n>-6@T_xzf_;x>ff^I3K`##O=k-VAfT(b2rWEdCCU>k&T=C@#9HT?iY@& z1?M5gY)=z&ylZSg4tdi54NsdO>kWIhL)lYrNzHY67t%Ju5?|^#;aYal*&bmZSA-D9 zYT9XOd2TUv6=vR0Wy;gHDo9uJJR;|)F&cC?-u;cKitDhW2U9;<7#}~X{@L!)`YQwP z{^sh@<*-KjAqlAc%2Sk&>OWj^V(mDCj2Fq}#w8fFBbY?>@GWxiQSl?kclxGrwAf*7 z_L;IX=l@Ohr*WDO&lsM?rayEobg;vkocS4u%#Bz_1K*m#6fo5OkKd_5SBCJ@x< z(~42DZ$Wor+nP32g2IHecr&@H_iUlymZvh|G`>X~M;p#xrOhmrEcVR~Tso`6cTeJ9 zd}_En{eqUxL=7)sai{(XYAM)70okWW)AxA+w%YwI`EfLjZz_L8|Ieh5AdYH`9^8My zW;VnHg7h9~s9^D7SCMNkg6$(hN;m9vkPY%4y_0VDTynx3ebi?t4c|o|Iz%jGE6P$X z(Pk>&U);~iu<@y;??X7W?k&37(Xv0OCShe{T2W4Uv$Jv$(3e$R*X?;kNJ5%5Q<$<2`Xh@&>2rwQfwlA!ssNH+suCG(S>(MtZf+= zy`h7q_bvGVt^oTD4$Ep496He_Ktgh4o3z}7SXygOz|TL|sRx3}d}qK<9B1Oncewx& z05$~misj1NpgCBPam8p1=!j!nsG(KSt+!_40z@fmJAcvUtMAqF?yhk=W~hJ9ZC>tc z(1Q(Jf;*L^yf(86ZDJ4AY1B@c06&|wJgSG2x%MxAVpf2#de@BKE_q!aH}^1^(gjH5 zR6!lF8{C3CwXMb_q(X-7!u!go?;jR~#L|`QG?!8vkg3mh&4s;YreK3Z%zUw7K!8#? zlwoGnZX;DpcH6CT*ZMymU$0INHwfEt+n(t95eDg*%~U@CLoC<_&Tr5b!dld_6~_4~ z4XQjXP%?p+?AS&u-^D@a@{QsB9EID=xYBaIjJVZLYqq^Ud-U?gMwX$`>q>{tl`}p9 z8a5NJG7rS4X^BrQlUbzMv+ZkzvCaAQd#o6PW@IkqSfRGzol&+2*7-9QV6nYyJ#iFP zJ$5=wI_@*jRj2DeH{Qzj=%8s_;QwXSeZ}c;zFsS^?s*1n_UvM{Bfr4Y zIraSxD=}BDqpm$a_)Y?|ov?BRsrWIsn81^vR(M^1>4Zwgv&7y=2&VeB>%Y)4lxO&m zCAuR1VUfMbe~{VY(>WMW1Lc8O_8#kTyYCTlzNbnSp;Vs(ub0~JxRjkSYtXmj)zcde zmRWPNDk?VcAH0@$skB=L3d3|}p1dSOd$&%3H}9eRv9`|V&LXXMvWPX5aFeq^w7rZ( zg+csp2$g+J_bZPLVUN}(RQOQ#3(dSEFX?}MWC9mg6kjx$T@_?t7+7y2AeLUi+Afx= zSv427p2y9%?ovaf8MP{&LS?^ttlnuxdYnkcYhKsf%#J3+dX^a6rS?A(uhScU(2@Q# zZnH!3WoDcGS18Nq!t?hT&u%eywvsV111HV8VlwMz_j}LN0G_ZVnGoan-+fIPqWgOX@EftcqY9^X`%!8A=`X#k{WB5!{%>qXAs#jFzF(c z5}p|8ZwxOYKf_&D@~!!Q&_EE!u!q6%oKW>;MgH|+6B@ToZ85-TO9^2_ReTTY!PHw|4)#Yoslq`a}+|Qcyj^pzPJk^OByU!Q9+~IpClC5tS#=5tu>d6h#oo=p7hxT-bAHjs zd@s<@Y~#$$v~RJ+gX)Shd&E1_Ot4%|E>jaCXdb~qho>lZ>U-#>&IeJ zK&}_Pt5OZUl3RJ4hxZ$BfJHw;dQp3|dWpC`bx~O2#d2A5j_znsDR1x*Rg%0^?+`}DU zpw8XO{p)>oclfQ5)8hQNs*foP#Un)ISdlqM>+yCBB9GwN)iOK2@Q-6)-9b=;W`>6< z+Ru&@kNM^6g|;f_@sUPgT1R>RR+$St&$@K8_qWL^*ncHzQvW-mhV;J>wR-vgj;Ogj z_5X*cy{7($s42DlPejc}>HmkQ_5Yiwb@s3cF1jQkeP|qoT_Lvqb@zA%4;Yn)7#+i~ z+paH&MKzhQw(K>jJp#MPdBREQiRc&}4o|-+>vR*w&E@xMKK~1i>Al1ji9`&5*4LSz zmRNaCVfvwdsuhSEHj(91*z(b{GFkN<3JjN`dK8f){{~W1o*{(1CDCu^z+`L77^Gc1 z6i*))!uzjN&sVxjDb$=8M3rym4;;#>aWSM=FWuQ$ydO%j;L=>NZ?|TzBLnNVf5YVK zA+(vuk7~yE(&fOizrST6HR5i!9do(xK^)z!#bD&-LAS-oPy|t2%0M+Zo|q`}gqVGN zvyU9Z%(e*7*S5#xh&5SO??z?8Xs7KUHS7NU|8Vz~!Er`Qnr4Zanb~4yW?9V4 zXvtz`wj>KI3oT}5X0})=F*8}r%rNEK-P1iY_wGjQ%9W? zxSorp&_MT=%S(4b#NbK(FL2r)@UaLLxay(nS`lfIeNC@9Y$u{lfy@E>Dqm9D_4LOl zS&M2jwowIR6$krwVtq%)NSE9~;MYG&XKgG_>rHm-mzB+`1B}JcKkua<&2~GjR{~+- zGCGb|ocgoSkuMESp1HP%*%D^18v^?kEak1$F4;b5gc0JqW^%O)Qhym5Kx71Z5EyLa#X2c-E)u0eV*fCOXm>y)C`*Q+Dn zVx`yHi+1Z9RW-I>9BQCUBwTlLO}IM-vW<=eWi|Fu6S_W9Rf>51)%Nf?y4*}F)7N6w zVg#kjVM4JpMO>#OSqD^^OUnF3XIP~FiOv8CTw}*mrsx=7FfEYO&np?_NV1W1g)Xz7}je9}?xXPfRCWo+$SH>L`pL7ZefS{BFJ4918-(x+^;pv<0=6Syp34w< z1>(dVT<(xc>-V$gA`N@l=1xG`n>VV-Z~k6I091{$NW$vh>4PnU=Q#NKAU+~hAE_D2g{`k+JT=XOi7NS>g>__X~R05cAqo7>tHZ^<=Lp{oR1AF zKItC6iB{%2oOL_LiLm7>A`Eii>s_CX-gBieW?}X*&eD@BJ}X5}ITy04)AJjBy7z}~ zKg&g>%o2xxk@0-SQ#(o(nAh0+*;{fJM?cg4zr}u)B|FY=TZXK1_BH9i`=YeBmUB1WVW0B$zq(W z4D`q4&CN|ZFIzPMz1m05ZyKAYYj>4=H^0*^yQ?g|{WBC5Mt59VzU1NwPD2pRvI=xxXCSLd)7qRAEFPyltV{Qg0l>0;Oy`QSTrnv zAR{CxnTDssU@UKSvSNAzmlYUv&S(^}pS@kIkqq4Y6-?M<6H*#0t!E%3j7TwqG<<4~VgU6y-SYv62qMW@xje_hFSHal=rJKKXUEN|D z1Ps`2>EwkSg7!0TKGFKx7FV&HNa)4s4blS*JeFFpi^Iirit5iEM3KBqi!Wau8sPDQ z-(ZFrSbcleu+`M-j8W+uV6{-JKFyzUBOyKKKUn9qv|POqwyy$6+ug)IBla=bS=c^k zzgUEMDKY>gRC8S1XS#fPm#{~08EkLhHOiK>11`0%Mp{c1#6XjSOA*))v5-BpjNgRzILdM+(_ zUl@w&_8D_DYk0zLGlG(evthA;{?|Q+!ua!xSy)r+gna&*pZ}(pkhfne^IR)Hl@Wk83cm^JemYRiUu$9gzYl=+`X#+ z+y{oVKCNglB%A^8L2bCJJ8V)fmh|s!bV_N^mEI3rMr=w)R&cPB89zI!zjyuHV~4V z#(vn6Qzg?{V^2dDsOpwoW8nh!356SX z{B758++d}-MBz=o=#D$}W>F1nh#>EGCC(>@h8=C0g>j_kNS6TNypx*vDA^avn{ zIp2aF@=#Y)u?lTN!RN^bMqIkh=R~%=nHn9%V&=6mIYkBHZ3`x#fSL*g6!mslBr(YIs0c}y7sCMr- zWP(#vjdtB=L|lr;_-Xnj{{-p>Qkv<#?&BxF zfX^v9S(A`}yp_3Gtq1vWc%yF6+?(LI`r_3-M?8%3SS8o2mX$hZKx}!A$L%gk&>eYs zOiJtY`n*L4orqyNVoF6kA@{6V>0-Su6TmT*^R-V_+csYQsgq*0BT~m&>c+j*Ya_=3 z_o?XW-sjUWk~6ROn4B=h>x|dppQr377ynb^pVGbbQCZ%;3p+M5zQQs`%xiAeqU&!; zjkbW`nU+2@p(H$Nt>upA3YImm#f7M10;x%%xIqBz+ta%Zj9TAEtwL!WiGWA-OOxJ@ z3bHIr{G9mMEduzjNcsek7D#!|KU~oCsC@-md%4>3CP}h$4jBnupw`odSC3;A_)y*4u@mSLT?Ix(!S8yH&S81VLfIS3e#F zL-8>q0Hl7cuZf`h!XNAlBe6bazfoDK@w&s6gjow<`Kn>yw|tuke8VVc7}8@}^*?6OtK*t(zwm0D65Tdanrj1 zp!K7d)1}~#W*c#DL^0IWI0nA_Ccr^-l$AZ{DidX?N+)t@GFzJXI0;!rK7UtjISXqCJ z>;eE1ezy4BPdg>sX_T^D2&giq`0yr3AxHzY&_(vvW=!elU2pxBrpO}4vaPIm?ONKW z0WMecpYJ{NJo3X%kXQZkk6Ta^KJlOa8Pupp?u>aH64+?VU-!)85p!o#jB+Yzj!C_-dg68{_5}h*#J|GfUJ`){BrqnK(S!ihm{mws`@L3L z#GedtXaN8;OJ??dq@NG9bA+fF8FR7G(S@*Y@h}>V&mFT{N}v-F0i?rL8gta=_Z!@!OOI?zD{|y)?kJ#gXvMAlh~6}Pvb47vCu}%WJ)HL49;;?(#65*B z&M;ngS}p`50?k4OMUTLB{_BsQ41&!2UKw*sQ2E}8oyaShLWCS z5@ZjZpEbYFY9D@;=X>vDr~^{)=xex%-`hL(N4~>X006F*`-yfq zUHXe-PgIo6oSr_7aKGpN2;!%}nold+iYUVW7XRB1Hz_~ow;v(is;g>rKAMssRKxCz zcesL@_sX^epvfU~%(sRTe|pOFR)+%j-aV~=p;g||KUQPWYlL-QF790BBgJ8qHy zo{g?9swEA376}U$kTP=_@f;HT$niewg!}=rt>r~_;Y$H0%XgIy$m09iF{?OH@6dtx zDH)Lhj>o`buV-GYQW>h0iIgr?fJAiMU|L0DIvzg%c?UgW=EP60OeI2|&VUnc%@xpI zX9zpPhcQ0Kni^DuG3W2@gBF}uyEz{_?uX$~?VeIQdOIGd6kdPp$Q`<8bPN$rF*23C8kpg4k#LNMuF$R~vZ0!5!iJ|#bFxSNX97& zaDcI(JhBnOQcm*u#kuL%?&*`xonhf0FR`JiI8dz@m;^p*I|*CsP4t?n%pL|^7uGx6 zRZIUC(Drs?XOvB0rL9~6^F_VJQ6tWKD8vVx?p`@SYUUVXL$?8+ zr@-$fcC(laiis*u-Lpnj^B$2;QtAsQa1CQK4#I7yQf``1w{z#TP*YR);F*BrDDGG? zTDobV^emHLBPBraWZ-E$t2jIP0~aFxdD%#QgB2A}X7u>#_R9m4a~Oq#K(fr={X<>a z)v$9%d1#$@`=HeeJ18Q$gwn(U3?NOwbj?K};M|$<>h~o|!`I_3>k6fVsYucDzQ8+n z{u1+{Td}yoPo2Txv|&-4dc^0fy@`TLLUjl+)CNhSv%e0yoKmO@vVOyuo9!O5kWg*r zq?itgQU@I@a86AQ&pH9fJNoQrp)P|z)0j;!+ErbK36@5}+t5s=+JR~nA$tG5_vbh( zbL?XTPfgxtf$#G#ExAhYb4@1z`k!m8Pr@$Fg!q?yVS|NQ<_8?Nm1d%9lJ1I3jgl(i zl+%&Fj?6eFeM;T!c7H3mlCfd_SbS6@6IyNXozASb>w+OOuQ~2ApAW(;E_(|p(QZYB zPj|KC9gCN9);sgrM}Q&as$3kCtm?H3RE7ooxE^~%p%rxIVIQ3}%R^|WHxLL=O9)2C zcKpg)?Eu=pL{xQipKnuF6<|gTMn0tG>KvQY^3OBQ-FRZ4M40eZ{fr}(ugEi2l@q+r z1`}E|E!UzBK))DY8%Mg0b+4g&9jgWIz_dxg)AT}ucjDU5VcTQ)VpxYI@Cwnnti4yQ z>RZOB2SR#tunr%+vLy5-=RcPOidO&{E%+hc^liyX~d)`P{F* z>hlIrez#r%r4=TIyZ{}WuI|;6=XQeRtjS!6@EM7L!`s*(2mqu6`Ri2J>A|u_jJpG$ zsVfu5T%W%E&)=)-`Bm7BDiIjqkfW%yMbd}&uFG9b`cfOE0fudax_15-Ug-r%Hovqt zBiomM3;ejnKn|k@ghz(`!8t|J4me-{dj3vDeDCai_O+R9iSa}HoZ_&yb;lRZYk&4O zX)CXyW`KQNW#o^p0Rhm_>x@3gY}RJm@&tADgiB?#LH09l@76}qfp7EG^yx4B@``fZ z)vnV~`48;spK#H=f9i1s9FBjx(hwF3qD^gq+;mG4KG<~>XdX}2dZlziwE`s^XklVH z`DDEPOv>E7Z}R7SpiK-yM8$-t{mBRa?Ay&;>c&`|>eKR>1biKtYzIq9VT=-#&^uoJ zRoszq7m14h;a*Ef(udq^;y~a6r8R@hl`qu?!7J@mwh#QdX3s3rv4HqE& zKv0b`ut?tBK*HwMmOOBioWiz*#ae8ZYI5^FC+NbZH(|9$5;@22p_)F0bIMoT@VRJH z+kmDGU1PLfpqYz`E!B+IIfah5>-fbIvJD-n=u6YlaKp3mYOKeZAvD`)qP4Eh;% zQap%73jXoY-ti6!U{`knU5A~kZt(+AP@J@tRo~G;>mA8M3t={>)<@%?_VRkMCuD{s zg&?N`#mP@!qu3rOre?Vq+bzwZ4EQJfT04Kubk@YcM%mMqVC&e$IpzL9;WLIpwj3OF zDy_HA7wCYRZk7DLOpoYnG~2JGZbB3>Bn>Hzk|T+E=A+*aof(hGUP4!5Aa0f!pb-QNQES4RAZCq>-qjCQ{qO>5blJHZisYLLKzQ zj0tCKU38vrfIDp9^=ik^>M5=34DzCY+W_HShlPIJ;j6 zxyoU{J#gct$+4H6-MyM+LgWU*Md_mtx0_SlyJFD^7}J}>nKuSMa>B=CQgqfW79H@c zW7mH~%rM)EqLWr<3#tJLpF^#GKioGe_Ptrbi(U2*{TlX+8P<@*xs6{|EPGBqenqp@ zJWrIc+DX8Qk&nc9CgVywgkfuFKJ$s>SL0?ky0h zKNmRWR+VAXd5Opj37bULzyP<7v4IUId^mF^itA+=ywiAA@g3H{dZ1L!^B2lDhEG=> zh!DKrzOs9B4t9>6M9#zJeY@I&J)~>_ohcS{kdWOUs6Y?3jwkNbUWvNv7H|S#lmJW_ zrrZYMf(90~GT%p*>Va=yc`E=2DsL5Qs%ixDU#ddB&>G?z8>T$*RgIf>SOuuxy9HN~ z4bfyeZa3Ho7k!wCXT&Q$P50u5d%q=ew)|Mh>)pXWll)*%9dC8s7DNIp6-K~O75vuh zOZ22iYE+;;s%6jK=OB=eMdBwl1PEJ}U~}vb?tg2$LREB2h_%Lz0g@ zBim#}y3Jc#;~2GDv{OpdI$e28Z(zY2V~!~01f3v-dB=0(L`3BLTsU*}J^uSM9c8AF z-odpc-zm1t6|D?LfjIb+^Ofjn{g1A_jQAh#k7Th#y8+vZzTT>%#fNhwlTdh)rG--- zw^sA_VUKvs2oeGTaLGYtNcQvX2#a(LXUVC{yg&bR2>EoTFrEer?w zv3+6!UFb?1`dl{F!fqGg3bnI;ccxWFFV^gZ@npD6D_w57^Wyqxw?7N-_9q3 z#n&yw28A`=8L>sJj@dbNNoD;gK{lFgms;9OS>_hIsOCc@Je5N9)+k}=T?Q)hA2gh; zGOeVCla^PlDuq_$xnYo`+xyOE=xGRxU5rz+2 z&qa@ln=HOoZuZgqxJ!)-HphdCfaoQ~MN;qI^eo{tCL0NTQo z9TBM@>+0^eg622B(KpxTu@uK&J^5cQ&y(>phnA4EUnS~7$ofIkSY&j@t5SDNb7N8N zI#nEa^A~;pG*55+bwP5&TbFJJf<$qkoFeP08Ny>6#mJc|WE0jQd z!ssV+iK)!p+^Nph^@QB}4{llLa=IHeB&RswCa~q=tM##4Tyyp>I4v3$oG!8Z1DGM^ zHo|p`_ZZ);GY<>n$M!m_>h!vm|Ih+R_0S{SJrzwxEY}Q<4DcQ3I?G__yfhO7K;xEr z###xk1}!X&58aQ^%s3Wh9MM_H&{{?%hsj0w3k~$&;YNiD(Qtrz6O2vld&LX>$mSESMM>a z%4x|jegOue4{V@m4ohZJQ@NZutfRdXKqY;7$>A&R`9Kb#ITbR!&fl=|yn z`C$-n%Z28lBKkUXn2`77&0|Mh*hD|b0vyk+ZLN6e6_h<9#1*>n8v9_qm{&Hd3 zOcQ+NXP)jxH2nCOiDh|MSA&2_UE)BUBkhZY7|6OW39o>HBJ`?AQCLpD(arB$ri3G?93-(<_qqRRE!QsS7k*tyVEeJ z@|&h=gR?G&Ux*@Vd&MvBi&cf;ml82Id%ua3Szmnh{T$G8b7=;-ukL46me*e9UB#+b2O?{g&#+c)Oei zF|PE;?B)GpUuTFdgJid+^z1Q-?2 zGQo6d0^EZL)|Z({F}@)HXlJ!Q2|`b0jd3jBw~2aUoOu?1C*VPigGF0$1g-I}+T0F4 zr}u=LDYD1_ijV%EYV_yT@VdT}3_rM+a0tPb!BnI{b+O>Kga7ac8S0N+M1Xnp&u$@p za;u~xNi;*EH|Dr>+{;I&?jEp(4}UZ&meEE z5M*y)17%AQ(hDE~fpwv%Y!ufmwG04&j7Q%e%~q?q&t2cVC=`P` za`%2CJODu)X%Lt~ai8GB`JlI%$92b^y0B?JVWb3=;TsO!Y?#t99cf0T!_9rze5_;f z-EQ2zlx4xJ0(89LLv06M!WX72slusvV!_R3;}YMKoAPkkzAwC)U5@O`yty=<8NskJ zo)#l9cZ|7Bte8|QVT%bEyGWKWQUVn@s#bG{N(XBPHUT7c7#i|PUc%8os)|*uXq60K z7>RSk;grxLMZ|L}f~rwX4Aq$=(2F?c_U9^b+|=P2??!-rH!#2}iyYf<*S$%Oru!zf zbYc;OgJi=yP=3cai)5h($|)5mYq(Wp0s@^akt8jost`Kr{NjgIj8b|PlY`3GR2-(? zZ|I+kvzGXP3)9wm()}+2?}|^E4m7_07CP(M=cY)nO;_cy#E0=KO>z;)1k^C3EDh@` zIZEI?bC!hCGO`6ArdM&;Kmg;exOg72ihvW`5ww?!@E}_Xf_AkG$1_xx`TG?8ZBg`2 zrtoyqxu)V(6$={xX2Xa!auM&E?4ZlN)TNlS2mirw*1 zxlhrT&}yTrGUeaH%d=-DEk7bOhN=0K^zC$b0mB+o{N6O-J>GHipU2h?&yU#*u}G^G zpyf4Xex@JQ&YkEm;s9F4@ZWhqF>uKgy>7(W84fUT=6kiT2{=r#{qUXj)Dy+ng>EGj z+%L>V^FQi1xq6)(;1%ZL{!F?3OHxTt$mWXk>$?F(VYlOADU{oT@O&K@tn44;&yU() zGW0EOj_Z3J4-E8}v+QvNUnKA$3T_Wxs)^*0K8CmorTj0~I?q?_S?j_)RjmSL#ezX! zg$*etdD)NQP-*hANgkY9x89)ydfR;Z=hyAl#ghpA`OD~PdR`iWJcB2UXoXm)e?_OR zCYQ~yLYKy)&JD7q?9iQanZ(0;6=5_izMjQ-hrC7!9b^@=OHSU=W4&+Yw`)Um+r84^ zJ|*w#2yItGl9#2N!Cn)gy0N!=#WZW?Mz3nC_Jj8nXt>>3%z7|AD8lVzdNEl_M`eke@x&bs z7TYy4ImWkSUa~XNAj?F-e;N~EBL4{nKzeL8+cJXl8EKJHrA{YM8huvzaY2MeLLDy- zK{z7kUz02t6Y)g)P|=wTJa@AgNw6Hy}2-H)4QTWtjnIMrpL1M-V#sLr2{qqj?6KT+EGADSqjP_Y$r-RUenXKu4L z5`s#MlXSmnF_35M&Mb`{0KhzDZ5E29aAhD>2Dxl>{4&~yo*QRj?#bCAF)q&T_*}^n z0;U8-rEK=;k{J=GqmL;Nddl*IoSGlHR0ao=e@m&iN>=?3;7lPr_Y%uAvRe=8)TxfB zNVXukK=bz5|B(?~LT9FL0ouR~Kc7NwGRljXn$!Jv39&`Bcv1y_w)7wHSXZ29;mec? z<`}RkXH$Ex3!Y~OR`C*gw0+5Nb#9$~3t_j>OaB$RI!b`%k=p9=D)EBjzzvQ+sF#YW zzMt*qJiV26)DS4KfvfPfw~+huXNjesmy=ef=EbBdVW>94R_R`+?k*hjD&`u#EgtSS zUF8=xyr9|E2+gIDX*vTgq7F9@=|c-yI_DsJ=o3Os&J;ALy^;1~SIMEv&-;dtt?cD z(uxT87UBLF+Hlg)NaXI-HUdt4kEL@0jiJyKj%5=Pkhjk5(63)he(2coHRxSSYpEhY z4+usp{-WlT-m~hg;YbXDMx@N<2#hD}Tdh2-TO4jdq6K@&Z~QP6{;bdd&O-Hv_Br;7 zrYwF_0>3U>uqu|wp@?}E>luI6Jxz&wo$$S`;cW&%UM3%=G_ESAsw|MZP)-&9@c?}Y zOu^xTO5?`crjeE($J%k;j=0}1r|`2M{Hk$bUpA8{WrR9*5ueZM3hThZI{CF%KE9Ns zJDS$4X1;v2tx|xyc`{dpv8XwPBc*BcS4ByA>aFYQHa7%?{{z@UwS%zu{|Iaagh$f0h{6j)qH;>%+tjJrf3Z4kxv64t z<>TLX6LQ+ReP;ty^sXA-H;*9y-dMnwSPpVG(SsR0Tg6LT{9<7Gau`Srp^_AG9=4=p z7uxgwe0{jBq1BO$;)%P!rSN-40`J!c|J$CfUvY|qghgkT2$13JK0n)7-BLqD=`2eX zfMmx!1?Sl634s@%hu-;v<7`Gv4t%QKFk|!7>)GomhLyB5`)y#C2m&nUIdsxU%d1%Z z+p9>uO2M(^gHou(!8|>(+u9kLe^$CBTFO$mEV?E(Ah2PZ+=0E9Vi7p9SzN6>;GuPa z_tA4=dK_Y@R0gAiq~!E*;wroPdEk0b(MQlVzGJb=hTl}2(rrw+WkH0lzmkm{#~=Nl z(=OF=`_9h45iTZ&Sogq8qV;fU?hga;bGS-{S`;C-A&?;)Y6hG-= zPqoOk4cQ6}QP<8dzfhL5dU@i`u0E%PGzooG*~ z$7LqSogH@A>4l~&RJi@5t4`8|TC3avP!8_V%lq%|@^EaqAu9a#jK09!saF8vtUs;n z)1!+)`~MmMhAJ-=@B>Yf^y62pH`$GN0JUE`zc4vt*+Ybg0gMwZ2Lq&!;`&lmvWPJZ zax%|$p3>7W6KewHfL?wSAVGBe4E%iY6iL3#8VQ&hO<~AmfeCPpmq? zMkk|&9GqUO(<4%`C*be?sGi;p?5q1^x{}-9w$Nz?oYHi18*m`bUV&l$!rK@qGdHhB zCR$lTkVsQa^LY>!&||^rpU)bCoZs5WdZJ0h?_=(udTYc@!9>*l$WfIc952pk%aq^2 zQcW0G!MV9c*AuP6&)c)5?V-hLBL`D zyGglZ@$&HtL5GAnXHoPMJtuDd`tNc6y}vIZ0V>muufd&QCl?tOc+5Nrzq`q_vmNa4 zA8KQ^VQ-=dIt*c0hblWiQln|D%Yb4VcR-~)YXGTDdGl4r4YnLKp_07m4mBqnNRqcJ z#oWwQ;#u?TX5msCHuCl8;TMy))2)BlD5SX9q!Vx-rPGV0>v)J7(}hVrwm|e9xD5^l0iN8q1CZMC ziy{A-R&}Y@-D9ilKsC{PEoDJE4>S&Rr4kcRV3^){l9R_fjZB%X9joyQIL_itXS8g% zMv**D7 zVmI9G?hwz>xhlLWoXVYHS2p&!q6n*$CbafogD8DKZ#A93*4#@ogt@8za02V-D)vXvNnGX^i|sEPaTc$do9z{z$@@SM<}$iFxD!!h3e3^!DYK;ABUk}fO~FhSI`oC#U9Ma*f?Ridqsg!-$awD znkfH-YEUI9Xx^>-;$$q8K41(+bE`=zhC~3s-3!IKEN)_h3k=GhqikSM#@%5NFMQl* zl)Whl%@J^tTT*ShXt4VY#lS=2Z~ndw8F1nDfbDrRfja0dzwCWH!8S4d>)w!+v(nyN zBEAK-Aq+J%xctZPfP_J;+QWH^%g5}fA7^3>blb)=eGEhVCT1gzbRcLIqJ3sNKR+`f$aNx zV;ThRcOVqg>m014z<4E6X!U=9Fl}gR=I`VCjyZ)c1-BnubwTGD) z?ObNzc1gP3a}b139` zL`?dlgI)A$#eG3Mq^fvlj;dqyyC`#_tBaPW(TH`)&i)kkh{(ogr@_^^ubi zaN#Hbj@^4jzk<(yz+Sg?-vw2VSjd~lU)Jry=%&zW2>GTg?yL%{*aZfmchWS* zFHY9V(vk>$E6b&G7$A^YT)B9LR}Jsm%(8>24yQEqzQFr=(usp|M5dWwWrEZo)@7c_KMmi_IO0;4aZ>>Gk_#LF7uwbV% z{UPWx#^olm9awuSMG3b{sY))MjifYq?fUCqP+R9$I9NQ!+&`kbn{{!bFo-VAbAa(v zm8dVJjH0p%TE)#`MhbYOv^Ge1R@!r>tvhaeQy+%slQoZ>KDFct(Km{JXpM)149&Gy%r8q| zM>v7&gqAlv5lYJNdKG2G07!RIx9izp7holFnsy?7s#sLcv1f1p(D4GPzX=7Uqg24&ifLov#BvVJqx$+!#2ElYWfO)wq|Yq+Ac2{Y;K z_Io)+F<{HC0KgL(ar)pC$$5uP;rolo#!J=MXm2n&AI>jG(BzcClins>n&0N$ujC(V zB>0X{sL*18W#R#WK7OaK6np;3JRS}*Z1{oUnbVWxtaJO#GB!9Y%UqRa!qj`8>)eLh7=|a?B`tYf7PBLsps1(f4HoXDrAimQ3 zi{>UWH02$g4r0*=iFSx-zgoZB0YyEdE`s&|_Scn~;!z9d&(AzC7s7jzJl6t7CjDuZ zNwV4CDE_v9Se%PUbAxhmAZPsq;bY!HKsf%zM+;J+SL^1(A{D(23bFQ^U(T3a1jv<)u44U(Nf%vVr_?0wq+{0!Bf=iPbSz#T<%w&j1drE5cq8Ru=vjE_GhdW{kD|Y!hl4 z`w%HUgbm)w(TN_|hxU9AntSBfC9w2|?Mrq{`2{062j;-zrwxByx*{>ff5Fe@YQa*n zmEP^tx&|%&1iKv&7J%_^KGg=1Tm+D;kXyi()j2}$iP7xNb-3xZY)2jFQg8Oy;fk19 zNR3gez&sJDFD3f<*S0(7q^tD{Sg--23^S8a2h!6;ThRZH@~%P!0mBUk#Zfpz9zL4t z(lVB8A-~NhM}Y2jar1AcESPL;R~7TV@Uk$lqmDd%@;xd$wZL6s3*5?7qg!Ahd^xv%y>6@$;o=)O+z&5A~p01`UMo#becOL)&Hs}OFTOumXq)O z`7}I7rwB*VQ~0)9!rrv!&(Iq8Lli5-yRt$<#>{ei*qD~{_$(Du7DvfG7} zbOyO-aEKA2gB87v>#Ja>)ZUxGB_8D+NxAj+nK`x1Jr%3w{RcE}Xvi3QBhY6=WhKzl zA}zFNypd291CN$1{n`C6=i=e407iC9#ZlDUiAVmu2 zLKRfO0X@$QkvS^))hRbIn`9*uzNu(lYucd3MM3+vQ@K9JF~#QZ4m4`fjj8Lc(3d?B zL;7PehW0YjnbzLmppyQaDu3d@c2Hdm{*zncn;x_LhSflAd__9Jt)5$3U0>6eW_8>X zR!}1ZVD4JcO!(6eM+szHl8MQ>&|^{Wy3_NLC^V_hP&8^uP0mop6i^fmq3o#J9ePeu zUd4?>x9dCEg}V-`hoB(VR0jE)Zi`*cZyLK%mLupu)`M&*sYNx~hD7S>H|!YY{t#+7 zs3GOYyIw8Wlo{o8wPwRP5N4XAW_}naVHj#As~a6}rMB(R|6C}LUi#X1+wv|(wLKb` zZDR{gdSve@Pm6$`Px_i~M|#Y-65ucSF^8dNxy+|)hY;bJ{ov=|nHqNjUTvFA={z?y zR|KOx`{Z8Y?Qu4kbQD%69I!&$h4`P??Bz=sNVi@!v9Fah|8~T*Aky$;6mlz)Jl8~| z;=07c3kbS8S%CIK2NVhY5s_6TkCx4~kSt#3sc~s@r(QE`LES}SKrv|1k}aGniLg*f zX5uB_B!ONq(2v02Q3hddp1=~mFM5aFRG_cpOlNna^_xTuGhGoWL>{h%%;Uw^y~6!Z zLl$!yNl9AaZ6EaYEOWn~jY7MCAnmutsm=LKZPUA4RDJ!Pr4L`K#6?UM4hxr6NaXc;>KHYv*|N&UJp14gGjHWLh{J<6HR{X5mN{aXWF`sFW>^vpzU^Q4V;XHYh$~ws(;2 z_`S*g|7-E;HhhGKJ1*kduRA(lRa&Fl2NYB#5+v06gbuuO<8(WtYJk{F#RJFW3G%JM zJ=jgvbCWM&&R5cn{ZQS2{4cVTT4dUBZGIh_-qEGm*LMGey^ zb~G=ZOofg?GX=hCZ=ObBgZ?n4T)3bT8elx69c}pXs0XB6jQLsx04UcCtv!qUoT?S^ zQ`FTJW2B_?WjJL2Wc_<>TgXWTi3SfK5<8vNI%)yzmC1h|1_wDol-ABV9TID=ENU8) zCCpEWL3K#OiTkWpKUcO|s1Y+_96~9o+Uq)+-EbKQh>SPsYlnM7jBcE4D@>*8PWb4Roie!Kb)OenAzi;}^seknvnvJlD z5BclKGFzXc{=TwYbEO|y{7@vZ=eD=cOO87Ym8W4-> zlaL+U5n&Du)6vo*)j1G)E&jtYYs?rN)+UeW{Pq$8h8&$tEdBJN>0AnFk*MiKYTk+L zlY;xwP;~hhB5#r_tl3&V!hoEQc`UAz%>`$X(W!U!wNIB#`dAr5BK??&h--C}Fvsp@ zD?-{AX|xFT;<7y;)noVKqzXnQKz_tCQpj8&vTV0GE9}%VhTeQA{Ro)H9{Jg9Me*jS zD80`psmaJYi1zC(Dd!BZTwpcO2ci5 zk_kbD>mxgDIAz>uuezm!9)Hnehn|Fx17M_Nm}$paSDss)6l7NJqdvxf-8sdHR z!2*QSJzL{43RlN}#A3uz{>()M?SkPWrNa=#T@_iyA!>1H>cK}pj#j;qT-)hD9tWEZ zJfnPSf~Kr7d+YUja@+7^$}~j60=G|TrDkjp3e+VLZ=JCyqSH$k*2DW<5$#(1W7>Nj zG3I#aO%sqn+={u^y?85LKzrT-T0feGfb zTbg9(7s2a+7QBp7evqU~RqpI$sj7d}Jh}O}d6eH7(+}g|BN(6x?`u#cl;x!4y^BkA z-TJ|;j@=G^zt>>*XsF+cOGtPd#ijU#^)h3ZOJo&v0VBhKMrR8T{(VbX{auqN)AH5H$uyXPfHuV! zkX9}0_4g6o$%U)xay36vVuJ0Vd%;XmKJm|1bwrSWbH-i$cc0?ZNL@46(O18(C7Gw- zfA}GSg+m9jz<((Llj@57K`trK7%*vWITDcRYEA`tH=ihqT-mbK=Goa()nEpXK{j0UvVKT6 zf5h46NlbZs3#nmz*odzUo6AuO?rwe`2X1QW@k7RUr0@AiTtO)(F}gt8-CP{tJ{NkO z$}P)F_s#%Ka$DPx1T-K3D0N&s9#fu^n@8cBvV=Whaq5~)z!OV zA{)pCt28jxatF!11lKt*z9}2-?5_d`Hp>8H=oNYI0w*~0`b|2H)p=yiGW@}B>CtivYE}Rj!`S|FE&Cn2qv7&N8^V&LDy=4ogBhhm;zXI zy6$Eq=Hhv4u3r{T{cWyq0=uBXE!!xd^1` z#1=YLANRSHSg&!Ns20HJY;DXpr_iHf{m`+AhU^PE#Rr>TySS;%2}yCrsm-?_SbpxH ztf+Vx+g5yr?V~Qlp#Rn4PDxUP?(C1ci@rOE1qNs;>$mw9IH~uok;Qnm#K0u-L^|Z{ z*tj>}05h{c{#w+&C~(Xu4s$OaBC3Axxi!3`qt)*4@e7A9xwKLkNP^q#U8oK6C-{<= zp)o9%sx>Y@cTSZnF&$O$ss(rDrJN5t*=eN8z0`IXJk>lYhwRYI4sGKS*`hHclJA@3 zM+Kpt5FDR)u|8?ir1gh8O4PbNia9{az;qY~7yQ(3SK2qjnbOKE?(iDMvL?F0WUyMc9DB zr6Vh@b6{T#*ubaQqz7^7KQ-JuHByd5iC5;Wy|}WjXRq<(l^?3}r7bg?u`6oQVWs9# z&;~E8^63&zYN(g=p`!MMoh)d(*{U75MdpMk6rYL$j}s$!0`5e-GO<$u$}M35prOyz zhjpKphMA?t|AekdY-Xi^ShTy6)26$5KRHI{TJgIDypcUE>p#jsc{l|ir^@DV$K~m{wMwc(71&GeVqlaq7 z3qW3{iL|iYA@(TA)mm?0HH@mJIn}a>n3#Y7|W}aq_;*7H>?-8r~4pEBhUT`>%7~3j89YbQN;iBqJ zRF;_y`hERX8~i{?HK;gQJPOprkj`zC*NH0ttMr23;YHZVNdcSW< z3kl3~*FyoUokokJDnBmonbdz4gi|Z+t)MA_c9TXDMtrF4RiK1$=U29$^|_%113cp} zbAU`G9zJ&^Bxvk2T|MxJs%yqcQAiYc2Gh>x;MM3By|U3~j_Fqc(A=p|vICJoTF-9y z2Sv?f$j(k#b5sosazwkNYz5D2jQmG_D1NuCgsObYb+ctZ1T|Zpm%*1FxVN?AGn$LN zbi%OPq?+5AbfdIfs?#=obB)#Q;Jgn#!b+d>{}mE5B>)vs@k{lJQZwet+xNwnYT`$h&-wLCP-?>cgNL0Ngo`{5g8HdJ zCmldy)GxnKvcr}Csd~<{(*Hl|#zt&zCpGx6ga=VH5`J34y(|0U`?wt5{R1SUt^aQz znIr0dhGeTM{}PgQfyPn)4#}Wu{vDDreEBaRnL;ez3_>}m<2_PDLrGmRrE@buG@C|+ zxz^}vO_w#CmI8xQHlRVf^}g`s2{!8Foc{K^Mrwvc7Scy?*w5q~#^jLU&DD=t)?7ao z)1uR#U&%W7@`47mL?AvHdJMWqL9~&xvWD9)J1u|OMQ>$!`${7PeJ!bPj%0UWugILn ziACz)V`>WiS@|)-%LC(IvNCft#;5HdKIf?S0M5%paf-|wMISCqL$v$^f%U0ekj1qV znXP7}uV564r{YT`kFq1u>Pk(@t&aJ?zoMFC6r@S_rS}De|Knynm9v$`%kyAT6X+_+ zoBlB2=72M;OBSc^1$}Scz@pQWfU{*gF3j8Iv%DFWFp(l`nge>EfO(S$Kz?vG(-(j< ztD2=JT??_d`YrB$GFr$E)If;~)2^^)3SKd{!cO8eZhh}x*DMc3M-%zTI0>Su87NC- z4X?in8z3o|wbR$&y_k)B^U9bFv-GT96GyjL95mA^qsfR%dggB`K031---S;;mwteR zY5nN0gH9P{dsp*&oZafVA@uGm(O}8(ogyLC0eLjPNNwgOioKWk+P=hB6tut=_V5y! zaq2R%8*F;F@@F;sy-S!rDFDH3#));gdX$RXT<|SpQk8KJmVN(}hp-eN%VdQu*=W0d zc_iF>56R)8Wi?g|4u;77^8tyFI!JOphsP^WPjM?=ie#v!yQLr6uz_jt6=Dx>a^FQXwEn9B3(lycGv=DiM~=vms*-FGF7( zd`vr;(QS@M;S_j3bs>d2q! ze(?;?=}=0_heRqU)#aM5*O$bRpeoix(tNBL!7^^`;58N+UHPoY^Z3$!|9Iglw4dRj zbN|Y751eS*UvVf%uBgW%eLdO;%S|rN(1FxpEWA^cIc@BStLp%d3UR2FaFbMottZTI z6CUgo49*tflb^$5ENWqI(ho-uXpSG1js9UW4}BT}tHA4g%1{m+=Z>T_%;iC$JP8bC z`Q{}xyst5OT{Q+PQ>;2OT^8DY*`zdz$+Hr&FS>$i^LU2 zZNCx;sV(WDI)r9cyVj$xc6s7~c+Hh@L0SFWLM#;bUFSzzc4_gv@OlX4r*gUPw43nk znP<2i8?G}{C-`pfnw2Ab=PpK$`cuD)1{H!;Mrxz~@&S;fyX)@c=Da*;>^E0;P<4f4qb6@B?9? z;|lgb&nd)xroCtc7lj;Fvvq6nw8y*uIW}O2l#^K4WHUQHWzpn=r^+#}Quw`(nxL7t z&NatRzcV9H=0WlDhF*_3pF!P_y^G|nYbFxw2*++4S^oVA#PO3cP)dTzick4w6nEcZ z(jb?&zE0RrTl~;s--@$}Ynnq|!X^q20C=|W_NGXuYO!_%PJO~=`zcBUoa`6taD7M* zh+JQ@tSl`KQPgTY@M<>lsZ2uv6kV~M`|gIYroXkv>xw(uF}Iv~ncluW4y<3Ud%}iM zxK^VUQv1!+o&1Eznb!*P$-j5eXce>TR46U@Olu3dRJU=QYJ$~Wt{ew~p0oFX@}cqfjSMzV%49Z;DOkCUp@5k_UR`i^2wo_5?V4?7Lf zn2AuWQZ_8(_Nm57y)(V8<$WDT42PFc(+q`{JiAtS2f)Alee3 zq26beP&*>sVLG;hV-Z9N8~5U`bEGp@znlPHwdFtxwb7>gE$6=!YGjT>B1S$Yt+ozE z@PJhL^h~rK9A7=m)d!1secyo+5IzLU{g#XBJF@E~=5M0&D{53X#|X9_n(A4?cBTb_ zsb&JY?n%F-_AiCn00-To%Hi&bcdt~0qHvpwZGy@1kJ|`8bF7pDVnBnazLn-%;*l}e zEvk=oNtOqDM{!A&FN1@wDHfpZ;*a- zyfK4^U@+b={8vH;nD1fp@fd^en`uM#NGSA_a@}@##$@M@Proj}VOr^3)BU&FadBQC z(AeUC&AUvj;pqB<5nOGjahFYLI<#$5HUmceK5@#HhiHAO+NqF-t*oVEE7*V%(lh$# zs7>Elb-v#~{A3RSFuaZIVB=)`KE8vX@5%8*6`i_sf1$_w{sV)RH}n(M8`He-B-G(| zBVvLLV$L!XNoQLYlP+fD`5Cm1OtpL+o29 zGq;8I*$YXiYbX2pS|Tq-$lM)H|GC@ak71DuUicg~!`rQ{*}87JaJ2BvuN9%Kn1S4* zBv18_p!JTbR?0o3AuWaly!4zC0X%q4TDE)ab-dI!!J-vD>_Ua_yw88IO z07Zt7fZ)L{YR|{Di7fiKf=u%S(fswKb;%t(kOAY% zpRY?&W*PItnf2B~Ezz-CMs(%&bZ8aHQZ+?Z9<#w3zodw>-*O3%ulq7XsRjK;DrrWu z;zUGB@k=IGg>231gr%NLJWMNx@D{7JchMYJz&3*WW~vVIVifx0#Yh0OMhS+KuZDZ; z_zeW8m3GD+c6df@hP?%jc$(^aT97h#o>J83!|>(K1xU$*1Nb~>J{11er~7>Evd6Dv z!aEYiV@&|EVw_vNxoFjLT!J_!1mckqRhqb8cp9>YOH6oTxb(W4M6IODJ5rg~;uSyu<77&{FEm6*=K26bV zYcJI4oB52Tkr3h~ufpQekCL&QT%(K7B6qLdrG{kpn(`7P%6ZjFGI4R2tgDHmkl`?m zb04z-wCdb;@&I0K=rz*VC)zdqmJ*+(U#AXbmY6M&0Ubm8m2vOaNTg{#wPh8us?~uP zEtfWg+=C3|R;?d#79sB;)#g9B@-M`DKS!o@`sDnhw~p!Qi@+cS<__`TtP@7 zr*~*d4&BROHdr)1lO)EkURZ5H|KsFhdR*fQUG9G z7MDfsr^_$d)}8d1;o=r3w3!mIp}MJf(qnh3$0DRHoO^wC&d0jGyaAY;nyz>9w%`ut z8d^z3{KJU7_8y*cC>Wr>Wb@phdoRieWZ-3IM`v7m zn0oH)+$u6LbH8VEA2NvK%;i3+&B{bgG;`?MRk*cc6PmhB0!I}Z?d&-oLpA-*QW|FO__Iwl9`}ulyiYdby#=sdp4oR{4*#1G#RPS9ae{K*t zxzQze1j+bLj+GMkBF6TkIr*0Wwr1O2$rQ<^j+Am<^V2CDsu@ifeyu;hIV9gp zmvFSyd~Q{F`YLWFORrtsn}Rj;_gR4Lh1udY$^DFx0tU5-;X+7@}0%}P>_&tP_HqB(^uYkWU}U+Cux zfu7|&YR5h(zW7NNp$sDk_6kf064*bqHRDo*M@;KSXoE5?11-I6)pdU`0o3X+*1z)Sh`puU(}F4yRv9k>oaR`sV7XC(Yhr-kze0 z+fy=z<=mSsas`;V?Y@keF7{z^-=DVL++2=eZVq^P{^pm|RgEr0mQSkd@!>=@G(D+$ zoJk*?r#MGQE&mZq0;IO~lDEHVofkjXA#3x{Wd9!Cyrij%`5q<$h&sLBcZ`o=f*D_t z8g_l&n#Ra%T=5Rjrl1JHAYeVPLoXpBF#y zXS3}K6u|c`ZPR%+uzGpvJUnSjn13$KYg1XlXs6&;$kzPW)5^_FUfxd}ll!HgUh=8z zHb1EWSxb_1(`GX*d771H>pVjq_rKvk(-2qwW_7E?DEV~W&eftXHgcn3wk>#XVXEXl zcg-rQ`kAG}KN^2uTfoD~CxYw7!98)@1Kn;Uzk|&`5*!^IAU88$gV1!t5GzqgYN+e1 z%^-HRY(&hc;gI$L==xC<^c1M;mA${GJreJZ|KTzO)IuIZ%Q|0b1ZpJ@grN)LNHhs3 zUAlyRn$Mh>D!PeV-VF5!)q_c^$qV948x+f)HnS_v&M=|nDJdW|%+O&D;dK<8Q+Fi4 z)kZy+){!_Ucx=RLL*RhU8M0 zVGqTS{-WZeu)(%=QT&c@*^mxAXUF+?zpsFgtkI(=9jfac-C<82whpyFbcH!r@ZfFs z?flSWV544F&2znbX2&>z=e;ZKRqIFJBU&C)*v-iS%@f_ZMs+Y?pWJj3r)xiyOCUH+ z$Ahn+_>u{lszYi+cpr$O}s4jA^@PA z+F%h4vi)?U+oa(p-t!tP2=IFNfkY-=RwJj(gc(%bmp#4-#DGsiXBSQ?7?R?Kf&?gI zGl*k8CMAvgaE=>Qr!1?-gj8Tl&<$4ZbX4?;$BfDepl|JTf1*>T)xuGz8=Y`H=3T0L zHI#|n*gv}45++eo)*MC@kpq1!ZW<*(0RD(alnwl1S?_n$0U$u0!k1c$SS`bXy4Ed91Z zLq{>Nlc>MZJ9DWoWT!u9P(cb!b?)0w&aDl3%q@*-Y&#@cVx!eK!P5msd(a>Q9sAsb z`d;~PJc8UToKLv$rOWp=hC5pg!J4JGbf<-};6(|=z50`b(fs+V=Di&w@2sZG=v(vAg z1fZq5m5hljac-6{7b_kKey>)pVE~*q+if2i(q;JdO3IaJYw^9_u2F#vJ2t%jFDU#Lal8_DfwuxFE* z%=N>kmIec2PAqPUE%St#10!P23qxw26G{z@wv!#w-yqJ$&bJvua*U26Me-chpx4}DpxMydm{l?_P1s+J)*dK}*U6oK~*XJ&pEH6rIx*53K zz`dA(;UD*cO9d23Y2>+=J|H2#(y?zjaTdM%^#Tma?8lw`WUIVCqrf{Yd!v85{_ zLb%Y;QgtiYMx7%q)W{QTwlY^hK(_>BHelA)hbID}z@hjlx)e2`=ViAkwiB-cOT9&+ zv;LS7Vyh4Hhchg%j6!Rj)|D2SXvjhHvq=l$xJ+?!pttfxpJbe56Vi}IsVD2vntI2# zg23Dbu*-+ZSco#Ok%4*Pbn1hRDssx-lItr5$<9_c{A=HEoLBcxIHI;x>W`IU>!eN+ zOQ)R29C_0wptI1B%6aI^Z^5J&W${+L#bLxKr=FRNGcM(lRjUy@vC!F@k=l+IKzg&- zRMF#uCXn8&XfExxfpQ{|=B8D#4@yjiTrLUQ$b@tBT=B@+-t^&dRRBnie9L z*dwevipBZiaOmC7LM@s>JKY$aA|8jkh#~)7T6E7oJ5o@C2%%iO)&5i-Tu{nl;{kyV zRJFELI_utJms*B1%aJObkdF))iY@Ug@Dt`oh=suwf4mi^GYsBUBg3pDfgr&dm`(?! zvLupvn_Dk)s}O)oHN-EE#iy~rl2a>hO=%O>u zgtYLBUxnDCp@9LyRv+TW(H6t|&9~<&+5dPe#w~PI1c`oWyoXD~^g!#-% z+T>mCNuSYyt8L>F@!H7=OFO9#cDP^4OCbRaZSLvmk(t#wE?n*5C0!L_i)sLT)}s=k zVCeUA?M0SmGji-St83H3vXLUjB~mkjEs?qmJ`1=0zm(S__~H?9A@GHYwuGv@c; zlwD(f!YTy&i(TT5la2-!6C?Y2nM-N<5Iy>vyd_SDAh3S_Vs|z0)AR!>J_;Ppu2^)Y`^_ zLAGpOkP#v+;)IbBf$1ukc6%O`;V6*gl#mwOKW?y--^YU2s{y98Olhs`cBtyfMJHmw zL}ZC>k7T(r>}96m4gndAty)1$9kK%t@l(~*nJir%$C=V(qHW^iqScce5Ker3tafw8 zyX-HhhIZtpEG1#|9l7X9?lzPM3$Wpt-xs)eo0ezX){M7>v}L z29;r&@!rsFR3%#i0y5x9iZ%g&T3{9U+lJjr=3mqZXn{+k3KZ?${!7yq{BdMf z2urM-;D>v}8txoY&uUEsvVo4al(Y6RA zULtqQ4SFJneah0xRv@g~n623N2Crp(7CtPc2qg-=L`GG6RUb1=x^Nz{0NKJ-=*TO4 zFpp4B;h<ul_UB6 z(w6;`Dz1wj5g_c-%P4SV&kiye)Zi4AxUW1m!JWZ}S-=mTFcG_Fxm5U^~ zDv{4Gn%q+qm)YOf)wf-Hl8!yHh-w^~JUyq*V2ZtPK7ooHfx$6Lt*H1)ZZA3$$zhVt z8RFmxvU;;8 zWe{5+aOL!JC*XE*Vx3dbSK099^n)wX*ku|f+WNH7`=PQDnx8*tv-e#Ueb%qW7?~nW zT~Ps%pgg}E{-!a0bk8DcI+?8+-`4k=Wq@6#sRVO4vaORV=&a+Dw!c59cTo> z^e)Ahb7vo#O|-9QcN~*}+4((|;sw2j&$=^Aog4d8#;!}hCFCXlqdjCDBo<~5fHW5t zaK}v7hURFDv@NYFy5r=145iBxS8W?Blt{`u*eh0i_4fLrBKuBK{{tcpOV}(P=p3Of z;q?rsbgSgXv^L0r!K11g?Qi+!Y_aUtC%%<`pJvqBWiT{pja!WBhqmQQ_eQp3UJdF? zu6+%)D+qn$O$b^8^Sr1}_NIT;B%b5H923(g7m?S|;kZqR9Uiev3qSSlw2dI*Pjv(uzM;|x1~XTc%PHlPdW-tQ z&el>RvzYZLeZXmQxNai#Os(uCj7s}eeW@<_cKX>`Xo-0>&fit0Zv_oS)u^#Y-Em}I zDW4$ImTr1kr|jTB7Xw8;F5Y!NHlq$nd`?^7jcIj5RR|61%wAfqbxh^R=IGp5HkPtd zPA4Ix9zQ%8q^(43ti+%o#s}4{G4lBgu6#POV>{Y&N)%Fvfe~7WoJLKly9u1u9+&I$ z^|4TNRPdieophlan0^-=GJ~?9!?9TL;mu+3q^2VD;IM`u%ps^pGEQmDct4; zu+*NwmM=8e)k28Sav-3eOh&r^%IW2`J=>qI{8p*tFaskJQqeBVgcr_^M1?Z^_I!wx zKa;rQQ(_2~LqED`?RXnh*6p4*&{_NeXF$FtVx7tu4A8tk6ONIB|C={~IfolsN~_U~ zn)Lc$l?Ves&sdp0+TggpeKyK=9m8z+nnAIX2eIiU^+J+X1JX0+aO>rnD=y`ptNhXf zp#i!jV<+4FoUzRr#^Uztxk|j1n{m1zP@FdJw9|-M|Eu5LD4-Z+z`(dGaubYS8i z*%|b)U_&Z-my*bq{yNYG`zJQ&aG9pnv_(1`V9>K9%U-{ZMq%ayMS#9<9Ph2k!=L2( z5tbp2&6X+y-%b*^+u`B8FfF;RGgez#vo;@v!THt(?jfkESQ*-muG~M|_UUcfF45=W z!=V8KDLjPKSRELo=Nn;gL8SPj7RWiJ;d2+oZHPvS(-bRSV#s56VYt9};b3R2g}<{f zWHEm0U6KlfL>n}vQAS&wMi9T(G~C3)VbIHjE)KRk!=(YbW=X5@eTYe8=A|g`(h#=A za0(u3549rd`f%+MAwsmR`z`vuZt|I=#wvtukh{biG3VRaEs%B+XfqTuQXRJoX z?Ognj`?<5F{WD$cv;>YEI=92XBlgY0fh^5f+;>%lrzN-L57d!$GI7&5c`$&^x0Fm> ziT#iY99$dZfC02@et0@a`e`~mZ&11deQ-bt*Er|*<}K;M z4x3%o7;UZa3J-h@FQ2zdmzQ}Q0Ri6&wO@)D{PW<^O%{@ewRfY+i98@ppvV4iu??U` zWj$p<#h6}L*mfb~T(fxy7ykap_G|*|S$-wUF4{mb> z``?8wf_jtx8NoVlg_Z550A=;$Jt5BfP6t7)<7994Of_qM^eIGgq1gdbGdi3)V}YrN zvjgLkaM($*&N6Q~cN-z_lrGw}d?taG`O9`ubz(SNxzVXZumKiMqRO)P7q$8xm zfo!m!=)egBQITba;(aR4n_9-bru}CpQt_9u*G?Cm+_L7Uvo<>RB%BF$yoWH;{jR~gO#Ab2;b+&jKu8)uMC+rRqML^Mncn0IilH6(HGWX~%HyFb^PMj=HM7s` z_5JU(>R8Bdz(bhlb$c`J@SWtNf$qB%tSTx9{=8^4goA(;2^t7kflbbRLPena}okSv9R^JmSNSb_y)BBzYG3_R<b;r}PJN}+Xu(G60czbOU;qq1uG0e~L*pZBCZHUi+F`~Piq`Gi^J`u+rm z_s_w)eBx{@mcg^gr|L;TRO%hPgmKuuqjXkIU-6z6auW?4+|TDDB;jRZ zQ{pV|TcAYYrT3ZJhlHoT;ic?vuS&ICl&}3SIz;!r8&kV~z9o^K(J^9P9mW|)bWEI3 zp?vA5a~|i^rC2&>) zI*Mt`NIrFCAUnmJzw8u?uOYYil`Q?<%}~(z+dV8&|EFxKasB@hoBDeCAK26>(*K=J z9sKuf>RdtOzhP6@ZvS&Oh5DhXS**lB+s`Ipvgqcf=%DQydW1-SCq@i-q2(HgdPqlz zz9CAP3K--_#Zwpo@23prsYA+Z54{hnILdU^fBr(X96-yzX>*l2ADH;Le(ilafv& z-cHh7gZM9`&vYPLMeo&xJV|K2Src3_Y4L*JMK>o4Hx@9?V>54Xjfrw7k6;Bsq;xE7h0(Dd3gKmNsd^BNzMZExce_1ItO(lxU ztE!4#Rd}Ctz#0`uH>P-Eb@Euz@a9n3R=Yd4a)M}ZKQM=Ifb*^Il=)J|>`f#|S*H^m z5VLgiJF%_6B*;qb7AVKRzBcygofNj&opq1+_c*Zcj*k1tKjwwy@!37DMaTx=N&t^m zj9DPvm|DUy<9(3^B7j~6$)^^TC5T$l`#w0-gF#bz-LtWFnc2Odoz-VsMaa5pd&=Of zC0Xxdw#)zm5Bk2hX4e-oP*Ou!-L^x5R`lMwoI*>ebEbwI=3{#TgfDqG@0T;P6gT_u z-D_ER;u9B}4%-&Ju*F}FU&Ri`@13v&5S|Ap>qWc=fo(Y2*7UVOE%JxHi9aE9XzerW zy9QRDzPj4n$ttHD?X^6EHCygPJYXZzB^qwo*>7UO&+EFPZ@^G4PY7#xDCy>H`0Y27 zeU7PQnh2VfuEk_u_Ug;nml96@Sa3$mBfn}PdLnj^clze5jaIk9)nMYqQC_T_a&g=} za%)5RvYuP2wrw)!HuN1sC@Ga^>l~!fWLWyV!A-yCE;C|owcbZpR-G4&S*X$I?a+Xz=2In!+1BCRZKfIrcMP*;sH=M%B zfLueGZiR=2gn{c6UWx9hrERzM_YcnrrD3Fm=QB|ZBZj~%E6_^zJhN879|*0xFPMKHhA z(>y_eaoN}ENLaovZ0BhRUqKsHi}iv^D8NQ9&6n+q3yWitLYG4s0N`S3WMPZ1Vz8ah z%i7&tfrf;%?Rmk%a@5a_nCp{1_Jtt;K$Oeu5x(6ZtSE9H1NB{X3eT$Uu1Tf;BdvdK z+cz$UiSGbFmaaCBgRUJC{_X^=g z&FTVAP1s8l8Jxm4M%bCk9g*qb)1)B>G~b;1j>m*kNd*@?-$Z!pX7%;KnEsnuR9M1P z#cD)@;xi=}y+w$^r;3WzF9~xb-9R>?StQjaP1#JAoIm2P&%WAE3&W$k-bi1QJAUq? zS|bS=y)BAjLTe>+_0T2Hiz=pIU0xjw+LlJQCx`PcQn)(dtz$DTiBx!`S&`k#8>#}^ zJe-f)M{LZSbF?VX%8El0ltG?|vfB`v1G5?GhYpoFyA-N&FCdQz8R@;Cd%BKxpGP8& zf~TY3G|Qvsi@Hx&*Z7eX*trEIOhk>3cwWLV0I`scaoMi6UxtAX+-+4dZL`1N{Sb{a zM-9P(OLB0nZ+@~?#nfMS_aH5qY;N{KywX+HtXz~NASk%c6{0ry1|6n!dVZC0jH0e{ z>Xn3iXTc(%iM7mj2&AqGRO)!GUh=U?D*dVhRut3qO?%K2MRBN-8;M;WnaYq1>u}gP zu)Y6AyPt{72FXKZ$@>VZByTEwWl&B|RT+h4Nm2#-W?y0Xhjisxfzma$eZ5&LhS~R{ zgnQJrX(s)(AWMyfAl?|iSP~WWqLSp$o`o&B{R?oNfh6^4#h+#=qce(p0J;2+v5wJ^ zzYbp-x3%8d-~lA)+RSk}QMyC;<2~Zt{A#rSnpSjB5A|;Ep_&(AEIlGLf(P@pOpp*e zDH%`h{4z)7#k}H2L-M4Bu>u83o0N~0G4r?#74Q>k7LpTzoDJc`qQ@uUZ{lTg+hX9R*y+YV3Oj(4(uO>Zp)mvcf?v6Q`u zv57P~RWybA%lm!b-RkGf`G7>woY(&%Tmsbnb7)4MGa3q$fB#MLcqmWwhew%8IfKq& zo&EamPGwT>8)}AR6LZy4lP1NN@S*;t7xh$lL8*e__;rt@^@r4L!ZO>34m-lj{Vq(WX#Y-Wot} z(Vt4az*d7>a!a%Ap#|<*dxh$MI?&7JkHM|uGJMYZ>DB6Yy)4CJiH}QyUE?WMks^sl1+#{1mRj)LJ}0dIJ^gZ&f1dV?O1#;|CCen<`*rRoeQ7OK zR;#lMg>PU3*#q47q$*L_njF;JFfQV)Y6|eMlfrDxRT*B2_c<7n``Y#ky?p{ek@wN# zywRG<3<2+;>9=MM$}1%~OYgQV`ep74y==AiUq1H4Ix(OwJs|HE!vl*DIgQra6mL-< zb6x$Ic{AfVpzfD^WC;x2m*|$u%HPFSy67V~3#U$}v0IxLE!dwp;er~P|22=8JuY%K z691}`rge%Guua!l3LwfNgHd}g@K@=u#7ccxw1T) z_!c_VzhkPdd&G~7Xoz!evc$qx>dg;#i7XTRY>W#|nYG7!A)2$^d`dZ>23)G+-oj|K zq@B*O*B%ol0Z-e&NuNxPm2WNzAZb_qmyKfUuDwaTNpGL`%($K7v$Qn4#DedXgRa&H zXr>|VM&LHN)UX2 zAi&ahzEWaVK~Tj8&u)zNBVZyvhoE?D{nT9J6VJAs{p!86@bQDPo!hKU#rd)*xeEI! zacJIe)d0l$9Ba84V9pmPVF18@)jOX_*g3a)sp-}tBAvU2mGrLic=O``Etd@W{{7Ac zB}+dw-6$PQmg(5N6P~t@$#u=77PK#$vXY;OtRuwo4`)2q726WLlSO->cP-nh((08J zu*$ozb}f)dE9!tiF3>eQJd4UNN-pp5M_Fx4gD=Ci?CbUD<)p@TtLzd*^f+t`JAFzvDQcb=vj%>pdn|+2x1mOtzw& zf)?r>-L?nv0%$-@qX$+}Pzp7!D;IkJDOa($(x2!qd|Mox?!e#p^3lOoZ9x; zJ8@U<>PzgJ!RD3exsQ5Ov1Nj~P-aV^mM3`Fsh3>yrI;a9$^xY^j_?+XBm<9 zcEpQjW@25)yqQ^boi>e^?7i)nb)X$44Wqt!waagoj64zU@X8;Q6!dDtI9f|&Y z+oi%^x$H$dedFGdd=8`I(okFjFkvbG2X3_X-*O`tzJKIK7H?mb9akUB!gZKHZ(xCL zB$fB^k;{isvFE-t!{_)@O;^1s{^?1PNmBlgs3G66z5{p}=T*L`Ijt0D(QVRR*Dl{= zLyjtM{R1hgm;HBA)K2nao; zko)J9_3wtvmNq{R$NG8?tudE-HW}0peh$^8A?Ez*wLxh8WfT<9QFGHOP*2MeUjq{* z8836};aJdM?^T2P&p44G`9D6`uMV>iwdN-{eAX@DEEoNc1gXE{x2<8879s?qw^*bh zan1T}w>-JO9u^?vZLp~_3aIrVXe40n6`NwUqaxEu&gaW_9|E3C!qtfxrjOH#qhmOFRh7#Hw;^@C;l&1uqEx^oCgIi1?AT-UUPruO8Ym zm_8?-aK%DOjTrrfhfwI}8_?0}!Mw;ma#>atSwpz;K2cDPmz6FtTJg!b!7YL znL5aJh;Gfx+d~M)wV53*1%T4QgJs+c?38VGI`a1Xk+(`#AzbTy;Q*Zf1c73|Qgeu5 zEWx&ri(SW(_yPPJr?oVBMqik~el3mA1cs!U_mxY!>j3xP;fGorg6_y9hc!qwJDBI&wCS=L(XS+*C*T0RhG=tzbbkOo-4Zv4cg zps+qr;N?L#NG(AXux8L-)WF&s>8ef;^C($|NI2J7qLbO7kZsl0ZQ6Y5dKOx%8p@s{ z^B^d5ND%I3!{ayiv-kzBF8FGaH!!XR?O*u@qg024Wmrc$#D(KQzkl^In3uiV2ict!CARSKWTj`-|S{IG6i>{LBCiWzk zYf3Pb9LQSS@Z~t;@vaa^Ku08MLkrn7CY@xmItQKat#_niQjz?v3ci-}5^NJ*YHA8e zNEgb=2CStp@~O;WbBI-fdJQUesns-Ri3hQpvwFwwbHNc(5!M`Wyeg5yd&Q9x z9^Xq5lHtNm7;KSk#(^v<&`#lql~bqjyc&HGpB)4|r&vn;IWet16eft@rZ;-uZWOq9 zvxA1t9-}KX`x(#9TXaC~f&^=YRb|87k)()-bZ`K`4$@qZC9Aw&aaeC(yW1G{&wc$o zU9Ok$?g1N{hWS~gK8gy>oA#BO4%P9#G0?kbMN0rFV4p4xo&dEg5EV*T-D5E8Xm2Bg zSp{uRg^^bnIzt<$j*3X^b)kNs4qNVsS&riRB!7luD!%>DK!ImoKO@LW#8#p$C&5_z zCVU`Yzx`rUg^PD9!F9yv{-r8E@oMqQm(RE2WL(>Y_*c9>R;CAiy^+e6#b+t2R2i$@ z{rH#tv0W9z?z(~+ClB}VCrH{L2g4^7rDW3pa0fWm!AHmQ2dIHu9liI#=XG~&X!j1P zP!mW!qfOlP8wz%qxkYx39i2zHX`!jNavVNV0HDhL{AY*b$}T=o@JUVTS2sYB>2!}7 z>|&JaBkGf69%A;Jxfr)|_V?RBFC96%VaAFyDusSz_WbQRHau(mruR5b`yKHg-Gffc z((!B0_@46s0=mV|6dVZ1+6*Hd2~m*T2T1xDl{^V3dmSc zI-ymwWZ>DdNqvsuoSUM}1Yd2Qb=ycm!wjM%$K;Gn*B=jO^$Pa~%700E{v0z=>#x~1 zp_TFWajUd03x2ORUQrFvR*1~EA(yxFzCUn!d!l^7B|!x3-q9e1+uQ2<=s{DzQG9@rBUN_>3_1wnitlArpQX=B8{w zbZn*Ksu2DE4c2KsZ0xZRpfOn{W3c_3iJ-fRwWY!fnjGW_MzxQ`i99KGl4il}0VK zqet(w-^;=fkV3gG`lQnwL)nkReYWqR6Jc=g#^JV3z%MAD=5kdID(uqDIIYM1r-;(y z6*6wMS71UYvH$Ji&U(V`@fTJ)HJ@=2Y+p@9l=FAmnr4eos@%=h4DCc1cN!%4H&Aw# zH~#Gh?}3kGm=OZjV^sUXsXVRh3vSP?S%C2PWV`de(;XK%Jw=&=nDF7Zap%pwVKe|s zE(b3~ASX1yoq^#w*_<%L@2`@@75CO>AL ze|)&FZ{&$<>ozru*jStC4hnoPVScln*}?4HHQ(cpfD?EQ2pb& zz9eO>PoJGAzpO%vpRXavQk3l3@$i`F!0(06i1+~?O8!fY`{jnY#%7{ONWbl;`MyImV@x`;3WDwjx?%3Exd#vq?vK3bZ|j}GIh-t3?q?VP`~?oKH<;@0 zET_u{15xAL_kSorIzV*Q)>MDpwkdMNKHtyS|6Z(HR)Q<>Tb6kwciLw3oYWo}7Ek-F z1-69%RfT1UuQm0FyG)WpuaNlc>2Bu?x`Aq}un0l35&8dc9di)Zd5_8e&+vyt?-)M37?n3fd_onl2@ASTrKB&< zvE_h#nvdrW~Q;!$rlOYcL8-(p-gHW9pk}+X`3} z9AmfR{uwUdFWnz5wLb~(A~704H3S7n@GJj&IH{uc_%6X>#rU|64ekGEHt7cae=nN^ z-HuX!V<7U&c~kTkL4-Sa2Nv+O@t@%ytGd799?$;@_b4I#&$)*H^)I={h0BK0^sl^U z^`E_m_5Wq>QI*mnvCo~yZ>th&bGq$nqKkblb=X?@($3v9OjZADfxy~hjbKP6a`E+7 zZ1@+j0i0N}E<_bJ5cy`adt#H8ip87sqC)2G*|oke#U5uNc+jt2_lu%}BV&dh^93`h zBI$)QNI91U{w_n)%el|Q5STo`R>yjwStlFHj~!qCEv42)6T-mm)tdz^@((72W3v&+ z_CGcux(cPlpg6pC_SupA^Ksc=UK{G6w%`c-IrW+82q$PY82EPJG5r@w452OY6rw1v zpDvhBA}#1-tE^vdON{>LwO_hDQ%N53Vx4G_My=|b=H?`G?BG6Rl6Ly%^o@3OgE?=> zmv>iyG1`@%b{)J^W91e-@k?na* zvM-od-UYYX$5!R{^9$?zxyS&cmp4xB-@BtfnAvAi0N7fd5j3Fi!IYWO6}`!vL_X3m z`c;hp0OLh!zg!!GdjNS#YR{*1($BW`L+{pg3LRU;V+a??TyWdd--A0=T8+nZ*tc|D z&nT81f>u;;`>iebZ${QPGTj1oF^l<@rq$UDccM_)!F7wJ?q~e%xnV^WBkX?UrF4jyKwVOh z$vHOgpm19}Bir7x@HY8G^Dg!f5;1?u z8nuEUgS{q&;j1m`Q9HG~qlx{s5e{LTtYNtB-s)Ks=rF6@j0lJwVGQxMfrZ-_uy3uW zr9maJSY&4Cys7LReINxiM_ULWNoW1{G2eFwcqM+~H0U`tRAUNCEd-O#FaoN_i8nmT zm7Mkz0PfbS@X;AxZ7`Tcn^6Y-w{?lbNjQMjs5bK31ILQ&dG27jtH;CXyjRl3ti5QH zB89pVI&DeVfnR1nWPMZ#Z_V_9j_3&3-zILQr;Z|C=z4p7T#GtN-^~>OgH9VY9k+W2 z7i*GJSga};$W3DphtyoapyjKRH_W*VDRb||QJ~XtnXEFB5yOiSIjn#(`kAc<1<#}8 z;y7%ih-p?}Fe>70N9(YCPl+a-_>o4Iba!I^ow}e|BC}E_4yM%5nsk|%iG0InG}F!Zx`mQXS~V=BGWP9r zKSnTDFy^H@>u6XyvGj~lekLfWFI8l6Ubv^U^g##S!L^MzfUxMWIOo>yRq|a+3HZJU z*dsQJV45^4(3zM8?t7i|FQsKy!$GIBQ{J97{N?{C<}_b^=9FVkb=_G;UvhvxP$n)# zDfkj`MjJ?v|Ho%wsK`IU6Az{VypxPTOb)Qxm^O5kXWD4%v4g%o`plHQr$_CT?QZOH z?a*7A9EP*$m-cxW5CxXY zrq8u?F4viLY&G+bt7K`P0xdIs4SG@r<>N?_^(_qj5p<$!Zv!Y zn6;leL-o8R{S`fKQMcOxy5W;5t_yWwF5{AVnl2@JP_lFab;kok$JL*KzD*4M)gcNT<#0tcgsD+*E1m=~Yj5_I58G(1In~VP<&)xm4kg@ZL6r?jHyx z-uo{RYE;S+SD!2jxOs?5M7LrDz->aVFNgWw>@5M~%XDs~pI!O$tWy1kLYZ(rT>6re0A^BulM-YBUI&y`mrn4 zN~!=HgD!qTd(R+*&!PP~$>Z5a*IqMk(ark+YlfPOuY#zbhgPCiEt1pFng^C;A#nS?bWIh`L4XDwE@I$d8LUIU|_p}7Mm`>H% z{yo16rRlvKqQ5WKO+mWNSpGXQy<4>>hQ8UeE|;gA2j46K;(z4;yZY7fWmCQk`LEC) z0VK%Wefme4@u_a85<#$XiN7@DxZvTYQrX+znBw6zSd}2nrPi#g?mblpdb<=i0*0U= zV3cxCErXxhLUO6GN^dg7!j`M;ug>VL@MCO^pgN3(?6)W^r&A1>ztZ)&l|7_PeDi(0 z#jnBS4y^}?0*>QKG$Cu3IZGVLP{~Bbd{N*Ym^%BjDn!|BIyOqEsWLX{9(=ZV^H^CF@W_UK0ABq-klNrj)Y`xnlvWzbo6 z6iw$Z^(9W`zmrgUHe=~PsLe|(a& z&HO=FD0Y8MSl?fusK5O!1SMGT1K@Y*Q7?Y*|C1mT3Ia#dq0L#r#JyfZ!f=`wx8{uN z3jW#w^+H<-s(TA;V|fsw;K-X(H+$xg7H}@;X8;9NsReo<#BgU-kdXwjegYrQ-iLey zm=@zdX%^8h!Xs}~$DBvWTay^OM3q<-1W6n!G(b?HA$O^K{zrf}>61PtYOE%Kg?6%|Crj$ zlw7UYiyRgxPZ9)KNZ{B$LJ9ppD_)T|EN$yH`!7EhGOUVeI#Xn*RTW@%#@qPVg4r9` z>E$!uVH7(ny_d|fjkNkYioRp{6!QNup zX93`k7p_*hD7R6Y_)CrtNbr~u7{#qJp&&dYP^|wpmkZmM5(uM48rcl9#)*jMg7uA3PJIwe+!ywIQ({RxzyIZ5m-nq4rjk?8}2VniPs_AwpZk zF{cCvRY_SsHFIk*B3mnT0M(t9xci>>M1oS{ zU^b;-%cke(p@Ic67HL+7QbA0KS*ZgClXK1Ud(hiext3^3nJ?^D!zUSvctV8Poxhj^ zT+up>7(fJ}`MFw#l!X5zyOH60d)XJS!C&4*h9JWRH9z3_S%i>f4#tDFD{{co#y$y5 z5mdotRnw5i_4!4OBhNhV%yUBS6$sw9UqL8e<>c!iv#m;9x{w836Bkp*b_A&Ao}js$ z-Go=k!bxlrfpID{~2mmJFiVBq<14T!JZcQ*VvNm8G;5^zUZkDJ| z9KL5{4E0cFS=B#x6PSUo zc{3{FIftZzzgG1Ij{8tE{rQI9ofIG`1~piO4u}B$M9aupPAG8t{YW9w^ zg37`eXaRaD*@`a_Iu?b!2mAes{%Ua$Jtb&CL9|a-f!W3!9+ebYt_J3du0D69bF>#+ zvg{J3GI$V8g726YWXAdVUJ)`M_ur6u60nBDgG}F1NuxAmLWouSQ_ zIIv5m_|g3VdE~TD7hwWc$I|DZnj+q_Hn~$lyR)eXT}i>zRRVeBT+L;~d`q7nb!HpV z$ObfNa0Pt`Vu*XG)kcFNdR_i4$W?^CmU&~$ZqhDUEC3n#dD7a-8&AtTe$4G_8L7`g zt_EIiHIlY+yz3w$@;1+hG&sO_@Q7Q-VJ>R@yFOMjzgfday)JiI_+DISbJm@$H`B&B z{J24qY?_Y~s))3Nl416!o(eSKa7pC!oS7-r2;CXekG^LVFRov7o->{9f=Rgt>u`~) zo4B7(rJ>w4Xqd;>4eQ+3H&kuh&A^C76g3n zbIz5V?NFKY9;G3ZhVoA15T%X)0-rf%`h@Bzato^=@UnTWX67aGN_P+?4*>#W&2C%+ z(}o?v%y*|2&x2zxCP;CfB-dt(#1YNF(|R7CQ@Vl0bDV5TFT*g(wv@9b-g=ECP$YjZ z{_IOzh&Fvg`Y8ng_=$f|?}c(VwXRh++;MEb?(%y94KqP$Nu3xN9G~C#Tt6a$V62Fm z^m5Q})Y*Z?x-&e5h~W(aY2Rv-H#Ba$Qhu{n{?aB2oAYNR5!Ndl~o z&n28^y}!Hfv=H2d@32Q2sS*WPy$31R8v2KzUN(hIczzmAzfZlwbD zDU|-I1_|)Js>{yy>qc2+Zze!|BG--C=Fu}ER`#xzn>1hImi1YuEhK7g#$LPTtbU)0 zjU#A`$&@2Up*-1obzJN`4~2jxjf^z0X|%sT$7(%rBW2jIRMoUYoe=ufAFeL;J$HOI&#`r z?7Egq1~flZ{As}eX7k2ol=fpd!!fY-mNAl%O8%;`vIaSoA5XUy4BBz|x>E?pS0@Ge zOn=9tEfxY`P`pEa4<{)*Ofi>ytgd`c~rnbzvb5Pyz33W6-w&Guf7{*SpGa{ zCi#*GQb%0#$+r*X@sBZLmBaY%+_GGUd%F&4fH5*Vz9E+^)sRA>5+d)D=}3qcJhtY~ ztArqvnm3HoAJ2ESV&s6gn&lJNDe?rI|JXPu+hpSh7!Dv3jOk6-|F*tw zlJr;~HT^Rkcv;NjF4EH-1o76Bk7)}W7jT@a#;Kj>UAa9zYfoK=>}0xCc$?pf>Rw3!<<0_oZmTgWtajR_2V`IOLhD`t+e+j`B> zG=@9#<6q0P|LSvVPl1ZbJUumwT-V-3RqFxGM$cS!FxK7;%0@?w=;rYET2Co-sm7PB z@ORYgiaL}q0~0^a@N}~NHVN7zCDcmr%p8-7fBASd*|~+`G8_>4{*mImbt~AswB(LF zM7bU_;p4$$c&{t*xVqqjyPCiOym*0APDMcdkdO$oprZ|_6ZAa;0_xi(mYVM`*+6z*nlC7<+d%}g>!w#Gk z*_~{=RL)OMe#ADhkhhamXaVc{6t+7>iiRXO6xUDS!F(IQXB!fdQO1s>#Ju4_#Y!0} zBwHlqc{%H~FHp`@SUTSuSW~;_eXXYSZl3)n1BTB|o>4usTgS=Y;jEv80;k`Zhd!>V zq#U?3bNTh;`9qXmGnZQyB!VxRJ z0e zEW^50H7T$Us;T-Z56%Z$jF4e$2cE7S>f^YPt~7fH%)YwMd)QpsYND`py#zSAA%@kc7weuuUI_ zhH@noScGEo{HBF44f2QcU8531*%e7fB&5h#S+o+BKlu>UyD27=a3Vo-rM3EVkv43p z<(RfG@j80#89Y6sx5MV#8gsz-bK&$Vz@B`;z0Rg$W0h0w>-B&f_g=*(DpnB_LP1%J z#@C0n2%nZp$vc)0V{Najb_4hbz7Kk$@{{Cs*8Bb-nHbQ`ln!f~IbzW4;Tz8x#W>1c zG)Y;@ewmFnhdGbU`)yd_GAsApZGRYhn85UJ*bYzCZ8|UddR~1Ao=h~Vr+tzj;C&M1 zIWEIPl<^UThhX7fq4af2S;A64MG9dL3a+gtTmouZXs7jq!P&~H@_!X;F23m=_2sZ( zxEOt^;PrMCE{d*N2oB1xMldmvqIYay4&g;x={2;R#Bu5D{Ze;^r|+&pga?3vu$_0@__HcAN{1g05H zfNU>saml)b=NHZ*pfi8L0XPMWArwUgF{;Tuo+D@ZB@lyE{d~a>yBXC>T zt3lm>sd9W5n0i+4?3z28?c<$b!oZ}~asClBuPisZJnv%v5KerH`;NRJ^C;Fk+q>}N z4F+cyA$q(A$cWgVbH-I*X-tD<8$*u`uqCq{MZgAwUVS*cO9!ICAEb}XIcF)vu9pgyMGfd z{oJ6{X$OsEhDHq$q6|E^1u~~YjALPf>_Wp=q|f}=Z^JTtrfu@Xm^RJyeEa3i8Qf--@yo(W?Uf8 zg@oWDY=DIlSj6v6RjHD(aZ(%|aY3cGj7shoHU!B_z`&rePga?{_x!_Y1{{vSzB4~b zxSs!1bpf;aV(n_>Mt<jM8L>>sSSOW1H6b~61OSKpN&PoN=?{J3cjAaY-o_#| zpCEr7zgDKLlRF`Ymx69U*&*<-k?v8_S!;dXKSm&&l#C6CL zNg@r3x*F(S1=iXp8blk~n7?;f%ffP?mAoG$ib{5?_zoXUO#7Ak7??M<6>zd2+tuwV zlh8_>`u&=Uty*v`--^1#MBkuq6WCLJM%F518V+N6HTDR#Z|!jv*6zS|Gy+z~$r3XDk7%LIPZ`3haXz9cw)D2HdH5C~ zTV!ZZ+(i|=$~NBXIh>`|PB4CHgQ-dh2M;~$Fs`#+<9BPHlzSst!F}YYpJ=K#EBcwk zxm45pQi!@EPZuM#ijKYko;Ll|(Xk2!8Q`mtVQ;fBFC(^Z5s@)&60PpVXnKSMJYOtN zY#!eEmI*VxX@8a}YjA6g!}~~kCyXV$F%ZPz8JS-Gc}eQpG1m;=Z;>&N-{Vm!hbGNPt;;+p1Lg%oD^aA9y6V0LF&+Y}*O!6nF*# z?C(0;q|(y|-mJ&~zQ-vTyw9S&x^rKjiqHnOf@m zL|a2&jzfxF1q^hvL$CyZA?(6keS>TX+(WYviPT9g_-tB+qmjKfdt|$(+$_EW2g_;e zR%6i;;9S7(!@_;z|FqY4m5W>MUXJ%pQCcG1zpG4^^1^)==%1*)s^<6l^Ic%5{PCGK zVDi|$IH$wihtYSx9PL}f#aw>M`#iSKL* z!ngTA$LHJ5XHod+W--(dCxsXjAp_V{qpvIHF0dV)bPUka)?Fyj#lWV~-%Oeckgua> z66CCywIZfpaN7#_ZX4tIXpbeH1c1 zlFzoOyDilax%a-73Q8bU-&dqgV>vZnLYhb`)Ip?Kq3e`0Ap#qpfdX6j#iw8cTljHp zs(cQVDH|WNz+WBooj+b}^|TKzW)SICp=K1H7xcYbQ4 z*A{!nGH1XUvBwdNPg6o3Qp}c;8gUzP4IU|3pRWbhmQSirtjTUeH%EX#|;nbOl^tS@CbyM(*o|l z`XapdTu7?5JbEboxY-abkY+I#KNtxe4qz@&``~;VY^dU=yXS3iJ!XJ0t&s#jLJHcY z17l4B#shJC!-K&|MjsVjt%vZHfeU7|wyDAe`z3?;U>U2 zHm0c)e;Ip+UXW}yee%Kq?r)8?h1l>93c8HJZ~=nuR;I9)nq4U!Ivn^*rmveCmSrhx0VK)*`s(*qgK*e5Q= zDZg2%o;B?i;GAD5#&9EKlgI`T@;Me`#Op-Uy?77K?&x5Q=@J)rl}5dAXW|>*x9l%D zG%32D_{5QAwI!{Gd3CKj3_pm&Wt2jbsTopnB$}}2iTW6%L=ohQOO{%_z{#l@_)}q9 z@v{|B&Qk53xm1MLw)56bexRCgtY|8QRHdpG78{Xg`FI$Bm{{3(S7sh@61A6Bn{Rwr zvF-E^ZeT1eHMUl|v>xc&c#!E9nh2mQ%MRS*s087`YYR zn^t=WPnM-9$@jZ8x=fLTph_qIoul&SP&OmL=+iJ#b|y5Sws_n8QCm9`N??cH99wK4|q$%1UCI@_Lg6djpEa{A!UF^{uCpGKf zA{+ga964ODz_H3>q`_N05_yTF#hfX_2n$2ArNR6D;%B-TDWC}-GOFT|wf~VkPtY*V zNx=_a{SZl?9frty7go8Y<0l~SL)7HbwRq;wwIEb7tHl8%@ z*r6tlYTK1*EBSyVKl4!D`zayIzSDy4t~f&tCHi~Q?Q?guSqjhmva@eqUYVdl0{T3( zH;=T;hKUuXkPyIkNm-fdwVT*j__-#0e8MJ>GpKF-;OR8suBm!_d{-YGnwMMmLZL|~ zTzGpW`1He_a2wBqQ4u${J`ZG91u~?{>~8NjVB7pSOu$W7*uug;dB4_7_y=^rltlz< zc_#ho?PTg#oIZJBJ#CH;Xm=+MB+ag+Y>~S;j9hTKIs;bnHktrra^^26?} zC^~4j{pR3Xf=$PlP$-tb7mos26tJj!!%QXMux>hTO&wCZPw&4uQXt8dFK(+n-ApcK z&l-)7?&!)OAdgc{`;}IrVkbtvg|n6W@J2$`!|y{!cfh9&pYXWarEXqnI#x!QL$TIoGtnxkZ@L&upbKRl zR0A1a9rz_bDDpu~PI2wJd?!6NV18ENC+@D#m5zb2`SQTxt<4048QBp!gX^|P-v#^? ziOzoL|0?q!C;ms~QA_?`XPzup*eOvDnnRF}KQ`XU=tB~Fy)pZSyByTRbMPi``o{cY zJGG!OGcK+B#dvKa-3$yq)7BqW9nPAVBh--wg+H`0WpxXz)CsTuxOw-N@YC?0g&&*$ zPv8f4@V@{*I)VQHKR+lFfYqCS>kIG~2o%K1upCI#ZK@W{Et<{BuxUjh_;Yve>+yUY znVPedlbsIy*}s$*3ia^$UwNR3eFkzXqm#4b8mx2uhbwZ_0iK&Z#olhCyjRwn?POcj z6&MW3SmrEb8P{Q1UZj`XV+xq%q!@Edz0W2072b9i5H9_=Qt)C{_XFI?sQQgpTz6yt(A8GYvUy8ShfO>EOnY7K zLuEr&^f8T?4V;~Q_}?3o`${H2eIFef`Hf5-zWv=?mfNn#_ASwWUEZsosXUBKK9ay* z@}bO*shjU{5*u-Mu|_DxF3mY**b9#5H3wTjvz9uRWh}Z>WsLJgE1$(O9_8R;aSR>e z$?E0gx;Y6O0QfHoPPFL%Sa5D1jn&_)FsbVln9D!E>1|=!5)QnGrJlkyoN?)%FY}ig zfB>lYm%f*+l~G){5=#uVMej zx#AADe#3*3Y{OPk7H)QW&1k+q#GI10stlnM{j_)FE)^>L!uCm5ox00fJesS?bfc-9 z8HzXP5v!nvp612jy%Mp_5)tCuA&G!eFFW>4rJrWie22#uT!2z4gsZ;u!hqbxLIr{r zOv>cz*gLqM53SqFZpf8xQd7-dZ7T^|8d+PzITxxo62+2SG`(X-R|f3?eRm=7fZof} zUntPG(>*R``tImCg+MxKHUb7~25|o_RvR37aVLoZ2q}t6TSP>YL2PGvyT5vdO}sga zE5srmCn)Q)(NV@un{A6KF(>fRi|+onTs03 z1H${8&6rwb? z8t&=2Y2}hFb-`5b>l8r*spQ45Sb6WDJnv_&uwTdru3*@|_L|@H|2eNYR`>_6IlLOH z#Hzw1fdKr4vLWeCd=kj}!tJ4%>w@{zJ68!X4J^1%*T8HdGVKG)Wf<4Xa=`)KLw-H( zK5Fq?S-@Ca)kWf^v;s)9#Z`<)!fNWdN`$C=^&wZB0mJ9V$KhDrmQ7&@-Qu4CQiM1= zH!cDK=09l;3poM;g6zdMTS5pi6bL{R2@M2Ia5-z4*uXxFO49KYL&yBQ!m~Qv*MD#v zgRH+h4qN(%0@6~$EzI%UwPjjh~w0#HRj~{k^dhYM?>f$ z@V0`Gn}m?x2=pOZZjE{+X(ez5@+oFK=%xc&LC2$?=?k-!8!@1b?c!-EgWJEIKNJxX zcoifG{H%w6Ksx_t#qlUWf`$?j0TD$42Z$nj_M`vtyMJ5<{L;ZQ&R03K2;)AmwHq8? z+10*kUuBgI`oJpdx9$Z0l2hQH?qW^J^}A(7R9Jtl7a_Uf^;F`MFr8 ze`M8WnT=`Kggbhgr=d4$F6fOj_^Wsu5v|vu%sBgGPV<2h7O(`3{REZ?K+;BM|1_+? zagf^=L_6ph4C5;T#+3zTSDzb|C}ExmvSQMazYv!hx<48ip>qbt-VvWC-;IKt*#W0Y z-RFFA2*Rd$-l2?+L#zUpWhragtc6~uYiZSSiK-4Uw%BuNBX3R z6BWoSez-Z?9+@7ELmD9ePq-)M^M8$d)aQ{TgaLlrqzjYWdq8IqQ@;JtM?%`cZ3CB( zR(~c*!bxV{?x}`NAL9#qeFWg2UTOzZNyQZy-*vCNKf6ogJ~(z%21~&C#r%`7fc0B@ zLC`Oh9d<~aHD2MvQhM9w%?_EcQa zA;?!lp9b;GW_h`=Sg&#DZYcH8pvg74IDe)1*4@doOOlZLP53)HKwL$s#e)KB!Z{{> zU~FT5dzV86IXhblL|IWbEaR+xn56gzJiyYO_u(_@r#K3QyUpa1uav?P6P8&uFEWye znR1^@s7*!819q-Z@ijHJlIS@yXkNdiK3F+8z#(@u7ao1VEN!G4Z?gar&KY-2E#tKz z7%Ctp&7P%ugyrP+(@0X*_x|OJ6{n+%{ZLrB?~?-37NH$I;`Wcas%Cf7B$x!Yc5N~v z*n62mAT)mf!K0Qi3;d727L%49ou!c3$H)Pj3Wfccao4a)x{x^#AO~If&dNC6ZoO&TyuTU z#L;;c`6%^#@IHsJK0ZYHz-n%NXP)`8njioUk;^N{*JEhCSATIePgz%`H7tb%C~W+d zpJ=qdUiU6xaI7S=aLQ+Am_IQrdT`_M-GXC?5t7bzg=KwXr}D!K-tKY`dPnPcrAIx> zmTUvKQO9Gj58LeRf{lQC5te{CIOsG6%Z4J{s0TrPV_^c`2x4dm6Q{QU5fhfsWNYea z#7K@GCH=LurJ@EW4BH+pbQ?5rl);ZEfKzWdLwpr*Cp%ECQUy?q9Y#~Mu2?s;UAlIo zH&Tbrply%(RJ5hq(w}uTb4W}oPAM)g#g~8JxYio1;NEva`0&tZS+rCWb!;|7jIGQD zAZGS**`y=w?R+#|$o@gJt&0haRC6{3+;E!>N)j;tet5tCkwOa~YIE0i(!c*B2j8d4F*lP|^$z!~S z_%ZTn9bI+@)!3+?BtU_;rRBbr^4h2}J(YCzn%V~|;%=B&f&=vWQ{)_7UsZf_9xXzK z-_7witxQzftK1macjdrF4HH zG^e}qIb>6k!hy)%?OVHFb$FGfl*y)M91YLOtM0-Dau#Ub2y>$^360l6&<-FA` zp+KVN8#$9H5OAj{>jB|Ew)EVW6O^wzJjMFnEK@Fvbxw&|>nxQ5(gV-Z-OiURYe?S& zdIl@`f9BafBeXHo|4Sg!&ii*D8d{&MATzAE`qqQDMNieP>;7Z7=$52j{(C(7_eYr{ zls!iuT{G_1yD|S+F4|)>*|*jEMm9-in|O} zk?EiRN*?TV8HkEfGVZ24s+|^&R_E!q;-aB${M7LT0NXe-k?{)9+C65H#Gdp<|3*Q; zqI4en6%N!JN*|pkzJ}a4xF{XOMK02rjlQW__p|}-rK^r3#N$c_cb@m zyIeisAgVrG=Zhw+48?(7W#HE+k7SB#TRs#6uxJ*DHYW5J8iMXkBU5g_7cv~18KhVk zj)@UIbF0$wyXGY5PSeAVsV60^1YyWJb2Y06LIFBUWt$poPRL1aSo>uUYQC1XW7RqW zH>5KO>id0uEUt;a>xi}_F1<^fa3dDD%6MIApQyEr{9ovaJuvCWv2 zijTK;{1P)=V8k{$t3MSp@E*E%?h6tiaB!(N@@8Y5MQ}BkHzo_H!31UVd^wy<&ky%l zU1xK&k?+YT)ozcWWz(PI=(5HD5u@d7lbE*cE7eEQri*q$6{KF8FfVEkZE6n+Q!Wcs1Sy1Ru0{6>>xS;@Hu*jOT8_5nwAoL2q%N zY$G+#H;gZ)PMmX-x@{d;0uBqXw*X7Fj*BD_4Nh}1yYan(d?9x=Nbl9+f`jB#Xxz%WP{KseuYx9633=5O;C>jhDOhE6gwMZ?Q5znoRBNyH z$pyFxmLd=WB<+9J`OL-l7tRE(rDKSaeL6~UD_67$;TzR3?lGkqF#~5*J$sP5nUg+M zqmFqPzvIyC1P~@f6yIdbU4fNxPP{igq=NobF2C^@HP}%=u`wv>%vU|wXGOF&60mTx z*5PYvxvAG?6`8}ZtXFYu8s^#briCTs%#k-Xj?Xwd^i{J%!+w+DtASEjS)l89_&t(@ z2gmxzu2Bmt7_2v^tJEM&IBuOfu*8NX&7><<;M}*TV zPB=M!h)Tc>V|V87wl$|f0w-%@_YFH7T(Es6a;m$e4x+9arBrtwFltyO=-NU?9uSOjE{O-KVvX)A@DVu+6Bk9vtvHh8;fY7S?Wp$dp(bULE8BgwSI0|} zDWRe(1SKq@y>iK%bo5y%hILa0=rYZ$Ag2Kv88CI zy=#2B>tg9Ny|eV6N{9#xHgCz?E&h9Ef{^%=nMVI5GX?4WA7G}!|2#9<6#ku=`16VO z+TKo|GH-`rjsiFM%FJ6GI_5{}()d`MBMGpGBVgaLZo>vlKnYwbMjt~SDAPA2GvDj< zE>6rrI3+y~m1!y3@U_VqCZ=}46g#mlWz*NLcfq;mK^i1G9}ru@ zi2iw`26y@wf0gt=v;ryFe7#pt0dQ^ z&?AznCz21VJPFLQW4e&< zN(G$6rqdZx;KRly!;3l*mK76+3!xT-hf=~30P3>LeWqc-0HYPVi?%ObN(T^Wsm0oZ zRGY@+?!rR_@v(B07ltLXgI`ONiue&|jF?Q}04YD1zza=40YF^E@m5Rv0y_B!WXX95 zrd-Q?%J}u>jA=e|!QFxjIIX_hlpUOJy}qzp1Bstyt{+xk^@_e6!0Fd+lxmxtm+9l_ z+MFS)Z5)a91GlmoVFiDDp(|)j1Fnm~dKYV-uN47ytWKiYtra;{3V|E*IKzm(Ef+E? z)O`2XH#YUnEig}E&Yqhdf<(CMasNzG{~TtTOc>Gw^+WM?bdDFQH~<>o2Q*x7(*WYs@eKGr-M`b70XE-v4QcXl2)qoE{JViN2ZUic|5L9W*urgL znKoj}#-z;)Nw_^xWi?VC=rXYd%Jby|Ov5yxF;!F1^l2SVU9Ooo9U_@d2#;>cHDLjn zjTRJKW$$5-il*5TXB`Qi#J%YgSpNL)*XkB4AhEIapF&ks)xSJmF|c}N)oDXPg8+<` z6pAik!;|5UCg`~MJJ9#B?%lHvYSiWrhPk-of>lUwPd(ed?zz(ouNe}mY|~Qy*Ry%J0_cKL z6;7NEMmJO(_9|YFfTYKGD+nz#J&d~{tKVhzHz!vSP`2=~Pw^qdfYXX6Z1ikS8x|8O zbP>&)B*Du)B{DoE(ndNnZB&w`)UVMnT%IpqDBu?oa})CxY_~t>67Rj4$j>V5mb#Ld zYd)^2e}$`hnrS;>KojnbK}2v5S^fq;oys8W`#bKh3jT;Un85Ycg(TKXKUMN6JWckr%`{{*-k+AzM~f};w8+VSIuvJuu7rX8A?5N|r!eHQUvYq#of zn9j!QpRVjx7}!;hx0TM`+- zR~ON2HYaiy5L#mXg&Ddt-S*ysI_#7YC(PSxeN9%vJ)i#nyvnC$}0r{ z&(%Lu?e-2KVLN=mIM>;yjZ7M?7M|=E-u2O80XTdIY@W=%e-AA|Bt%knHxi0LA_14< z|6R!>j`Oy_-+#0re3|FK)+g{hjDWO1)yNrblxdOP16rS@M+@lHqW?e#H3B{;nZC=QRuMJ!TrIw@^Zc6j*I*CWv=eaD z2C>~oh9Nw)WM-B;9z6*)E(4pq6C^*LjBA#gll$oia*Z>2;+lqJR5tIDbu-Hw;yG$< z3@-!gP)>tx3**A?Gfucd9q`sU z7^{Jzy9^mOlDMpBod_WOBzZr(i?D8OGe{3!TRB32TYv|?VHUe+FD-u_&yHeP@%_YU z>H3QpiN9(r+an6tW&hU3PcXxb=IGYv>E2s|_XvG0M4QM&SEbxY~IRq4r@ z|AG8p0k5t3KiyZ^Cm;-BWJF;ZMPSUwT0qeBQz&Nt8 zcCaQ;acm_aIQY=jF+=^5zBtS`lmPOVJMBWlo43+hq_OUPr3@yUjXT;h{m4I{uQ;c^ zp(%#*VJpxEAbCB=)*W>b4BqQ08VSLjEkMjVKQ5O_kOC6?`oz-JV0llPJbaRALaAqI zy}_IE+s2ihAN#`|P>X8geyt|pdHe5GP54drXmL5G`#RA}`kT-)eTXS|xpR(MdOM-1 zFj!IjjBegb#Fr{?)q4YSI(`NwW{&IWWUVO&Iw(27h40RogoS78dNb&RJ-=Ve^L=vaeMwL{rHbw zfd5RfzCEM(wW9ySkv0Jk{D7q?Q-Pk($>GcN0C^{uZS?4JD{I5evj3Ngqz{76b#&rg zU{3b0<0-nv89vkp03jd`7O^`4q2d0KS^ewy5LnSWelZP)`?t&f`ajrJ?!~{es}K00 zM#70HRmID_Rt)&m+uJGgfF-$wORhbmY*QtMKs)zgB41;Eo1@!*e$!f9^Z2rE*f&sdJI)0QK?|9blg;%iWlB?t zc(pW*`9arK@#GKye!*UY!|BJyPzdR@ZLBee`Cabu*2CoNQ zWv#}aGeHW4%@BLil_0ZC-OgtF%Ba2QY^M=DBxSRZ34Xtf1)HbKR_qTa{lpW~_wklz zUa+p^o9DZpp!OnDyE#!9QaTBA*H7>DjZ%?M{E3H8MTHbf;ETvuib(HpKP-LdI`794 z)?B?C>W9VL!+_^#{&8?)=-z(c+w~kq^Yll(yn2kU9s(8PdvnkR)pwx$kGwn-S_0w# z&l)>;BPY~cFkgmfJqPw8!&zwlmJv~@uYT#A2^X@Yy%<8&b$>kyQY8Fcg@Pnwh(9rr zqEmvio>sLp@PO2i7!FiEk|Po|wd<;`!YtJgJ~CB@1gbs1 z(8)^)@a#d9hLp#t=k`vW62mjM!&_$$5#o_H++ICGG&HX_(7^b>Y^mFh^IuWKJ8D=g zZ+m{2i~Y@P2`LMIJ&luCMZGM3K@!<1MTxqk8f9+$db+6{Q-ASnrGH!Jw%sm4#0fD4 zS4zG~Ab*TfSLlMJUr_Xwjiwy=Yf6+p-y#a@KJCr33-1H`#$s9reO@8Ke)e8QQ|p zFfRj6UC*ddkzA9p{uhjh`%h1Z(anjg9a>tz*M2K127N%zPFR{|T&nxx^Y_paIToGT zm%hkUUK*^-$;(8U4YEPJrY*}^7w_oa_Xn1~Zqn}&)+N@_DxN)w9zSVC)d$2a`RA6t zxy^Wr`%N}%igvtD z*JVN}F-qb5Z4oj)E>)PBtL-FA-=zBiB5dP|qy6>}LcBN0Qj;vJdgFMhp86}lq++Vz z$oafGBE1&xW#Ar7Zf*bKG!e_1+2Z3*FC3kKPgKxwX2XMb8I@djjFMF@_F#LatE|J#)1HOIRJj0P=6n;H5U`ZtVo^0dw9ZBQ(chTL(CNE{uW83*>5HE?$h=eD2)9G8bd0-05v& zHP~%_iKFhPJ&fgKPRG%jwCm?P(7{E)mZ5X{P~GyTMPKy_7M+hhm&+0AdA~hAt2jun zM;@*^r}5NvJ{KN#62vPHOez%g+nxFFk~#OHjo4#&*k!VAjve(|2%R#vp$N8DZM!hX z`li|nvbE$wBKb294kUk@knU#SU+|QsH>$$43|j$cyK;JfTaVw3x0Yce)Emfxdv%{&Yj;^7V-wY8vw?27^a}AmtO~d z{?}mZH~;?xwxaU>ufSF+-Tyh*>Y(ZG)QPz1>$96PI6b+(1}c`yHxmnC_WM#w2nR4S zT>fibe^7jxUwCRYS>J5?QIthRQ-=nYkjCNtIoD$;WIA!!Mwv*-GeclqrEb$UB(UjB zf{w|Mr~LVIWWvdzs|=h}rJ0$&$lVkRQ8C}_`m~3vq8}1arfLwAm3l}G3Oec~EPQ z^4(8xR}P$cZ)G3SpNAJi3*z*D*}nd~oe_b6r1Ov;Pl+uiK286F6}iBC zTI1??DW}ECcHhc^*I&a|>duxMu104)QA#Up(rhV~qcQ=190@E+6%Cb8*>12w8;ggL zEg5qDby^CNc~mw}3meCC@>R9eAOmj%&6mhMdGHn|0h4hQaO8ITsx3PIR&RLxgvaW` ztfLGA6vNX`f9#?A63nXU%;Q+>sz)Kuc2Eo@2=B!l@&PlYRYW9_@^vkhS1%512jo6ygCe=C{YuK(&x&?sTn ztQz{zTpW%+)+@nhYV3jTQ)8rD+@k72Xk~@}(2#unIh-z?CkxhQ zup;`g3s`(&Mgw{Kybr4|4~VH>pLMu!9VLg7C8MwpjmIGeBVfsVHFey?O`Vsvyk&5s z`5mJBC>Afr*Vx=^f2IY`wHsHVUX*^d_gjRpv{a=ny{M5xyffLohGtiCSwSKSti0h! z(4~LU6K;SdXM8KTG2{^-uP#5DEZF`@hGHVHJY3#IC*0BwbOx%^ycJHR~xtjt#e|YyaE{n2I4Bk!o zdDH!>UkvJV+KIq)Vbcw=+Bf!CC#78%yO#lW;JdkufisS^xJ z0MVv(8!?7X`0L|-Oi6DAZF>7341Ya>TQOR;KNsL0w+SPf)be+QMB4)=Gt!o>iJv3M zly|u1fIzi8$$+#$b48L(gmO{j*@8he);G~|s%fyFZX-daDwYNA-AVYO2#(%)_W6S@ zdxmBCkWhJ1VkvcE&7m%SHo5j{Ide~sRZLjTEr^%({l#{ zw}4#|ue{x`5EM)I&ZQJVTJYS7qldqr^w&aUMC803f@z~ZaF_xzF1l)14#*oUP+yzh zl<{k*i6uhjH5+n7Lh$6=cLwC9sW$o%jvJ6^2kT;1j1vMJ^{L@XefiT@8(Sbcsm86p^m;IsIAyIBHL{7X@ttZ zPQEk*((b=V+arw~c0Wz!-$s!=x>_~;+*EQ2Vk}%uI0srYVBu-CkB}C%%(Fy^3li~S zMVTe%+|R=ezIzuxEGXp9)xKD@-8AmMU!spMe|fzngwAL&ip~{NmE_H?zSGHt3bKF$BH+>S zNo0nBc4x7Gw`1#ujJuC&uit8Na8fPvZD}RNpf2y%&ekap+3M+G&e8$#3!Ag>&Tn{< zx@&3#bAFx1V7!SEdV0v1#o5JA3+eE(O1OK7UXQtiSH7GM%_7+}hc}u$brfM#JN+^0 zSQ3lEO+N*{SJh*7>u14*Eb1BY2=6G;2w3*ia)0~7AyN1H8zr_(`gA_=1y$`&RZ?*j z5wfUn-+d8m@F$c7!MQ0kb~%9@;`mv_1W zD&{`1IIWEJf=7_9(`Y%c1av<2Ae3HOH4vEBi{BaBKhkx%^R<=) z&-5V!S4nggeoV#Sro*lj34Id5UT&80c73X!S##LRaHFSmQnJcMJnLCot1Hl&s6?4l zyV$tNY$Ic8BK)FMRwAS(Jx9{yr(p1z9Tb_9Q?l04YHZt#iq5(>aNxVqSJG~{-1CJ> z|6Ff$;K<5i-VzgW5XJWl(23BvI~%XGAp(5A)s9h0(S&Rli(YtDMAQ3iSTkhAFl>No z0#)VVxUJdzUb=rUdNv4`mEEq}m#n;{hFzG+yw@=S+kPD{f?&b~BIZLboFk)9tGlW; zkPd}Z!a3h-NVxyy|ADKar>}}<)oz3OAfq0KQKfxtKC`1IHqa*m{*WivxliC$$$4kV z3m&sHiPbiQayHDMw%W@E!Fg4R{m^_?qiQh;=HMZUq6(QBV33feEJD&{l$L4A)Arse z=y)9q=IBxVWmY7srV~lhs3mtdiC^1mJ^E0w(2w4SLBcfU80#Qo)0KPdT5;w5$IC2y z*cAKjxMW644Z`HaO$Y{Oan5s$*6e2^`6GrabvdqL``)Fgda`W` zd867GovxdWHrZcRa1Ok+b9lQZWyVz^tXts^dSIe&ut`79%|vJnAWs|ty}9OND;1JgH~zxAE#H6&NT|`5PRYk zXbh1zh=I44J3_X8vkH*-Q*v+-{wV53-q75iKlD2-A%TaB9z&H+KnIq$Nx)oQ#u$17 zbEZsN9+`mJA|ZEmDOJ-B(mpf?W(EqHukj+xc?(8?=j(uwC`&O2Cnw4FUNQ`0lnm$g zOA6#^HqZI2fBdO3$ibY{nwK{A#y2|Wby?xzQR}_+Fp$2vXYU%#V2(WFE-ce+>7yr- z_>f`nQ0-=~<AMP^g<4Gp&o>PgJMoIdUEDTE=#98+0?v%47%`YT%Kmuu>KI zML){-Mb7<~7~x?_gnHw;tZX*aV@;6bOP2I*N&}spDGg|X4*aYqarHVoSfc3nJ z=0fuT0wCXtgu_{f;~=U*e_K5r#Z!GfIV0#VbRhXq$c4#Gg%ZI-=tP@j$^ zO!JI&QJQ(-d|X1I3|GfwFy@~62Jm@E9j4WXBYTLv=i=%4EOnNokQnUP-`|?B~ zEWQtj>0)|X1D3uZ9L54C$cU9*7G}M~$D7^*v{l`InH*3C@QJryvhvS+I5-CiJwVXh zZr3bdEQ;8l^+|+)?K1f*CmHc6o3j@+;Xs$s<4;Jp&KoX+n%F*CX0hLA0eUzHy1aC?)#YwzN(xEwQlEQ5)y%!#jL69TCmv`N_ za#0^t|CjB#DpteOjE1pIn+aJ0e)&wS(+}1>Qp0F;Hpt(|1pD7d)XL1k6TMDF^n#`GmG z;0tD3PkLv$GSZc{>*J%~ujB$Xz~@grSf=tPiEztjfa+mSIv&YsxAf1&Lr`3+$x9}Iet<}mp|A;*uE13bsPx6j;toZATdgnn zGOL-b0SC4#VX(!eGH)$y_lpuSU~4aP&DG7YFU_alc}yt4-}9OY8WTU{gyf0AH&JzxH^UVfxC5Km!bT7>x3M^FJvWX+=?AlVM*c6IIITzm76-I9fV# z!i0e>%vzU#QjOsS2sfCSk$c`4(vDXrBL1b{ptEs~ID2W=zdAB}ZqF8oGM5k+7w5#6 zzPpGt(SY1A6X?m2!TP}l(KRSkd+7Q{y#41Kn}Fj?_gaoZ9>e8oawE;Z4a)M*pkLBj zrV9cm>?7w)0c#@}-;EnA5lr0Eh`}cdK3kv06(WH;BHw`jIQIAkDs3I8gA^E1-^2C4 zaqLP8{`+y0{mGiMdOI6sZz?HZj}N+V_49W&HK6a!M+4CZ9VHH_<$dciGI6xurC^LG zF){HmVt|mANc@+ocy+|>O`R$MyN|!hdO55hhj^7LCb32rDs@nmZ(2`u4(2@2eV z3su<5MT!gu#uz7WcTH!d7fk!_reDri#S~cZc-+HcS2{fwC23(=hV9%CoHC_l#eXry zmF`?}J7llLQ;X0K%ezNtoEdP*s->MHcQ#ah=sD!EuKdOzy1*q<6m+tP`@q!vl!f?V z2sK^=V$*W-A?|NgwG+LNi%Sy&L=>#VNSJ~36T0C&>JdjYU-RN!8OKxQev-(gP=g~p z5Lq{^6T|x-SB zS49+9HC)@+X*_E6X(mhAE!>@?;C`=cE-Mm7me-On_>A#$g_4?TMf7Nx$#8f1UH@SOTY^^fuGK#M;Ft|* zxdg{(l!s7Mbdf1e9UMAFsLm~zNWuXJVN0J7@L7b|QG6b67w6TOi8M6vp3?4e(jTL6 zM8t$a7+n!pZ+5xECy(Wgh*XD+f4|I}twDxO)neL`QqnWhU2z@}w%B=2URi$+=7WZd zLINK|F0r(2kdr2T-fHskl=!A3XO(Se-r2=MdB&ntr{pzA6P9AFp|%JtGx2Y-_Mq8= zcwN}u-FA5IA>?+;a-Eo4SY%>xzG;` z6K%~R$7@ljd-0vEJ0Hc~j+VdAvJ)AzPg=kI5cH599`fwH5j18a!8GdcoN}?^YyTvU_>{os8o+wBrJ+$olo&C*4=)-|Ow)ve+=| zHvGjREsCw2e(Urk1axCg5GA{f+bwHr$=4!xrE5*=P@f5T2`~bLnM_3$>jn+E%xHC%y+q-S&i_VN2 za*fk3a~}tMF8kFsy*NzEG3WF$GzUH~T_=omvJOn4IQohX7!_yfLff zKSo@p^3AdXjjitF=fDdug|kbrT7J$wotl6fH8lm1$jI8pFIgze-Y0w8ck)iCo~3$z+#`ZL&K5w1vuXnijbr&a#vSI3 z@o#$_W`K;7o`j}T^TvRpu$Gv%{%!a9^|>Rzv^gW z1i0FHX{mpnPHIa_q$&siwA?qzSm7?p5ia?UP)WAcF793hN>2+sr1))&vB<7|mBpEt zLi14@cBwW^Jd9N2t@-959Iv&f`9fhy2LSLHbsvEq_@v}9Y639kFR}3MoT~AQBn+{D zNe?ERuU{eZ=%4gYp(;5ej`N3%2Dqc*ak;#e8)ps$q*ycL{%ix7{lO74>lC=uN&s~Z zCN>^tf|uG5(&>cHAd-MNR;`N~vy+7Fw>uULQ$Sl>a6_%mrONK#<#2Xz@s%;s)tFG5 zxrNnsrCWIWo6LEz6hlZ;fA%-YWL*5?*c zqTz&qt;ocPG09vwH_gX))`o+zFevBIbZejfKvn=?OU<~=`(fv{6>E|-zqFEXxyABA zXOJeF^ZiV>OM2Qhxte>sI7lf=C*)L9mQA%AKxx+d{hPtlwP_x37jhaJ4xo%A zLc(HcLBUd5->JVQIp zKPPg^;nAdPwPmpi1-Ch#MblI_#LI47ejA(ZXaWGd-W061vQ_=mt6uAQ(mu#B#DY9{ zD1;=E2~`AlfnQRwmQg4Ye!8g9X&x{LybbeI`@*;TWA)!=^i^7l7T7O7^y_n;Y{`!$ zyT6Ld>n~$LQEc#e);VX3*lsX`$LAMa?pI`udfgY3is59MJ?wcYV%1lt!V8k`}(g zZdChzv44`_#o`b9XVQkicLZ3avY!w`!d7i14VG#-wDQZDw zUynYDkOesigcV2;-70CpUGeeoIQ<#NoWz8>2&|J)s^QicLG?7^)3H86y-h9MXaoz& zrFcJfzq6}o>`&=*w&L-7u0nDG@V>Wn7L=6MNSV&k^VIeDWP0gZJgiaez zc3v`}AaYJZ7a7z7fy(|j{I?2qrDAA6|GZSkQlayQrogPh)TH-Nq+&7&a5Lu+F2fD; z;JZ`DYlrD`nA+W<=H<0B4}H=5)set_4s@>)>)VZ(TzND;F8`ZJk(rT4s(bf~x> zf5xd499kHOY@XwyQgGUXA*5sP27DSb{!5?`l*>FV+x70C^cB$SMSMjE?Ahj2!vafre67_h;7i%4~i~5&X)^|V0!}2rW zDeiL>?xWz;5`1{RKqC<4E+8N-lLq{ReK&GPFhA4=qd|HX{ph+yp@d0KnNo4P>d!a5bNi6 z)3$0z4%3@^PIzDd`iej)%|jZ0k->?`03hwpcNxh>yzYp z4xb|Nz-HO9G*el;_Je%_l4>`+q|%{^ReuD^l&aQUPzRF~aX-7~+M$^X$-kf6({wBf z-fqBRyW+_cSn`x;T~}0(4NNeG?M2av;wrysM0MVYZ#FEwxImz6&5xp2B*e^X1#Q}d z!1AXmqAORpwyu|#_7>sGmRp`PYX&vkl+kqByFVCS?IbbXG%Nde;4l}*I`}Fksw5s^ zAOdW3dyT(}?J(k0flEFIkIVV)@%i3xD6I~!JH1Umrp1xxYiwmTAZihPD%mC{4VBmR zw34zW^`XRPMGUWk`??!L8PdA*_l^pmz3! z5i^O$I^c7H#bNBhuFnrZ+2BRZHP8CnJ>aZv~mx5`fau>&GW|6stDR zBxBAG>7XOOEzhQA$F)`60aDrqi+dM>F8oH`9jNTQ(z1%rW2ec4!YWYw3r=#g&4+Z! zi0rW`W8|`C3CdUi%1B*(OJy%`eovSYP*h>&=NX;efPH(vFurbpxc;5rMb46GfUwB@5;@=c;^bAR-IsC~}i`ppuQNTt)d$Y^&$H zI`e-8w|tn%1znP)1xJk-u=}@?2Vc=fky2mcyHjhIB`M0hl?^kRGgm_Bt8XK2$l>1x zaQL?qi_voruG12R9w5tNdzp`~6J zG&iVariG=FhG)%cgT`=+_XjX(>Y0fAFQU2>iz$n>99=vmgLrIW} zc=yoL5&i9qy#3^mq5?x~p7qcUN^FSZD0)7Dz*g7kh8tIA3c+?$NcK@vo=6Uw07hrb zv@heo%@D9lrH@*F2J$n;0VhM*c(K5kADNeo7bfNDNwH#%>{9<8Gt8aO$V1}CKccYL z$%rHQ!S!9^PnsIXnUlZ5NWL@{U3n^QzZ9@d8@fgGmVG_he3;z5W#G5_A3yGipExn-DMnU4W(*Ix{lC2;7u5BdGtsBUphE;(|UC3pq*Na8O|*MUsj1?vu>9au9t^d}0bzhah~O%m+#w2ka}hMDVxL`h zK;R8a8u1X#)-AN3>gDbT_B*Bp_KqJN1mb{+lJR zi6&b+q!J;kb&2t;U^*^!~nq{3LJ~4DR?S?Y~9<7YOB~?$U`)eMk^-V zljG=(Dl8F>G(|m+{Gwe|;s{Y{m7J^WKIi=gbXAQq#ChqXby9$?p_9LF6U!1aIJxtB zb)1|HE(~DgV?uv{)w?8K*5!lkXGK}&Y73VXY||1I<_Yx`n%D{^e1;$_7E0E-YqqNd zm2%`glItQ4gWrCmQzh;`HYvuCJD_9@l-Q;$N%{0ES`-)!S@iR7Fp{FPMt3G5?jvUr z^Pgvg&_YQEzHC9_!NN!SL2PB)&q{Xv8j#;kqE7kS?cBaK`=UtyL&8pH1d48ap88__ zcSF+)&gPASDzf8o*eT`(j7pb$Y<0q>j<~OX9?INTw{b`$Qa0>^-b5$+ zg<2F=Vx=ww{}EBi7SWW(2~LLA|Wdaf+LxX6|E#X z?pXAN_j-$ni-AQtU^>Qsfv8aRB?GSh5~sJ5g$v{$wcX4In(sfCC8aae5`K5_x_3j< zQ}op{OmLcsdEq3y8<6`-m(xEN{K}r77@wj&-SZU2L=G=)S{J{nxZ;oWZvDrzRl~Lk z)FZIQrZ1t`X4hXO5$=tT{RIpBNz|UX;IMAveRCCrD_q=)_@up3<%rB>b_)#P!BHIV;>R-U zs)bBMiy|1k13R>NE=%B|>W8hsyfGh9d(Iu@1`UXj~>(X||D4S1i%q%w{Vm zn0vhc#fl5wLI$iZFrB%#_R!RK5>k3>CTc0f=#331NB{si7A?eoS_^TcjRqNRMlIt6 z1nF!3DQ?W@uk4drSD@gnrSE(4h&aZrs_x1);$0@eO*Nx(3YVzGv7&~kB`AL$$;Nk# z?%eNm*FB1(`QTPPP%-K#E26i1cI0?ZD=gH(bv;#}Vmqv=#*%G)^>-d3jHXs)`kPk4 zFdn`K08FK1cVVc1oS9}5WM~6Rfm*n(xB8(8C>|@~Lm#MUE>4zHl~MvLgVx-Cl>IfU zAk46hs|x0Jf0GCJ|H^@ih5D_7fJkI#X5*wzW(cG74y1Z$c@$oIUP z+;{S3nJ%X`6W^@csiAi-=L?k}6?BR>*}TNZf*g@$7dRF-u-Ilmou@GJ;I@*_N_lfM zUw*7e<$VjdFO}o)VzLGecy7phtxyz66DdSg{g8aAw+J%5JD*>8(n{-SA_J&1STo?KOFNxEO zP|wys#7O}Kjh*u3wkvnCQm*lVJGS|gaX!ZCvsGy z_95x*RMLj=dFp9pPdk^}r3X61YclSgs_1;f6E@dd-|?NJRSWv)uD4s$im3j_MZNE# z8s!#CNwn@W&SITWFkaay!56_>019H~$Ij>imK%}O1qIx;~T-$95LY;7z z06)`lOR&YJR8OIIYHXl?IEM@KYBI2j0I%Wk4cvGNu(3m4wUocxXnS)w;{9dF%gws_ z)?#udm=W-gN#Wiz;;e7ni)%%q{KxxJ#wMfpVWe|;B1BW6X)J+L$D$OqJ{c-YEzk$EcyUS+$>Z;N!kQ zDL-OfZ?_s>V4h=z(4y)y^pJ(F@Dr&j%=9pH+`B(Uot|=2ytY4U%vx%_t@5;1B46pE zW4ucJwms`8=p;ylthzd2pizP1RwLl;KwScRxdI@4`x+U*x9HV%W#ep$r|twVTZz2h zx7~P`Q~l5gba*oZwn@FwwHmMUB2RM+01nND$fHhclHxxPVs=oO%rYmC?v^d1HXasL z`LO@FGtvZSg`^*K@y~F`Xkd)I{M(G-_CfT;DZa<64ix|i6PxL>0DrGhsb}EqHk_^G zrIkHkTm=YqwWKl@K)Jn!*pomB8VRttkE4ajWo^<}^dqde%}jD+&FRNg$}~*4H_NA9 zF}!Yox5kRjuT6YRlyF8FzcS;f+0dorG)kiQ=JPgf@^bJYW7nACAyUVxvN3jUDr~R# zZ{TfgV8oC6{?7AI2tpnDQWu7^nb0j|QzAA}upif5`tjVSJ?jTdm%+g1YW3KM?&v<$ zju}Wc3mS&Yz)&jx>)zf9rpTldciKILRMlxKnl% zbjtpVLQ)hEM)5r>8y}6)d`E<81LciPAP}JlN=y-95YWAp-{cv~pGxQ`fJG(w{reCf_J)|J zdQtn9-FtKO^T*#P@8vBn!?Nht!JKMH&7mPGUf{pRO32{YsecXs)KI4$!)P)aI3@$Q zx}G|7CBRk$dlkyaXF4#lnIs&IzTEGhkDQYn`+3M1pHiBfh{k{AoMcf1FCuB|voe+& z=(a{@7sTJ8{(ZP4W;$^q@M-_+c#6K>_Y3g097y~R$P`fUn>e_EjEw9v&9U}+ zFZ2Hcc9IBwiC0Qgw$&F#(MvT+r zq>vz^O29AyziF{Fa!if9nzgRjquy8p9xrEV&}}t#N$vU{aPo9H_;P@vV&!>)sbaZA z8_Y)^@N@G!227MvEJpd`OM~}PyPYU{INICAT9NCsjF3}l z(6ZfRaO|{W1exlH{~_$xX!$~MSwSC*A1d|{=2zMM;O|%RhuZm26#EK>MT&KWeZ}2} z$zW=bJ1c8LeT}N0ycA8lzF`jYSwhuc=Di)N-OKSbdnQ%9K`!Q0FOC(pZ)1vDU3LEb z9XF?t{V%{&a66*5Xl0RZRsIM9W}=4+D4dwD#g`hf^S_N+iLTKrS4JIZEzE# zo~#32`GIo{9c-L`GSGdN9v$s#iNSv5JiTn>9I^di@+JaYzglO}>4c(Z5M(qYE$hX) zNMMXpkLa5zmP*ExNkf4;r7j}7S}GO~up33s^JkaW$G}E4EDkRSpI+Oyk+l?&&}goE z>9j-eJ1_rGK5pMxie(Yu{iyIv3Aw{CV0tdx?XH-?eFli zX&VKgRt6?4FAY8GxM6Nr0SOtv-l*xI4i_z_MA>RTH=iE@H2mS*82*B!8Wbv*X47db zZ5lIMvr7gd=LU=f=eaejp#Zk7+P}n5V0nw z1NHne-d)P}xuW#4&uafnG_T1n@5$IMZQO1+)q9_7cOJ?>S3GPfkm8o6d#WTelIISJ z3X>#giHg7qqUvK{q8gTh|9PMAtd$WD9PA0I(NX$*+i+YTHKmleVH2iGXkHo~U)G1I znb9x)sd}80R^!2Q3!Shz4|+{jQ66h%hxuxwp8yhYge-AZ^sA;$!v_-IKj}g5Ms~;= z4d*tjie>Rm0cA*3B!ql*9_d-i&XIZA@fkft@o#nmQ0dhG08~(e?b=>=e$eSm++SB8aY2E#KmC`MY^ig4jjP*VRKkU% z({`#GwHC%WUpdd>0fm%16#4LE4apV;L=GX!VACcUXQLq`>(SC`j)r%JLUvdJBpvrP zipI!OAj+A*J_h;5@~Q2kpb-yp4)?9oAUyuz+N7qf%p-{i=)$-&s4{RHQZt1l+Y=wYvV$YR>IQif=Y!%>xPGO!<=|KgI4AEB3}yCm)p z?F(ty3$8$EI$WtX)&dsSGM%!Z{~w&9HpgqlM9`n>L#Zc!`^@oT?t?QYHW zY?5SJJH{{Tsd8QRKK`W?!lo2KX{WMk9X)M@QlR}aas7CbdwCkCp$nfUk_Zl{+Cc2uH?{~#xJ`Atq*t7zhv z^|hljvVx;_r)&M@pjF%U8oY#joX5W0Y=3;c=)WB*E})fg!u@Xiq>Zyiwjjk%^3I*y`Ur5*LQ$)S3gc9(<2$oKM@(Xoj9ziUe#%S8QLT2p_D`vmL`5;m@=ra493#QwzKiBd#}Ph zG?7q)5E*v}BmVP>uR?sn16q#0NT!KmV^bD3PKXSu)A>64{r&56-QH*+76wbERUJ%2 zSVIx~v;~8V<(8b(87y;0Tf8>;T;4*04uYeNWqPZvwfeEbr64QA5owx)0GWgemWX}B z=`)kap-#_D0Mu_;S1001bB=X&XsDcGr0icI`-8yHtSAKGMQVUN3t~NGIk!=u2`5S{ z8MI}(^nXi)VwzE9M8ArgfQx|qC-RUto)jtON*FM*uL4pBFM?<(rN_Qy0-Ye)wb})% zfix&*6IB7?P8r31Ko0NIm2i0BsV=kN^nPG1R*EJ)WBr|5H{`X%S6LwZisKrAuHNcr z2WU22BRdosDMcadG8MxJkR_=5eTP5WBcasw=SM>>z1jcKf>&4&6RDc|W7 zcrNTqG&)=B8h89^4!mt11AF0p8oLB1Ip;Y18I_Nm|O3x@)wY+wz;Jgu=)pd|K z5fQlL={K4eKJoA3X`oqDFSpUHxis4`);4lSJ0w|v(fwjilUnt2T2QafOv$i%|4-rH z)`wIid}|ElY%vr6JSO6;m2RZ=jSELj>vN}I!;bUm<=;J9rvK3kPzbe0mZtba`P>xZ z1vsy>bbMc0BGpvj_vSwk>QFEVibn?U?L=GC$> zMSSp6rQO>3mtm5}`(U6=>EDsuRxf7`pXUZ>2LQV)b5!nsje`)y|0f(Irtp7-gN(xe zk8qGmpj4)C4yvt8(SHwu+B;lC(AYEteLvmDDIk_Ohy!StekJNHH?4>PZ#wJ-67ty0 z{o4m>3lWgtRj2^s5u-|}uS4BlN8N`^v>7^CnM#|jNwAUo%N)%SUsZ_X3d&S-lZUk@ z3!hnHgEwl(LvjsTCXC@h(+im4R^DdzgaN4j|AQ%+DHmyfhQmcNS{_%FbkaDrKgb6V zu~rO@iA=;f`oy3D*bP&!trc7LKN}?!4hkQh8gn&!1Ic0gxw|wtCau9W6Mj2Q-}}2% zE(&DDmbi!1Qsd($>F^r!mO(TM6dzsof)VF1;q5~9##~O&N+hgp#Y9u`xNfm_-wJ9% zXUkjIW&Kp!gMcUjY=W4U+=;3O4Q*}B&j^y{-{I3RD&9%E3_LT9boacvT~IEdzrr-+ ze?UpwYX@ zIm(7A5u#!6}CI3Y)i3?I?eb_RiMfaOlOxbRt0tXG!a(?eE;n9Kw;Y^w(4IFnnm@!Wh5 ztD+aSXlQ@THzn~F67^ffPsEulbTTxns*S>NJ^Yf~o4nU(Q zd8H6U=B>cvwc8{qm<)001N84KlHhQ(1ktK$R_e~ydsmU#&V0&a?E54J4?9{CpHU{@zz;v~mX=8&cRtz?F9$Pxt``QHt8+05f%Iy!|cIvsim z846ld3HSb(VxdoKaWBBP%SIt~5{&2nhr6>3itAg~d;>v(2X`kp1PgA#3GPmC*Wm6D z+#$FGcXxLW?(Xhxv-3aq+?jLh%sq2!YNn=Ub${qjySjVtwb$D3?|q&p@=R2Tz?FkO zOG&{VovPz7wXi%|*E+^O1D5cW*L*J24on?BVznR($9Fr**s{NN4a496_nab92z_t7 zQ$v>x7$O$rC(RC25G3lOWb$cGJoM)=Ho|EIsq@AX0elk&STvxmgl!c$q)gcJ*=}HZ zLpfnon<=D|A@YGV0hj5H!jIXwI$l!wtzd}#J6G)ot#5nSJ73Wr!&$w%XynMhjBc?~ zMV~<`lLnbiZqcN8lFr7NP^#~0L`oOK)gidv^cqNS6~9!!tilCVhoid$&(z2(@noV~TvxBRV2ENM85W zFKu%KJODxEAsqPER3i@B$|;O-NwpHs${o^n-Rg+v9ooJABR#E`#>ADlQ&K|zT3R0n)Za>TD-?McFQS&Gj$c{n-GDQK7 z=U?U05bMamwNV167&t%rn-aGD=k#+XxI#t+odMOFakBY0UZk-gf;1Gm>c@}&gZjI~nhe`yDGo@v=LMSMxAXyyFurR7RKO34M4s%s&DkAr+i2@PFevF`{+Y3(CN% zNxjaF$e-mt+QJ~94VJ-x%s+feVSNAfe&J>j2?EbU|EI-+r?R%LV>U^FA}mY;H)C4u zUz)c6XLL!VA4qD%udnQ&_?~|w-Sgu&EoYC%e|IS*P!D~d1H)(#Dn$0iG|$Ht)3sNh z=4Jp9a}5kI077uCVh`R9jv*Wg~{Gexs6qa^!V#7 zu0wWD`+t4DrjR}y9(PY7-TfdEsu}#TKBog?;3JfJP)yVpxygzD8>%Ds6+3D1PMc@s z0mSoW8!lcRjvX!gL%wlHj(|e)-)`3?qYUU5tjZXne-#mZKA#V%V3x%nm8)B|jd-T6 zKP(&xyNg450x}G7!P6u6-?)5gHQpEsgqK^g5>k40!f;45eQ}hZawnv%zM3L^zHg7d zK{x8%n1zG3UGpawzZgPq|48@hU?8apycO-loA+8S94~C4 ziGChlx8xgqp2mosV%ncl$gM8}|2=&Z2+vYh_>`nJZDjTJoa$0hRcXH|eI_Pk%V-TI zLUjulYyS&^vvMX=*M$C0&oRO}1};-;5=ptG%nT^4+(;aJH2WuPq^vn~Ws`vimmZ-_+JYJJpANVtUO^c1sOM+aOR`0)3 z#~(di1Ry}_o4-Z9qTk^0 zy|8B^3AU`1bhG<*>5Y${TXjo$eu1>zlG*b?!qy5C7$+dI{R0k*l6uq9r%H8M!j zWePJ>rQt0P6+%PMyuO#lqAOe04`=C^P1~@s{i4Bg{{r8%42?L=Obbi5)A#FC*VF*A zBp&K`+N^oa9+XSIWggp!gCwW@v!T~|?RejdyTeH;p91>nGh9A0qi#-UilbEXvrycF z$2A9t0uTsfHKwD>km~pVeHO(>pj4t~z^c)1Dg%mhHT)vtCXVL!Tl<(`xAAMOIkp$! zFJ|IA!rjhgQ{4E<_S->5I%KPH*KLTrw-7@l%DuzbNGwpGbq^z^ud3jK9yu@4k-zm( zMM)G*1n*r!9#u2E4U4=u-&{l01ik}lrFR@HkE<=H*21Tn7Ffc)5(Z=>2ieb8+wjnM zZHKH(t{Jt)WzDelH~Xzu;_uFNtbS`?D=qCBA77*9Pt7$RNYF;U9c-B42D~)SL8a?t zc?0rLPDbOqg*s*!{J`f=d(1MHO>ph(P&#(+@}91RgMM;{=sBh7RX= zavpUA*l#GdX9s5e3=fSJaH3w%fYae&x43vBpMd{Nu~)GIC44rzBolNBp}gCzU%gTu znt+Z>L3{`_#y0YH+h=ZjYMYZ!xAT48V;fm>*}^wB1X-D?{|ZVwtCa^D!ww>_RuEW9 zZ+WU8_x5J?ER8rnRsh0IhHyxRj081R<d zgRE!6m-;x9XOT7q$kfLc1|eXIuJm5kL|70kqxGiSSE`Q=L1*LwodA*QKmGa$$73V3 z{Y8wj!1JKW=1TPL29fu*49z<*BrM5k67h10N>?AqeoUDLB9Xgxi>APwkExBm#Myuc zsyJUI#utI5(;xv6gU2z~upl4)dlCeRR;Is^_W}f~+1ho{Blmp6Gz622K1E~f+}6c{ z5J$C^(ypc6t$hn}Ps7O-LFN{9>5_WPkcgkT@1eeVu`ISdc*QQ$ebo6-DuwPu$Bat@ zcR4?GmxcuS4ZXz;dw<(=U)Pf&fB_cW`j~N}9^%$@2n!U7?PcA~^yWsFh!o6BF0}`p zat7)+)O1#W|HhMKy8GCoZHH;uK1F&xAN;32EaXX`Kyb9#7-DB0AtM<8NXne-_737d zn1f@iF(Q3HyzLE=Q{)#CCW$G7oqcA2^43lI5%a-2d+^7evFN*zWM{b$711}TxQ}=( zUhNrgpd&s$2~@0C=0D7&rn)*hDp(e85C3Aj|0y=_HJx8tKPD4OP*nhrk zlsyhsAQ@8627OU)?53&kY!CjCI2#; z*f0O%c>qs!e%eUa0fE?89}6u5->Q6!rXEx1csim0Z$A#wI|}hpQjmzesO2+$$LL5~COc3Be9ss5k^gQ8umxplr! zZ1IvB(P%d>f?t&JpJBd>$H}&|2G{x^L#WNo+1D{-nn>{th+(Q#T+Ye!b7{gW#uj>Dp76C-c^wX(R9l>2Hb4cm8ihCx zodLCvE4rh@M|*Tj7D*cH>{zHFkb}8$_F0W8XqS<9XU|{1L z6ohUsd9$T0dF%eZWMN8G(2$c?rayTtU-tdRb;PISTF&lhAQc@MFt?Q46iF8`qnv(n z`VFI%uSt4jK9kX?JXgkU>Zp6UiW~64tj&A1opCc$-tUVahgFosThTfVpiZKLaqY)| zRZ&of0!i!~-x9!*)M?qDd|yurO=WpCZcjK(+2LT!@#Yofd+L}Te zI>mFiq1-h6IkIxH>FF1*yBYg&85TzYXWRa`AxKwbKlf^k;*u9_=efF(;}7L?Jp7>+ zT0R&`OK#j?b9eAi`{B&&9+b4$K&q>)jGaF_&;69iv}}8K8|pP3neM?94q+E~^*oDY zC^(*g#PUiuVVfFi_8^?W9U*%bkdaF{KCOGQRzC>F&n_)} zpCXwGM@5{~ioD1l>@(Y^V*i=(ck{t*wxJ8{+ErMN*{9{9?wgLBQ`T;$o*!ciTj)@9 zDYz@u^x+efS((y;zW(@#MT3`*q)&P-n5|6ZP_}FL$~KquqqVL? z>hFbSKCNM|GZRsBH@igED`z2CQ_^pP$!@bEz@tw&m7af%nj*BWb??78iuFhs;YeJf z(&(l_Tyk4oD!VODJGyHr%)BAsHZu@(sKz})$s@Dhh52&{42TK6Bk9V{_LFpoc89RR z`&1HuZS()JZiq5CrQ|-)o)S4Q995FHHlr?k7>F10fw_f2Hh3iCr!((i~A)w@FIIldc)cU8Wz_|OI6~)t_ z#|(&lCVgIXtp_Q4vfYf15RCx0jeKR16=kFlN`#*pqWEx@+=%3N2 zy!}i!NdfC!oP0|-itxi+n2urt?)jRbD-o&;Re0X)K{~rqkJvg4kT+rVx9i8J406g4 z)h{83cW{WVT=Rf;O;xDEup0}$XDCQ6@wws#Oa;I1TF!u3pP+v*JdLkNNI@K1O8HxLzWFoB z{2!q|=*sC4WfKgxhX5-*2&S1RH&&ap`$z%tG;;RMVGED$fI73_r!=E~SbGk&kk&8W zr->K4-izJ9kThZ)!A1Je15__K5B1BPNx(EonoS)-Ls&y0z(gW3@AG*+`7H#F&Z>AB zimQ1kRWrun`r>D&t<{RjoYepe?cbs-TE1d2Mf4%N7IQcHA!E({JMTqVQ!kGJOIN$5 zN?0goGG6QjC0@(1tcKlTizsV6<8s$Bqc~7CDQo5Pi1nuF$Tgpr${(xHx|D zkz)R20Y{p2n(5msI|ahn>Yn}d%uDOj(?OfH%kAQk+IaP?>#Vlq{soNf1fwcOS|bXB3`x@ z?<&)#N3Z8cyEPv3@E4B_Oq*x6S}%jwBwcG&i4w0Uzs0`{?muy}B7paMh2q@D4sVieoKfHvQ5wh!DeX=NYka zfIpi=IXc*!brU>|7uvVI2Hn%ev}StI$s*?lvvqVeA!@jCHc7_7u8F7;j+5sZt*-?P zPV9}eH;-Haq=P63sV$T|K?qZW?~^RIaNmZHU7m|WPyFoq*$GpMg~34U@l&TK3stKY z8xr65Lb3gnHE(r(C&GIlNpN3n3Y_rtE;^Dth<9kG%$Sd=aFj24k#5jX*S1$E=xRWe z{%A`Xm`XM&qbZ4#@T2=k6UXB|VzTd?zdnt?Z5}oK@qUfFrE;#{LmIbanc&lCov5ZN zFTY3$O|Rf=>aN!}^_3kht2493xk7=T7b@0<17VuHnk^~0-WuXEg|Qh81`=M4pX>YG zf-|E}&8s_l^s;^g#5bNnV^rjn^NeqS#AJn+RtPpBbw-S^o74J#P%S?<6Vy2sI)bGu zs~bG{(D*vRhpn`81y2}h=`F#8mO^TfpI7_Hg>mi>-@2`Q zq0fScYxjrZj&5iHfea8Z0ZsoKyUtg$Pa)2#mZxQh=mMNo8j2`w%QjoWpC zy&)eFpOzoVT&TzUq!_Mh@b}PvPq`roqmlv}~)T1_3 zJo%E#^*0*6__et;^)o_YdaHj^bg+>ahQndbc=>*YfJ)Rhe||UjeKdS~RiqMR7;kJi zcUQLaMc+l)5wW%Ps?L&?>|kWkr2N+Ip{x6j<^i~|HA=*i;vEO!d7_UhGO3+02jEp& z&TP8rEViJn1Bvbi2l5*x^95|fRtaCShdDE@gx$T9rU{raxkBr~A_74j^uxhVQOk5G zd^xmqoYXRG!-FrF2-uXn;6o#x4qU)p7DeHTHGh1W!#1kxX1ScbtcSVWS-4oiYSj~E zIOaDF`)k+N080eVhi11kXYJ4tSHir#DgoQLnO|1DPJ+xhT-{WgG<7iMQ4Yo&^heQk z9zX5|-RV1;>&bBjJI(75n@^CTz4s(+qgZ#(Y^zHU(;Qi{>Kt+=m}=tJR9`}u^3VJ* z^TX2niH~lSa`?j=pyNskO8Ci%LEd(_ZA=S#%@Zb4*L}4V40vmaShcjY*N1~NGWx^* zJRB_{;Z?(z*oGj*w1*%~k=d2Crf2!jaQrdU)WUAT`0gq9Woms^d$#(p<(C<)OA)v_ z@UV8wDoOh1j%Ne7kd`&iyj^<5#A?qZ_t=?~?znZr$oyQT=5UlLwzuV&(xP)e`J87( zrtJh!?#y*DxvGQG92dvVSwLzFHp{*qL2N6{9jt0Lyju7CHhgOfpKtXUx;J(;>YZCI z_rg|?Uw?|q&(6j{_m!H+e--49|D*WX5mLN&nrgi*XHyuuS%JfHRkl(%DVWwS zHtM1Ck4Q<{^vCA0waYh5Y>N0A96fai(eS)FEgW-@jRZl)jT`O347iBDXXblP8t2Ek zk`?Qr-X6*Y&#mjMb0dT3dG=wdF-iz@I#z1X*X7!iS=q9;22X=t;yJx74eg=n1PU+> z<85SCPrdWux|c;SOgx0F@*jw3+TrNNN4I{La{OZ6neOz2V!n}fKG{6BwP$&dMt-hE z=j{os1>m{T5$_txdgRin;wL8`zDlq_6**_lY*9w2Mm3C=p4ZWzil7ivNwj0s$*+nPG`wE$o9xFZ+eYKEvr zB7ffmK&(dgVpH-V3Dc2YCko^Dv$wnNur#!z)(zuz9yXR+#OtBnJ_8Wz3QjcN4S-m4 zc4RmNG0Zl+ZA&FAJtNFjimG493UDWDf*OJ?5_&~=!jjTpzheBo7r=Mc&_kANYyM)(ker1X8>PNzRb-I;Sqw zp73esvcZDhTV95oN%0Egt(BmI*nU(b51OCP7O8aciHTl;ukEVfs@c_s%jVQ|JGV<8 zXPNWnrq_h!;C)klCLRw*!f=KiL;mQHQnhv58vl%HZo!jXtidzDPNFG<{!>Fu7NTg8 z$3WK6!Is#&B%+M-6Q5#*9Dil#vUi#UCxUHB=LdZk(^6t|Q!b3=R*?Q3^Qj=5!oEZH zrfacmP}CsV`u7GDc*yexZhoKaR+I#>)vdjxUQr{=lsu$YUFDL%>9ggG? zm-0n4@$F>Fe>v}64a+$QTqW!WrGHlCRA3x^(WciJLE!45IuVqV2J)*2V-Dv%w5QbO z@LM*8X@_?d_dF$}Q7dQbAQch(cojY6tm5xCbd`q)G=lhnok&Yl%a=h+j0-dQbS+00 z0*qs{XQN0Uzp4&1M4d~)UuioGAJG-p&}9@M%=EO%$r&9zXx|7sA6O-YzzweZBF~_? ziICJxSN9%!mzDiyNl0iTaP+Q7?jKl`PNY{L{72c(2=kk}hQy9tsXZ;9hc&Sb7{wa^ zk3B5OKOTFxkU4)m_7KGjB7ze@J2{k5lz_A9OLD9_xGQrYOr4?t+KuM{q)v)?salZ+C^4*me8D0yO&y$13cqzr)-S*?oA@NDB9H*;3<-=|1-bt|lR z(fofDOdrR|MOG?`g+fWLBv3X(sr)bzl|GbgO{K9HGB9kJIzm`Q+scb)X2AffoV5$p zrCCr`o1aotY^+4{(ea~@!%cc=dkv6SHC|@@j>Dlh!TRU1Zyd@#k6Bz3+Bn5f*`BvM zTkkD7dZDhMv?RSrGS&s$RJC2Qr`?sA3n(?)KhEqjN(q(q6M+>ss}Q;xclMvPDhf3g zjuSQiHo*u^MiasOtQ@Pf^}u8J;3LP2tw_|4*ZyT|Lru@Nj2zWkAEd43kDL~Ju|0+h zvu~;prS47-MvY}B64mIp`VZyw%hcOHnm2%iAHZ6#WgH^SHZ}mxYfo&j?uPh!wk8x z+bmmWY(Fii?sd^jtE2!XGzZF4`yC(pubFbb3L>!RiQh+43WfD`c(RHPVNf`;)98k1 zbw4{cy?$_`s-su68P_%}*;ZLW2bA+*A+LYA_4--PvOJ+5V0FupQlC}>_JO3la84$? zXj(J?)^70yKD@x8H*6dok3TN3fjz85VrZaT&=o$ZMfVEJtgkRA01uRTo!YV>!NtH@ zUgI;}{q6aYE~oH-f&k41UP%w?Bm)yV&B`_5K|J$-*+g8>KPw{2LenYQ@& z(r$%TLOD`vB2+#H7$e}Z_NYTZM+e5hdp-RirxxOs@=B{VjQebtdoFb%| zxRXQ}T^wlskehn^lx3aj_yl5{H;KI03qI>SFLh)hSX!BZGM!=iYpRdL99sM{aJYHS;}>Tjsj4!8tHM~T zBUj1JL`tHkki(6>Chgj-9pp8B2j~? zDL-%C)2VR1hPJ&>s?(-Lq$sZhEB%Wg_1gccvHWCV?JjaNuv^x;qVYlaU zEBq^VZ(oP46IFDo(hso4yFR>sH5u`G${tzHK9sUo`%VE-KCt|pd4n5wcecE}SKd<` z47bGmU1#dnlYO>BI-r<1@6TgIPN1s!I?<$TOczbtgUbAv#u3lQ=jvUteTQab|bzMPa!HBxKmn<(&Mwn$NfR!4r=jY(E3%crw1U3d(IA8mCm_y<9J#o z7W5FPk?C5=Czm%H0F?Yy-|+SK0v%HB%HttSO777-_jgCP)d@g*S3mhmhG)4fwJI*M z(`Z5MoNRq(`pyb-7%B*I!WfYSitIR-#cNHpi}KrTot^#T@$Y`iMiabX(fKZEXbWNnHI@DTd>$tbXdgfyNlz#G&^;s7 z=?Rf{BtmALk90sCmwKuSegp1IQ`0v}t@qT6ueZq6jQyqw7mF?>Nxqa3wih+zD`{J( zTAk3}_R?1!93Ae}-^h_hd?C|3CO%*=aIOpS_+}tXy6(@ac7pg<@2895x?hZ?T1YzY zviMK~-Uku#o$j%99G;PgtG~TTHo`O!os?Ll1wX5vo$s~tq_femgqIyXeUD+5TF1Pl~el?q`7?xL*!NSL(f zedz~~6zd|U1YFLOd;N;`A9QdE)CK95F`UMcTvDa&0SOaw85t1~(Y~TOtuXSlbtvR} zzt1{j^Y9>HQKRuYu|#KvUtW+q;z8fRMPc8>%ybsZH2)km5;&@Fw%I4s=qqjrC0I~C z)6>Jl$TQ%Y73kY*l7XHG8BFN%m+0^4M0Q{#T^>8p!_T$t6PZA zkc=m5ud?6t%H{di;{6n&Yxd{8erill>We71Fzrn}W@U{S9t1Cz@;~->tczP{9feo# zVgwW|zP>JB_jpsl- zmB()A^?<_1OF)U$N*Ae-t2YV6Q_=3*l7s{%h|&ioPMD5dV@~v2QrwwXO}4eI&W_uw zdrff+r-uOXRD>gT(P-f+8MI^YOWA8h6Y+#iq{X>`j8^*F0KzJZoVnF!JljmN$6>z6 zFn+>>m$P_D=U2w&9Nt*o`6MFmF3_P${$5Dcg(~8LDzBaqjc!Q&_W)@~VD-xv!uTmu zN!RK8(3HKS&khTNW_dI`86qMx!1vjvD0feUSNZq@bHiJ~K-2u&BC-rZ;ShPe%Y`tX z{DKhw#L{Jw@*$tP_;ao$(Vdq2`sCp&Rld_mRi(~84%TD(L=9WZa&WlkoRf46`(Z3g z9${YodpM1U)7_JkDTE!b=NbhIRxwx)1h*KaYv=+`ozaTnfW)Gl2ezv}xmyHR{HACHSJN-N1|65x>w zHl(ZGat-orO>;-q@h>&gFF?(7>33Z6s(jdb2vns4cz3l4%@0G=Q`1V>0Utb;Lw?1y z;5GsMYhJjFo;+)R4#P$~5Rthgk5jjsnbAPr48v7?82*YDLBPOIdidua6w1Fq7VJ*R zZTd5Dm8Rn826MfYqa#i}VuwkrH(7bMw^0M#U2uT_7-&ZkXrD6#%-F!3WAmsSU{x7YxQ{yGIo)2oKNn7doDq}N|$sU~X2uzPxNS0WVNDspw8`W*k zmpxLn&MKJ0mrW%*P&a)3I`#2zq6h~=(C`*Q3$=DOI3CkQKn^$-_1o+J5#@U_7|r}%Jf`j2EuFFc~; zYO-^zm2>>^$2qML)Z&9rRAVO>;KAS)>W zJE&ISb`0l{8t0)F(&2I`cs=(uep@r%{F*ib??tbPM~w zh{&r^g0fk3^Vbl`eosF;F5SKp^-sfWFC!w(;y>rAJ(JIH!68KCc+6!5dAql-u;{|mbMTYBB=wNe5rhFOR1do70N+sC} z2LAe-K>MATv6g!hcgjU(KWjG)#elKO3pbihj`Mq2)_yC;r5fGG4gv#5-7Y^50#OFz z=^RjqzI#=fD$r$B@)XsC2=c~kwV4j=*U<<`<;&v)Hpc1ojWeAVl^#A#$J5jIIKh!` zNpt4cN08rxTzcEe`V}BR$Q)@u&C}`_l3A(}xk2?YuLjkndnfV)bvWEBxmgEp(7^uV zYBuDcSU-8Zu!|n^Jq3DMAlZ%%Cc&*^1$L3N5qf^yUDUdeUTTX$5TJwH_|z214d^dv zm5oMxqgNz!An8|}seFEb%U)yPyY7Eh(}{l9F%r?X)p*pi7SPp5#DQPE;+A?$ai;|K zO$C#ze^tGnl`K~-%*8ftnnmkCm&;+O!n4Wj5)EWEsF1Qy7Fi^B@Eni^yMzSXB6p`BX9SadM#*Y)VeWy6BFQ2MN_f7tq+d}qs0SrO7-d1OT1@U zTQ>~&Z?2LvIE-qs=xr~*f7DBYyzi4fWxcy2j=^=me~7weM7MOx z3BuRSg#){6U$ppK)^1oowdX(wJ5hKk$Y-U+b+rHVo8cEPTx2i)v6p`BOiDt* zTyaUSDGLRhUmp9j0O4ThSM-R8tAKH8;P!pZDmJ1i5@5rLBuWOhhK{Y`uRt%!`imy9 zW;ed$5^Lc0=eIoZ7+iMSmcZ$=fG@~~sB5@BUboWo&0|)5>TA$w!yW5<6jY=j*$ij< z?1#%6Yn-g}#q0$*DO!wVRp(Y+Uz6y@sh`h|`1L`vbDzPLB0_@YAShdv-)XiVFqJ&Z zd8cg!Hkvz~HsOgEZ*CNIG9a#TF6(W~^Obq5rFGI{YE$DO3?@&F>8#ZHKiUPw4$GIf zE3n5jpi(eMjO%vW+kqP`-S@pQxe>e_>OEyHGmiD|n#qAc&O0@3ZgnMW8V!@n4|;u> z=!q|w*W?hOsHUF;%`VPg*J=b)(r7K~U0YNLE>gr9irD`PAV{;ekY!%4>dQiRe^_9I z6RdVxeBA)A5Zcws#YY)!=sXBWSEux1>pRt- z;|wnco~LRH^}Iy687J|-wEo!FHO^Jx`sNe}*k&$>Nhk^3FLY3fq+KFEwOSD;$_57L ze1S+8)6@omssclKMx(q^%gI?sEo|Y=%C89Ses4((-3L=B`C%Y_U2Qqmv|Gy36Gjd4 zu<}6RVQVp8Lhb#aizQ?bZ7aMveA9|E8UI!NN+OdO>VM!ruj^q{;>NQgZncTSm;`M) zgV18Zqe{tm8{hc0&x=hy4pEN}l>x?c0ezPx$9S%xB{o7ahBW^j7-gvHP0RiR%29uVcO6IXi9La-m~7@<>V_hU%45{u9B3 zFlurPpC4R4Pf{WzDjY`2s&F$Fd>63U*J5h6T}0h)AS0=CbjpER&m-d zPWUg*o)`?@D|zbQFj!@@Marf!xe^4G%&CNfvu+Z|R%KU#$NK|u3zqjo2B9Y+Ijj@7 zbLlNM?mBwYRTaOBDayIS=}>RCBT(GMHPfyp}T653&_Ie8sjeqEpii5C^1g%ddX zTV~@EdrxYKqMOAG-4{K!?o3muSFvW$@K@G1!GqsW{!iIYm|n3@N}_)N#eKbi2GYWp zJqJrLL*}v9o34X>&MWBg#bEU^rA<$|V?F4riYe(O>~tt18r%qtinH@PH_V2QaAWy! z8R(~bTuXhP$A;|7?nfArDzB-PxLtf#Vnd6`mmLibCxb_3pn>HLQ>L?+-bt{06ci4i zesAjn=G|4Gqztu#G}l^WVs$14%lX)92$!A#Bcp z_7}gY{+`$Nj{xZ5-mJnw1W|5_0;=6&sr<#Ma{|a$+UMVxnZHD2!x|C=BL?%mY;-3g z?z+)fL{)jRQvde3ARqS4T+NSK_HbJaM6_g`%8RxdM*G+{JiVcvFs374)JYS`i`o4? z{jPcS0Zt9J&)icXFQYwiGT5to?EBE&zzuE=G~}F4A`EThESc!X3p!DFrTjjn&swCD z@%K?IBX#&0%9sYI_ovO{!Z>UANgkBqztezxrCv2D8aZVNefl;oj;|GUY!n^ym%i^9 zil2v&_I9P3SnuoqCw4TYrjIuaq(yOS&6k^ zzIocDasnAH>e=i-qsi~4$W`h5ydW<6U2^uaM~w6~V(PHX0-qF2fy7@BbBiI+r6Ihy z_vF(Ko<=FWaly3`Ey*p^veUEj9|h7fZwCty0F{z>Jl}x^IA~SHRWW!g-If`gmd=4b zm)Tz+R6!w1h(;{iBba(Bi?CJ;Kza;`{f6Jc;#{etvy!2KiTrGLucZrKEDzcaGa{2z7PyRZ*u6#We*VwAYAYWzQ zENN5I3^VXRA*>i}TQWh?6iS0>v6j<$2xcX1qC(me6^B%h`Vs~pfPR#H z5N=f3#6|l@UZX*zEj3gDdWP^#toArN>WQ$EK*z41R_FJC-@D|k`OEWh@{3U2eI|OPr>isz|L(ePpCvd&R-N~UlK5vOQz$t zWi4rK*Q>eByQABS+rI9{7D#x@8ot|{M2Y1S&UMGdG{F27$A1PyceS(iL^`XH0eH6s z2Wys}W=*S2t<1c6(jwqR^|ctT9v1LbyBCx;r9j{~yW%%qHrN1H7n<3xC;pY}-xGo% zk~^(T`TWCL^EN0HcDB?ehX61&BwAmp2H<7tn$ zhYPk$HDoToqGYO71CG#XMe=?kv+G_~X?q=@P5Nu%X8;p_XQ`t!Glk}+fQ}?5Yc4-u z-rABQv)~X5fu*F7W{A>)xxV)e#pPoSwSmXDnQi@+!3rX*j@u`qj)3DgCLPm;oPOAq z%g^d(o;?0#&gX+l5v zu#&s`FgLb=>?6e$+wK`$h4eq!M;d6j3Kc8617*S*f~L7l9(z`r%mo))8?->L;HFKz zWsX{;V~~>BE2r!^6>UBVUwKl%<`1A3a>79W91#vZX(U9$ol>*_LOR-3$a$wrQESF|)Fm zlb(shh0MtsP+K6lWDuq|ZQ6HnZ8HeBH=jv#o~tMghIz+huHJ-apjLfr^@~-y9sRW_ zQgq7jw@9N{55DX0DXaF(v?>Z6Od4#}u~|zX(rCOzo;bI?r^x4^{Bb*0#cs}G@eE-H zehw4pbN^dLfN^Qg@V(y5J#l``8czNfdO{V zjR~d2pL<9crq^tf$j`XyI$Z;%i#jUP)gypAniDRIff%bvc#Z0YZYlOw^TFAqH1^%E z+jJKjkF^@M3o7y(GS+Sv>8si#xoA3GU*r=BGaYEcCosc}I$Ned2m~-tgAR5W%10gd z6%((VAnZR+mL=2X{k-ZA1gnV$9yDq$F-xDj8JzG56E48Ke{uHpdj(vsjd?8_D#~iE zjC8q2l)13HO^a?|l@5Fg0j?K-U!M^<%q1)uuRLg!`C9V0p1Berw$$S~D7Tkce#fRc znO>;5v0BsvOqee1!)up)c#gp7OJf9qute$6h3{D>@Lz(6xuzeU;f_vy`SAS8IKjI; z9yfE~>BZZcXMZnf9BaDDf+Y!8e&{!T(3VD({4rd7kfPqqe&9d>@mRaQ5}UK@rG-9{ z0KxTCup;7eM#nW4cnodSH-%cgV*Q??zEYUo1q|dZnUSR~d&yp3`{6KFdgKB1;`{1# zhr|bOg=CxqU8i#+DngJ!O;F?^)M3Jtj=E=a%VW%qWWO^;gxI;L{_7H^;Vy;}ARJD9 zB4iitL)T6Cd&R6*jQ}Y+5GAyva4GbBm#-QEBm8pQs^p(z6@&L8*Z0Cmt!W}>cXqdp zf`N~|CK>+CGGEDN16ACw$}7_9X92f0JF-|32nzW3c^N2XzTFXNNx-33wo1E$T21bNho4_$2F?4-EE1l_ z*k5VSj%M>o4yJ=fN_?0>zg>zHLG;BTAKuhI33kvmR9nT8a*rPU zIu|C%2?wCofq8jOFz6GuZRF>&bGK=`2X9Ih`I1WaO8)LF>C_}M`d+#F9UZbbmYP1?P-)Th=7FxV}OOaJX_(*4$ zZk#CrwytQz$Jg%B?BzDzND2TSqJ89da40bUK3?_L0n@pEANMj7jz@rf95Gm@7p#2! zhO||gG=!m79myM=m>FpaQo{n)2hmO^VwiknWMq3N-?Gw{i^4mWk6Pzfzs;jYWM&V! z6!X$8JB zT+M6xmgAyDsB?rVYT-38kN+MT`BS< z&%H5lPT-u_!hV}W0Dn(R{kii^WieGWum*TP5nRenuq_$YYhK2ui=4_ z{ujI^=D)~mEIveBHtdiT!dLRT?YYpU^+~#1>b*U8!mi;XiO6HO->B22VK6G(q=c35 zF0$^Q=>aeW=R>3QDbd4j^)E(*fRs6a>YWjpO7cm{peEE@u8b}%<>L<3Q(}r|mFvn> zg}j1hA`U}_!sqv$Jod)pAJ}zj1&(~{F?KR z96PoG-e;S9bGg3sL*Wb;m!b6VxGBo9z51Z1)fBFj8p42h|-6TkD?*@j+FdnuiEn*r)aa2_MAyg;)|ExWRYEnrG#I_*=y`N6}l zZ{Guh_lHyl()S@dV8=9@ zJyU*K9mi77!{W$cZQF1D3i5OvnE5)EZ^wseymNhc7u2z_sH!vD-LlDTOoWC8^ z__r$rI#tXclO}g4bX{k2NdpR&=*9S76Cc?B72-ou@}CeNmw!!sL?HeT5FhF@1^{fqi;&Z`I+)(jK>2}f|Z z5G3Bb?DEUzVZN`c7gpNG!)>oe!TW#&0y!)c7GAI-6TUH)&+X5_?IHrHDOxgt?9BZVdS|_ekD}EL4eDj&Ra2n_5+(lw zX#$JJ0S7$I{t2#vL244+wl^wsSZp(y9MHZ5ElWJcj@G5ue|4ERJGTj0CYfnMDm(%z z?h|mLmd?*gVObTdWK?fW=N0vSqp}W6#q7B)qEj37?Caa)T=sr%2tgAb+iGF^#+6L^ z7-7fCkJL5?eP7>8qIqZ6@BbF8AAAfU0~tA9>F??a_&1jgB@Dc0{x zM}K0GnChRq{ouS#+b`Mz8OGw1GQ;Dq!z6s*T$2f(ze|ojD77ICr{E&UWg!4RYvw>a zW7YlTdRJ-ts7PbH-ZJCv_eImYQYp7Av+$&nLD)6V{T_{vAbxkrBw61lr1eTvJAJZU+%0lXzd3q4r*acuI4t0Y-|Bb!33XZE?(ltvgS(3$MF*7qWSZFab zv&9S+Gcz+YGg!>b%#y{-(y9ON1G~HT?lTiJac*WR)=jO7D2n{nmn)xq^Hs!=6WDL{@S=E?6zCN&N6JAIdP7t?<-Ebr zb`>XOR+XdLM>jgdC5-_y2Kil4{K)zEkQyjn?6JkHGg_)@l!=g<(kc`lPbo9g*Rs8(*shBNr7~CD zZmx#a(XSb7YOTC_Y1Yv#HJ-i^YN}zu6`T{FJq>MR?dzKh4b_VNOncRvqcK>mo-MBI zQXtK7SqkL*b|VQN_SQDhkBEZA8%rj?LI;FUV5uFp5NPzobv?3%Kw@(K4sF=36u~d; zj6*OW|Ajbd_fhbR6nw`|;b~H{s+7#eXN=3SaFn4%okuO!ZTX*?sc{1*3T;;|i{bDu zUuSej%DmdanDh5fo1Oi%6V<R;t)wWXY%MYhdey1^%ZNm>wo`q`-VM1&XuS&k=nL21= zjTHwUvubG+O>HFTtA6ul(H;727YOO~=ooDXM+a!^DfzRVkc7cv!uNW#iA^TpS-W#t zeUyeh(iv$0@*gnQU;auK60@m|Gdkx7H-W*Isy86W1`dg2;vCBeoNrWVrABp|re8P> z*2)GRyBgd?f6Ifl56>3Ld6iIgCI|_dSFqZO~&^e>qg5kh}0Cf*YkA$t7 zY(8S@8jea?Hc9cX^xv3%j6)=(zW;Fsy33Ii9a_p}w>s<+1fI6)0^7w+b*{ry{^nXq zq`9m=-vX0?y#a4GE{~hn9q6g|e9}|K{<{?A-#5Z8gG^YQgB1H!t&kQ8PABcP7KyE2 zkuT$)wR~M{rC8$pm#lD|*9gA?rV@7vEXTL@Ow@6?&dr3ZPstjL&8WL;Uoe{GwxH-` zv3R3}7f;K@etok;piq}r|0M~u0z6>zG_D(P&Ywv;jsz-zIJ)Q=E!5SH7vfd329sbs z>|N2Yjgt?UM*$^Vw+O8f746+l&xKa#z9h;@VGoGhPi)uPF~4obuY~}km7G-=x%Hn9-@G5VPM;(aTb?L)rtGd>xwd7pQ~Mg>hTi9mg+9t^8@ zdKG-8ARrO=!Iz9cA~Kz(&_G`Gu+h+C^+OKrW2p{OIcI((7O<4aG0I%1puy$yy%e&V z=S2&S+;#KP{fOR(60`bQCe`~xN0Rsho_mUNi+IU40uNQoN1LdIMWX8egzB#FEW?_!r-pWn%y#=_7m2y2i{3*niJ(hUEfIz(Yo&-fWn}Bq#Xe2%>ShMO za10i?qvD2|KO>#}WN~}zkYm}}d*|43s&D2)BTA%C*dB6n$R#~7D8)@I>5FA3xRY?& z10qJOprqA23Kr1K_utVj3#=?~Jt)cywa{2#(Hmg>ilshu^aIU{?MkZT^lhBYivkHY z&Xv_oIj5wuP#ScHrZ!^L7w<=^(sMi?CU6>3p?Dz21r|GT&#c0c0+%pmDhDf2!Q@A> z8eGDJ`y#(4+7|t8@216uAy8V3j8*3LmlTmcc*_Ym!qdu1K7YAGU}V@PNJD=aSHqzi zLO!#G*OhY$IFe5Q4}&fcC))Clgg>Z$);(e!fBpFb9_HF=#u|AH@ ziUmRcfYpv-rd|{VppfxJK?3pr+#*D*T^~E^~y+TG#Jb+Q7fZIN0 z$#vT1ui6n}+?w%cU2epjXmPd4w@iOJc$9v$5}BW8Tyn+m6j4GH;H#RfO7Z-g=>H-; z`&ym1i-=qB^P2;mGc+PWKD)Ok|2Bx*u;eY@5`B}-w_vmak#a&dU?XO5j$}SX7{D*j z>{ACSltxOa5|4Yo+4Y0mBBox>Zz_pW z#0H0TL>|w$z`*x)i~ zbh=|%pubb{HA}l-MlQom95@WzJ#K|xMuyU=w&@aiS^1;Yd*OmPtf#XV@o*`1ljqp~ zq+x}weDcn`Q2XtaP4uM_@Yw$m(T#y^qmmXV#RpfUmHfK?xmQY9HoS|J_(i-gC?iE{ zI+dfbnMKoe*Fw$1XTa=Srt(jC#s>%S@D0D?vyPUA!A)^Vg6*CkP^K%d!&Pvb?8?ee z@k^zv-Lqb6$+>Xl%WLhMDuxZ(P5;JKaK^0cH~Y<_Uz05(zabhz%4TeZC0JoX(P+Qv zB31Q+$zvYuH)Y%y3ms9tl&(_{mkdvXOUOrLs_b1`1p;^tQQDh}~^HpJ*8b4H7!zdJ>i0GdRqiDoPek*|S z)BDi@ZqE6EB61`w_)b3FM0d+E5K-kJvmAXHZFw>MbQqeCAy@ zPpkeQAaq8b$R>fw&+}w40p9*5P;;=NP1<%t-`G&wgfNSVD%PLTAKH+AP5vd?WB3i zNWu+t{J0FR@vPbon{q46r56dndmO@TFmS|pjvLvf2=y%>G5cn zH@!byWlOG|mCcmVyey)9@a~|OTT&atU9P9wo~7b!AS2zK&)~%n88>!;s}s(g>aMw< zd+K96E+b}GFQ(@k-HzLDw}j8^9GEPGLi1He#kTWIx;$X%RqF0Y>nd#wkJoWw%F%`0 zW`|Do{Z<3QK`5P*Ao>Hy{FH9#17UIX11I#<%lc_oSz(QP(s$vD?vuZ_V_h zZe0peQw*z$CRt7v}BoT>wEmii!R0<4|Bcgy20I) z_l8%b!hZ_KUhjeA{3;yJojY>#^5D!N815coh7ZOiJ4vFHu$#jW za0sE|Q*JtYyd_ZF`d{$8|DkjpuJ%5yGn0yag@nTAS49>O7InWP|IYn*o_rU&J*=dEO|d zoG=!5j2h6kTIp1le;$ZB)Dv)P z%o6zXYnk|yS-n0B5dkJ2#mykH7vfomP6|fEu``2sC?9u?OY$Osl!z8_Y}F@Ti&js8 z1Zql+y-FVtz*xAx%+9Z8qoUH&a`$WHhWB$qldAz31=mPU6=(s}p%&NGxQof_(5h{) z8V9*cu68cZ%Fj3`lU~2cuH(PTxV3%of~uepsQ(GkdHqL3xA@7g2vjLaa8qlN6Y(!{ zzdhSVlgqqQXQjNp*b2AA{YB{vfs_ti@W&S+B4TJiK6=Gff8j! z=Td8le^bEN(M9=xhV9nouAx6r{<~PqC_s~h<(*J12KZ6`{c(kFc!a6`w?2#z8k8bc zMv&aZx38ZKY-&!*IzO#@J~FFMx;fkb*qRF;f;3007W1KXjP*dU4~zU1%< zCdZ_{)-nBvf+s)UT1n)Pni~b2Jw<6-Lkf+A#++DjRCv?ZKt8JCxs8|cQzqzRy+lxEL;7*o#8Z^`60L&lV~#!Sg@NDF(B?CGf?IEOhS3HY)Md(Y z4o}Z+kiT`G8BY@RLK1lrd}97P4w&Y-dAvFbKjZVCqiVv(3F-D_8KJ#{lx?XppV{ve z{xSQQ=xE~uVj2#o4_zVW97V~sK|(6m3Q*tSCnwWzJ_z3e&OJSQ1JHO`Lld#WO}-Y7 zHXA4&ofLvF$Ru%keu`Y+4-S}JQmy9t#*PoUsH_!=q<>9>B)bi$dof$e=?(|dJ`0ik zu2z4N8hRb>Xl%s4Al{K*)6=iT;@I5(9meDSXBck_`u`5bdlvrRVmv&Re~IxfvHlsx z>-~2a4+lKA*C;gvmv5;&@_sjGZd*ue7v51|pI z=CV5}IgxaYG}Lh=oLFfXyMQ}`G19r~bgiCt2lN@u{a5Uc`=o_`8y&nV1!JL}E^+fI z6Rus$we&*<{`2veYVmlOiyrrEz5JFY8+z(DS$XRD%_G(o7frcabCb$7>^uL%By&~i zzQ+?eJ4|N?w4VZ6zczLln&`#=Xjm8o1R7eeXq%cm<(IIYJc<%MDAe{U2<a}=92Fr-N85JjBZ~c56P!uoH+_8L1=!tvYd^>f)y$OLC^H5v zDD;e#YPWS0_-uPF7yQ{}u*&_0bI(jf`ykW0UA;(+L{CUAR{E5nJ?#;U=Y9ZxnV&Ir z{frEIm_5IcFnI7o4Zu;#`Rf0$BXl2m@o*u>5H~$$(4&!YZceRZv6w$>>#!K*fdm;uAbt2?k;9GT>Rb;Y+1E28} zOoj{dgsis0OYI^Baq0l@dsYy+^&@jhBEbIc)2j}Y?5FZbDlD=hBaiFwj7e4y9H6n3 zi28c+K|6K@muEhlupsY)Os*W_mON4+5rrHuU9PJ}`I)tH z4H6biafLm2{Ot5nRxYY81t(^SuScxc;&yozQIXY=|IErThfJng%G=XzYDN=3J+(tR z^haZx0g|-PNNbbzm z8~16*FmE=&EiB=<6Qp=69t5C(d|{`+U`teM_p7>Uh0?kGhk40n+^rjM+M-OuRwiCs z@W7P_W|hpFDy-^86Zhh)m!YN_Vm2`!qt{YXAvvFzm*~7ow)73Qmu2{K)Z>IS;!IOp zObd30bW>nV3FbRb5@v}p48r_7zQNBT8Z~S6Uqib}pUbsczq&yYu{xjAVjf+rj?6SQ zXU0sOcI)9-2cU$z9y0vJ!r>l7x~eYP??7YazX_QYOHhtVDlyIV--(EMMSYro{a2nHV@s@8FQ4gSCUBJo=TO)JYVL#&}P3 zRe=K_Vls;(qouC!)zmR#q*WCJKwn(y8zc4oK4V8Rf`so_E^&rbgk+!O*NVp6Xi|WB za;AJ>i3~m^QORK~J+uhgoK#oal*uZpG=6yiV#2c7{yKfri+Vr?@1PgaoH8h6EV(`U~@N`n|=5$1T=v37i<>eSnw z*w#(p9&d<@J>v|Eee45`^-{X}eg_6{tir?zS6WqKi zWz;esQzfgK6Q)R5-hN zCuH5EZ$cB%-x~gcJ40n}n}CZ$I#wLXbY2P^;_B z8ZZH!Z@-Ec!1A0zl2eg&w1${Gvt@T@{PhcT!Vz8{Zp{qz5=i%t3STY2(R&agR&RW- z@9$6I*KFLa@orfJ|{ z#OWud7a=p8Qe}6)3H`@mX!H>dibh=OP*vc((Y#g5PB=Rs?v3Fy9EAc^zSRrn)6k>F zvlaSm_9$&$$}y+Dfr?GxfjIXj@%06!4jev~x+hs7c?q9#;I+Jyin85i5L zu*sZJQU?`!7d#^;ZK#7l&{)d1{E#^LzE%d#{KDz9Tqi3=(Z3SZ!nCP_NB6~_xhP~* z0Ry|09a|NO&q5EhfGkOJ!o%E>nefV*CsnkRn#u-yMJPC`EpIpOw~eSi$+c?5GPJg0 zbtG_k4Drjmh7cB-9&zJ;+CLsPB6L5vfBlWy@W=2r z1(q74jV;9qAJ1FQwVDwJOHEA@V#M6UAy|nwWb_gfF8|7AS*zifs^dnmD(uKc7ye#${HDvMCtZRRn2X9qkz(4Cv-k3>)puZQ`yCGjQ%3~#hpUKS|1C( zx{6TT*F=Y%LPtTvFJv3wD{A{GR&)cGuRd{2w>GK8=R`tm)7M#YYFgDPQE?z*uLhqk zT1iX30E!4yYjMa~do@@ZiZDX>W|L6~6bE1EbD!*mPUAx9mxR%;$BX7V0VG` za`f76S`G{8B>6KFdRK7={lW?^9J& zC@rM2@gHzb6S1fCO*JH9M2{KyYRdgbiV-jDnM%@PFcHBtscz{ZDd0Fw>u^s$aV5rc#_=N4uA8>G z(b>!T@@aZ*^H2;%*HFMfL$>(qw?&a}?gR6VUGbys)^KXYOE9W({d0}6@#h#c*Le#{ zQgo-@j4GCG(R(YRGY^(nr4Q-({Es&8$L~Br!XlJX!&Be0HLa(GGyy7xZ-LX*@;214 z?gKxx7O5E1#=Z$EsDJ+kGPzzCvYw(p9kX(U-zf#?c~Zf|F!wQA+(kq|NetmZ9x|Uv zqh^|;Vw#KFvrzsbr&cNNg|0N3qj&;P=qtRM?gs$Zxf||V6_peqCl44kG_VDOn)FHK z9WMNpmN}s0+@`iqVnLTe%`r?|A|hEDZcL;-V+Yq%^bc6Shhv^!>3G)rc{&$HnY&7d zc%xziz5_3Oq=fYced@0>7{=mMBLvo{k+|%iY?GdEFd`lukJ;s*7UDmFRs}pM#>$qd4$vkJ}y%dQ9FJ6*@ zo7PW)h*^Hu1Yqzk6Vx$ByVB>aH{8qa)X^j_D!ourCy!~Y*&w1d%!iEA7e;mj2UD&D zS6B&$asc!il9X?{YeHr+-lvq0R3Cri_HE(byc|_79MJPdj)+nlv^9D2?S*%!29P-d z)kN;%{TnFyEo|<>qRhio2q^mU>19+PBFah!zcRGs&MW*wUd~qXeLTP=$LtM6`#UkoFU?49AjU@8N{gB!`a z$lwPpz&}oSDkG)HdkyN;d=U|G0H>PYWm!w;vwAkIA;?QV#-N|l)P?(`ceRrWqH1%c z-{*=8Y{0-=0~s}#62i{hoiQY;Wu-pgZdPy327ZD&F@JJvLgy~}xZZu$VT@Zo>BCq% zyV79yhIWtNt{z=R1_jiVOrRYk%9L4tYEkQY-u@A{*?V|1$9wl1FCyojFiEL6cuUQe zfEtFY(fP@9j`nFXEk6sULMY)ePZsOq$F|NjQmvL)5AfhZzOYjMt&SqZVu7 zJ?qw_@t{klR7@-ad$G{EA&8c7^Cc|bMACO{q~pR14`0Tyhl^L>Q3Nx}Up_NUK@_vu zJrB;KN_|1E3X=F!l(8M11B-V^(?)~wbsWx5vgi_F`Q9?xsg~lMCk=Di80LB91P&G) zuW=xhqNE%?`CBOsB)EFwHP`AyrS1*2$AmRw_h3e}MMMMkX8);uLteZ7%-WlfP{wty z?Pwv{nukUix^9Cjzk~(<0uFHO076|$vWz03G9=HaxbQUdK2r;Ypxx&>% z%v%!z3LxNI0X8&^&iOxnL-kqE@BSiHPETK+S5p%Q6uc=+k$Ps=!j0#XRKip23=^m& z){=8bNi~1Qa8vpb@**LH}$x7 zXU9$%MHZs5^3Vy3GncB0hqjv?@4bWL@WFX5RCO>_R_kkC4UCakMC?erCo`-U#DELe zsDgxaJ(><%t3FocEY&D2k}CdcSKO!2-n zxI*z7V~D|HSNuVlm}b>HC32`ZeSOCU_}*J3p``0&P;cK$+D-o@e~7x~bI78cEYb0z zdhA@M2n?_t9FfV83zJavP18M%n(XQFsodnpAa5vf^3#g>ewWlpm5uOzgAA@JRqUPt zpUb`Iy3F_an)^m9MQrOtlDx`%c!0pC7?E;(YR8(`CpWJWLij~!jTScP(cp+9^Jfn+ z1fNS?!BN}g;>SzR$9Gy30OAT(S8vj+59j-}uaewP2lkF54};UWMAJD=;E>jLo;Klr z3gAX7eH7JX1^(4K)MAZ(!_Lt5l<}sg+)S^-MScZ&ZT8eOVZ9#1{(L>rO(**Len7>c z)-bp!Si}n5kkz!Cr~PgEKro#WJ@eS{r1AO31IBC3>4U(HTEhc)XjBM-a$1X3apNrm z5#U*BcT7?0z51}O_+{XL<$fX)cOiK9*L~$~-z|!mkB(_ID8S+x#uCFWJM)!J1P{Xg zBYbX*=i(>X>`XkvC@=#-bKBmG7ArZ zh2QsR1LvKv(etE}1gtW36VSJmCzETT4WP(-Jub~?>xK(2O2g7!n8_};T5y|p_c<@+ zuk{1C{_u-Jt#@S(429s`j-lWWorrg4dS343RuXNp-}i=FbQS6=ZG7BresDWyIecus z6s3j|LZ06~^N(Ae9L}cftHNEfU{;CFq7i6hF1)ih$?K@@d z84RZTz&pHVfq!RH21h+4#X{>nK$`4T^c&6nmjJzoU0TR8HZzFkKAqKPTACJ|_4CNm zUM5MO#u?0`4jbFf==!5lW8{dS2J#^c50`AUOZt$wu3EaUJ%>seGD|*lJQ0T*`xP<= z&h+tI-$tbxZ_)M3JEc$VhpeYT?{hy`BN= zipU8je-(|$R4<%f05`X!FE+MouIw`(F773G=zS>qoL}ADQZoJTX5P8|{0cGezdwGZ z<&2x|2krSj`SYPp2#@A5vf32%htw2qOAV>J=2hEJ(9W4&w#Q$U(wR}@8;8EH7TjQ3 z8C3!3zAYCk&B^3Y^sFs|L*@COq{t4S*}T|jEQ4p&^luzNpQ-LJ&oC#ZhA2b<{!h}` z$Ew}D>FwK7s5>l0h=f7`aCA1zB1kyfb{st0z?9ssrAl5iBP60D4m9#>ge`pJe)f3s zo`?~eaVQ5OKH28h03W|oXTV#)n}8w8%_k+tiJj(Blr;^_=c=qyn%P;Gvzgm|J&(Q? zwMYme;pdkUSmeProe38RU;3fs%DeGB2h$QCn3L9Dq`8Wmx=gRhkET`0G1)Qr=2k)< zp8*8rtS*u9rAag(zKcKJ{>*N6_I6IqqY(Y|X8thc%q_bi>^M{6ber43GP*}rjEbq*=U;sqDn2#g^4MMsQ3Y(V zg`Px~YXaZ!A)$Q1&}){937y~h>4z1>eRj;=BR>K?J1j}_fO&c)H7JF&B}_Io7y#I{ zjV($S(Qe+)nF>YTz3-$muFh)*0QkL3n)2Gm!hSyB4n=X;#jTPJRf{d57scM{3}x4) zu~(FDy`Z;yBz*jyc^PBx*tWkRWGlHBB5`WYD5Yv?R;(AFqT;jDm3M(bSvL&z;|Wk6tPJ+EC-_jH9K#6LMD`P`gNZL1>i~VkC)?7JLIi}a2?~jI`BE3H#Ngk zu)G?I8ir&=$-dwzu`NHL0HVR!8>UU0PvxB$%@^Fk zV_n=GPLpkhETrgeYZjup(U(R^*^Wc_4bIYMo?jR$n-U-au7MC3w$C&aA?vjVGOYQM1I5B15HwxZw+-ix?fM=wsO=3SCOt}MR2(o_sL-rpxyCr6{Z zm+9$-B)N&ABYf?S8`koZ+QfOShtq+|v@_XhSOAXHRPy`|nVU&lW}jPii@5h(uO+%B z8BJ%p;4egJ)L=M+Xks7cu?r-eHUmhi&9C!**LdbeJ(9mcJ4Z2*K?SWnmemm=MYgmB z)tPR2))C%iN>V%c|1v;uD5HiFD z^A?lP7m&@A&joC&hDYho(3e2{Gtz|^c)PBH1Tjl(=|wC*GB$1>0sS+UXG!5?Hcnhl z$BFD6 z(e`{pM^ZE?J_@Re-;#y(LADDH&k$CFVHeoj*4pQKB!uY0S2SYNG zI}RqMQ`x|MbBA_tXjA)jw7-N&Ox@2siyZubbjQUj0y{rR6TI_iF9cY6H=~^#`EDMR zkZ@OrG-s$$r{%&@fB`!U1wM{6V?)HrdFkci_(a*i+ zB5LA5MP%W)Yd(jFMO4rEYWx)CAA3C^4T#Cu(R7?pg9P+Y@(uw*XVf!d{4LCF5LAm4 z96&%d>FBhzQzK!DnWd5X@)U9uTK=5je_>}pCDp`vq0Q{_2igwcF1+KQN?qN~3g^g( ziK%>%Wa(i)=?p|oZ-30cPIX=XKy3>MxvMS*^Rl8P8{MN+UUBNP#)dV;-CSo93Ndvzvg_D72ML0g*!2Y zsQ%dAG-xpR%u*re(%-Y^op=Eb4%PrbkJ;$h+ug-lv5T#t0rq9bYUk2j==(%97|;Mr-h7ltRPt`q zckXfo0HB0<995N3u#&i?BCcnuA>bQ8Mx9_Gtg_nCj4aOz}apySnEwq)@w9|zzbJ=HypBu z`1m4Vba!Yew7FG#pFuXOa(APi`9vcuV|NzeH`HN3Rom8?U+Bq<;p6PF@A30${b4vpVT+rWuKtLqS-jcvZp zQ4?q6ORmVnH&&JS6c z{Y8j%%)_#ncu#e*W`70akM^N6?rtURI-y6R_l*Zi41Wi$Z!AirC8?+5&i^8x&Zhug zKdNT@UUDdpsGM$C5)yKPIj(}Z-5Rs7I13`eNc0tuqCC@1hFzWYJQUg0g^QKvbK|@% z8@Ucp6-O!8&cZJ&ek)?nTLW#4D<(|0##waZ&40hJf1Iu$VS zj;WktRWCBz^XP6?$3L}6L35b%ero1=h!x>&+H|_6e;WFIH+#xzo#g-kenXGN04)#5 z7kJ@on_Sdttv`R2Gnz-jNi)`zjguzVK5{c5i0Vs(sA{>My!>+NXMe@XT=Mu#l-V1a z#WY3=l1nR4K&~7A&3}+=Tr_@aY5iN$lp|9sR|Ejin=j<$X_%Y*c~3@MO#N&~TMbz~ zt5;nw$WEH%UP};_VQXXT>w{;%Y%s=_KOvhQy(#%Vh`jtaBJQ<_@`>sF!Nj0&z#>^{ zH+V~8k z8t>=l^m=zrkf>~{H@U9SpTUt1;Kq3u^!rT3&fn=)Jp8_mXHf zJug~1WR&akDE^L>T~4|0S=8Y?-4OX1l)QlXW&iDu?ba)dg`prWoH8yI==9<%D3|~{ z+MOQ(t#BzJO~=P?aHs@7RU{7{x(~%yUPzLNy0#=Y0Vu#XT{qj70lva-Bu;R}$lr9u zbfF`O8ztpxIM48~dWo>03Y!c`uYu4(K*^&rnef847&|p{PW5h7e9g;*_qrpA_x0d* zu(q7sxYed5Wx=CFO=0RGq+KH@xi5G#mO>0UOsGW#OIzso4>WbN$qM69izw81a*9wk zpDL)4*c&2_WB0|&_;8)X1f{@~^M;JLpLCVzu``&Y^k2a3K)?PSiaz|BHyNj9DGi>VDA>2w0hRkyamA-c-oF+9sNcC*cCr8hGY!y7A z244;XD3w>chpHI9(LeA-fzn87%iFCDqjNdVqoF0EKDcZ)H3$3`a86xvYSM-8fDQZG2pP5Gpgq z(&6AxVktVO`&%9XsIsG8Z1~nDEhI2|&#)g5m3qLANNiDmf$vLD`*T2RrucB)K7~T* zX#v&;q|(!ky%n!lS73b}kvqdZzZIw?WSP^s3;qZyc@ODf2DT$C;&DX{z4xfqw2@MSFB_9r14J(Pc^+KbLpKY)N*ixwj$p>r6IQ zNJCv7N6f{#E8ZG70OGadPMSDkDVj4qO;A|w&$co;Ktg)Wsz~|K=ymO-N)|r$#|#do z#`PaZ$E-Fi>bQRea7oO6cS9(M&ub~+6hd5QM%BiF~cOg+Zp+L(-Mp7eT*(TkZ z{%{pV+SZCG*4BNCe}dGml#S_(^)UnSC-Q~My`2euY+0-s|C*)>0u)g)29U#&H0V7b|9}(I zej5PSXgRt3lT3&4{n+MRrtNCB@9gUt?AI*$7a}%`ATFi#h)NU7tc47;_z{*=Ci$$C z`RQlus-k{Kd4_c_3w_HJ(c@q~+c-y0jwTv{c-%?n`DBBNqJwgZQY=-z4E0f+HBIC^ zOZ(L5U}Y2G8_~H|m%;a@^~Kfu#?C!qIgfN~Qcrkv#Cw^#Q)ul?-&VAJY{Bgk)q?NNyxi zrg^NYMn%d-MWjOuWvE#-8u>3YB?*GXvmgaQQaib!Ab|PR8?Gm9)Abt`&@E0C9rUbh~z4HQjxb0Zd?;FUg7kOhTps}@N5jSHZ2aY zw&wT51|@z6XeKg}6tF9?_*dL8AfY#wmLUr$i7Mj_kKE7G@%NBo0RA~;6C9`jX1f*m zvu}X-e+SNL64P}r?QD0iT)|UVxbTHR;JCnkLVt*xvbRcx{4eabA1h+o;wT zf*&;(n#@5?G*^mZa1#{r8EGPC-pQbltzjhpY5ETEBY^Vz^a9%N&1Mf$9jo@oSGq9*3wwlF#P# zKxF{%>&M5gPEZ%}LRPlA6Dcu1{RHlz*lL;njaxE|B_6*2fYIds3ydbnvHSA`Mok(W z77^4BOwWsYq!jXg0A*RTY@1}k2Ma`(+0rcKd&gMZJR@5|sn1Ko{P_ufHG`N`kV35X z)Wy;9g84|cppIr%=Wb+<&7qGeEaChMLiA=YwHPwD*ONgyuFmNof}kz(Mp*$iwEjDho%R<7_IHq``Gw$iG1hf2@uiE{jrW#vJN(_ofp2>h@= zV1;=FB;@D6;@2EjXoH>KXZIQ)$Qmob`u9oO`HdB*>&o@_8_aJ&*RyFXu;KfIB_8Oh zRbkeokR=7>ZF%aMs!IxPs~ai;K?Gjo(l!FJYgPn64i14RLNn2=j}{{+;G7huFvp-q zuYf?))j)FjX4t;%CMtTPIK7|6G%`4E+qWDc-k!ORZ@}0GAETdvH0a8YFs0Kq{8t{l zN?&k!^QlrL8lg7>V>O)Z>~$;2K_&cI02r#0woMwH9W@Y$QO2sy-&lVk?XFt_N58cke=Zr6 zXy1|PpcAKV!$$9%peO0a!hb8$vZ(7UF0{B74S)0p`g_T0$$KT>$VX@ zmP=%xn)}A5ZCi0SGBS5}ps`zx^FS?O^}p52QJDh-F!`nyq+4ly1x9+IIMJ zK0x>MX^3o5yw1-+YTQ4WwP9CW{t^cPGVmOO7e$k_(6~-IF&kq91dx+Y6WGt9xnmrU zoisyLnYWJY@F~ig4aV0=V&ob1wY7uyZu|bn0JDoOD%-E|5Jo1qWLuNQnjF@H442=2 zD1xe&QPC~2N{a#*SYh~txl+SVZ~JGgLvwtwK9Z2UPd~s` zyGL(|!5ivoytl478==pva3{iSO;wx_m3^>4e*nkqU>5cNOJ+8yiL>`tM1NTBStWQ4 z*TQDCD1IhL$~3K+65UcBySiih7U-#xlvVT9s<&>(ZD9n??4d1x8a67&OL9Ffk&c!{ z&6%IUC8(b}9SoeA!SNfN1;EJUuq-Uk&S^3B`V8r^`ZHa8$7$`Kk|loBmUMQ)CMvf6 z)1nZHgE4ph4t-HXVzKJtlSl_t0!Gbb##kbW%yv`z$W|!zL~< zLPr?npa(`GZ7pr5x7Y};2jSABcIweR@HWJX6@%N^%tNBzgi*!eVXS@(LHmMNhCwex z*0Jqw)sx~i+-up%gTReO!^2NRyg!&qMyqLV)eRHL_l@-WptSHq)nP^Peb+wi<#00U zkMMQRi^}!RGfX~zbv>|wwDBpRF}!7J(hGwq8kF;M;KUfug`*bM{qMjh$YYa-Da%fL zP!iHSJUQ_ADJaX0m;N1e+QQy|r}Euqi2+1F#O+tO(LiLR@OdKg&wZ3_^fN2qs*;cN2||51aQ&v&w!ODf)W`4$`}^`Gh4^m9jq zym3Vx_!18~ke$&-l&$$}uK5g2I!tb9ZaMNbH5TIYxmrd{y-e4@<0`|5&*61efc!I3 zHPuWH0Qf#1ghub(PJfA~U6^3%(ACG^>r+dS}YUC&@ANvCW_`lKinNn&B7@moBtbgZxtO^lV$6s&|=AwY)KX~ zGcz+YSj^1KEL+UX%(9r7*Bso(MGe2){+oy8HxGL8lGqYy7qh8MILy(I=L734G}IVXFfhZjy>tq^w1H8^Np+;4&fp>jx1Ykit>!2Kni{YKuMGT z#kUZa%?u5+s`gt!yOMTBRowTlni*$118-NmVt<#U)26(QzA!FG4#^HhF*W%4{}WX9 z#?2}{B*vA=|uiB`d_>Z_{8r>Ga3MeFsL1UnKl0JVA*E|BuDsF z7{NcN>=hRzCQaXaY)!xIQtlxODn}kT-ZgD6f>poMq_-3yTFpnMYt)ygsDk5wF@M;M z?Shz#Dy;4sI4BlguRm}QYH<+~?0*Md>4b0u73@|^p42HHk5i~xaE8U=o3)AY4h_ev zEC-@xXwLthhXFId{=vh#Om74p1%W&a>WIfY4b8A5uhX{fUF1W6XT2VI3b@Ih{{n(q zSRXi<0CYHrlt&Pt4XiP3V|50^>0EQr?w4l*6)AqNgIb*Cp&*}^NCVMyHgT)C9o0Mw z*qI@>svTMNam@L-0$^|Qf7_=HQKS$zQ$po@~K$#v9(pMN)!8d%ljc*dQcB@%j6h43b%2fLuD z2n#@Vihs|1?XK4r>K~SLZsuU0i2a0jH{$zaRP5LF8moJUr7;K~Y`%}ZJa7W<#~csO z-oCoH>ThQ5-BY`y^rDlr-t`L%Qu_I;TMXIpwxN^HGA5F|s$YFJy0HkME2t#ymkLg- z!|bieK94hp(3G41e4iZy?m)-5F!rosUA)tt(k2z+P7%*qovW>uYaG~>kft;-Ht8zq zu4Ti@NrvqxBb!>*ioS+Fh!KLRAluj?D>h_xbc$Dpgy9!kA#$GN#2mI#l1Un8hP>o- zLNmubkTO-%jS5T#3$Q&qx_IFz*H0Z2fR|f^x9`f3L%TaLv^+0cnzkg;2G|l z8UNV(y)XWP@(E}_%l>~@7?6J*#szEBmTP_#27Y{8)tVaMt+eUNNmiw$avh`xMIKSa=n*s^x9li^U*(sDUvpGI4^M+B(y>CZf2kET`Rz*0{VTJh0NDO_zfoA>JpzD+H ze+P6u{U1OVFt+Ny1YNw{|HGh58?P75eYLs}s|JRteedP1TjgI{fsFLygJNKT+-A9p zAyijoAA;Xa{80;cXP|iREC0n4+b0~%+-)h<2W*5e$Kb7!gp#Nz*UYBWjRDYq<5Rl- z0V+Ak+Dl9VxsNXcE+J#5er7eFg`JFy1Y>@Feo{m-POEu8(M8`P3l%*8Kw4O1n6|Ud z>`)Ym^eLMamB*$2y5)N>A6h_83lGJ`r5cczZd7a55$BwwQ{1}aqc_tL3+4N0VILY; z(97ec4tuM@WA!i)BP3D%5wqjLsY9g2w=uD+;S@XPmVX)N;BOqX~)$ze#7R!0yX_ zE1)2i0c5Lo{!-h&ulq@y{Fh?}jI{Ck`o=<|5&kP=VT}P(%F@C{MkbaKJv&~Nmv4ms z+U3rWM(MA@2$bk^d=E5~Kjpilw%4J!GR2bfGJDHtH1XmuxF zcU?$-2UJI^R`Jw1XIieE_~6DA(3Wc2$;o}&fi}vS-OA!P=vQ39ld{YDJpc6u`ywp` zFW1Tm-;UKa#S#`@p8oIuh5$yRZu3zXuCGPUgOPhMuU~wJ4#yV)+d2(S*ei-E4)loo*kFH`Bs*13QCe(l#m}|*HNG`d?G@v2? zVp5nyQB)J-doi$0?9YM0yrX6mc)JP;+$QB;fCk6h&?91Q1Va!SzzG1Z#Ae~*y;|H<$*)@!Ks_ga8|Z~iin z39o_bC6!hnhgLV<%DNt9P~5+(XVEKQOqZ#YBLFsBJ)XwFSvE6ia*vCdNqDVJR1Huy z+XMkb<3E$yd^(>Ug12>Is$SlEl6N1maVPxIHX81BR9JvgfVJ zF>7MiJ#a0rgjaER4S)-d^^2h}nJb)S+i^p#m(7e>{O zBe|KE1oPa>&20z$b7tW#ytbX*Wpz-6Dq@q5>A8+vFF}!JXB;hq(~jY~@mC;w)^jdv z>TY?;>vz|}IU(_n6z~aCb{{Ca3m*@EjU(ra=)5WohwKtXIddrrnS01}CvaQ{-eNo4 zL*%N!L8=gJ8;if(=1AOnaYT;7fg`-r@LXK5drgi*zOKE=TgQMOSXd~MwQfDCcN?3z zTsKn~I53A{&mynFX0qDp+%jSg24(MjUU{GiTvn6&B&Zw`3aGp5=mK=<=Wx3t=NpkR z2L>(ZByajETvF&q4fgw(cMkdn%Bw6eARYqvb|^348y7|81M(xclmvE04`Flc@>PzY zSwhwb3Dt;pvS*#kiL{MC06)yD?il*s&KwDA9gM@YpG;dP%SkgAYD_vk*V&x!@~IZ! z(Q4fhzepZ0;n=B;UfMtY=H%!T+s=hcpa!W-jnbSSWTDUZAc9kl3ECgiC@kL>qj&R< zHN81-kH#XW^$)P_m2V&2P6=yur?2zVLq%F0QTzYY;x&yBjDDL)3qg(7V|mDlPa*d| z%bcq8Ep1BVTy0|x#F4Rm)#y8>Y@P7-1MUu&w+*t6&gn?x)UC**RD%# z12%?Vzv5wHXU6ssO5BkWHt5ksw$^?%n}Suf%zF3!T5Uh^oQR(R;c2T<8G_kpv6$9c zAp%e-UV~Qsx{huYSDfuZDWT@}h&g{RJD*R~S>?UEldD_qVfd!4B^U`9Z?l$b%dZ3f z+zs50t-nV|?O}-2rtWApWHfsoi;1iTd&nohd7 z10M=t1WNT3>=ADz+x=ORh#h4H`eFS495VH_fT*H}4TEBVvVD!400$q$=_VkO#n^9Lc2>u$3&jWEahNBPD6L06O|u$)v!#SJrUmKOo$c3=$_`3e$@GD4^BPGcFeFA733GAwObih7X`m}_)|#-`fs^`;b@*0&Smw~!<~xvCkl5a}>wc$lo( zj9OJ_>8x<_+}1TV%l9mxM<*xFlmrAb#{_HBGiO}nUt42>%^x}S%yC{iT9HKt%%z_1 zxH`+%y=jP)zU_Bp@TTq{jfq1)J?X*go5FUPhj$`9Gmlsq@mHaTj%pB#IH(hfQBaB# z{vNURBCt0I<`*>X^|_@10qlI&)69R%Q4bT8l2RhL7Q-qMwx}GEDjSlLj4V?o=hCYe zxl@-T50EJU6N69c5kvt46xZ)LUAC42%V0w@XS-{uqQBX+t5sgFztvUx!K9z2w{Kx$ zbil3&j2t3;b~E1_jt2na$jaIlO`r$`_b*y6ZBcG+RVXJP3vnLUM37aHnm1T5hY$ij z4U=enaNX_S*sySTOk+}{@~gNdLxn9XDMRCx=29T;?z&UJmQis;X|B$N<-qgU>je}( z`G8>|bayX!d}UdHZP8$lyRNtUP2j)kWwE9cP&w!p^)q29D4i2t5H4_79|YE045!=J z&;uvs2TcxoSU)IVG;Yd+@bIW1UGf;t4uBvP^IXeW&hxY7MG{}`k4T2A$eMjk&?r$~ z@jM4NP^`ZuNk{)7cmLYuvAL#2@)5^)v4h4*lGwgG7gfP^($Uu2~0N^viMU$m4+N4EC8LxD8l%KQ&$@=z`}9n*W*tGH#mNC<$B>7xsetOxdzFjOYCBl4#m*6%(5%TM z4g_46?4n`5^Nqyhp1EnHpd2ajE@^N-C>DZkfTtl?f+IPb_}sK5*JOdpSYkYD0o}YS zjmaQg^lyzOS2d4qi)r0*kxkq{LWCq4|9-=206rcYV7@Un-CRzG%ddR}Mn>T+>GLIX zZE$c(Un`Y3wt-;EbCIn08YJW;j6t0t*_WleQ<`Y)jKo)r-TJ+yuq~)#<9C+^B!P;L z%R}roeWL1_5ZZ>Nt$J(E1rmmT=DZ344L_cZr|4;#Lor&Ed{u(qH>bPSL2Wch49b9& z2A(m1s{}4x`B+d#D01|DY@mYNEaqhS7$wEgD~LbpxaD~e{p;8_5BL2#uX6rS7BzU> z%JoXc`ej2?Gsd{5`|At|$ST0;&$Q@u#`+gNtVjbudVF*ioaTYla8&s6 zwh-#(pND5@)1|;v;BG6r-b(XhGZRs2~lQ|Wq6xyCw7ggwO@x;-uU)-T=TD#xlf9V}@sby& zJDLcS#QBfH33AncbD!iMmk(cKFHL$_;t77lCd*YXY(M%jx8_cp3o)rQSz@om;HU`! zH?--e9UdHeN8KLqp`FLSbb<=zl9H6=)zrj+`{t4Z)-$bI?PdC2%*M!HNsH0JNx zHQ~ps08b-3Z{{EfzTsv&hP5%?OEJI64638%^Va%Ko?ku+qkUh&2+@Mwr|SJOB#|g@ z0@HF`1>=>mi)I#&H2)$bce9gI_(_c+IBhtkuKVX^dck|*W*;Pd$?MT@deSz z#*}TA_Pq=m1aVLTpvK{|J5yiV=2RBU(cNiv=njTSm{xUJzg2oXVBP%PtecyGN^jdZ}`xCA? z-;1jHd%Um8*ZB)ho}#aQ85MczS7&3T2)W0!f`DUS%9YA1*>T2BclNKhToe7W{5q+` z66bSh-vVtvq~F?H{e1PR-{(^-3ckBw-TAe^?qAhQW$M2Ir*&0Ct^7UyAdTy`%$p(w z^OAMe&#|KHog*titiM)FamRC?@t(h=w+^aEl&bDW)SQYm#nGxx(n`D3CqNe>2B)3? z3Yj!>!!47l)aAyN>Uegz2eK&5Rqf1>S5mCjTJVrr8b_rP!C=3m2fbe_`Oj|+9V`as zc@?ojbxw64fWr;3d~=34mz6`GqLAf>T#rvwf6f5^C&yLYDt3tO9|Z>iG^9bO{w(Rd zsk-qF-EC8uiEh2M*z%{<(H*12`4Vii^Z5u@)!^f^ep&Nkwcv^%0ZUkQYOPMDmiM9k zM#%w)fMf1V!NR`alFn&wUwPxFnTh?BDDZ*CdwFo5EI(sHdnFX!`CBsbKdCt4ZWo2K5BRT0@9GFYJP zaF&FE|E_jAQ^ItVtKAckX2@*NfKeQvAuSVLRKIcdjRf$6Og57Rd{;WM<4A-5H>zGo zA5V~fOyB#o{QJ98MU34}>!Zdy0ntD4^Ykn|A(m0yYN{OzFF+d8@RyIpc~gc`hjzT2 z99CBK<69I$pt&%So@&--)NSaso=jQk1F-M1a>1-OCbkWPqW&2gV&0ghE4BV`v-!a0 zoMiX0@tPUyLkhTmdd1zZcaCgTY1XX%3ZcuAKmuMM>Jr?LtY7!P;V8XNkwB$}$dIMo zMZ5MUEF_@9CK?m;w{{lV$IlJC&MahSRN-=m1bF*~2!;e=(BI?{`SEJ^;Bf8R@4?j5 z-P+$}($&G@k5}CRByn#9@QLma0(2f%U%`|y>-<;rXwP21e$_-czaN;@#VF`pHVt>s zZfsm1T)LTMfEE#4j@t=qZp(G4c+zQxBXVPHKVN9ynk0@5zgG}1 zEJ{cKGPIYq9>V61wdnr^o=ysQ$NFerlC9H{XK*%f{xul)pTSUSa?kUF zCcd_W8Ul=+&TARJH$pl)XK{l5dC+%hcx`qdOl17W_J}L!tBM{s*;OL5$>mt2!cnga3sHk_5y9=5fl? zj3yqK7bvKJQM=gho*qm#itTNq{n2?SVBt7Gj@M+3^aD!18v1=Bz|Lg70fs9DWb`hg z5Rpz}U-HYA7A3USgNZmbH^5xM>yQX2AJ#qO+J0kx4kfoS!4YzszZo0a37!VF20DvC zT)`5~dp}`JUIAL|?#2+ce-vkvOfh5)VpXS&QQj3nwnW?viiQA0~aq)weh)+fFsX~%I$jvV6 zct=&_uEEGuI0u0O{X1%zS+1Hl-l|3?rfhQ<@3U~)U*~Kp*A_VhWm}Z%`Hh~B?g+>a z;gnwGwd6};PQWTplZotS(F!j^M!P5(N;Y!e4piaAIIFE1>NEE4H!oeD+7hmP+H$~e z7;lc>9nmbHDlvIs#l4E^?$1OV57{sP9XV(7BG?RoQkEM&b9;h_RH4yGnNB<11-J@a zTQ_L%m^o%%$1QCP;3t))ifVBj?#?!Xtv=tD0O>}n%0Q#Eg@U97-wej2zb1H0@q}NZ zzJoECRZRc}I<&k~){^zjALBOjP)6ZsD{dPczjah@DVAB)8yz&QU995XqYkz0S=b6>syr3wu7eTf&&Z7b3DC@-}0Go(R{a z@M2?!C-}1bwg7Ml$2KxW>i}g==cZDyWV`^jMU0Ht#v$aZlh8E zCgZ-ie&biaDLHDxX?4TbOi)}Ly&}K`hq7BX)ViQIP z0R8dU8lx8;>Yon7P+JGB=G0%JKCAMkp*zEXJoNQbk`@cX@Wmnw{RvND{TmO!sH?}x zf!IKm6SrBT8$?XvF+bkX;z=e?QZmztKQLi>#kOmhjD5^~Wk|8ZYlS%0Fh2jVA9uQD zg?7D{qWQEv>Vcg^(s(((7n0*zi~}2tZ`m&Z zaduFEd3_QeFAo}!|MEdEU2;3-$M})Y2w-4&NmYZufKT8}(GH@w7buc}Gh$!|wsyZr z8`mVBtWYHT{bIXhQ=cCkqt4kOAn0e#iCld2l+igg1MR8CKMJAhN0df7Y=QYE}dfCB)0v!9tkImW}^ z^3uDYmxtYle~64Q7phMTHaW)uHc_uT88s<)Un!KODKM)U9UZo|=Y;@>SlOAM-qok| zOuHJzGjZQ$H-vx&DJI<$IrdimO6EWS3`O1zH=7m$qefnN)-V77n1^Hy?4d8qXq#n7 z0N-4ei8-r)9XPKq$azFp>)KI*Xf>{wYlI4^wexINT5M)YHf8`7=DV1(h=U0G23-ux zbb>|>b1Tnh4FJG7e9v?+L?;kk;+KHZyNl!p_x*fty!h>OokT)a+QznTT+%MxU{~3_ z!L!87jX~ysM7S1Rsp!+_X2HoM=`p7?7QergD> z;H;f~@HQHSr|bL;ydRt{kHsTab$GhoF))D*ZbZaToZw)DX!_5B#myYC13PyVT`PCfh+^3CWk$DGM&7kz--L#^UWlZ@C zHJDPjZ771_JEn4f89@ZQERKpq6zf#XIgFR|QLB^*x(&34_PpIOL}~VVz^YJ^qGBQn zQ@*6i?+=5LwXXezhggfIiu&VtE!a8wdg2Fz9WxAhTme>%`#t!iO`@OiXr){xtvkuF zH#A!itJ?5+3`OWObZI%HA%JX{UeaT{AiJZsq8+St2xtHiF}8BNO0-VDhvv_?z)!+6 z+u>2&c@Zlz`%I1Ijbg`y@XTr@tc-Im>u!pu3<20THNN@027D_I{2agu;`)jLgBoQ4 zT-mP1C{c$yP^4$&$h~%;OZ8XL^ds)Z`C@YMfbPJEMW&uHd*G>zbHKSSWNORe9TVsx zZ01N=vAlLA<+U%>yHG*dy~Y8rsB_RfeTse>e8$w?@xTKBB8Ef4rIRW==HQ5v&?c&x zm};4roH*2HOEMlcD8Yr+e?ORCCi47jU09yb-0_IA#KCGYisb?Y@SV4F9gZ+3Z6zT3 zTVi7!R4i5B2pB5BW2!=G$2?&f?Z1VR^vSWoh?~z$YA!b?U+bsEjVfIDOeg0`O?3^2 zty(*Q=sV3Xg9r~A4r-cLL_H%@j<_nf1QYwm`ZjKGKkTNK!c>W}P^9)^eaM&)pK&M3xkg<>6}0W8z%-Es}y!z zIqLRldaDe9BjtoTw{Z8tc7U$9RfB#iJ8TFUw+gk2E=u4K*YI&WWO-ZkY8AL%8J9do z2L&HSq6W@k7`jdFT4AIvx-PovtYsL#x2LD6UW-cCN~}k`IUL)7Md@xGGH!&k_s9Ou@xo(Y2|W00THuHrq{ zpn&Mv@4IIHuP2`Ddnbg#D#L5_9s?T>P01`mO? z#+)uD?h#$kApuxZzjh~?XTEf8h3sxlA)qAzAu3-K70;lqRda6eW$0c$k;Z*H-Y4H)dCk%m*ur{)<;wY#jE6Mlci zwJWoZ!jxWn<>N{WoRAxJK>Rj7^QXePcL9g{8J~-`To9u8R~y;|lpOBeISbH6sopMB9014$u)8F@)s2|P9}K}HCQTD2Fh|4t z31R1+)-GXzgo3s){hTnOdbRhKD@zQ+G!|YHp4)&nY1NeaA@wGBTU1a$9swl{PrWFO ziLtPVlw*!cWZa8QDYD!MXn5kwwFnKc2)YQZWIVaP*EM=9!JihG$HG`;n^SMLV9ga; z5M~OG<+FuNy!b7Bgwjf@VJctNs!=6HK~Xfy$?$TC5BD=%X z`Kb+K>t4uXa%2`EBw`bian!F3@BZ> z+1o-R=qW<4DFI}uH*cCE%&Tj4r=B#}eDM?%B7YWZ?*c(iTH{S!)sI$>o6i9b`1sa^ z3=U2@7dTG!O&JnxK=mouls|M+H2@EwHD3=A9^-R-aUc^ipStd`OjB|fNHm`mYu#Xi zNVpSNu?`K0ZCihY@OWcgWglhGv?Ymi;s3?6zRY#*Wz+t-Fpb5%4bCvqA^dSjWRH0^ zAOGWdPgK4h5ZyjL^Lx8(Y1(fPB`(E3E;VQm0>F@`s&S;UuJck;S|BfI#N_lW_LZ0O zTTBTPKjIOv6ToW@E8>8%&kJO!?k=k10{?w_``J~SvrDmm+@r5~vh`ZUjs9NC!<|2k zrbb(DoqFcjHNz6S70Tl`3GgdW*&$V~%)Own0}JgOx>1}=7+13A2M~Zr@F1xj?-$;8 zkNZm11cB?gQ(o;)5|zT<$lpv-3e>-3XIBb=WW&B#7k!a{N8iXI;=JAN;jsZ~ngDSj zekFTLfs?9frhIu_)5ve7ec}jSQyn@l4&CxlZ*a^xy9(uW-(7IR13>&i{q5AS_&%Sb zP}KxqQEb4&NPaKw5$E5vX+#A1QW+TL#~+nmf{zIC!i;sK~ZY7(%YNUE1j#Qbl>iuPn`io3f6i zkNsNMn?^Klb3b_{x#et0aK8_Mk(~8q%Q!(1+h}?#~+`RuZ=BaI{KmVnO2zd32 zs+uYwE>X?8qsw&})2jjO+jqs}Mj-(r!t%tgIR#>nx==FaUsKVB;HxuAl17cG(M)<<2^gS(3pS}Ta`iapf z*Jx4DOtciFYM!9d*>0^r!mYwqGXwly#2@sC&1NCJ?b@Y_1;vO^*`yMoqCgj^Sn$Y> zJVaTaD1?wu{U%u}&S;DpHAAqT556H}W5I#Jb(Dn=WbQWvBbUp;^wI%P-*85u*b;k< z9oVeCD#ZVOy4hD3tsnG5__V%1L;RBF5wdbEgTI)-w%s33nb;|mIOYAL707iDgOS4e zIkre0lO|%vZ95gaknDSKx8f)8iHagC`#vdSH7Mwz^EtnSZhs1&w$v4&X=bj$Il*}C?LFNVj4#PrWeg8e zC_vtSx`!LS%0zo@C>VY3Ei0ybY`kHUmsQ&YK%YUQJcD71392UFx7$~q^)d3}`*y0+zcQxOcDDB7MSZ6ovLH;!|q4E75@zfGZ#uAaPU)o1ZP z%;sYE)Bp_+(DRLz2M4^wCTT-1GltkFDe)WD`<%dMDUPHxiTB*Z&apDe7rS5LbXumtYQ;iz13zsV{xUynXXZQ zE4qIdDXZQObLEvpX#XU3Rh!{Vmw|9v(-)|4tvjj*v+CxlF%b7$U5j&Y?ItrdBFDCU zB}*pOrhBvfbCA9Y%8@DF_ORd0?MS>aqmfrZbFcoWk)@T|7CmAduYhXhnI=v?T?Nuh zBueG$&T}7ngjDo7{z|jp6NTl7$9I5vupk?83cH(*4-Cx75@1aBr&)b|4rPQggyyO% z!{Zlqw%5oW`NjB$1^`n;(cNbgXj#pmJC~%Wsm066JKMPUiAVfsltY&-8BG!U@ekP$dSKm#NEe2@0pK@ojZH2<9anP`Rt6h4MNmbIXpp47b^l9-8`G`;WtI z&~-nyqe}#*TKaZNRU&9{Rk!_y!kz8Ei+I=Z;AyWmrWJ&Ir^f0FN0de0N}zPsa$jv7 zN?rtB#k(~!QEmni7_=xOzt;nlHOi@r^+(~VxexN=HXGk;jZgOF0x2kDJjkH<&)OFK zz~t#1TUxYO?b8zM_|}uLz0E#iInPJ?qg5# z@F5I^$MK)to#3--B$nZI?RZ2p;i{m&FO;b)9woE03J}a=LBZJLLv)bEVs33#Yf?Vc z-JQ^A_(H{~%$!#V#hjG!fsjYMy9<)R7d+vXCHoG+J5}Q<$Hgko`WC~bpB{1~#yY)v zL!$tO+DTe9%uox_5?OO7T2SV#ump#>+^dqI0k>nAq_s(|r}wrwS#JGUZQc(=_C0== zT#(+#GTJ~t*3>s%foAqI`7~vHwJiOOuQv5OO%7Xym-+TTy>I5LaAsfEc|#BYc$_^} zH|Wm+TC8Pr-U|mE7bE2q6jTKUu7Bv6MH7!>S_-IC;UM+(=#IJWg4bBdOJc46JQ_ej z+*$<#8!Wp>hv#*DWWmSgKJ%pHI&PKa#H-`Xw$ner=5KP#XQ14Ib>%-!iRB%P{8?r% zjPTs95v*-Lgu4CuY>KOl<3y0!EM`WB@|O#fa{cqritI>AvrDfI`xy+>622Q%sglfs zXJjH7Z7djo&p}UsXV5&eNJ~V_KA^2o#A~-=(1?KN(yS=@jh^7}ba_)N$$u_#%~h%b zB4{1#3&W(gc*S5g{#M|_idhIK%__S6yS=6!vt(|O$mGa@OXiJ8+m+!ZWsPl+XB2XI z^xM_@RhW$EL*N@VrtOO~`{7$9S?Xu-y`YD;{ivVpzb4j)DIPQ=%ov4F8gT&1K+DXI z1lLVyQ1Ux6guZP7rQh zT}Lk&%+3+C;P;AOvX3G*xA9_qRa_^YR9%p= zeIX&i>w(+q_vJH-9kTl~F!!yT_UXxpDe|&q>giri_wvi?#Evj`dY2zXz{<)Id!Hd)7 zERu&aOBnES=RU41e|Od)GRfvmVUUp){QIVwmsh)8$h>o5Is1mP;8zQ!g|^Syqt5gAy)_NnS-54217J`TcOrQU@ACli=I51c!*E zW_q1REZ{}qb$<$frjypr1O!0%5Pjx;#EsdQ0kiU{u6$7Rph@T8P79oLYZoYSBYTCE z2rl*dH;9-@v2(b)Y!2UgyS%~bqN#I0f3-13+p*rj+_BMqa@@r&86fy>N#oT@dvqRWulr@= z*&)F*`=C^C@GEFLRUV9Q@8{=x;JdcvS=-oQGR|tOouo!)`a1YXwC=4*QYav^wh{q5 zzkgw?dD3DNfy(DF7XsC3v7qp0jgBJy&`_wJFq`qeJFp}MVXKF*0b3XKJX_u#*;F;$ zx&$6d@Qd#2M|&c&Rp&&H(TVF#_0bkomc=1Cy zSpxnxw}Bf&8o_MlV`3u!QSQ$%a{}V(4><8Iaw9){Tb2Uy8{zz)@M%uy$ZOiX(8Fny#lES8dNns%T zCq)haZSwVk{eMNi^8X|GYX8sVOGNd*CSR@b{}uU);QD__z6h$un&y$pH2rUS$QdHt z`W2uyRDpd^Up-=4DX$;N(>F&&1+;Rf-(#5!=82q zbL5CrH5{j-*Z}@fW8Jm>1W*DhZK58F1Mv}qhLBf93F+Jd-k+3RLXW2L(Wmi ziKTu)NntPW8ijs{HajXp#?doV1~?okdPx(UxU`RIu`gB-4(UYvZc{UnliHrru`c}L zhg7#5_1Qezg4mba_1B=WcpSV&YN0_~wsa#l5;}(0UP<>D24e=RD=?(?x-xZT)$z3_oLe z6<^x6`7-i31qK-WMKk{xR)CU(1u|FqcoTyyDpa5z}SzOWp7+x2HmZe=Gf}8j3~{DO`y!~sUXo(?^!feKs?!k z_b72>#kOe}k7e9$wM)LyafU3;Afa%(jcB%Xrh2HCpn1PO_<|Kj%xE>D2ZrrNlo1Jn zXOH3nZYk&=A!So%BWoKAe$a15CL=|)?_GHN{n#Mq+r#eo})+_%#eZw@GX8A-yzY#V%7{ukM9LdC(_GqFKpFmEbv%* z{H}Rt)?D3R9jx|`Uo=N<=v%FT%_)5ube0A7rADCF=2cE{goD${CYzv6P#>9iTjRpc z@1SxKI6mic*$H7r2!L<>)sY1VV39sC4;$CpEMxaSkt)+6X<6CgfWW|qp!Pu_>SWec zPL|TovXB70e~qas3bs;OKY;)MXV2FdW$O*6io{KtWE1jDF!E0u)Nc=q-w_o_rX*)5 zl!X>!&`D{B^&`4m3$C%k~TK>XKU^r+S;Q}oDfwLJKqH* zM*FN9!!qo2+*FKS+iSnyYk8>-e%_bx(;c6iEjO=(bx*-rWN0`alh}Akpmu3~-3DgU z{<2_Hm<4j)O^m+G|)&cp)srGU#S4nQ3!xXFxka9yAPM8`WS$!qX?f4O)fl|jZql@4R% zfsA6Y=1iFx>l8oHg})jJibIo$u^WH!f`PzWa>@PqjiSJYi(mQlMF8hVTh7JYCbbu` zOI3YF^S}en5*M4}D3KdD;9DFbMjFlchf)j)8rpONGgD(TQy@!%e2tUJkooFl-pXBG z-GM=-fGYF@4(~x5$8j%p^m61Ae*;3~&HU-28$Lrxa0F$5;3*t=-*zOZCuXo{<^?vly!HJ=9Y4=LTdsnG<9aV3?KVaHq1R2v{Ixl-|zHC0Z z(owtl!h9P|%F+j#N8%Urua@MMVM`|iMe6l(>E>?ZI3tR4-Z7i!E1B-H8@74A1QJN? z8=Z}pH*Hc;%0>^SxC+?`8cZ_$*@Pba5^2O$-uA5?nMPKpjFVa2xEoEL56Fe%-UZt8r~S@e7`zRHd(z56WvEJHIA8AKJGT#jkpryW}O zPiG{!&Ty>$hMT*>m$=&=d9`?pSy{N;ZTq1IBYubiD@DU88DvG*JTqCG$BToW_~iE| z&~@cCv>T~NBGS&px3kCOAio#i!Fd62D2^xMiK^L2aYZ`rmXQGNm!&7_^P(&j&l9lN zmlaK^r4mE{^JLpc+sInzH^Vz=kr<0ip>&wY37cqK^TrkGQ?5jtuhENvNkmk%0DySA za3;x6=R}fX2hWmW!m3uQ$*WgXm>EhYS1E=eJJ;OZF0-6$xINTWfa9iECS z$!ty-=amnQKybn~V-j^bZk!Tr?P+y_gN@7%4*6 zierL$SbES3KolQ9M^UrAt?039Z>(b2Cxm9c$JYE&NC8qn)n(dDYqJaFvi9yV%i-#r z;h%;z$sYx#nH%>1H`S2h77e{w6d2#pF4$H2KwWQIq?nl< z?+UkAPj>*9n&fb?$DXvTH_MktA;>2y4RIAas(W)lNzm&MJtz6gtN@94YZfxbaiCT< zk-8fOOeg>_VE!y%0Cgr};6#72fW_%y2<)Vi#o9}Y-TKJZ;J*;pTegUvmrK?O>YK~H zF=?dKyCyw4aR6*LT9T{J&fm(0#_$TvSLfTcBi%3IsgladX5cJSu*cxJJ<6 z-{_t1I$K$B>Dkbbw~Z+nRUhuo^z@kV=7$HcRVMk#Bh9XsU(-m!< z_eRQ+9w8&9$G0(5-p)(}ie~;e(+;blPl7f$;brgl@Jii7!IgmQyu=xX zXh%w$zNw}LGr`nVVmyDtz{%=+Q+j>8SZdW)w!bu@V-kf|-X;p^Fx{wnYu+Ra^bSsy zvnOx34#9-m(e=&t)y4YyNpAfd0 z!#TyfDXIS^DVbq0fxc*iL6G|WH;)60=z#8>lG||#r`h-;=_yB%qfqIGniW|GvhqMZ zmrByNlpcCqcBvF()werNPpzMbrRFtHL$|?5C!4I;+Gu9pwLXzLFpZomn##V6X)5{U zy91dX4wft~);8MFeoyM3tyS3Pu8OEhv~ancD%&eg96l9s;vhID-3Ylu5*3_y8YYRm zCI2)rd|Gf(2wI51oj>#nvLQnLwrqNZFk|e-Fgj{@P{)HYf9V}HbA|C4A#Cv{0%bF` zr^RECJQhY15GRNp)>KjhR8Sl!9vvRh79Lah_xDo|7;oJ8!_-yNW0lflQE|0$#JLS?PLx{L&Ofz6@+qX%e0z2g!N!rSd`+~ zZ6ncdaE&}=N3?cLS2yBVh_5N+vu*kmuNZhxp)LF+{lQAGvQLH;q<|g_l709P{sQxNhy;@K&mj^&K~9%m z&EqP_yDe?l0d0&?9qx7|usLN5exH7|%>QEUoueZQ+dkcj)v=9^jgFmkY#SZhcE`4D z+g8W6osR8vc&fj5-Z>v<&diy$&Z*QNS^1-C)z04aJo~=x>vuoHY!)>bv20wSF$QK{ zi*Xb=LXVae0I4JT@Wn&6V2{C7RFHyU9UuAvw5|NHxh~sd z9~wAd1wM!@zeV8xDM*^fCHaVhrf94yk2n)h5EcP7Tu4p^h+9}tfzfq`-!y$eSwkhi zhhmEju4cUOJkS=*2wC##r;Pp=x9nQJjzDd##L0GTGUSA_-1 z+&*tw{%w$N`YL=CIzQm{_q91GBSJ8Uq$o1rTuRpi+iV(dOvf4`Zt=xa-+PR4;9X-DqiqS= z-t4Tr!Q5ZKv+yOvPLkR2w)+DOZ7Je55Y6x#vtWCO)zP<^h`Zal1RHK!-@?{0%X!=Q zej`SHvf{<~;OcLx=ynkMqdSZ^8G@1;&5o|q|07_O8vmaGBkVzQ;~CR?vxDg1X99*h z5guQd6yjbS^@j|&W$Gp?)l}LR++lb3M-LdS6_}oJs;ok)D;;99=$wfRfe1>3G%mC% zDd}p9Meu8TGJ?mZa zD*ICE4RhX?3tsi2!8L#C<_V;AM_DcypLImjW}hWmA@uhjQ3TM@-#IRLI%t{l5_wh} zQbAos+mdezea7RAsFrgdrn6C<~ zR2m}ip<}(H(ba}j8pBs9j39m+mh}}$qCY%-xTBWmbN|>JVoIDScnVJg2uyd{Gkb;& z+aO}Tq^V8xow>@9P~bsN8}9t0q>ff~^EEMJo}fuXAozjm(fUU9EPxx+23C$b<(S>} z{Zw%B>fP}e0I2`E!4{LpzvA4WdEx4PSy4Mtp5L#?6`TTWw5$(46K+YP>NWD%AnD<$ zhIH8+&TO~kq%rdbAxipfk~GVtZ5gUU-`Qyw9%;CBB_9gKFANisU&^Z9b7*Ndm`)wx zP=Q7G)qkoQe#@Ck{bD6*ctKPCm{*?o?mS5uWS(DhUOP2*x-R|5JOw#^gQ%uVfzbWT zJ}nf{izA64x^;LH;X0kL`CgJQBI;|w{{#-zmN)P%#A9&2H-UPJDXCP%biNmAw+eNO z!KjXWxP3m0loWXOe3H!Li^wLzxvz_58$brUKu5M(iJtPSvh*Oe-A>fCW^>Meu!vec-Do-pJwgTGWTJ**7+FXBF4{2Wt~GN9%V zGWJSQ; z(cqX=D-jX%u`-W%?ueh8-Ws;i7YUTf49xBZ_RgM3`S@T*eeJYy>Yhc#`T-$E(m5k4 z*W>lvl~nV&b;gO7?ahhZmebnXQ#wlp(^IC%y*^#Kjw;ID9W}Eo(K%!4N5#bV zUgy&>Y7B8}S50ikZ<17%^cSNyZMvrGF+^{Sq#>L+?%jnHPnaRGQV6kEe1@}mUKrGy zO5Q7(QO)$!Xn?hn6$&wvSKW~vga;{_6D&G=`?*UA&~vGq46zXD&+dUN2tee9aPwKw zlhuX`wH4t^Jpp0XzE2i=D;)<61@ML;_Ly55e~bX5kyXfWY_?4+7H|arRA~f~dT}jI0&z=t{(jh%m!Adr5Fm znIynQWvd`JrzLr9(x{DWvBtM_+(tVmeH+LBg7S#CD|YZ0GO$Jgg+819Sfdvm+3AwxgQWTR8}ol-^dQ_{L-+wmS)uBNMw z9D3?-)xmEyHMbkdnJlt>BHJ9i;@HCrDu`8jT{GStlDmw40lhcvC%Zw%cC$?~c>lHd$gY?=da z^)RHY##z*`R2t@@(b;4X6EPge$$WlV_zGp}(L$hpMO)e)mj(i=?@GE>eNZEDS)5RF zeOP?kk$jg?5dnM5@|cAPmW%G~hX4Dw&$ayz%piuuK-LQBjXlc}stCZ$?LI-J9>I0) z!##*kHED&M`YkRXHK*ebE9A_-f<*-s|Ex5spw&+)_-seRgZy+jFK^AzZFuai8U&7T ztE10mJHBY+V^YBbi1vkLm8gnT!f1Omg-m`h_78rtpO5TszHzmijXGF?HDIJA%u zG8#Yx2~AKldyNDIcI>oV8l$#Hd3mN?gI0_bZ4r$MTD(Hs)umppg&tV`{LM{`+xJNs z`d`qaWuUr*^!BBjPwl9SdEP>(pJ*9QqZ)91vXl9TAT2*?>Vx(-#h)XHn7#M-xi-TN z$2RD8;%%i>=nr;cnp0WLW2?LhU{90k5g&Jhv!%Z2Q`^_SCcz4 z1c3$+L_(Qsitt4SzV|;KPWb9)pFeautLZ>M`eGn2nEFSpI}*Bo*I?XkgR0=P8TDj5 zAQ{j++ko$)0htsb$lR%(UyY8IdBFZvyqWUlwD*-DO3!y(1lW05@1&IP9jrYqGrUBt zPOpCt=|H8`-p|KxPrm9ocKy0q3lA5gyzm#Qn$n7>jW&eTH7p)eXgWc9Udz<#kUnu_ z{}DBj_A3DEB#|2D2E4Mui3bQh>@}ZyPI;_c`)Eko?9kr>OIN@@X&V3ktx>V0NWlIw zS%s@r@$c<0`ULfkram1x}W|@*z zXw=w$XK&;L24piY$3<6r$hW1}qzVG)0Axy&v&lkoy+zs*%SK0JgiN$TLd|SJt&N(>Sslp;)?0)`CL~#bY z^tqrtU-9cQl=do<#P3oD>0QK>pK3;mJtD8uH8`;@2J2Rq+~XI0yH~gFGzXtO!AipG|I1hj!{9Gg0!{%V3c>^x|Ie{fogxq``9Na*{Q=DRj6+5$ z=&7hGP@TTiOynbJRrvmXspRo+lL?C{dwOjTmaA%BOwQW3u|@0RZ~rN`oy%!blO}h& zyd08-4j~OR&Skm1ou?bmYvC(&(MGX3T03~46PWA2dATJ+&- zp&A+5Sy@9gV82_q0ZFQ{ef1m3?mT6`006_K+efA!b)$;tPtjISlt0RF)ZN-zw{wkg zp08c9M2sLg@p%vP60luPI`3}$W60XJG1!MCP!chDFP_f_mr32#q5`LcYLwtkzw#~A zfglChhy3cAWRa`ZxZNw*u!E|x#*|}^&UPfp0zu)rd&h%P`t{K)Ta|>*V_S3fs18rY`o{o8Y zS1m|+86=rO++RB6SUT#syg--7)>fY7%PpD;Pr!j#wk(4x7^J_ z6YVkP);)*<*tK?>+M_FrQ)1Psc7S*kJ}RcNNr)^K|} z{&#!d&?v|;9Ql=A=pO3iqn;e0N6bJ0Cm+7jO4PiLI}`jTU;H8`yUA4rMTHOKiq(EZ zX3mtM3a3dU00b6Z5A72eqH(GPWygMi$i_3y=+1A}tj~2>z0p;_G;VakHbR!0bPgzU z{c;`-(;~z3Yg}YDWOl7#UjIDZGewYX8=zs%?y;kd(E_<9ww!?NsvE8(_o{a8wM1?X zg#!2mZ`|Jpa*2z(>8*H5FZjFv>M|_AQTTWGh^?7VRC3-ZB_(0=w+}1;m{YN^a%RaM zRCEJNV(xJ)XpIN~TS9*!aU87kgUJ~W5Q~47;5aJ{0_gqY-Od64pj|RGamCU!GW4nu z0{|k{nHB4h!`Ls>q@oggU0nnr^hP&q?P7)BOsnkI+U@2_x8?wq7N=j;aHnw(tooQ& zI7Dom7uKHdn}CIUtnt}s#2#p-ME#)Bx2xn2&-1Dfs)XYr^CW6L_MSnI|1Fk6+qPhD6h!U?qG$rSZ0II9N$h>vJ1%tgmQrE!J>QBl^{@3IDOV<69kFX8C^!`Ap zn&@cg7J}WB)%$=fe(k+;)~Ng=))2sqiU(t*dRS--pvD<38z*YQ|+ zm9aD-^uYYUzOZ!Xxa{?-s7SVQ(-{VV;muI0%jlc;l9A^FquAIPMM}l2gSTbh)q+1y zw}+`@TJ-g8T++imEDuixDc9!^fnxrQD&JFy8_J|Wq$wKCI2PY0q$K$N&c|8`|93vt zoo&mS7Fd!(JcO*UI~Y5+tg)s8)takxPBUs2ccRn=30xy_HgFiG9}?-S>^BABqWdU{ z(r|mdP}U`OFp+RzM{~(HgL!C{aeH5#ORV)-0@09~Kep#7yGN%+HVvcuS#Kj{!ChK1 zvE!adjdN4>bw|R7glD#HQCB|!fN$i4%xpT%mntlY+PWOWb2AfjGYcn13MDRkmQ_ed z?!wy@eOfQ1m%5hRj!{><_3n1Z$r88F06^Q*Z7$8ScCZ>BbiK1(W{b)26kMDHtCcpk zo5-PKV%if;I+E}%C25%qzoYq)!B~W~EWK3Mr-WfRvk2J#9{vK#1uP5%iF``QD_98x z5Esq5O+!vacVpgas6F}yum3pd7Y8?FO)79REN-ZaHuM`tnbDsJ582<{{z`_xEr=v4 zSk0fBt9PH8go31X-t^HW3eyz$MBo**8@o^pb(yne_oHMzqkYQRf>E=-=u88pAUO)@ z(u7H0MQI+VFbY!+n`rU!-VGD^o04}GCRVxzPP#_g%h3E!WXC@m#Ha#+)N3b?NHrJe zScTvrfcO`2VR+TkN$H0y*DbW53H{+tTB4I_EFy?r>h_Btju{5Hzs-wePIz72u<0S7tOR|g>^)z`Us&X)XLyr{CAo{7fuTu4$pk0|f?{kKZ;K!@e zQ?~Z}?~Qv}gs~gjhX!M^-hfi~!}lYVOZr8k3R~uI?K{#vWjiOIfH(P$O`9J_bzTjA z1LU2gKiok8;-_@C-vmFLyEAW{pTkugTraY3o_OhtW!!E{O=1tOm6!SDN}7F@X)Voq zmaA;*OZGExq<@q04b5mD9F;q|zR#6vHuK~d`7G%t4GkvctKz1_czKePfvOxY>uI2j z%>8DQu^x5^(=z(WHqgW)3xNdsuSi%H9)?Jf2d=ss{d{=@&q$WZukz1C9YmDO(`cZg zIf<8Cq3Ak!&5=0`nu~^5#>rUpfSKNq^Wk}f4o{S)d=*pbUMyUwD>e^O07PYMk7cHU zjzD%s(A2Qse1V>y-mtt*)unE7;@grA7K^1t#QrC&Yg7I+h3OmTFK0d_aXGdcZKos0 z4lPnVZ2t(_zkD~N$#i`xS;9r*%<&KvYR9^LtWspE-`cML30Pp)u)iteb>L*7VK&Hz zYjVik@Ks9kQ^e43+(=<}009nt?-I8js>B}(FserL>a!=yb`OH9`WHqCDZ0pu$yFs%viTHA&Yk#T^>dj1y@UM{lXf8lLqiZ2L4+USyC zWbaVSs_1C-V*M%k@VRs{t2*f_xro=46F2atIx+ElWMr0IIn4qPjh;p6)h_$~%4(qf z1!2nUjtPFYUp2YE^|XZhqusnmR%N?BJ}2Isa$&j(Ef4zRk;15Y=VL5J_g z!<0q^gdgg<03sHTq9mJx_a=r4O&nHbQKga?qnm~TX150=_X&7CCT>MK9a$8>Df(eq_ zTH5W*bD&1g6hS)@%pv=y+udZMKBNScz~wSEZudrFLvAqUGrQ|dr6?AQY}L0DAyGTx zjr7|Tvs44MfS^tor~u~UrYub&4r4dJgv;^4O5l=Sk-2z5?+hNRa##Z1OTKr{ z(hIhQ&}fnRkLF7rEGRH=2=M({4!>KMK4MF(n%m9VUL$!1h^drtauFhS@jSmXNxYkH zb>D%Agvq#;#!$A$I9T&7&->6SI~?|0buRrzZpB&lBvkpcZcW~ctUS`vy^@}l zImnRDA(fe|`sK{^xgCX2dC}-D?gZ#@_t|oFO3b~PeB$+>*|;{hl>C%$qj;YV zSFA2KwmONx?ixroDjmxA<+P;R`P@#mJ++pP5M*6>@XqOv!tUL~C71t<&?nq7qE3%E z=+YtQ*@Vs$?DeyY!$f&Bx`miG@T46W*E?$Fe6e)v89sTAgbooo{~nTrOt`-6(+6ZM zs<0ywx!kkHI$D5A@z=S5xQ6a zecwFM5KgzK9Bd<-YIi=C9L%&-=Rqn7;PYk{J$*r#4X%j*60KI_3x=OI11HKtJ&2!z zf-;P+8C5(8)?fGU5W+#&%9J{3qcdq?&QcJK!UkSv=rOIEw=@>w=vVXvf9B3n+s78D z+$BN3Sq#;>?50K^XZzaF*W%{MpvZ&)Ol9*^Nkb9zR(#v7+u^Sae6mgR+wlUZX7Ctx zr`ve0SazCqG3}sh;#V!ZV?8ERHQ`!|pnM1Y5-6%hA8Z5mW7EDtB!=rGEl2u0K6Bpc z5;#pi^|WnKPmxeyAP^GB`U?PT5%AEGFI%%R-LS~uB0G07mK{>7bj!p*0v8NM3H1vQ zaCMp&TGCdP2TqgN&-eu((lg8q8huc^iignX5*;{|!#>Sb&Wqs0am|)Pzq-A_y^-t+ z+XuA%7>c#)-pJ}BAB8s-r|G`~_m;FvF#LHPPRUlmuUVkMv8W%=B~A#$oX$>Ue5HG> zU0W>2YUf?3&(h<@OBi0_lRGTS&FE+rcOSy0HcKk%a$a&88_*t;gvlKWFeo^+2v*i09^2j^UC^Ky<=;9s$}oc|eX zgZYoFP4T~EZLXiBi$B|8@An$1ZMcW2rNTd<$2`V1ux*X3X|~TQM*5n4+gh$V_ekyM zJtrI2ciP;<$0eCE*Isd}hSC}K-f21S35W)#UDo>Uqj~34m!4lRMRn{IB&wG3doZbv zbla}07k|0?9H4ZJSeqIDl2z|^{Qu10nrRme_|JIU|2u(82JnAU;8NB2r@$o$O95Ux zj)E#V8bB99WoMdbi7j_JJmrx&P6v^%f9&MkVe^}fX5X)qiTjQ1eal3*(odXJ9MVS@ zeA6!(Ar!brLxxeg=mS5g0^5g^P`^Gz!08sO1GD3wpMYB!$gChN;Pk9E5ew z#TE;V&{>J7!6>-fql=92d-VFj0S+~z)v7o_CqV}?rQw%>&bY(!%rRRuCZGV`yP?r@ zGJ+0X?c>kkt+Zj`u6N(J_q4%oQe=@L#m)8N#&+u`i#$p)kro-Jq$=+gv?6gT>T<0- zv+c#IMoAKlcyBXOp-1B{4c6u~g8)LAN- zR@p;f07U#l#%JJ%zj)bc7JTu?e7BQyvOn8G!}iF4@q(Qn!8`avl8jl{Jp)ImdSERt zQnC+E@kx!AAR|F-8iUekEv$Z|6};bF<$DAZOj0WwuxQ>7M=DX%=(_Wvt5O10hRlUC zlZQ_LB*;th2K_Xi?i;Kh(c4==dE?byzTc+HMqcDaboZW@CGYWtWx5Urvqn%{F1u=% zqdnjJT_kcMsTHxT49e-IB7Oq^GtZnqryA6EY%-7&6-!EsH17765)7CKpBoiN-cgY4 zd~|lQuLT|w*t2KK1`HrHA6E-<4G$a@iCk z5~X~h=K)9r0|26_Zqn6ANE=hcu~Q$*<#^qxY$u1nvgKWtn2QrB6h%WK=RTG=&`k*K zt}AgJ-psT6Qy;jc6ZxL;C90ufQ_jN|J`Tmy%uRB*?^Ud4pjkh*XI>0mN{Zi|%f{Az zg{ZQ@C(Z`fziEG%MQ#|bjKrzrGEKP!WfXZ-J`Jst>D+E4thrw1J%BOmQWT;uCn!5j z;$d1a=IeQxyD0U`NZ{)q8FLqY>*vyybS(wO5tJm$GMHR{e~Nm16}H-rz%INN0}oTl@<^{qpMZGmb(J0}x6!Hc(&i&7}g zu+H>U0KwARCyAN9>rN$J;a3qE?wwn$^Oa-H1&UFGgsfb6^rco3 zy(1nD{R#ehNnffoH&ZSs_`hB6=CIb z+v!E(>~YY54=dVm-dHDwdTD9#c8@feA=3A~VTCxLK(VKcR z)@a|dAJ2!!v?>H~Q*p2J8AX;6*3!oAFQ>)%(PoEsTfW7?u=TdM*f%w9O97Lc$HQ_M z&>HXt#HJH48toFR)2s9o(rK{0KUC*X^PgG3If@4?b;DvObn}h%n<2ShHRXT52shME zzqYs;mRCg1Z7r2Xy6CodZOpG;w3gwukeu|zaT3r`EUm*y{OVOl1gYgEuwH*#CRHmq zQ3JPBDuUO}7W+nV07*-5C1+bXGHp1;hlB##JMwu=-aGp+k}$15a?sel?)<3H7nAK@~|3I35+5@M`L;_^K zK~+4+D2huD(|2uzn+QPA)Cvn`u|*N>gC^2U%O*F3tm*pG8mb0e=F# zcY$_-szH*-%!R=HZ%D9_(<~2XpUBV7vXlYfh%ZwT_Q9vwf}cLZv^Kuz!>^yFr@&Z6 zb5qkZAtMTRQJ&ZL*~YXG)KK7rFSbCczi5yv#d_aZ0$PZim=u8G9~+AST&t+aRNz_J zpjw;IlOl8Q#(sVZockYg{%*0<1sVi|B*i$!p1o|@0)@S2SOk<|ER3$GldFhnoq zaTvlkMhYD7B?ztbFLF&)Ex+wcg{d^?TemnCQXTT#ESKHtWp{RN2DO*BH%4jB$ zbn}$cDtkqTB&@iAZOdg?J16&H5l$DdFhB65Ak%N&@zKwAG+d79Lq8kqDWiUB#VVnc z$qUb|xdar+YFXC|(Rxqr!1n~5to%PkfGQkBV$U9i^`8Z{dD}tx0F8hz$)58AZp)Gu zwPy{5hsXfBGIFeyF9OF6504s?6jj_N=iI(ZLCCvLFOuJG!d{GLBJs;w-u0BPhbCEs znbqf|_?&d;L+#RuKsPka2V*^Eush0hCLW9GlZUs~tne+SBrz^Ybh6>~bx-DHIMClu z0@i@^M-mzTY(?l&d0u=z-5*&3;9Ebyd8&&74{1KX_DZ9Chxv%CDwF!j$8QlQe7dl> zm*=FXIi_&ZS&2OX#TV=G0~}4o-`d7LS@!6l8qWPwx$7d0q@o_bBi`YHN7+~tIhfZH z$+%#CC33VeqPtW!!2F!^y(=h0`GkSZ=U;=p^&^84Rz;NL?lR0ys`@k4TkCpX+_h^w zWOLn7Z<)TLkWQDO)Z~Rv!At7gygh zjGcYkr7U;u|MTG-cxxCiQgfCpW?4)Hj}-&mSyMp z!+!*kjnm`ChlwssP>MDT7O`d7lJ84pM=HuMy8R%)`AqOxU0pAnVr!hZe?4?N2=rVd zY2Lx19%V&wXKSPM#=G9?A3-*Z7W9{DE_*BMyp%XG2j|UY3{%tbjP^C`?}U-nsLX6; zk*l`nNpttnj2+)%-~mQWX})?7nQ8d#_7CG;5WJphMUs*%w2IDX)#ikRp@Gs#^*#mE?iTCaRPFWOHjfqC3yJX!2j8q9p)0?e^ z2n%3Du_Fjlk;HI6k2LdiWs}z*kspokTlgs-)r7VlTv-r`TyWla!Sh0hT1Bd(hDTs9a^jU z@Le0<8e(9qV!Es4E3r==ya)syAimMU7k@R9x55jhu#qC8a>M!d#i_>ljscp}z791O zzlncfzW8vB^GSr)n%#`>867cLVBh{H&!BX&ysn>AvI zZp@7+E50$5B=*x=0A!s7EikGETQOQABf-O0;|@|vAZORPC|w>>8VUIk1@If)-n~v* zS!IW7l5c^8ue+RdQ?qWJXyaA`6I>5_Gb#iRUQwvZC6f1SvqptPLsleMVR;{ky; zvwxfb3Y>q~Xmm2uURq8JS;90Q5Za%p*09Jro^$sJ80_>J)_a7Jl{g_?=8Sk7} z*m_-gH3p)Z^Im?FaQyaR_{0x7KGl}7clb*g8T_hhw)_oqQb$+cRAjK{;WwTrvRVlGkwJvX)c_?o-e zc98deSUhnjZ6~R=lEFd00%biXWx8X4ts9P7@MO!a=hq?5>u32z3TubeV@6Li2IdOJ zn-8Cs0?dX}1;C#$UCxxqBmiKkOHL1%03O9ecy(RcY#guT(2fcKcs+ir=SZY+pp{R_ z$j+9Bhk+T*d6f>;Y}9WQ(^lrq{sIs%YCNoV-spB)Yvrp4WWuiP%Pd{8OSY~sx2}!% zGe5xtH`7B8=nZPaY&l9nIt(bX^x8qBgL;$Rycd35ZcM?90_N zGj4A`6hK8e5$okkJ6)c66iGU!SYdmgB>Pz!izwoPYFrV(E<8s)?b1sP$WLGx@Q#liB*fsbfVaVIr$1tlFyQjXd$d{Bk-BKLGk_wiu&99km!2SX8&@L+RzOFE%;8(tmM%}K#pj*&~qwG;5 zu+Y=|3m1joj^9L7@1R3AKH(Z+=>c1_U^L7pNZ8EtF2W#HuY?NQ~fZCZp>Ur z_|QHmZ#4{*u#}+Cpp@DiD>cy5Vy({K=~b=3b8cMe$c7izeq9 zl|Re1_(DCWM?znaI#)Y$^vNM8Br5C0%Zs`3$s1(-M*>K?>}Oc9WNRfLq)NR@Ca9vBO%kq4i9FUBfQFbbA^myy}K3IatE z@xH3~x&A_asb$JyTJ_`|E}?(jY#t5`SSZ2EvS{>rKNF?w>|9yU-d+Jd_gTRLDX=-S zM{SqwJvvX_4t0-|UwG~)(=yU!mas<>h_cn$C5 z&pr)jOxKRiDx2+GNMq7Kz3F(I7OzM%7AZi9f3hkCxARG)AafOcj4P_(*U5E@xbC{P z?z*73Cr|QP1A6|~2}q=Zi01W^-8SP1BtQH$J03QQ&*+Q?{Bjw;jvz=4m*emqeBphB zbC~=V;Mgy&NQ3cXc_*T0b0TOj!d+0Oow6$E*6r*Zj^@Yk*K%US0Id=#tQ`707#|Zp z*O|JAGBO&(W0=Uwy|pX)K$SEdNZuw-Nsxt>ZUG9ve04ous&L5(l(EWd3UX-1hMXWP z$M;wBlP4x3&?z~Edb!=3@i zPErNnW>EZ$-k$yYhkg57ow-SblACST(Qhc5lsTUWFKx~VFQ?OD{!dx!_fmD;ZJQpc z9yHgGmZZ`Z2_YO|%cg1aEKl5I5fyv%Am73$AxSwpV#`lK&fuZgndVLS=Teb`FzOP%n|)C?&ZuUi#6Af!VF zRMIhx4frRo)WJWQ#~mEbUYG20>u4#SP^&}~I3)JaY39YIC%oHS9wNRHrji&@9@jjj z3r26WTa0enR&_(|j_fRWO;&?Y>58nwD1Q1^2>FrTA zAvs_{{8ZA>KmUdw+RB=XO5dAa;E65kEfnU4f>C~bT8z>Ler-uitL5;zE-(CWP`kAl z)f{@HSupc7>A){=1e8L2rAC}YqSB3A6j1q_hZz038|gWE9+U#t!Rlsgd)0m5LCbc2 zCN*yO^UW>7oEKPIGiG%OQuyv_MO-Dglx_NHS`&F8#VdE{2-xbTQk8<&Z7{xv?{EX~ zD24l1Hrv%iNT{q-7KE|#a|I>eRGgol>S^;eM#-Nmu9>p6eFD&7l_S~(M{mO&luGdx#ueSb;^&<9(j$%dO-C z;x=i3eS0amEFyP5+blV_eh8a(%w*NG>GsmT2PUw-82S4U(Wk+7W6@ugdOcXd3L8Hh z0h}KleCO3-y&7i?bSyuI_if|mn5*DbPK&HbyJDb>?%V|Gu9jJL{Wu$v2-v`>+qmtz zzj=rEE^@>S@dSG`UR9M4|9TwFv{t`*k;LyAFFb%rFQK5MgK@mfz#m->>UWNR`C>vm zG#;EODgDEcf;F5P4)A-ZrXEZCQGc`I*2GsVetzzRM(6tc`}g88+jjA32^!4kPIuDo zy;llxNyuoBr}G1bmDS9bh0}2wmv|)cbkX&vlTPg>zBb6aY>eVq#Qm=KiMGr0cmwx& zHcT5Duo7B(BXLp!F=B-CJu%aFf~K!v7|a3Wh@|5&op>qN0hBTtD2(kUrv!#uAq)XUtTu(P3}ny7XZ9C8aM40oxit_$yY|LeTl$oU5P{&(WBb>Bf!FV3 zB95mPS5XmPLLOB27L(a1!HQ&qfmS{k#hJiv6QKGx5FW zcjXh4wVk{QZ*+8>$GKrxaTYa?nCK0A&)bnyX6iYZJzc;gbSF0yD^uL3N$2~zkoX+C z@TG+yM+MUe{keJaj3mkyG5y8sH=-%-_??~Ve7H(t{{Wn=+|+)}#XDNAse^7LLq%u! zlW&Gh2jAP%9~ZWa>~-!f=Z2Q9H;GD90p@_L=qn~#7*;1=g}Hm#^5gDVbJ-f0yf|?q zvtQRMW;#GRU$%<;DAgMFSV7X=c=^5pEP@kBVgT1@1j<~>H@gn!)fo&xRU{|wGo95@ z|GBCmC9!2v>tYU#pstc|9Juq_7DW+rA*Qld<+H>U3c$|Nd^YdVlVTc%k!coov=Gi8 zqoaMtP_b{g@M*S4v$0?)qKWX&fjuWJf}fBr1hcaJ-|JWp($|be3820r5k)c%8idT| zs0?enC28R!|C3T~m7p{8jMdV#*AyWzkU-Ckwr|+`*SpB&8%v-BugN)wrz_dj0FGr# zYB}MheI{vMtg??Dt4bT@hP&E)H<>Bav5Go-YJ2r?Xbk z?_@B|<6yQMTZ^O66n!0_h>(9~_z4_8(Y@JN4?k^ldBAhnGDeS!Y;>-^cZ+wgJ>42j zEnNU}`3(=7lpq`w7Ju&RYUDX0u$DEJO9?AL;%u~q`IRAN{NTpNja^XkXgcEveczEy8f~x~*#e`Lf*M zPK%6r{-vN15t*!sm5h({K;o6xgr#Q1ofKLldAxe;H8!2tsLC3y)FR+j!Cmi;T7;j# zr1+w#8Lp57&|CGYP5IGJV&l9vA2Bs;1IZ29vvu}ypY-sjh95^sykg{d75^45ZoiI* zvDqCs5{#Q<_ph857EVR9_}Q`z35q%LRSoB%!-4oJBxFg*A1(SzoH4SKmOPp~_yK?G zMSmV0Ai`&gf9p?e5G}UiHUDUZgj*UE!qB|(l^)#zPzu`7aP(ju;4N_-v;e;$hDnBn zvqzys6#4m`m>6Jo0aTgQIZO+0PyAsCh;H9~Pr$aTlWOe~zNe7!FRaLyy)6lQL_mQV zH4z6SrQSC>bi@5dqv-kseQ7UO24Db+dV-!F783=|7OR=6mO^$(Z{|IxHLO|79#3x0 z%2eKrbQc3AF;EZE?k#IF+9oIbN# zrzj=DJ5E68ZRoaGd^urpVnYUg8Ilq(_%O=VNki7XbKt70u!eCwx>=nk^8G_R9;-&% zzG8lVyGTkE0g(HEU4s&yWr}bm5>x{!tnX~qhRlYE=Zu1oMmTPDayD?BpLKW-;6~XE z0xmgGlqcM}o1D*s2oYd7PEGFk-6KPOzji|+Q=_Z3VkdBReul#g=a_tV&)E3cArZsMF}&CG^>z#0C%rtP?Bt>RUrqAN)DX5vLFt z)H00{0yH3~pYwbnhnt)}$&tbl?}Gen_PGPMI1GD*umb3tY;h!5pEOTTrnz6TdOinx z&r`yL^z+qSC)kaF0s!TYznRLT%wv341cL8a>6`UC7UMP}S^~+E#NpLze@xa68ExZ{ z1N`2wQmRl>5uY|HoaN=sB~mzwpvtxgJ@=9DkJ4>VDNv3VQl8!~l#s+?tvt zd0HFJ7cGBe;025U!Csap!+Fy_K~JvE97RDm8e~SQ1^Wez-*P7kabDN=vED{C@6%B! zcS|;c>%jVkWF{F`m?;Quqr}ISp)$r-zW~$C*nPP>w4uuFANluvSK4w^1}* zZ3v%18Fk8v(^ONG9j9~BFX(^od7e9u2+WA*>YW;Q5jPKX?o7Ot*8u=z>9TYucET=k zFI+uRkukWzcY@gPVq_Gvj}Ll;Zkp%yT#pYDv*?4_yP~VzTd$StcSb|5iGom(xKZ$- z+u>0Vt;^n*vO2mGdaA^>H>XMbUQGg)PD|5O2@Op$xiaduM3jC%0Pis>>k>IzU3COT zsIeQl=x!I@x{kD_iJWle3Noj7Th2#62l*&B2#%{8Qt*l##p`)lMbm7W?Jq?j^nt9E zhj04T0MfTyPxU{-swq7PK;=dO8?F&A`xOVS2LMY$PByh&7n7EzSGJ!DSQjXKiJJ4< z6LaTh6M7#;y=x)%k;T2z8Ud@7n$v4t#cNmX2Ln(|GVOc%m5=^RnM}A=Ax?I@KuzV4 zc+ zp*Zmcc_QnbTb}$s%Nu@!`|pmp6^85#nqu1rwKnrVo0tJn2ZSVE)jCpD$X)7z|0#-E zvG}*FtMYJnMBkV5F2(r7W0)?2O}jP@a!2K0@P$n58@#o>@dCxwx}$UGQGIVNKW>Bp zBI)KYLXN%P{R$%$9{ZhccWP=-+zdTgq<+D-Ky7Ug;dZ^OmWjgXgxr|lw1bhwm>LkG zAt4vKC)aBSYxCZwIlJxsFq;tZQzKIWp?CjAudwg`D5nbA9KRn5f8#kk2P4h{M7|-~ zg5v4K@ch{j*^T%vit8z}dT3oi76V{BzCmQKy!Kpi_~XZ@r1;IJ;SB;HO}}B~&>cDK z2=CHej=3qaes$0I--?x~1h{cI$LBUO?JV0g#hFmOW87V@=cl1fA5vGikatk8{Q+pY zq^APFTi`SzKTx8#$rF&-1l%t~6|Sd?f0#b*ih&GeaW*Gx18rL@2J!{IuJv6dv-diu z3}}`WW@SbB3HY6pPKTQI@Targ*?}@eNeBoC%rsfyGl&TxF~f-a#R9~k=iU}D;uIAZ zQZC6<@Dxs5fs4B>NWY75Q@h?RaUs)yn zR}e~>$x+_pbiJB6qd1y%SLpv{RZHP?U_E315opO^d`&R}W&zVWH>Vd;P4TFRjlX<~ zU^a_-MuM(*2M9=qM$24(qTYv0uF3-%MRrE-wU`$4mxuxmw!SfKHO1qcztEPsg9}KN z!(i3h~0=K*h7GodSj;3M6MeG@)W0cy3@eR|NERHfzI)%0zZ(h(_L4#{#n+C-=Nzki zw_F4c|4R0fiw3^+OAs$@0U49oEFry>X6fcPBZ>;FN+;i2lJ@B20deoQG0zh$k@#a$ zdm^g$<^uigqV0Q0~4}`k1V5=LhnN+Sj3;pnLh@#wB_(F1L6*znK{q%LW7pze2tvc?(IB z03iDNJNnCP+Ui2KwTn^kH&g~*ms?M2@<1+G^7o*S^|Oa(o0dxh$uHXxM@M9^cq=<1 zP+|S>g6sutdU=)Uw|l^$J5RpGM^LNk8>+`0rvr6OLAs&@ql?aZT6h(7w%RQaK)>K0 zGXhR6Op&}9+hs>qa+yqe>eM9X&wicH@vs467fn9A7adJpj)xW*?$Gbgb+QP9$FNeN zeDrSzRZT`^7Wglm!6}F=lp8})+Me+ z)2Fi?d*Das_WvD9Ige3Q>g3kW_f^z4KCXa>Z;{2o$+4{L9lfxle_YM#Xo7XvzG>Co z_D@O^z^Q`9seEyL^@I;=Pn+)?UPsJ>x2B}t0mK%nyq=8!i`)kZL`A%-MhDdi%O#$4 z8NRzpDOT_l+!nr}B{Gv;n+UI4DM~L0gzU|E<*QN7a7qR*x_JBy8aurp6kOsMHqh-%i*q7}^`n$tJ!k=g`Nr5jyJo&a`Xgnqf<|1LcIQ(Xzjk6= z`l2hQOHULGFoN)ASS&f)CVXU5(g0v?_Q2Hy$BIr_8!FTVPYh$x*k6lG!i46b)!*y&tJcL+DNlAS#S%@uW z{bvd66&^@0jDMuP1_Q$j_g}(SD-6%H4&!E-HyV~_U0wiW096%1i;V|oEundE9r3l} z<6q?jlFGWynnu?{ym@a*GY1qN2inZ4pa45bSy$k9+;p}mMu>w*G(;dZI3TxNZtZvd z?2pG8T_e>Wd++ZyVhkpWcNI}1W|KN+t=>0{_TEMy9O#Y18I_y1iFS3ycJ}2PB+Knj zCucys!*sZhPp}wnMrrjQNLD%mP(J(LL0Lv&-^gVD%4h8ACnmg(L&rbYsO!-HvNxzS z^I3=$^1upe7O;YfloWJCsE6ZaeM-Ci{R2zpq~&^SomH*r;IV9v-=hxWM|j zetOl#f?q^-_4W0r1;6#BI-O!HF*P>|y|EIu8^!|{e~qo~WrO+(%6L-GFDQr&I2ldV z*yruK{qfhC8bdyH4gY%k=K0U}B-<=s7aA4Ab0=q$0hb(9TPy$orj8wgs+B!%!fx9% zWvQa2RbDsuV}m8l3ZS6VxcPy!{=!UEay+%vv5Flb@Rq^aXOS@`;zH?vwz3v z8h{J#U#^lhLo$EgpZ^zW?--w1v~GL8sW=r^Y*xiirDEH*ZQHKcwr$&1#kOthzO{Fs z-RJbVyYIc->z6P2^sZ#h%*-|Z&lsaJC5h)$-V;H{{IkKfGt~t=I{wc1i06P?cHfUi zF6-NKv4m4?PNaqMk-5mGK9l=Nl=nnWqCU zG15)-vWcZS6;Q<{55&jJ7^HhbmpWJO9tUWtSQWz<1xaT%2{Kq)__5t6GZjNt@Z!R2 z3r%n^pL`~_Q1}~GF3l^4^dHTHAU@@}c|v-7(_`RMYPPXg*=8vjw=?eTu0tv5Lfc+t z5q#+f18C9<7-dx>q8%wEHLn+|Z`sRh$;z&KIdzaDTcJZ!q#?j#_+y%0u~aN3+dT_2 zbSHZ5J#z$4LJm+%q6}SP7+mt00oE@MI>{mU>o0n+APiqE@0sXz44h}|EN$Mu)~gUa z9_w~fs0SBZL@jw+G}k!WApln}*Zz@0-u|gJ3*YwsK;gm5;K7Sfr18zFBeJ%5pby!J zyEfd~0*mb?TNw@`%u@+Wqve33^-R|%qNC5Rq0LF#BSv9lAi-DJ zkgz43Q;Si62_=%R_NCl@yDdph`@+US>%f*hf_f4eF1?nlLpW;T1x3efKjSK_1e4Yy z#8PHMph*8K6Bz)oR-51E&Qis~q;0zAKxn=c8uk$e5e;G^8M4^!BJ(;~U7soDg;PCc zb`Q+1k}8AOkSrG@ZA5pXIa}Z<)4#~KVJ^fn{mNF*YqNW7SAc*wjm@@6_RABridlq0 z{;lfS>L{*#bGoN@pR3QteeZdnKVKkKj>+I&^#js)UUTjIrm@x2A1giv(Th{uZ0&|V zcY+Ee9Y#$p<7}>g5n`mim19E^EP~0pOz`ioYY(bQ}bz|8@PSWH)FAL~L zU@|DDucU&qA*y^Ss2}}cAVv>$(Uz6o+|=(}5c#n6op-j6GJs-_gX=@Z5At~e?l~Kr z0tSX13mv8oDck&WuB1PR@m6O^OFl^?rBncb={o5}&@i`D68BF@ZCjYjire(J?sK^n z>zF9Y;FKt-^}EB(k_up4;_2$S^KsJ7#Z@CRD!ZtNzDdQya=yKFUu`i(W$sl}y&}}o zL>P7EjJ!BzDR<&cyyMGgu^dx=Sy#NjhqfX)m>NgF8MRiq#M*10 zc{&>D$lWxfy>_MM`wo-f z5%>Gyg*gNdU(5x*?ALIi;r0-tFQZgrBNdnGeZGUW>1)#U50k5nN+L68>RhRN3X{UYi zbWItL$HJ|uMLb=g2_%vapp#%U&?S8yGnOWwiuCPWm3?UX9-Wz-YzHtp?CD4hOpukE zxt%wjT4#1lUQ1|K!;#-%t}@B_C(zOlUB>$L&^s2mj@4e<tHE$pv|p)SDLv z@+mA9ru$RzJ4D9*C^wJ^@-idvgd3Z$2mPFo6_)FW$ zG9!LX*g1SUal)$VZ8;8ysMAI?H1(vGr_1ZvRsj`YaA~v1@|9le=bnNd3^sd-tb!_l zfW<3eV5=7LR4ajnojEo=QA+#R&-e!sgQC~0pqrFhi_P8y@ipouH?JIn4Q#V9t#{Al z!CaBjrc6y-0M885N~iSUe(C)Pb23XMU7$-63Tfu`hS!0Hvy*5|yJ=ec(vGcNgL00@ z(m>SY3#XZOW{vJ;+!Hq{2P=p5)F}g!Tt1}Kf^V-mZD(kB-C1tAoXm_&&KEjC&&G8a zLkLMckwkn~R+^lBVa(K85*^bB?2=w_Xs=~Ajn_-yX%^zhoLAQ+y|~ee`#t!KL*5Y8M~k}aKk3N4(1`b#gE`znTv=Yf)Tr{(Q;(cM-5LN5I0zU9Fij`aC@ zJ=6la>)zG4+b45(Zt$a&boAXZimILWO{3XLgip`TjETa-he+r3GfP@;Lc1 zREO>VhO@rL{%4#;^Zj2qix&33<1C_Y|37dRUIW3Xd?O_7q1(g?=2Z$%${9k(6ThM%%Rtzn<9L zt?(N((nU&;mzm7`A(l^7Q7{lNqqb7o?V>%&cikU0I&T%IDKHpGN;Abfbsv6O+{>hv zQQiE(U(7#jfPA%tLyre;!>Yj}vKKjN1*7=;|7KpD2(IJS2^<91K-6>e2TG7(g8L^* zBOfM;Ac#nQWIe2q7GBcWF0c5m$nl%&ZM*-=H}6;e8i&F=o^Mff*gd4xlE8K*z82(V zaSP0fqGrlW&G5>v4Cdoh#| zFPbgUkA3{+?S5u3qT$zBq)Lfc+e@XfhHoK*f8!7VP_B_?~r%-|*vS0fNV?O7EZ~ zvS#9&j6Q$CO)$bSb?1BBd=RXX9$J0^FeIhu*YP{L%)H`$l}p}T(^Y3@DzeFKlKE*5 zr4%xE$0N>a#D%yp(38>9qL}s+x6ghWt~U{ z3j69_V+N@CsQjDPyNaaE+_FlX*aq&yO|)e)fq%&tkESTD{A^eI6tf24VX?oS z;$~P;exA_4^S{^S1PpZn6U{wC)p^wUHsaTOS43nS05K7eaYp& zuy^bSUjKhVtZ(w8>c6xJ3;RK1urH5l({Eh-H{C@ytrBr9Yg{m1Jyrh2usVK+xFdZ- zPmo)?V70F20=5~^mrPx0O;kk8*X#=|Y1qt(UM;&))fE(>WUUa%nZ3W>D;<@QgQ6H#An`kvopu_b zHl}v(c)HtuFK2M@yrhs#(mz~-3RQ6@Bj`>!`()784ewZmIbZ9l*l?JJ5cpm0_UTKZ z5a=bQ5Iv1k%o8m0Q|C{jf@i~CbD-zdXPW*7n>c6ppe#l&6Y zO=C)MkM*|tGV!fA<;MkjHHc4&>#js&!73Mv@j=Vt**5lrWF83)%xizI^go3B;+43e z;-7__AG%2xlZ(wue&O}Q5L;JRkEDeKx(@TOH2Z3FsXlhYK};)R?4zF>Tt z`nLqD3SEmv6eaY6trts7!o`p_s%>!ddbN$tVL9P4>VOqh6~A;?9OqLlq*K4RWU;;Z zn`-Z52l~T`ZIt#On&UWGK^T8YiG~5!7#v{j_P^m-SxPW1|Bi#1!NE8}7jfztqz z2&H1U?b&%Pt_NSbkmb+-HHVSJRp;U&T8G4{Gi>hSa#|D zHae*`$h7YC>mO8h6RW8A3=}@okw21qLLQ^eD>!5ZvWs}+9&i(@8MCtac0@68W*^*H z3Wt?5_=&BiE%7;5-$kRS>i+a+w9uDfMJ6$83_l{q9TuCl7KUjMv&yDUA?kj^r7d4P z(_QX$lC$26XYe$je#b2~v@&Iv4^HSVjCR6GteLz7^sLT%9mRm~ zD%+T$Ls#wbE$REQ(jyENHui^0QHc7+t@GVHq2RvfGJsEl`<#(~`QZVsF+T!;_;dtX ze(}_==BpF3lqyiHoVSjLK;a&JtwB2B&P?utyS86(+2q6X(Tx4*ojCZ@fQ$zaF^$CB z1XYlPZ@19ml|j{GUF7l&iR=F?p#Pk>l_TCAU8FDAnR16#{yp3NYsWVZzkY-Fy1O#M z>jP%(<|)nn@B;k|{r3+%_9O!s!3EXaATvL8hx4lm&Betw$!FtYcksui0aAuJ!| z1oYD+oN1=|frP({87c9rFk#h6#O=<6wkGab`{24l#?)&o5f#WtoogGAoJ1hT!H~#(IUQ^MU(7{4GGm6*&8#iCeSaeeBt% z^P!{d;&8+RT)83HWZBe-)x>Ug{vZZGClDL=p!dd{xE`>hi!ml`=k;isr;8A+sVj8% z{gd%8V5zUGb0n;d;~>s_|1en@?}P4NTlB{6jsIJ2l`$s7iHXdY3#_dJK=X=-gcUXZ zj*l%3!b$^OTL~2#l#bl5;LVSpPbh&Jeu%Za49&FCr1i5Bfn-xZG?l^WG#aTEQ~PLw zC>J((X&7-J8loW+r z=A{PAI=u&4PDUxxzG>tVKBiXBEt|y_{&L51sxJqIDe9Wn50UxI9zyr~9|6M@{+Z9PuSX?ik%WJ>GA)H9m0huPb0)$5?qnh!^ z2?^*=!h6>H^wX`CtngJwQ=(a;&|mpVi(c75H{ksL*+FHJ7233DWsy}uxq3Y-Rbv>v z2XXZ9o$?q~)@pU4`ZO@9tnQg*?Bv5CX#wbM`$V4M$DLJci$B^DwFB@0o4O|0P=KLF z>HH<+A+T!5#O!SEgE^da4eZ+wytt z)(i8ny1IQy&2!jX1ffM}Ol+pXGnNN2Q#avc&D0?XK<&zSSC!l3IQ)9^i(#iHzTuI~p znG+wrjH({ElL!>vi$?z;_~_GGVE)OOTxbz7kHYoY)4XZEV&cE?JOGz*H+jf0XscLz zj4fF5t`Aw2x*X1&&vPDdoVNAuCWq3{MO$y9$yiwW4%epT(()l0_~{OO)JNl7w3y}X zHjHsYes$F&6hUq89YF%X(8P_3^WdkzpD3s{0Fjx}cSi%phw>ZI=$TB5TD!%O)7g&1 ziLO5{DE*VXPIDiK(rKygZMY8|v_*HgTvitRigi^dXodZEOTVT;e$;QfTTt2L`Wx_u zX0!W$A(#-374^Wv9Hp2TBQK~9!}5{Wj7}9ar>_L3Atv_Kb250|FX6pwgb&qxCp{mU z0+oTJ*5cM?vx=C#E-T>h$q%Ta5N%RA`w7+Lu>jtqEabdPDC{3EQ--TQ<@RWvAd)B_ zqYKO(8MEr(M<}|g9Rlf@qF1$JG{%{ol@*vtAp_*n876JQllQm|WlVk!qh1Vzu8?@1Bxb-@orbuiy9FP+)l=*#fHqqB|@>_=3f0XplicaA{08{_sG zKFUn}J1c1sJ22(YSeiJDzlCV%i(||2G4y3tl5EZmgLALEfG}$RvJNUL`%O9kKu1HH-rdpSmQ``-o@jfoS5ZXnZGLTW zcG4`KB1JV`X+b>vTZrvwEZ+W>_q-J!x9WG!1Jm@me!*S0_;whLMnaMp-!C#Rv=6RZ z44T53VBNzJE&H9X{pWl=8qwj2+nF7ajkAzsAl0QXa=VpPtH`MfWVx=k0;SmH4t1HV z`gc5*sH!l4qNk9Acuk#{(-L+$DGn|^Qk;FG~m zhg#XI7Y;A;VH51uGyBGj73moHhmVhEOUTO3vV#x?((fkv;M8S))_xm8!HtsTTuq~| zysCA^h-h8FGz;~F=j*=H6@)77j^Cy29~P%hb&wCr{Wj$1fu;0Lt!#{XZBrpEu)xg2 zr8Ga3wKNf<=F2+q(|L6bGFln$ixi2UKE*)oz9{&-<~kSD$)xXLDc|d0Xa@nVwROdA zH_Z%B4;xY=Ii3hp( zppTkyCz0K>SMmf8;mV)-Q+jX;>o>e>?m|Ly!CMmt?_iANzeIt~b2;YqW4au=epad| zZaSlceU$8>8*;1vm<323taC&~1jNo9k+TgSJ~{Nv+GcKPfdgtoBe6naglW+w4!23R zeF~z>>6NtO;@lYJ^&i)po_Xt9=&Npq`Hc}`d#Jy1qZ=jIo(E=}vR9mwX2Qbeze>_8 z{1}1Fcu7m`-~0+r5c;yA4BB)rxz;pkG^uv^iW1koWjTw21SpnfWt%s7ep!r=adE9F z0a|>3Uqj{)P|^%`9C4eKyAOX}QiZZdWsr~=S9@3&E$2PuN_)uAft}pGOSVBxuRyVND|0DfDrCZbmQ_!XWK4Ix0&CY|F5TM_LN6k5;jqoOFc0WpzQ9Zra{gmSew@q98gZkd?sO~|YJj?sDv)QTez|D)( ztL95VGkbf5z<`vQu(^zz89D#`kX&Z1ls2YfXpqBwl3ny=8ATvZ*pO_+7&4{uD#h;K zb5>AC|FiAj1Iubf*Os-lM=fv!0(u&0UAO#QXx7N1-oE2( zzx_r{=6djWL2mb_mfdMbp~tL7F|!t>5P9{b3HSqD!}P{!PB>tSU6-`VZ2_X-a1_A-%j|3S6MW%GaI6W* zy@OI_D2ix+;RtO*`sTBqR^|PPk4TcDf?4I(t>uv45(%3QF`02nG&rueA|3;e($Vp- zIG`8HW7^eqtoJ4JNy=v=qH3T%|A`l!mj5!`-a}S1oYvV#HlwvQ(CMS`a#*;OWoOVK zWHhd07PDjJwtIP~BH-|6H|Lx!>-ZYN}hlTidvzPImdcO*G71i9aZ`0C;? z8*V+rfyGu+b;j2^^@yB+az)_mekGWzB%C1f+_igF{Aje6%yrGqj}CF5f`IDXuQaFW?{q#Esl*Iv@le)TT^Ob6<)%m6q*$VKX3QtX#pE3WHOsXC&3bXOm~+R#l2k#_rIQh(hcUn=Wq$dLKE4 zjhV6u6P31p`3vTG99=L9^{vA?XQRDe0IHU_%sQRa`uYNnA!DSiBgj5k;_)3Mh`Yu< z1Y}>dD_54X#!SxkJrS7G6q}F1wWE3 zfJ0vXLK?GUO=!7{lM^g&u>2yq&XY9wnXXRwaZN|*npVM22L}Ssni%>rf{u1w8jGJ{ z>*>Kf$9lK_vr2f%QrgSPN&-nOhSBco_BiX9llWJw?eNDeZp_gU58_I{n+0aabe{Vc z1Ts*xv{S8L^B$5|S`N`{A~6mw)eoGtz8UsJbV|lCirzKi6;JcFQ+7F311j5*x&+pA zwsuLa$v;@nYp{6jWO9BHrGpI)(ead!eev;}kRt!mF#-zKRzU#c*5&9=iyz7wAi8rZ zcciadsNwWzB^3t=igLdJFv2m-Xq}Lj?*fjWX%`p(SAAt)a-J?^JQlib;+8Xip=1|m}AE_wNeFGeqr(3cu*>c*L)LoFpR6Nb6 zZ7SxiQzywsj-yTxQheK{*1{zvCEV~+-p*SH*tvn_A_&-p4;@5a{i8%NlUh3i-O~_C zA1~tta=5DlMqy{dH(6Qj8r|QNw-7K366OrMo}pIq2BFda5K+8;V)!Tx{77WJt|pQY z1ta1fU-l%t|0wlon(6G7z&BuSqCK>9@dK;UxGt5`+vJD{b;UxxC8{Z&x8G2)Jh^Qq zs#ou#iC7stUAlQcmts8~I^S?0s3@t5%MNQynFW3O`}}`%{>-&F^RSKUnT=2?1X=E5 zxzu`fuXC*VHO>1%AUG3ay0oZt0+bBHTQjYc2QJj?coe5EHixQ95A5A|!&<06l8T0U zDSMTiDo~Vhe%y+Q^xJi16DW&q)o~2;L}rFL)PB^s&P%y}BXof4$Sh?N)HK8zHoa#$ zlP)74e^wX-5wP_s>-!UmaO}z~lC-g#z9#f%CTfj*3jk<1{l!9A5k-z4cKU|~B2T#z zQ%aoOfjtWpP+m_t#8A%JDlJ4kyI&T-T`3j{KxF5goNoAlb zAPN9v>$Foi>kmw>W>Clb^6)8*K7(GCzdc?IU$vy?Gc9;#Y$styI*UE^>mly< zS~A3RK-nQJi-%(f{8orpF`;04e^FopQ!cM$qAd%5Cnq}E3*D+X^katCcI_?(+qddS zn3d8JDMi~nKIIQE}qljI2k`4a`dNmKxX4jD(Gg^8B-3`i?Guw47V@j8IzB9WE zvT(}KyuRE9@eAg=BF*}LDt9x7dxTp;{gtii6}<4PFEy!s{2WMU?hekha}#WPFYDZ@ zK2H3)bQ=U&m*HMdLt7JDfOGg#o{+G`U=ulLVH_3Ax$nx_v{p%nne`X)Z%Pj$o|s7* z3Sp&KlMa~$BjFw|CDZ63KS?Ws{i{4LW1&`6F#EWIfEq#-E32SH=TqmjTT$?3jcp#N ztO@beQt>F%X1Ac&qUJ|ujJ(kLo|V(Q^Ji^aU1a+=uDpQ|@)=0-*iSGy1WVIaN-2#E zlBI>b*Tf;DZubT;_v5e=G;aL@Jl4$C8BK8u*LGTjMAfnLl}4hYJ7m^!;9Pdh@v2m# zl~OC}FuVinb$@H!R+#=UtMKr3GLyA8JbHoi0?seXhzxUdEWoY(c%Q%g`&2$m;mdL9 z%lC!KNw*Ag;J)eY>D~35Y44{9=$>4$ZVJ7qGupkb&gho#wlPT^GTg5H@f?kFh+Y+NUCzfL+lPfF$&yCwA`n5hxDrxk#5-AO;UX3fQ-*c4T8_eRPkIYDZXXhv zF!=tLb!{NImL75vl`HKRJsxcAuHcpe zzRV>Q2zDenL~n{gpE62MIm<)aI6`HW@PTgCQrPWiL4DV0eqQ`gD@8eKaQNJA>822) z2Hm;^r=3A8QKrbROLC#NY3LbgM!B&m*z6CF^Of94Hlxj}SHeb(sk~*0e{OceOaDGa zDcxLWUF$p>a=+kbma2k52zY=bKF9t{-O}Z{@UyWjEjDK@>g1qJVm3WIrUMvlyejif z;=ST|SQK3a%2mJ6=r6pkno|-0#?zPD%Fw{qEL%Nz;>k-=^D4YS0b}yY*l!HCA1HB> zQ|1HC(+ljJ8c~wK1R6f<${`^Xp=P(`T$aLDp@eIYr552P9Br%`4x10lI+-3FZ3l-Z zUjo6KEC78h3m_XC*VW6;W=mnV4!ND}g)#=e?s20d6QrY}(mRoa?#*~ba0bNG(3qGI zi4Xty+x1hFyZ(=}5aJ?wQ4tZ5m85wg2QWmKP#J&>7;oA|w9hbEnQ5tgbN8#7R?nFZ z(Cs8UEt5mYbIE6Yu9pSBP7@11jNtGy_EQ$Iz-#Q_zCvfuvn0H9hyfa@~t=NO}8Y(|b3o|yil5hMbt*Yls&cH936?d3Nko+7wnLQ0q-D1yS#%`fG^M zuBS>=ZP=afV%Qd1O=)k*@ww(Qfc2A$OG-i;)&F|-2VF1g4_k$@CfB`+9qn`i*_+xe3 zn-V_!^`JM-6|sR_dL|Q(z7P~3bHA`=o)|XrwAhrT(;q^Hp?1OkO}1A=r;sy*&4j&D zJa6;mMNd;YE~G=E@bjLheyk5g@YpFArUcG zDl4XozGP#?y~iT&rU36o$Y2z;t0K-}W$UIFT$ZkS&HKO!iP(4KH?5cLMS7m>E|MPZ zK>RPfG%_|sR(n5@07%&Y((nYiIl-9^5A|Szry%BaLJ)oBB-Dg>vDQz@AGH0GC#`yq zq`~l1v{%fJUdoEMEh9B6FtZ#u5=72|3%@b2=Y-FzuOuy8Jd@>P$3Os~F9F^(FA~F0 z>K%8gnYl4}!KdqVtZ}S8m#Sa3OGCv0Je~3LEBw3yjbVlKE~9EJ=!ddq09I;-YzISE zs&&tt!#)aF0G(9970x%BC<FH-cexR5lNB!%iu~cLZgZC zIQ2XhAxOxhZf!OnXd7IvjJ6jRTw0*|vrQzpP&;k!+VsUOiNxF9w`=-tJ3XGW8>Ysd z0`#`hVtHf(z&}KczkyW5DY2LZ9qyb@Es44LQ*p99bDwE2o7jh6rE^+&UFD|4XqwAm z-0Q)ZvGj{99UwBRDjAC)kUW+@mI#;NjM%?RKz}|Sk*#!JVsn3Wx@bvBd<>-YB`Y;j z|KjQ1)ttKAJfvRtCukn^z#c?Km6_Ai?PP(pZP&m-NR?*8OeBZywEZP7@oR67fO;)^WvQeH z)dRaLJ!pIa!izey-UdN+iAhy%t6(TfS+_K^%zKklZMplhF~rJ|8O%7oa=L`JQ+v z1D8!CEH!!r+>b=>iX{KjYS&1?ec7t+GRzD%SMCTD*tx{z_?dP^>*1&Iq?e6VxNvZ% z&@>@jg?a@Nn>2zTz1lgaw>VZ80FImte9Qviq5h@Jq<5iFf`U&DX+FxxI7kQp0JADN zxve51`s0Ou(>ATq6viIzZ7$lpDq?112e9mvj+QpHo~gCb6pz)iu3|O)eCS>VLPz=F z$AE@b%}*-Tr9gv;$IXhfe2HCUQf^qy4rZ#-Py_%Bu?ORn8W|{{xn0~A7#9%5b)e*> zsyFn7h!kilF%5UH*FI+|kw%AUBlviLpL#c*34~lHwp)=;WVcRccQRpN12m=EZcZ$m ziqRuz!{YJArR}L*|1<=qp3<64(iORD50JrV^C=uZvbuZXSU{A@ssxS{Xkx*4k@{rQ zEc;3UL3GgRj4G>al%9dmINnOhlk1hAV$p6220+pJ;)4BR_YPGCV5Bt1TtyvRiC#UB z8q3oG#%GpH^-!Nd=OrVJtH_4xqkh+Iv{KlXknHf#I~7<3C*Zg+@@fo6lOnZ-O^cC7 z9>w)|^JmK@t*34FWMzpA%#%O-=bpp(T2tFf+6jfN_~r&zi`U@*i=u~ZVLx~ot#N+R zSBXFKYu4|-OTUS~UB>_10EEF<0^cmkBwnvR_7@*%v$#EFZJ)1O;TSJ}X+6z67&px@ z1&7b-2wE(89-)2%5YW7o(gj`-#hx}jUN0wLNy3c6{mitZiU1|33~OA$-*LC_BM{sg zza~a1Wk2L8*RBc^uTbtP-SH34IloSJ+%jz8APbg6)D7t;2zMjt!ay>&T*WH?X?j^H zlF_9st(;W;MPb>coh$$SHCJLu(2Nm(gR&rsVYcX-aeQQJe8oYW#9}Zf`HR;vcxm}^ zh}w|coQ!;b+Drk(F@64K>fVg_hLhp!zX92!{)0!v`1W1pt`=C=-N(YHRsrrm5;yos(Zv`or8Z#g7?FlG2--?H-?-j=~?WSku?K2`u2zVt`%${RV4vFWSFnouv(j(Uav51BV+H@^3?wPi&2Vv z06_6N8n|Zj9$WF9Rdhz)Z1{d!Q@U%aOb;=NfAI*BovKThL8vT>ZvaX}$d5_O6lwRy z>19XX$9scFlEm-DVJnV*2+q&4O@Dsac1fm*^%Db$O6N=NiYLZ%J%(gW+kH$ zZEMEWCB4X+z=W1hb+qcdN$!tfkZ7P9vx1KduDwPOcsUMDgv4?gRCErPsu`V>@I7$D zSoUa;i=MqHXs=!+X^EkCCyW>8UW5%6gNeO1M{?WK)$XYK=Bt*t+a{c4N}-8ueKO(O zxZ6(tCE|TT?o1vd-E3H=*X_5n&~Uk<@>x}g>_$TnOF+=}y0%)Bx_#HHGlAHU0Aso#y~`b3?E39PU)zNFM%1)e*a~Ozf)mCrN{cLb=Xa zb)P27^w_Z@_;*`5%6i`O@`^8t_+n2KFYEhr#i_N5S))8TZK<$d8j``zU!-8IbS*3h z%^HlRqmS~SNsH~GGRQm{S1GuolIfQ6ZFx3ewcPP2JR9$4lamhLfSP0>fb(4y>`<+vblDryI8atKz3l@ zK0WCB+Pl`uM9_4~XU5A{F6K3gX(z@UY3Gh7}dp@kA7f_9C}>=Q*-Ygw1BD?AGUVz$+v=9rnF|W)e%pr7$w!0)8r}vhF-^onk)iOo|zU2-H>5XGh(DlCH8w z$oqY{L{!f^opSP|oHPe_>j{5o3!>FUAtw!^+355KHCP2eBp>RZ%VnO{W@z}-|9(9` z;VC`)N6F3h*!tqK3qdO#c~BT$uqv1WwX|O|8wH%y6)O}NJX`TPY7mAiq^~GjmWa>g zY9p+-r>)#Kh0FCyP$=*#miS}|qm6{N2+XID)4b{QPpY~(dgi1ah{%j!!By~6Pm}MZ zA4(_Vk8pwZ8}Ftnb`u8*lKyoKuhyQjbAH-`rs$hjs4!Xx+d1Or0s?BTro}&KbWW4k zoYLu!RdikN#e#CP;G%0);J9bwcups>?0tCv6w*G~I_EP@&s&m3mxmChZSbCV2g~(g z=XF@fw5lWzQr`cV1<>4m=7?sTA>a9ipg1#=%|E$+`>3t(g=bKRb~mMn8tsk?IcvB_ zx)fa*9Wacbu4gFYW;}3PD^wITYJTdRG~w+*MkMK2PdMYcx1$PLc@aka`S4X?xu5kY zF|U^#vW<9|`asWUZKK`TDcPqv(ycbBs@GdrcXOI1YI z0T$1!XbPaR?XqkLu-;(SX zI~;2PqvSa2MxZ=_Hm>F^=!dMnQ_|vdFlA4nq1MBIV@Hb;Fd|iAy1K0P?r?1 zcO{nh5pobP`6hqaKO*6pXXs5vFSRC7`GcnVJ^Y5#j#K!E_ahKp@XLh0qNp_Y6?HJI zLf$|k%bQR>c?j?P!~$-*$~V1lZ!c{uq9@vysg1AxI=|Gl6UD1jm2yi_gwx$TT}pK< zt(~G{_C=wsl%DskKT}vA?7FxM*_T>4Z5=v~k4?O})N_aU?I36%n^IAOQ(QTz(H@YY zUxJuEq7h?w#VqE&;f4UpTn~3W4CDfKIkeh$V}DCiyLS~s0ZYntfkHxv6ZXm%9aPyN z|E>V*)P!k0SW-P+Wa5589iX4LUm_*t0b?{N{_|IH)2!M+=W{hs+s*ognZT%cq zMj~;zM0)8P0`xOJ@`g~N3FE`+hd2^XoOCe&p^Ctp9+JX}(yzN3L^>)D2yIr?(*oea8ONOuqKCJ%M{83;ubH*ZkQ z5u(7rc)%7ig*dfmWbE+z$-~492lKtFGSgwk1@Y(zJ)Ic=A&3Le0aq>!q zhgg;HMESM-s40PkfbsMye6Km39+W_ZsI(Rfdho_TS+(Hg)J_&s`r^@H+>JODbe#5G z0jjZmg@aCMG1QucMrbBSP))2)d#gYf?LM&$qfC|U zS}p?RTPE<-!hTnS>4~7-i+HiBv{f{q_D-@QVU*Pkmv$}PE4-aF8@K#f)GN0ETBul( zf3=8fj>n}x04-Fk#WFZZnSfn=jBEuIknT>SA{5_^JrF-?MMUt9&DNeIgaMphl50ou zyBa!q8lYvnXk?vRu%pSBfs(sLV(YM35ZapCH#H|!X8>DqYV`9)&a8TU6OS6Q3QW}R zt}^ai*?r=26S_;BDJEJO1z%a@oW(f1RtG3I953Ou-$AMpWy&*ICt=XjIVpN+@fJ+B zbKcI?(xkf*pTuza%BJ#^laa$%@O%;UgrwwVXD8hb8Y_II5O1n@uUIzy>fvO`Ib1@{ z)G=mo_ye8yQMYd{znP2Pi5l`K14S)KG5?=*OLr|xJ329C{fhQcpBcgDmX)g|mO&?^ zgl%#_k|e13dzi2S%@^p?+B|#SRR=z2)5a^3`0AI1+-3h3I#S=O8Nv)8mGjMmD}TFB5iekC44Xh(j@skqc5U(bQQ3{pAVyg-=5>oy zFC6iWCRCxn2wz5m7(hm zdp@PP>s?X0iW7%-erVrR-e{$x0+j2S~^~dEzKQ?&R zzb(!9Nx*l6<;JOK8rnL_6g_)lx|F3PpL|;q4*Gispd6foia&E}7ERMJ#M%;(U4Y*r z-wgsVTeP)OQp1<$LR-wygcYjNU`$VRI&$KI1gMxQM;fZQTRl1$X1I(TH<`Vvn5ApG z{7m~5l1&37SI6O4o&)60ZmMLvNIdW7Ahr$)dUKYAm(?-4kWH8P; zt$v+eER^kIbv+`rUyhQGy{ZiN{*DFGg&r5hBcZQ`7(<~MP3-DqpuPd+@wbp0s?V3} zG28a6qNe4qY<;vWIG6EP1NC7%u<@0%tJO(XRWZBN$|`U%o(gKC+5c(#LcTZBo%-hYd8Wsu1h?61~JT&`StH3UY4J^c3 z)rYGvK0(kiQ?}T45qJRL9)H*FNr|!jOr9UvJifl6G)v1}hGZKw3k~^(OAstW1F8L9 zqk3?g5&IO=ke9@nqisq3(v9bX)$uA3cc4bS;gXDjLlHC<`8F$ zf0P|6WYwBU$s3o>W}6xS{8%jicw)IrfO0or)A(NNeIDGq&n(QY7W-kbpycT8RDPOH zX7EJpwiYapUaY7S6hgu8KqgEua{+7mqpS+OY0O?)?UCGz(mlU3T%4v9lvC~;Jz_L7C7oQ&hxL8b2C;G1Kv1!u5-4ECKH0?W_@=bt9!7#vj zi>Tm~#(Q&^JkQFGrR}86dwE?|cmq0XIyAgm065_cRQP%1yU6eVBo?;q^zTdhb+ETu zyW)VfE0@(LbrxG)Gb)|L?3PfjH}oeCz24}gG^|xxQu;~J#`FOv67W(w&kg=Zb7vVH zx3_m^nK@=ViJ6(1nPX;-nVFemW@ct)=Gcy7jF};(n3<{bztG>{ptW8oAF*--kpB9mOgF(XAD&rWTW-HrQw7FH)Zozp;Ct`RAk)vKi5T3j6sEH1TsGuzBf#-!r>9bpIL3 z^19G_$BvgWK}pzG^(JGP#*v+;+J3cN=R;o4iO=^lnbd>|4) zz(hr3epc6)^>o#xvrv>>ItZkBoa;kzd7XG&)MpdpNcSIgMroeg)mHlhj82BhA{Rn`_2*OXPx9)#Lhyn^3nh}okPGFD+#F^8S*oYw9vC>3dqEP}X# z$gVy$Ryb<4*4u;^-$>=o*cU{&_sG5;I4h3-OJ-F>^%v>#rI*Dby>a15Jc9;u?`1Rh z(#e-kPNsw{PBu=q@&_0Qv{GA1{gijPs*$IP>WA@F@vQ=Z<2gWviVax%qd zhzMn+goTA?-o7GPq1AnZf&+O&{iD4zWzb6s{uQ#CI?`;1}V)-TU!uB{*kB|HW$p)b+W z7EN8yy`Y2rKWu`!kg%leYQDH%IgPjGhB~;3@d~J3&jBNCHNpl8WUmIZ!#I@hzqOUU znWiUGyv|ie@LZVg8LuX7Lywx+~wGvJ&9tvGv-wW`Xe|;_lgmNk35gUvW zU#0?@I33`up61x;zA6&@#jdcPSV%!>Rl|Kd4#GRI{_zTU+-jcy;FO&qYc#CuD?P6- zjAG^$>FFV=5jOyuC7tLtZBL8x^Ld67&k767-|JyPB?D2MmBg~3mYojPj;30MgdB%*Dn0#spfC<04O%`dxs=R*h%Q}$%W6(2}E0N8b|X2%Wl#TzpwWki4X zX>z&)LiP{T6_a4(TpkX_=d+L<9)(CS$s`9VWekGthzdgr(1@#{0O-XsP3Ie^K zXMy9LMSOJ@w6xLt+>@+%`5q#%pWp!n?B2>hZiPXBZf|=QkL77*=zv(|9NC2(^)DJI zL-_%>hVreHF7GC-_4sB+Z&ZRquDL$9k&5$0R&H?P!cjyGN@s~z?RQ!1-(gxy)5~o! z4G#Gy-`X;@AO>ja&A~bvG0ooApZDvCy}F|9D;c?(>LaCv=0SN=@1(}hoD{9jAL8># z_P|7kYptwq%7LVj_OjR&gYC?vix|dI(o_fl;}-5+=O#T4 zwZ-$WkyngF0(r61z>(Z3aI+C|Kov6;@b{*wY^LxFv&NP+x=3oarJpRE101!C1rL8- zX>>dbPlc+20-3XRr1_a$-pDk!p~wma+*U7_=TXlq-9cX1KOnX@QY=PNv<04v zIDa^-4mZBfeaLiW4MAdlYINnfH3~khm#R?t!(kM}w@vy29RcNmcRub2_LYVy85o}XwJ&4O z1C4c5|ANZ2wHqHo{^zL7q;-tk?k0do?s-XdbLDr_tIelouiku-BWfHU)lfz<+hDRV zQOJDRu3T)WfLsdrFr|61D;bNH1vPubhB>i%8AleGvaA8_Eww$0VwMb$XW+<}=)%dh z){8C+$;tZ<5z4nz?T_bR=H2@>S@bxK<9k~}X#9f0Yi9GoR*@}fS&hDHANtiN?VEEO zr3}+1hKWXAU9?G+c2)N@9?uh5w9cjn={V23l^?jMb$tgOAjF@fCE*bu1TjXeKP-ho zW~S*|9LmEcTpa&i+#MM?K;WPCq`k;4e{*d$612nvroG;{gqkmcH^Yyqto`R)-b~em z$RUzqijxdZ#-{~_gB>}&0e|fCBZ(Lu9_KhLHljoXNU86Vg-8I=2~Ub;$^0H zW7CEw&i18x;;`H{Gggmg3xbp(ksznVr+la;)vWiTm>T6z?`qqpdA*j^ljnlZL1h?E zeQs8%^6T&9F9^Ay(i+bp;rR?S&!Le5V($*wJ{q{m0E%xVOfwTc&9g=Px|An@534-9 z_qkHFLjVZqo8~lw9)>mkJ6e@V-u^#;u>X|1rAUHQC%a9hv~C-WZYR^W&VVh~PETg_ zVzMEA&qv;DsBMeYXV6sH^;LnCOd-xx`G6g^bX=sue*j^mobhS@Cmam+AaJ*7qQ%y! zgim1dy?-d5_i1fRBxukE`dqHk%BT?K*2B=|$6;E#om(@gu>ZNHAyp6m1bJr(@E z+Ht`#-Eio-C_c4|wa5?|wx}a!KjFWLfCEsleN@wg-BCwxSDznFq@&59_Mma(xl)F~ zP!`3sPj4hl&>}^;Iv0hNth`$GI;Wbnue~$uF)&4Z~_^ zxL;(fqC~GEEpn+4{v9Fv1N+|yS!<}b3zhZ+MS2agm(tDa41$VgBYJa8aan#z7{{uN z>e=-H`18hXtu2KbEN=VLL$wnd6VfpclU;f_!$xRLdLd1g6p>^?8NG_l3VG=^RH^Qu z6BLAztA#0li3!uF0xFnbGEDR@3I5>{*xZ=wkVR@hLFIN{(bQHh{lbAv2n}q;90D+3 zVUd6MysqDPsbT7aE)n)mCPoO?%gR-cGLN^RE4~6wl_3(<+$NLj(y9U zI%B59z%`&FySk{D}<+>Fjb$ZIs936 z0=vdr6B+8@KrYkBnrUQd;F%0vlp>vnV9aXX!Arx&g>QP-JnSQr|B8*`bcjq%kn}n9 zG8gxRMvuo>dMO+xuQ1a?2&xr~_V}mA`^WQ8mWNZ~pJIeWVn)BiowWC7b8MVlb+>%@ z(n&_qkODi(bYYNYCO>4D?hxFsHl@EfU7v_JO0?mo=%9m$QcU=}Tvx z>ABH4J7GXWh<}6jSRIbY0vCL`nyabye5YMAi^nEX+h~_PnBHi}o4YTZwyhv4BRb-L z%(AjAqSmbZ_gG9Zmty*V1B+c!{hwp8LsT)1HOXLt71$Tve~-nyAG&i#&>?E+!&hXl zB832y{_9nO=t=jB9$qfzua8i*WZmcATD~YZacYgD_?q%L%(#U;Nh==y`jmDkrr+C+ z;wmOi<-Bl63!$*u;Li>WUfA-LOaH7gJo@g0OpE%}gqOd2V<%UFY;)LuE~mvz!1@pZ zz>MvF@1W$2_>A$ChE%M^8^sComQXHa?ep#QTC$)WAtvmJp_I}AjYu25U3ZPg`RPvj znY$PL_+N%&I2I6PD>81Khnrf>TViDL=FxFky0s%qBUJ?szDYu)s;e%~GpWcEdxW zj8Y-7z>zVx*GmaKM2Jpbn&wn3s4`p7P&#M0h$>U|`KSJmSLt6Z_ButAOWdQ^f*-K` zQ#N}C?7B3z$v9i{nIC78pP42=%CAX1(e{hxeg+?(Yqlw`8qNFeC>?f6#KzC7eMCQRo2C$xLcIt*MtZ8*#IAb9QCeTxd%nruZ zA$enmUx?u3=N=@#clxXg6)F=Eo$X)EBI(%>crx{dB#HX=6n}Jgky^4%(1(Wx{0RX` zFC-f+c@#@Yk!cTBK~cmET{rru#wquTuPG7G8KkMP^(!uaS*;4td9Dvs_7Z zJ(@N7#f50^#R>bm#}&4mDF`l-Y-0XP1u{A$?p+;zzjrY*z}WhRImctgQ0ScGG934% z$kV|E%>Sj1Obxo&O^uhq>c*|CtHsxC`DG-Oct%A6hd5h;K8J1VsAuWQu2(QwHY>=M zi#p4(jwfOL_dcdT`Ds(WNsmG2TO%3GrmEk;nxz0F1N=0C8&7;UJOH=@ak=WRbnvYm zf<)u3G3X`k4iS+UB|cUa4?4v2G+1)Kx_7|tN#FVC{}pr9{)M^5?=*LLNMCFMx0K(4 z_>^0FX!p<~`xo%J1(S0>K2`0t-5m%M65TK^d<%49Dz>R%jEV&d1P{Dy_ZCF$U&mG* zb1r{BS~m6Rq`vM=nJWjH#Xo@5Z~x?Mo5<-aYd>d}Wu%$hixuBRorKNa%H4h&mvsGV z5J>t+VN1S*Y#uK+gdl-)mI_LtZIfavNo!eGU_4JQayqkYK_%QJY!=IrNB&8-^W!y)0pnH z^Vq`=uD0^H*`TD_mE5V6KcC{V0>=8QO@|Cj_2eUQHl#2&IabCG*$A1@!jWu6P)f>5>8xY0P^5D5I}y>l$iV6k zG@D`H)pqWCa7Pavc5K1=N@6H#51@~JlqN*LMWqa|23a}F79;wnM zN$My6}LjjFJAjYcPJ&S$?; zdDAegn1QnGYPKHty;v?4IC-v$HM*+QCvZ5qjg@wjHEBwjH@Xe+qvP)yw>u%MroGVh z@Wm`McZu&`N)7=jyjQp_`@FS>hZR(bne6AES%m%@^15^6Kb8^ejD}U>m~`?37snsr zg~lRf30D6c@R5>W5C|ejkm&fdY}yV>nl#9W2#EQC(y}NRaz}QqGf$H!|EFRv4n-SV z6VQ}d{YSdewlRX-@G7`;E`5QQvi?9S_;P#>r)5KUYlOn44@_)6cG89l$?-g06!r9+ z?jzwEDP!g1KDkNMhSfIc=10&StZxTv@RzZnnxm`Mc!3tMz=b70mSj&|n0oTdpQz)V z%KXWEhE@+gPg}1mCnuwb>4>cOpj`R)FXx~7e?^Pj<(`F!N)QK54-eg54|Fkm7E0Vh z;wwPYvM+YqS3Dju^9nF%A$E1FNMV!OKr9sW8l7@BL47^Qf{k)nHxerqB)(*L{7d=O zKWbRDavDkI4g8N>%)Y!1mLlMi2~mMM0{E)ms2uTiVHb>A;(F}SpYqS^0#c6-^*#!D zc&$u+Y)HD}a&sq_EIy*boEHvdqa#QKOCP75ba99N5vSr8umt>50M;VISD;meOd^R^ zMn*LKXR-J6NXJ%Have#k#`HkLvbp>Z(Rrv^RXv-%? zzNYA<{kzJmoM?EN7ZEYj!^w(goU*ccb|fn3|4>*c;V}5DKYY2m2Z8+W#H-2s{ z@i%5R>jPqD1ns~Nvsb$*sO85|F-C(WMmE;=Iyrbi+cc4dza>Fj07?))00U4=j1D3*5p!&tR?6FtA3^-g2Ty$AGjY`SRrOU^6b#X?6evMQx)s0E8mA#b9eV}EK~e=wU17lRc+$^|K8@_F@|?;BPqW>4R?J|yBwG-c&d=5f zRF^OwD1U-M83L>MAVR}mbTCh->ly3hh$AE;;8^Mp0nF9xtW`Dfmw40Gh;)98(rY*6 zq&uBH_5J|V&D7wI)!nU~9scCLOqjKszpJ0)?7gsNclaAf5S;zQrcurR=-Y^7+?H!p zaLuuFvdZjc<1SqPCH7Ng%5Ak@D@P&}kjJ>>vu?kzUadaH=6g=!j+vsIa$g@8f=UJ| z0}Z^an2yH!$ryvlW9KF!m>`Fvn#)|-Gg?`7jp?rxm#p`F004@QZ`e`5?}>E-{ylRG3#in){1=&7)OLNxOji~2U1?ZeB28dx4#EPb_a0awT2kk& znjDV@5u6{?5XaH~k2h?QMqaR_I{s6uy@NgXb|kQO9eZ z9FIS<)B0A9fRfJ^PjvvBW*8)xyj|f$JNwvl+(zMep;+^KD;b9_c@yTuOC2GPP&b^l zo9j8%+$8JbxoV@b*PbzI9&68-jkM5f)q$cr(z^2l5dwdp``{a_?xvaYRI(9b6eI@sR2m!h=U_`Sz ze7_r#o_?6Q(ErlL6*woNopBa{p2`8&a{H%e&jIp6uX;xBsi0$MN~2sNrnJU+5ltKa zd@RUh!LhTY8kW0T^aH3A!rl0(CGnJ9nU-gI?>qYOWFSKf(E%>eh|x^fE0<2vhNjb2 z6Ps&|t~oG1#e|G3cPo%copw}Od6cQq$$jin0^G5^-@d-?driWrfdM>Lz3bE+QyI}C zgRbB#ul@NJ_^Ba@cMnpKE}%;}>P%3UvLkg>2d- zh72%k1%eWuu^k=K@Yh%!PYh3lC+==M}Hv{k%ht|)SNAu47M!`S=}^vuq^ zjnpLIKOt_R!8j-pYPA}o)Y7yKYrzdi!3iA#U66cA2^XW4^Mx4MT0j#D)wA*;A2S9BGq2ZjmoE#~8-hI_a51q^JSW53ZB-h08lSyhR{__-8!)Sw2HL73vf8i%;Xc~F zHTR}aLwVAz`?=HCMJSB{58nNetp9h(+L6{|Im6VLiR_98H==*~{hMlB<46w-!77z^ zK1Nl~SlaE|-3mM`z(R3%Rv`xFmPt>5Vj^9!Z+^T9^j*!(fBV?iB`{<>d#!b;+jJ|3 z%rSr_3VLt=_4KGAs5N>mf1(e26ivJV*Rx-ABdOxF$XR}?v?`2C*rx~K-~~5KA-n1U zU;Xo7!C?cx!UBPWVewsH07y4=ofrgBnvs*dHUCRL{3WgX{_Ga1?gCaSX!IO2$3wiFE^f0)e`QbnZ zLUyC_fQ2_4ESO-1?c4m~>6Z>1zP-YxUZ zu~!QvL0qyB1mv2)Cfw@!>b~Vy|JqJ_$cTaj!IROpoptqn>@e}LtKgk4;(-^N&6?|! z2_}UgA~zdXDbfO>jKn5pi65F8_cpxd9VGB>%+dDqT-jUnnVqVjH+p=^65i@8c94?% zE_G>oK7N-?`Hz4O1J3bZ2%NRszY;j#O~QDTzX;qrq}2n#0^_g^n)}TEqA<-eumSb| zwJ?ny`~RviO_bVZO9oa@5vPZ0*OLeYv#u@66PBUI=(k=5w9<0GIdEKD4VZ%tqX`tR3*sn*E@NqzEY5yoHTk@ZvxETA= zmlkyleu2iC70Uf2QtEQqvefUPTqy`N+AC=Usrrc1M=`)76sI1m?vLwpEcAI|q&m`~FJKu-oAXhR1eVoYy zPG8!1D|ALrgEDy$+K$9oTH8H!3`#ydmcX_If|P{Z1l%X(xmd1eO=IzE@=%(a>>Lyz z%o>^OZG7}1(=bpeF79{MveQ^evY~znpzOuN40O}Y#?ZC;-bp#c?X*Ojy_e&$pPIwt z7=vQkU5`d!SB(-?%BSsyKeWm&E`56CLrW7(5{<%GA&f&Q>!1;ialZ+>)WwM_;+-7y zS?!(s-Je-V!!$tZ?S(o|mh8C=O51`p&u;2aWZ}iO^BY#1!7)B;AAL7Cs1V9D3I?TZ zT?b)LM4f0Q4wxq@YpeDG;m6}}fk{bBPy~S}f`8MR6|GNCFF*pf zwx4Bf8G{Lm`J)kyQg=;L6u3fM`l^4*OPjHNS_F?x|16Q+Znq8UaI((3QA&@L9j`Yb zradQgxpdi0)5rQjV@Chrwy6rZMJyX8F0g7L zVSAU{YHaZ+zn+-!A8?++TO~CmAeQw9Q>;pEx z5E@7cf0Q8CZJ2K<3)lVIND-BPoqQ`9@^4{VvTD-OI+)*wx}TS99wL`npgl&q%EVl- zf=g}AK^djvW0B-^(KR+15^}57$Lwa$4tz;qOUaK?OsVQsNHSQiM4H#HZZtepvk$7H z$Rg@?Na$ICHH-rs*Ht0Rfd5!02FTdr;g6B+UMiU@EuoSy0AvhHa@^0$B|bUl*CG72 zJHJ@-Bkxw5wicE1`ssLp<|D#N07ahi0Rs3KUBvHt}iS z`MmO@*tSd<^(((wZEVnlARBxoV|$a#;C3q{${ZQbG}T4HpuH|P4aJdS)Ogsk2oI(J zvR>VhGcP(s-qFOm&xlV}4>)|^ctpp3^WO9=c#DQIT3M=~BvRr~P7C@l@=vKuRcCc~>?KRD?Sp|u=mPHJ-PcCw)Grig(bzg1KMSY2d09EvOfSxwI@sAk${UnI zBrZIb`_r1ck`C#$nbubMnoW;OSxo&bDu@1~u}_D4;ONe5_u2vlN8i!jd5WVs`U-?` zKs8g;v;19tkGHR52lDzVI=)@DgX26g*gZ|JOkJ!KL_4e+s5q_!oZ7=H%nRIzG2a`$Tyi=S!0be4~p9-}Qd%>hXHH!*oqdecmk5f)1@As08WH6guhPJM2eY6b{!3c_d0d zjd9pD;8CW`GgT=tYPF-MsbJLNWy zb9J3&#d&YrEScEN%`_uO;2GHKLzJZkfLhk={T4QwiG5mjH?HIjw_oXf%Y2kTFsROx z0k!FDr`krA>OQDtl~&ib=ex=1WaOnjQ~7B~E`mOehU#3jXiiCadrX}&^kk-4!`Yo#^eoQXUoTBlz-_rm+P~Ry`*}08V-2C}iYiQ9w5Hqq4LSZ?d#6KKQam8= z+XW=2LA)0^JdnXQE`hql{@T`kWg~AH%0tsa>5mUqi0uh_qmz}ST%=3*W+=eRbaC|5 zdpF5L8)1d8WoGJjC`JVjUcg@`S|=*YDlThyl2(Sw#xx8L7Z}EtBB`ioL=gxjA}FL- zm{2BU1cg8h4Tc$4P1vva>AmZ9a8EUEZ?>Pqbuh_icD7b9=R=YW z4<;xn)|zxw-2#u2B8vOA_w1w>`K-@Fm07}a>V7FR%FbXYreFGJkrtHDrI4z2^CZjn zOC?Hhh{dwJu$r2#ErpGA$!wfFf{{kc{p z4ERl8cKD@jZ`Zu@UC%jt681nhx6Za&pZDA`e4GX?=;KXm)ruw}8oSn{eOmtQn$2TP zA2_PuI6~p!wHoyTSWqx9t&)NDOj@q}&0N|-+F7M#h(60nZdQC0!F;=^jhPa)faqlviczu zO2R4>2xfRTO;au3g)^7BsvN82s&y$7R`qr2e7LwRE|qtD_S zV8Oe7r6DbXYz`22Vr}?3{I|8M%u+LW36Qndol6;fvQ#5@Rk09t&ebF1%k_S@dxZUA zTmj_?Fv4-qBTv8Ny)=Iz|2T4<_>2gbkj&yuT5*<~)% ztHw%;8NrAYftFc?lyKssx;pTHJXt?|-Sf?KX*BbFPtH@*p{)7Q}qTr}; z3E>#aB|9l6ntW!z`*J)B7K@Rd`fBD01AZkT4lI_FHd)>&DIywZ-qYuCGQ-lZ`CT%grpZ*2*z!m!=zs#!y)hLD4($ z+0WpjRG*WpD%{?o`{eMqJG*lEJ`qx7a%jsJ+7Ib}Fg0nZ$fT2yRF6c&ce$xlec)A} z=T>k3?AoV#47jHbZMQcR=WakTKK#7nrYgFQziCf6L7ncJriYSt{cJ6-m;4KCL|T|* zLM}Btf7e+OP0dU_u%$el9qy5P4F964W_H8zVx{T3il&mTQa4f}B zT)o*d?o$G{3eF80JoQzD(B_v7vpmF!Z}-FC8>lfkkgpS3>0P*oi2y;3 z%ITj4#yQ2r* zR0=ZMIyD*XSKLRV4Dw9aEFu&KcVKPJZp0Pvm55`qGW^jLG2*NffIL039!l^rs+QkW zs<1X=Lfv_!^=VUSMVt($V6)^$$@-nc$)3+F zSI*n(f_=ufVUU-%l8L0UHk=}MENdUx*Z)KYJFa|^#HH z+M2R5k~8&HAwdm{Dc7P==9jTwTrsoglj>--AAWmFs6K{n*0K?rQ`v<5{B321Kq2EQ zA+pbUj#30ON4}yw2RUQCY1OSl2M&kXs3C6z7Dv(dsB(PYPji_~81NPHcElWWz2r2? z2+fp2^k}X6=wZerxfJ&)5o&*jpF`OMUS1r|s)qKd&-qqhCO4DyDW*O^y~j&lH%8VY z=Z2R0QMQvXi0V_YI@0_}u?FI28wJc*xon0;ji>eRVljnc_kr}g2$;GT)loBYpPAoB zp|6?HN%73#d@|*2Mvop2_LP!qag~{c%%dG$-cx*xlBdvBB{-};H0Scfy_2#Eg%ha{ z9AVeLi;4@xMEQEZd&Cd?3TaTdrMmwe@k1{tTB}J`y{_3BSFY_YdbRT~RpszVA)L5E z+D8&5J5gz(6aex$25#?V)#7nZM;?uR>pado?zO5v2=9RZ`JOj+d}@d5AydY#t(553 zeBMtq7e(iFKgYx}547~OPXNb9D}hbk>Bt%d2|x5jXhgES)Tlae-{-~NFV5YbAKUA_ z&-eczx?SoR$6u~4BJ)^)6AL$nn)IIGW^Z`nPBWgG*$kG`?e3>s2Ta$yIDOVkPfJmj z`FNXKXE+g>)l{f{{Rs4(aT!E+TiivS{Dz+SVOe#(g3MVS`u=kV0${lPU3-YY+v?GA z2~KbUQ@g^RgV)N#+8E9iP6TpE+0uymWV@8+T{ut66c{+dC>ar zZ2fg-_O;d>09FRq7ybG=Tga*kM!X=t@8~}6aV>}NMo__lidH46xZ52v@V{(N2s!{t;p5+BK-uNI(J z`{r3LbdX?4Sr*OH!?%AO#9vCk0+|~T82b8})8im#ZqWj|e;ezzT`sB=~v#wuq=jl@c zrMJLJg>Jmj<9z>6$zebzLe#sF5$zj}s{Z#0>m2>mLOUjRK@+FEFKkJB#$km_YOMh+ zEvjFc9ao5_p!f{$s@@vglvnt;OlRGA?xj3XKn9EQuB|zH+^a?O)Xc5L83}gMas;Ki zF|RU%slyeT$aT;FO4q()b5CTMbr?vHZzRzh>G1PkpJx#Z?W&LrP<6S$2`nBv~6{5DeC6Q|ktIv)T42{5mE* zyS~xm23<*oU{sT5CGfQrwC(NI0mD<;sn1Xh3wafZc6hIbRtlv)RB8kb%#4Ns0q!G1 z?@qm55)hnlekim3YTkNXvz|Fv8HoMGEqsTG zG~Dg86TWzoT(;UHVMi0$4+U8qM6^J{kxh?~v&o4{A8(i7y?O)f(sT11j5wn34LwAU z@)Es}AF4?Wun1G<2&>-x%hx--sp~erHkE!IHe=_n-Mw7<1Bre*`l+Czjto{hHA zboFb=U}DFi^c1DJ{3VOlR!hsaDq4?Wcv@@MZeb9Pt_$3T^gA?*3W5uc(wd!8oH%MV zdQ1=QKLgQwQv>%o0=X(AkXr|DPlJIQMZ~*d z1qByWgxWeSV!2n@uk1C3Lz+{{NBfpo$8E~N;pjt6=@*{w>|=1tntcixa%Jjr`Kd1j=@X^|YIR9Ar4(gL#w~XGZBVf+`W^g4sGl zJ8)(NR-9|~98hiid?dBgSvaXwz2Wm;^D`Hfu4b@13&z9%S&k@*E79 z=PO+xvDVm8NisF?V}*$rfXIi2&N)71D{M}o%8VDXF!Efhe||8#`8EY^V(B+wAaM?b zbf3+1)`YgBhgyVrN^6}Rwr_rZ!IP^;@c!7-CYOGI=V6vdg$gOe4OyC9IfQd`03jLp z6%|qnkV2uoWMm#)VrJtLK{x6Ff@^6ij^0Lkbg+bFdqep{0a=oXySqQ}J+(h;T=gZf zcj@4@M@I8_+?Trok{O(&KXa0cl(bK={D5oEiRhp1MPVfiB$O-_?mBc94C7dGU@M>S z)5J??=-87C1pMz^o_duZ|4ifc3S2Kqj>;K6PvW)htE_wmC^;FOTFfe#S@ekB7rSH) zjwzR()OHSPvP_DnptsbG*WlLb`qf?eICu5IGSGxjiW1{BqoY7S4;cp%@Y`y(Q`$Td z6h!vd0uZhfZ3_c%keP&k!-Zf%KQr0$JzBF9$^Y?*ADy8n4DGADwRASl|6EHKBZ5#X zg|v{eoD7GtLkxt~K+Bs83LqFxqERq!Y5Z}W`0v|)C#NjmfCV6z$(tvz{s9#gJCCag;mk|^@-7AlF^ksNJ*_Bx-1^5?&_yaJ?xcgl2-CLt zG^lps_K$;bRt!stPMQCa6m1JS*MDuLC~|sjNDysPiI6R-$_Aied&Iu${Kvs{;LZq9 zg9%cv?*WC{|M)nK5Go{*rlIE;Eq&d=-)e6G#CRr7$-Otd-<1(K1pC29ybvSp>T&<{Nl$U)8DWA cWl7)<42_Wz^>#%47yzhAiOGr92!9RyFZrvQ2LJ#7 literal 0 HcmV?d00001 diff --git a/tutorials/zed_depth_sub_tutorial/README.md b/tutorials/zed_depth_sub_tutorial/README.md index 0b01a073..7ca8520a 100644 --- a/tutorials/zed_depth_sub_tutorial/README.md +++ b/tutorials/zed_depth_sub_tutorial/README.md @@ -2,4 +2,8 @@ In this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Image to retrieve the depth images published by the ZED node and to get the measured distance at the center of the image +![](../images/tutorial_depth.png) + The complete documentation is available on the [Stereolabs website](https://docs.stereolabs.com/integrations/ros/depth_sensing/) + + diff --git a/tutorials/zed_tracking_sub_tutorial/README.md b/tutorials/zed_tracking_sub_tutorial/README.md index 97b754b8..28d6e107 100644 --- a/tutorials/zed_tracking_sub_tutorial/README.md +++ b/tutorials/zed_tracking_sub_tutorial/README.md @@ -1,3 +1,8 @@ -# Depth subscription tutorial +# Positional Tracking tutorial + +In this tutorial you will learn how to write a simple node that subscribes to messages of type +`geometry_msgs/PoseStamped` and `nav_msgs/Odometry` to retrieve the position and the orientation of the ZED camera in the `map` and in the `odometry` frames. + +![](../images/tutorial_tracking.png) The complete documentation is available on the [Stereolabs website](https://docs.stereolabs.com/integrations/ros/positional_tracking/) diff --git a/tutorials/zed_video_sub_tutorial/README.md b/tutorials/zed_video_sub_tutorial/README.md index 2ee2a00e..94debb33 100644 --- a/tutorials/zed_video_sub_tutorial/README.md +++ b/tutorials/zed_video_sub_tutorial/README.md @@ -2,4 +2,6 @@ In this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Image to retrieve the Left and Right rectified images published by the ZED node. +![](../images/tutorial_video.png) + The complete documentation is available on the [Stereolabs website](https://docs.stereolabs.com/integrations/ros/video/) From 726331f377dabea8a06558e4b373cdeb764a17a3 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Tue, 11 Sep 2018 12:09:00 +0200 Subject: [PATCH 20/55] Update README.md --- tutorials/README.md | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/tutorials/README.md b/tutorials/README.md index 2c7633eb..643bb2e5 100644 --- a/tutorials/README.md +++ b/tutorials/README.md @@ -1,9 +1,13 @@ +![](../images/logo_stereolabs.svg) + # Tutorials A series of tutorials are provided to better understand how to use the ZED node in the ROS environment : -- [Video subscribing](./zed_video_sub_tutorial) : `zed_video_sub_tutorial` - in this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Image to retrieve the Left and Right rectified images published by the ZED node -- [Depth subscribing](./zed_depth_sub_tutorial) : `zed_depth_sub_tutorial` - in this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Image to retrieve the depth images published by the ZED node and to get the measured distance at the center of the image -- [Positional tracking subscribing](./zed_tracking_sub_tutorial) : `zed_tracking_sub_tutorial` - in this tutorial you will learn how to write a simple node that subscribes to messages of type geometry_msgs/PoseStamped and nav_msgs/Odometry to retrieve the position and the orientation of the ZED camera in the map and in the odometry frames. +- [Video subscribing](./zed_video_sub_tutorial) : `zed_video_sub_tutorial` - in this tutorial you will learn how to write a simple node that subscribes to messages of type `sensor_msgs/Image` to retrieve the Left and Right rectified images published by the ZED node + +- [Depth subscribing](./zed_depth_sub_tutorial) : `zed_depth_sub_tutorial` - in this tutorial you will learn how to write a simple node that subscribes to messages of type `sensor_msgs/Image` to retrieve the depth images published by the ZED node and to get the measured distance at the center of the image + +- [Positional tracking subscribing](./zed_tracking_sub_tutorial) : `zed_tracking_sub_tutorial` - in this tutorial you will learn how to write a simple node that subscribes to messages of type `geometry_msgs/PoseStamped` and `nav_msgs/Odometry` to retrieve the position and the orientation of the ZED camera in the map and in the odometry frames. For a complete explanation of the tutorials please refer to the Stereolabs ZED online documentation: From ecca1140a276a43e978643c68bccc411fcceb028 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Tue, 11 Sep 2018 12:09:24 +0200 Subject: [PATCH 21/55] Update README.md --- README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/README.md b/README.md index 86220b9c..150f06ed 100644 --- a/README.md +++ b/README.md @@ -1,3 +1,4 @@ +![](./images/logo_stereolabs.svg) # Stereolabs ZED Camera - ROS Integration This package lets you use the ZED stereo camera with ROS. It outputs the camera left and right images, depth map, point cloud, pose information and supports the use of multiple ZED cameras. From d009a33273717522cbe230ad300211efb00b7b59 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Tue, 11 Sep 2018 12:10:10 +0200 Subject: [PATCH 22/55] Update README.md --- tutorials/zed_depth_sub_tutorial/README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/tutorials/zed_depth_sub_tutorial/README.md b/tutorials/zed_depth_sub_tutorial/README.md index 7ca8520a..a60c751a 100644 --- a/tutorials/zed_depth_sub_tutorial/README.md +++ b/tutorials/zed_depth_sub_tutorial/README.md @@ -1,3 +1,5 @@ +![](../../images/logo_stereolabs.svg) + # Depth subscription tutorial In this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Image to retrieve the depth images published by the ZED node and to get the measured distance at the center of the image From d998cf22d84de89178929bf27c066b3d9e473f52 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Tue, 11 Sep 2018 12:10:29 +0200 Subject: [PATCH 23/55] Update README.md --- tutorials/zed_tracking_sub_tutorial/README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/tutorials/zed_tracking_sub_tutorial/README.md b/tutorials/zed_tracking_sub_tutorial/README.md index 66d81cc5..c23b43cd 100644 --- a/tutorials/zed_tracking_sub_tutorial/README.md +++ b/tutorials/zed_tracking_sub_tutorial/README.md @@ -1,3 +1,5 @@ +![](../../images/logo_stereolabs.svg) + # Positional Tracking tutorial In this tutorial you will learn how to write a simple node that subscribes to messages of type From fcf433eafacd3fb7ab91aa231854c7dbbda52856 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Tue, 11 Sep 2018 12:10:45 +0200 Subject: [PATCH 24/55] Update README.md --- tutorials/zed_video_sub_tutorial/README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/tutorials/zed_video_sub_tutorial/README.md b/tutorials/zed_video_sub_tutorial/README.md index 94debb33..0d98e65b 100644 --- a/tutorials/zed_video_sub_tutorial/README.md +++ b/tutorials/zed_video_sub_tutorial/README.md @@ -1,3 +1,5 @@ +![](../../images/logo_stereolabs.svg) + # ZED video subscription tutorial In this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Image to retrieve the Left and Right rectified images published by the ZED node. From 19ed184239e95fc2d045c5b112134e7aee613b8d Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Tue, 11 Sep 2018 12:11:16 +0200 Subject: [PATCH 25/55] Update README.md --- examples/README.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/examples/README.md b/examples/README.md index b4aac315..6969403f 100644 --- a/examples/README.md +++ b/examples/README.md @@ -1,5 +1,8 @@ +![](../images/logo_stereolabs.svg) + # Examples How to use the ZED ROS node with other ROS packages * `zed_nodelet_example`: shows how to use the nodelet intraprocess communication to generate a virtual laser scan using the [depthimage_to_laserscan](http://wiki.ros.org/depthimage_to_laserscan) package + * `zed_rtabmap_example`: shows how to use the ZED with the RTABMap package to generate a 3D map with the [rtabmap_ros](http://wiki.ros.org/rtabmap_ros) package From 24779e9032213ce490a8e76a6d39e94e3c02525a Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Tue, 11 Sep 2018 12:11:39 +0200 Subject: [PATCH 26/55] Update README.md --- examples/zed_nodelet_example/README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/examples/zed_nodelet_example/README.md b/examples/zed_nodelet_example/README.md index 70e83c2b..769e9f29 100644 --- a/examples/zed_nodelet_example/README.md +++ b/examples/zed_nodelet_example/README.md @@ -1,3 +1,5 @@ +![](../../images/logo_stereolabs.svg) + # Stereolabs ZED Camera - ROS Nodelet example `zed_nodelet_example` is a ROS package to illustrate how to load the `ZEDWrapperNodelet` with an external nodelet manager and use the intraprocess communication to generate a virtual laser scan thanks to the nodelet `depthimage_to_laserscan` From c3ad465020ffab92976f28d4a807a5d71c62f700 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Tue, 11 Sep 2018 12:12:06 +0200 Subject: [PATCH 27/55] Update README.md --- examples/zed_rtabmap_example/README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/examples/zed_rtabmap_example/README.md b/examples/zed_rtabmap_example/README.md index 98483107..6ebc2dd1 100644 --- a/examples/zed_rtabmap_example/README.md +++ b/examples/zed_rtabmap_example/README.md @@ -1,3 +1,5 @@ +![](../../images/logo_stereolabs.svg) + # Stereolabs ZED Camera - RTAB-map example This package shows how to use the ZED Wrapper with [RTAB-map](http://introlab.github.io/rtabmap/) From f028f79220eee12fd1ec9b279b48401a00c14f2c Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Tue, 11 Sep 2018 12:12:31 +0200 Subject: [PATCH 28/55] Update README.md --- zed_display_rviz/README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/zed_display_rviz/README.md b/zed_display_rviz/README.md index 54eb06b2..3d22c0e7 100644 --- a/zed_display_rviz/README.md +++ b/zed_display_rviz/README.md @@ -1,3 +1,5 @@ +![](../images/logo_stereolabs.svg) + # Stereolabs ZED Camera - ROS Display example This package lets you visualize in the RViz application all the possible information that can be acquired using a ZED camera. From c2c863f6c1ff72fc5b35c76219139586906644bc Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Tue, 11 Sep 2018 12:12:56 +0200 Subject: [PATCH 29/55] Update README.md --- zed_wrapper/README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/zed_wrapper/README.md b/zed_wrapper/README.md index 046e86de..df1f05ec 100644 --- a/zed_wrapper/README.md +++ b/zed_wrapper/README.md @@ -1,3 +1,5 @@ +![](../images/logo_stereolabs.svg) + # Stereolabs ZED Camera - ROS Integration This package lets you use the ZED stereo camera with ROS. It outputs the camera left and right images, depth map, point cloud, pose information and supports the use of multiple ZED cameras. From 4ffb7f1569ffc364165033ea003cae66fb18d579 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Tue, 11 Sep 2018 12:15:26 +0200 Subject: [PATCH 30/55] Update README.md --- tutorials/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tutorials/README.md b/tutorials/README.md index 643bb2e5..8a563237 100644 --- a/tutorials/README.md +++ b/tutorials/README.md @@ -11,6 +11,6 @@ A series of tutorials are provided to better understand how to use the ZED node For a complete explanation of the tutorials please refer to the Stereolabs ZED online documentation: -- [Video](https://docs.stereolabs.com/integrations/ros//) +- [Video](https://docs.stereolabs.com/integrations/ros/video/) - [Depth](https://docs.stereolabs.com/integrations/ros/depth_sensing/) - [Positional Tracking](https://docs.stereolabs.com/integrations/ros/positional_tracking/) From 606c4535917a37bcb79945077312cc445b024cd5 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Tue, 11 Sep 2018 12:22:48 +0200 Subject: [PATCH 31/55] Fixed display.launch --- zed_display_rviz/launch/display.launch | 14 ++++++++------ zed_display_rviz/rviz/zedm.rviz | 21 +++++++++------------ 2 files changed, 17 insertions(+), 18 deletions(-) diff --git a/zed_display_rviz/launch/display.launch b/zed_display_rviz/launch/display.launch index e27842c8..67f45814 100644 --- a/zed_display_rviz/launch/display.launch +++ b/zed_display_rviz/launch/display.launch @@ -17,13 +17,15 @@ THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. --> + - - - - + + + + + - - + + diff --git a/zed_display_rviz/rviz/zedm.rviz b/zed_display_rviz/rviz/zedm.rviz index 69fa257d..6e423132 100644 --- a/zed_display_rviz/rviz/zedm.rviz +++ b/zed_display_rviz/rviz/zedm.rviz @@ -7,6 +7,7 @@ Panels: - /Global Options1 - /RobotModel1/Links1 - /TF1/Frames1 + - /DepthCloud1 - /DepthCloud1/Occlusion Compensation1 - /Odometry1/Covariance1/Position1 Splitter Ratio: 0.5 @@ -97,8 +98,6 @@ Visualization Manager: Frame Timeout: 5 Frames: All Enabled: false - imu_link: - Value: false map: Value: true odom: @@ -122,8 +121,6 @@ Visualization Manager: map: odom: zed_camera_center: - imu_link: - {} zed_left_camera_frame: zed_left_camera_optical_frame: {} @@ -238,11 +235,11 @@ Visualization Manager: y_scale: 1 z_scale: 1 Class: rviz_imu_plugin/Imu - Enabled: true + Enabled: false Name: Imu Topic: /zed/imu/data Unreliable: false - Value: true + Value: false fixed_frame_orientation: true - Alpha: 1 Axes Length: 1 @@ -318,25 +315,25 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 2.1419313 + Distance: 3.77481484 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 0.546764851 - Y: -0.0699039996 - Z: 0.35577035 + X: 0.861115396 + Y: 1.21251762 + Z: 0.619552732 Focal Shape Fixed Size: false Focal Shape Size: 0.0500000007 Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 - Pitch: 0.30479762 + Pitch: 0.0147975748 Target Frame: Value: Orbit (rviz) - Yaw: 2.96410108 + Yaw: 4.01910114 Saved: ~ Window Geometry: Camera: From b6bb43fb58c408eefab263e911e3df2b812ba6b1 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Tue, 11 Sep 2018 14:55:19 +0200 Subject: [PATCH 32/55] Fixed issue with SVO and timestamps --- .../nodelet/include/zed_wrapper_nodelet.hpp | 1 + .../src/nodelet/src/zed_wrapper_nodelet.cpp | 56 +++++++++++++++---- 2 files changed, 45 insertions(+), 12 deletions(-) diff --git a/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp b/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp index e1f987ff..783c8fd7 100644 --- a/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp +++ b/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp @@ -306,6 +306,7 @@ namespace zed_wrapper { std::string svoFilepath; double imuPubRate; bool verbose; + bool mSvoMode = false; // IMU time ros::Time imuTime; diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index cf025b06..cbb45110 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -282,6 +282,8 @@ namespace zed_wrapper { // Try to initialize the ZED if (!svoFilepath.empty()) { param.svo_input_filename = svoFilepath.c_str(); + + mSvoMode = true; } else { param.camera_fps = frameRate; param.camera_resolution = static_cast(resolution); @@ -1109,8 +1111,15 @@ namespace zed_wrapper { return; } - ros::Time t = - sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_IMAGE)); + // ros::Time t = + // sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_IMAGE)); + + ros::Time t; + if (mSvoMode) { + t = ros::Time::now(); + } else { + t = sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_IMAGE)); + } sl::IMUData imu_data; zed.getIMUData(imu_data, sl::TIME_REFERENCE_CURRENT); @@ -1244,9 +1253,17 @@ namespace zed_wrapper { void ZEDWrapperNodelet::device_poll() { ros::Rate loop_rate(frameRate); - ros::Time old_t = - sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); - imuTime = old_t; + // ros::Time old_t = + // sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); + // imuTime = old_t; + + ros::Time t_old; + if (mSvoMode) { + t_old = ros::Time::now(); + } else { + t_old = sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); + } + ros::Time old_t = t_old; sl::ERROR_CODE grab_status; trackingActivated = false; @@ -1328,8 +1345,12 @@ namespace zed_wrapper { // depth information // Timestamp - ros::Time t = - sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_IMAGE)); + ros::Time t; + if (mSvoMode) { + t = ros::Time::now(); + } else { + t = sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_IMAGE)); + } grabbing = true; if (computeDepth) { @@ -1360,7 +1381,7 @@ namespace zed_wrapper { std::this_thread::sleep_for(std::chrono::milliseconds(2)); - if ((t - old_t).toSec() > 5) { + if ((t - old_t).toSec() > 5 && !mSvoMode) { zed.close(); NODELET_INFO("Re-opening the ZED"); @@ -1393,8 +1414,13 @@ namespace zed_wrapper { } // Time update - old_t = - sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); + ros::Time t_old; + if (mSvoMode) { + t_old = ros::Time::now(); + } else { + t_old = sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); + } + old_t = t_old; if (autoExposure) { // getCameraSettings() can't check status of auto exposure @@ -1675,8 +1701,14 @@ namespace zed_wrapper { // Publish odometry tf only if enabled if (publishTf) { - ros::Time t = - sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); + ros::Time t; + + if (mSvoMode) { + t = ros::Time::now(); + } else { + t = sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); + } + publishOdomFrame(baseToOdomTransform, t); // publish the base Frame in odometry frame publishPoseFrame(odomToMapTransform, From 85431d8d94f7b2c7f913f0a2597de5744191c60a Mon Sep 17 00:00:00 2001 From: Myzhar Date: Tue, 11 Sep 2018 16:31:33 +0200 Subject: [PATCH 33/55] Resize README logo --- README.md | 2 +- examples/README.md | 2 +- examples/zed_nodelet_example/README.md | 2 +- examples/zed_rtabmap_example/README.md | 2 +- tutorials/README.md | 2 +- tutorials/zed_depth_sub_tutorial/README.md | 2 +- tutorials/zed_tracking_sub_tutorial/README.md | 2 +- tutorials/zed_video_sub_tutorial/README.md | 2 +- zed_display_rviz/README.md | 2 +- zed_display_rviz/rviz/zed.rviz | 58 +++++++----- zed_wrapper/README.md | 2 +- zed_wrapper/launch/README.md | 2 + .../src/nodelet/src/zed_wrapper_nodelet.cpp | 2 +- zed_wrapper/src/tools/src/sl_tools.cpp | 93 ++++++++++--------- 14 files changed, 96 insertions(+), 79 deletions(-) diff --git a/README.md b/README.md index 150f06ed..ce84d37d 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ -![](./images/logo_stereolabs.svg) +![](./images/logo_stereolabs.svg | width=100) # Stereolabs ZED Camera - ROS Integration This package lets you use the ZED stereo camera with ROS. It outputs the camera left and right images, depth map, point cloud, pose information and supports the use of multiple ZED cameras. diff --git a/examples/README.md b/examples/README.md index 6969403f..309c899a 100644 --- a/examples/README.md +++ b/examples/README.md @@ -1,4 +1,4 @@ -![](../images/logo_stereolabs.svg) +![](../images/logo_stereolabs.svg | width=100) # Examples How to use the ZED ROS node with other ROS packages diff --git a/examples/zed_nodelet_example/README.md b/examples/zed_nodelet_example/README.md index 769e9f29..7175c103 100644 --- a/examples/zed_nodelet_example/README.md +++ b/examples/zed_nodelet_example/README.md @@ -1,4 +1,4 @@ -![](../../images/logo_stereolabs.svg) +![](../../images/logo_stereolabs.svg | width=100) # Stereolabs ZED Camera - ROS Nodelet example diff --git a/examples/zed_rtabmap_example/README.md b/examples/zed_rtabmap_example/README.md index 6ebc2dd1..4419ff1d 100644 --- a/examples/zed_rtabmap_example/README.md +++ b/examples/zed_rtabmap_example/README.md @@ -1,4 +1,4 @@ -![](../../images/logo_stereolabs.svg) +![](../../images/logo_stereolabs.svg | width=100) # Stereolabs ZED Camera - RTAB-map example diff --git a/tutorials/README.md b/tutorials/README.md index 8a563237..7ece0db7 100644 --- a/tutorials/README.md +++ b/tutorials/README.md @@ -1,4 +1,4 @@ -![](../images/logo_stereolabs.svg) +![](../images/logo_stereolabs.svg | width=100) # Tutorials A series of tutorials are provided to better understand how to use the ZED node in the ROS environment : diff --git a/tutorials/zed_depth_sub_tutorial/README.md b/tutorials/zed_depth_sub_tutorial/README.md index a60c751a..dc03058e 100644 --- a/tutorials/zed_depth_sub_tutorial/README.md +++ b/tutorials/zed_depth_sub_tutorial/README.md @@ -1,4 +1,4 @@ -![](../../images/logo_stereolabs.svg) +![](../../images/logo_stereolabs.svg | width=100) # Depth subscription tutorial diff --git a/tutorials/zed_tracking_sub_tutorial/README.md b/tutorials/zed_tracking_sub_tutorial/README.md index c23b43cd..db58515c 100644 --- a/tutorials/zed_tracking_sub_tutorial/README.md +++ b/tutorials/zed_tracking_sub_tutorial/README.md @@ -1,4 +1,4 @@ -![](../../images/logo_stereolabs.svg) +![](../../images/logo_stereolabs.svg | width=100) # Positional Tracking tutorial diff --git a/tutorials/zed_video_sub_tutorial/README.md b/tutorials/zed_video_sub_tutorial/README.md index 0d98e65b..6b4da070 100644 --- a/tutorials/zed_video_sub_tutorial/README.md +++ b/tutorials/zed_video_sub_tutorial/README.md @@ -1,4 +1,4 @@ -![](../../images/logo_stereolabs.svg) +![](../../images/logo_stereolabs.svg | width=100) # ZED video subscription tutorial diff --git a/zed_display_rviz/README.md b/zed_display_rviz/README.md index 3d22c0e7..bbd3d5ef 100644 --- a/zed_display_rviz/README.md +++ b/zed_display_rviz/README.md @@ -1,4 +1,4 @@ -![](../images/logo_stereolabs.svg) +![](../images/logo_stereolabs.svg | width=100) # Stereolabs ZED Camera - ROS Display example diff --git a/zed_display_rviz/rviz/zed.rviz b/zed_display_rviz/rviz/zed.rviz index 931d66c1..45111e58 100644 --- a/zed_display_rviz/rviz/zed.rviz +++ b/zed_display_rviz/rviz/zed.rviz @@ -1,17 +1,15 @@ Panels: - Class: rviz/Displays - Help Height: 78 + Help Height: 75 Name: Displays Property Tree Widget: Expanded: - /RobotModel1/Links1 - - /TF1 - /TF1/Frames1 - - /Odometry1 - /Odometry1/Shape1 - - /Pose1 + - /Confidence1 Splitter Ratio: 0.5 - Tree Height: 452 + Tree Height: 441 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -30,7 +28,7 @@ Panels: Experimental: false Name: Time SyncMode: 0 - SyncSource: DepthCloud + SyncSource: Camera Visualization Manager: Class: "" Displays: @@ -38,7 +36,7 @@ Visualization Manager: Cell Size: 1 Class: rviz/Grid Color: 160; 160; 164 - Enabled: true + Enabled: false Line Style: Line Width: 0.0299999993 Value: Lines @@ -51,7 +49,7 @@ Visualization Manager: Plane: XY Plane Cell Count: 10 Reference Frame: - Value: true + Value: false - Alpha: 1 Class: rviz/RobotModel Collision Enabled: false @@ -144,7 +142,7 @@ Visualization Manager: Decay Time: 0 Depth Map Topic: /zed/depth/depth_registered Depth Map Transport Hint: raw - Enabled: true + Enabled: false Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 4096 @@ -162,7 +160,7 @@ Visualization Manager: Topic Filter: true Use Fixed Frame: true Use rainbow: true - Value: true + Value: false - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: @@ -175,7 +173,7 @@ Visualization Manager: Color: 255; 255; 255 Color Transformer: RGB8 Decay Time: 0 - Enabled: false + Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 4096 @@ -183,16 +181,16 @@ Visualization Manager: Min Intensity: 0 Name: PointCloud2 Position Transformer: XYZ - Queue Size: 5 - Selectable: true + Queue Size: 1 + Selectable: false Size (Pixels): 1 Size (m): 0.00999999978 Style: Points Topic: /zed/point_cloud/cloud_registered - Unreliable: false + Unreliable: true Use Fixed Frame: true Use rainbow: true - Value: false + Value: true - Class: rviz/Camera Enabled: true Image Rendering: background and overlay @@ -204,7 +202,7 @@ Visualization Manager: Unreliable: false Value: true Visibility: - Camera: true + Confidence: true DepthCloud: true Grid: true Odometry: true @@ -263,6 +261,18 @@ Visualization Manager: Topic: /zed/map Unreliable: false Value: true + - Class: rviz/Image + Enabled: false + Image Topic: /zed/confidence/confidence_image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Confidence + Normalize Range: true + Queue Size: 1 + Transport Hint: raw + Unreliable: true + Value: false Enabled: true Global Options: Background Color: 48; 48; 48 @@ -288,35 +298,37 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 7.54095364 + Distance: 1.89739549 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 0.946748376 - Y: 0.731980622 - Z: 0.698233485 + X: 1.17609167 + Y: 0.259650975 + Z: 0.122633442 Focal Shape Fixed Size: false Focal Shape Size: 0.0500000007 Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 - Pitch: 0.170398071 + Pitch: 0.310398072 Target Frame: zed_left_camera Value: Orbit (rviz) - Yaw: 2.91542745 + Yaw: 2.44542289 Saved: ~ Window Geometry: Camera: collapsed: false + Confidence: + collapsed: false Displays: collapsed: false Height: 1056 Hide Left Dock: false Hide Right Dock: true - QMainWindow State: 000000ff00000000fd00000004000000000000016a00000396fc020000000efb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000253000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000002400000010f0000000000000000fb0000000a0049006d006100670065000000028b000000c40000000000000000fb0000000a0049006d006100670065010000028a000000c50000000000000000fb0000000a0049006d00610067006500000002b30000009c0000000000000000fb0000000a0049006d006100670065010000028b000000c40000000000000000fb0000000c00430061006d00650072006101000002810000013d0000001600ffffff000000010000010f00000327fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000327000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000005cf0000039600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd00000004000000000000016a00000396fc020000000ffb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000245000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000002400000010f0000000000000000fb0000000a0049006d006100670065000000028b000000c40000000000000000fb0000000a0049006d006100670065010000028a000000c50000000000000000fb0000000a0049006d00610067006500000002b30000009c0000000000000000fb0000000a0049006d006100670065010000028b000000c40000000000000000fb0000000c00430061006d00650072006101000002730000014b0000001600fffffffb000000140043006f006e0066006900640065006e0063006502000001c60000011c0000016a000000ca000000010000010f00000327fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000327000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000005cf0000039600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: diff --git a/zed_wrapper/README.md b/zed_wrapper/README.md index df1f05ec..6fafb74f 100644 --- a/zed_wrapper/README.md +++ b/zed_wrapper/README.md @@ -1,4 +1,4 @@ -![](../images/logo_stereolabs.svg) +![](../images/logo_stereolabs.svg | width=100) # Stereolabs ZED Camera - ROS Integration diff --git a/zed_wrapper/launch/README.md b/zed_wrapper/launch/README.md index ccfd6be1..0911963a 100644 --- a/zed_wrapper/launch/README.md +++ b/zed_wrapper/launch/README.md @@ -1,3 +1,5 @@ +![](../images/logo_stereolabs.svg | width=100) + # Launch Files Launch files provide a convenient way to start up multiple nodes and a master, as well as setting parameters. diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index cbb45110..80cc0689 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -1263,7 +1263,7 @@ namespace zed_wrapper { } else { t_old = sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); } - ros::Time old_t = t_old; + ros::Time old_t = ros::Time::now(); sl::ERROR_CODE grab_status; trackingActivated = false; diff --git a/zed_wrapper/src/tools/src/sl_tools.cpp b/zed_wrapper/src/tools/src/sl_tools.cpp index 488511d6..45ef83a2 100644 --- a/zed_wrapper/src/tools/src/sl_tools.cpp +++ b/zed_wrapper/src/tools/src/sl_tools.cpp @@ -29,52 +29,55 @@ namespace sl_tools { int checkCameraReady(unsigned int serial_number) { int id = -1; auto f = sl::Camera::getDeviceList(); - for (auto &it : f) - if (it.serial_number == serial_number && it.camera_state == sl::CAMERA_STATE::CAMERA_STATE_AVAILABLE) + for (auto& it : f) + if (it.serial_number == serial_number && it.camera_state == sl::CAMERA_STATE::CAMERA_STATE_AVAILABLE) { id = it.id; + } return id; } sl::DeviceProperties getZEDFromSN(unsigned int serial_number) { sl::DeviceProperties prop; auto f = sl::Camera::getDeviceList(); - for (auto &it : f) { - if (it.serial_number == serial_number && it.camera_state == sl::CAMERA_STATE::CAMERA_STATE_AVAILABLE) + for (auto& it : f) { + if (it.serial_number == serial_number && it.camera_state == sl::CAMERA_STATE::CAMERA_STATE_AVAILABLE) { prop = it; + } } return prop; } - cv::Mat toCVMat(sl::Mat &mat) { - if (mat.getMemoryType() == sl::MEM_GPU) + cv::Mat toCVMat(sl::Mat& mat) { + if (mat.getMemoryType() == sl::MEM_GPU) { mat.updateCPUfromGPU(); + } int cvType; switch (mat.getDataType()) { - case sl::MAT_TYPE_32F_C1: - cvType = CV_32FC1; - break; - case sl::MAT_TYPE_32F_C2: - cvType = CV_32FC2; - break; - case sl::MAT_TYPE_32F_C3: - cvType = CV_32FC3; - break; - case sl::MAT_TYPE_32F_C4: - cvType = CV_32FC4; - break; - case sl::MAT_TYPE_8U_C1: - cvType = CV_8UC1; - break; - case sl::MAT_TYPE_8U_C2: - cvType = CV_8UC2; - break; - case sl::MAT_TYPE_8U_C3: - cvType = CV_8UC3; - break; - case sl::MAT_TYPE_8U_C4: - cvType = CV_8UC4; - break; + case sl::MAT_TYPE_32F_C1: + cvType = CV_32FC1; + break; + case sl::MAT_TYPE_32F_C2: + cvType = CV_32FC2; + break; + case sl::MAT_TYPE_32F_C3: + cvType = CV_32FC3; + break; + case sl::MAT_TYPE_32F_C4: + cvType = CV_32FC4; + break; + case sl::MAT_TYPE_8U_C1: + cvType = CV_8UC1; + break; + case sl::MAT_TYPE_8U_C2: + cvType = CV_8UC2; + break; + case sl::MAT_TYPE_8U_C3: + cvType = CV_8UC3; + break; + case sl::MAT_TYPE_8U_C4: + cvType = CV_8UC4; + break; } return cv::Mat((int) mat.getHeight(), (int) mat.getWidth(), cvType, mat.getPtr(sl::MEM_CPU), mat.getStepBytes(sl::MEM_CPU)); } @@ -118,7 +121,7 @@ namespace sl_tools { p[8] = 0; // R = cos(theta)*I + (1 - cos(theta))*r*rT + sin(theta)*[r_x] - R = c * cv::Mat::eye(3, 3, CV_32F) + c1 * rrt + s*r_x; + R = c * cv::Mat::eye(3, 3, CV_32F) + c1 * rrt + s * r_x; } return R; } @@ -128,40 +131,40 @@ namespace sl_tools { return (stat(name.c_str(), &buffer) == 0); } - std::string getSDKVersion( int& major, int& minor, int& sub_minor) { + std::string getSDKVersion(int& major, int& minor, int& sub_minor) { std::string ver = sl::Camera::getSDKVersion().c_str(); std::vector strings; std::istringstream f(ver); - std::string s; + std::string s; while (getline(f, s, '.')) { strings.push_back(s); - } + } major = 0; minor = 0; sub_minor = 0; - switch( strings.size() ) - { - case 3: - sub_minor = std::stoi(strings[2]); + switch (strings.size()) { + case 3: + sub_minor = std::stoi(strings[2]); - case 2: - minor = std::stoi(strings[1]); + case 2: + minor = std::stoi(strings[1]); - case 1: - major = std::stoi(strings[0]); + case 1: + major = std::stoi(strings[0]); } return ver; } ros::Time slTime2Ros(sl::timeStamp t) { - uint32_t sec = static_cast(t/1000000000); - uint32_t nsec = static_cast(t%1000000000); - return ros::Time(sec, nsec); + uint32_t sec = static_cast(t / 1000000000); + uint32_t nsec = static_cast(t % 1000000000); + ros::Time time(sec, nsec); + return time; } } // namespace From c2a93067e7a97c03d61ae38ee3953371bbb98cd8 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Tue, 11 Sep 2018 17:41:35 +0200 Subject: [PATCH 34/55] Changed README logos --- README.md | 3 ++- examples/README.md | 2 +- examples/zed_nodelet_example/README.md | 2 +- examples/zed_rtabmap_example/README.md | 2 +- images/Picto+STEREOLABS_Black.png | Bin 0 -> 10783 bytes images/logo_stereolabs.svg | 1 - tutorials/README.md | 2 +- tutorials/zed_depth_sub_tutorial/README.md | 2 +- tutorials/zed_tracking_sub_tutorial/README.md | 2 +- tutorials/zed_video_sub_tutorial/README.md | 2 +- zed_display_rviz/README.md | 2 +- zed_wrapper/README.md | 2 +- zed_wrapper/launch/README.md | 2 +- 13 files changed, 12 insertions(+), 12 deletions(-) create mode 100644 images/Picto+STEREOLABS_Black.png delete mode 100644 images/logo_stereolabs.svg diff --git a/README.md b/README.md index ce84d37d..9795c0ce 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,5 @@ -![](./images/logo_stereolabs.svg | width=100) +![](./images/Picto+STEREOLABS_Black.png) + # Stereolabs ZED Camera - ROS Integration This package lets you use the ZED stereo camera with ROS. It outputs the camera left and right images, depth map, point cloud, pose information and supports the use of multiple ZED cameras. diff --git a/examples/README.md b/examples/README.md index 309c899a..9c127a03 100644 --- a/examples/README.md +++ b/examples/README.md @@ -1,4 +1,4 @@ -![](../images/logo_stereolabs.svg | width=100) +![](../images/Picto+STEREOLABS_Black.png) # Examples How to use the ZED ROS node with other ROS packages diff --git a/examples/zed_nodelet_example/README.md b/examples/zed_nodelet_example/README.md index 7175c103..0766d27c 100644 --- a/examples/zed_nodelet_example/README.md +++ b/examples/zed_nodelet_example/README.md @@ -1,4 +1,4 @@ -![](../../images/logo_stereolabs.svg | width=100) +![](../../images/Picto+STEREOLABS_Black.png) # Stereolabs ZED Camera - ROS Nodelet example diff --git a/examples/zed_rtabmap_example/README.md b/examples/zed_rtabmap_example/README.md index 4419ff1d..79283277 100644 --- a/examples/zed_rtabmap_example/README.md +++ b/examples/zed_rtabmap_example/README.md @@ -1,4 +1,4 @@ -![](../../images/logo_stereolabs.svg | width=100) +![](../../images/Picto+STEREOLABS_Black.png) # Stereolabs ZED Camera - RTAB-map example diff --git a/images/Picto+STEREOLABS_Black.png b/images/Picto+STEREOLABS_Black.png new file mode 100644 index 0000000000000000000000000000000000000000..5dcb9be4caabf42920d0c21f7705e91ade527231 GIT binary patch literal 10783 zcmXY%2|QHq_s8$pcQYy^!YE9#j(s;qYKTl_mn~!8$r2i687Yz_V~w&Fk}VP=Sz?f^ zk)<%mn#nS<{BPgi|9QP^<1Wv0?|IJoocB2i*GvpK*#y`C0N}iG8I1)12o?POG7A&< z{b#V?74Qc`AnM8u7H~wc+$Mm3v-(}O3IqW5x_@5~mHWXl;D@J!3@n4L`{IH^90Oc{ zkdP1=cOTC{XGcF58Q%cc>~&2601yGLp!IHq=B(w0MVuL_>$`6vDx1 ze4R`d>NtnTzr5CCuA5eLQnEt=Po*yXg2A}Kbdt~H|CKn z*5&k<{PGq1G)=Ozo|3m4f63udon=jV z9w6ZA0G{CuC*B-bfxLF4NF*$Ax3{B}tRly{XN`%5XrDdzi5y>PRf7vB&0YH6Ow>^}#1d?orKjgg z9XbfZ(ysHO?$)eozm7h?#((EKVPQQzn(3Gh^Qv2s()c%mwCKu}BdwU~|G&IYv|-Jn zkQyvfVW}FXw)O8Ruul?I-_f&iT19PC|uNN@D$&Q`(kq#wV0EeJD(MJ{P=O}t)`&miSUUN48`s;;)N%G zX3e`ht5!xC7k}T+dr?ypXs)l{{u{!rK_+`bnoH~Mlm{0s%(f=SlACq#+;roNjSlN6 zZomM&C95v0==znCp?lIHNu->x3+WFltZFFgIBm63dBe>-zxf2TQ_^Bs7tD-D?PhZ) ze2N*OsfSL64qjaj+W#D|n1a0n>^TRIGW9zZ4UZYNN)~Afl8%Sl@>bHYe5Y0%vM8GH zCV7(D7@Z~kth?wZ=f1wa6F(h9`&^L<93C9FU{>B+Y5s^wJ)5zJ1+Cq@4$@A3RIC zhMD5~sL8BA)z?ebpz9+i1ABFIstxePYxHgQ--`)LfxwQw%h3)it|h|3VYX>{db+?# zXzrAi+QaS?3ljz6Bj52iKN#TZMxKYFg>R2rvjI!8mpoPFWtu5;Fxh*uMM$?S=mQgA zW8oa~MUI+DWF>3n5_U@Kw1D~xBhiE`vlb+RkDfGW?Ri^)7@XlUmDPunEx&a5gxCPN zMx7BwK6|lg$s4%XpSu<|Z2^g(BRyh^3)R8TWzycYwYAw}5F4jZ2b#GivfMqLyFAt_ zraXgbFxgy)h@Y!Ao62+lpJ>HgVgs{C#FgLlFVkEhss@M=n>B_E7opLanR_r;q{FA) zd(M=2$T<4XMda}V!YDle^De84YK1zn^w(y&oBh`Q3*?DEki z*7a`IA|acp%jbBQ!MRH%xIF{n{z8#6;zhQX(DrY<|0V#Pk4j~Sh_sq&%hjMEMOj}D zkNusuF1^#G4Q6#OL95FS)jSd#plU~dzv>1xhWO=-?yDje9-s(;L(4(el74DIU<*T! z^BFfGK>VHHVDHJHA!>kS;Dw@#4DSL=&hcc2<%IyST&`I^fC(n8a+Rvu<$t#HHd!r@ zQfop~SlEIc`SFvk0+r?%ty}Y7TOWr;&;$H&)ks)m96`ICTmyW+Z8h3PG^S8LeE4wY z68E*6ig!Vi-rn7{*MSK&x@UD^5W+b~R};@KaW{>?_icob9kkYo`Tp(76S6a<3v^lH zv;Jbg408xAii(Q!=XesrSFywNqD2P*nrDyM@k7uYG2uSCir|U2ukFQo68cbC&Z!^e z9?>>K!fQt*;31kPdvP`S<*yv)&gGgMclqbsO~V=jZiDKky?n|J=%v`$T$%h5-#ks}OzE^9Xy6)l*x%T3p<+^j|pXavmH zf4E=lVQ7L@p;vtaUZ4^j6#UvN{&qQQWv_8R9lWfVruP9a+}g=%bPOe+Q>eXKUUv(Z zReaM||KlgQM?`GTUx+Q;b6zgxPO|;5wFb85gNNMA%Q!;+rm#$)T?iw-l=t8-4*^#n&D!$XT0ad%c48pqWnO+2)31R~sig>D6vf70}O6sSS#bhWi7dQ8e*8bzM2e%bY^P#?@(885%L7&Kc#NyLI z=iJbdL=$xD+Un}-+RnC^PQ^a0Sf~_45F5W70{J3Vq*=)oXv)UX9x4nITG0V_UkucO zHqc;SgX_D$Z)vUtI-;8u+Xd)a2x+yTpuqRp-HOqDkNN(0@tHKaF8@l-3GFWbbv>EQ zKq%=5v<*YC$*xG8_Gdvg08h})`FwlbL_F1y5hi4d0RO8w-;e8A@CEY33N13j=mR!9 zndh-*dT0s~@TRYCU)Oq1zA|inmq)y(ady)14I>^U)xHg!eRcbqC_1RqUV9_CYcBD6 z*|47DOZt&SG+f@oGg7Bhcs7G^^Zs#aGQy4NjaI;7<6L7(KHV%1v0z*@T-E8`CC&|t zq-)G=w06c)2gCzna%09vbFrQDnaO#^h7e57N#y@LZ9bwD z#=wwW&5iF0P1;6i3s%vymMsx9d$wSOtAVC~#EC&yvu2qC963T1e=wyO(WRZ2{jlN9 z#T7Z6%*ncai=rC_bLQRlket(G~khZLf4!NdjfylZ@r4`jcW%rnosW`sXr|*?o4_qzaI{sdh8sG5l{Uc z9Sun(azp%{<|p4`gUn)w6lXY`W0i=%A9Rq&4UgD5o0%G=DPo-My-$ETv+$a)#( zEj~Go#C`t;KAE5jp{B(!zUQISduM=tEXMAE0$f?BD~ye#7UyUy8T0Ps(LFavQU>-8 zLrQ>rTc|$b6pqV7>Ge&FmStP;Gtf=+)sDKJ7_^dXDc5}e;lts>3p%~BBY#7dq!JE= zdjjWW6{x186*eJ}Y8&t0zt>=QXgsDy4k>br7E*yUHa|GL>Eqki&%7t|YNh%_emg6v zLv&gE`?{4Yww**j835K!)#DP79DC*y^ljjiiXwL+P=r{?pJdMVOlAiaKrpeRzcM8u ziy-4bnFIvY?j0S}7a2XPlwKi6obaCq0GxJhMTK{@Bfq0TS4$%3H@s6cRwO^YLJ=A< zW%kZFWqg$@EyZc-XLaSHPoQMD6`goy4Zj_!AZ3Bg4Y*x{yQe4nizB_h%SG5~FXg*P z{2C@`JCjCNvAv!&XKVF?lS3nkipP57*#p1ocn;5G(u&b=v!4201~Iysywkb)8%^us zxE3KGlZIqzg}aU)z<|uKTh%5g!okjd`<$8Qs|;iDz~p=NGoas1W9Zq7^~EGbFc`9n z`hdGLnm|c&3Ju*upRByL$SRtIDH$@gK*nQ#c>#hnSdJ5u{pKCr)OF}* zfudoZ3yrFPAs664aYho!g>Qt^VSR|NckW)J?kz5b(1o5PJvbUqgxE69I^ksQ;DqJ% zKI3Zm3O9dgR@P0oX6!J;j_xbW-%eov&0Vn_O>>))TUuE;8vpXePXV7l^0D*zZ>6sg2fKt{X=eesKubCY z7iwjCqy6%NN+v$Z787PmO41zY`uq3qy~mp;zp;HJcl7Iv!MDa^1v0}Dtp#`($OjcX zYl{>0Yr{Qf$AVSZM76n|XL5B|biQD#FMD2hlykgU^sUB~udl$QWT;AkdPuT~_6rUP zNGFkVkJ_<_avCu5G?w_0BGj)*H0~UGZ55bk|3cX<&%@1aycG++z$gX}OPil1R}k$_ zb)+quWOx(PQ+EYmzXwp9XvMO6B&aGi&XC#+n%-%wznhcwyxniJr&r3yyR6_0?j5Zn zu0#yU9713NEtL?$>De=-YBRq(f`!MVA<&nKMEKJ-;*P}3i@wu za^Pc=b&f*YWM2mSv&A?feMPe7!+cQtIJJ4CZ#fk(;j~3!XmDjM>xZ?R!{mp+7wi0o zKc(ucMvT7s`1x%{%zNY~vm#A@tw#TT+J{SKmJYKB%!f6-e?Mc};4=l2guTWxa$2u=qF4x0 znRh^ON+=|YVf4^74;A@(4f6fu0?RK`6?85%$!OB%Q%|3?_%vyOvD%d$5qKKX$(??t z_08?iJjp~~h5)_JR5`!Rzul}6S~|hMh6@u7;rqGAezNUyJOwu9G0jK`(N7(cIqY_b z=-1tbU&qE&_>;Sm+5KZ%y5cy`m~aP>cx;p^Ksj81hQopo!-T8MP851}Wu8;tX+$?r znJOIw<*vg~t_{{@nU@HCrQOeSI^13&Ys*xO2v149JR)i~IQGn2WLZ zt#+L4XFKR1cO+xm{qg!K`dI`3MIF4(yE(@ITt-~)UjD^&#X)Lo@Xwz=95Ib3iNZkW z^ULUqyzki!=sYtU?K}@(x>)HTIh-4wQyz~if^qvAFv;t|hf3qoCdxt0cw!sI<71&A zqhE65tr`OsqyVXb%06`+xt+>gC=)VgNI-MNF`uM08cR;fXD_NJE5+gR6*^mR1$LPZL#D>%9g*Jm?w-JFt2=Iw0nexR}<5=?h%%>=gZf$ zhQQs-2FNUi7Y#?E(`37;jEIG`ZAml1jn&m01GL^llN;$#%4fsF!nmW>5IUQ%vV=f&%sv&sSMjASIe4r9kZsgZ-A4jr@lnJc>%8- zy>sO2%b`r0s;RH9cZQG|@USEgTMiD6?}J~zZVBLtEtPkh1hOyodU$$y30kZ@q`Pw! zh9U!BAhRMB+y32*Gzh6DR5NNXl&=unpyZ5-NXhO=1Dv{rH71Y9pRCNeps22nCx)_TZ)Asdo;SeW(7t5~Q#)0bai)2u)x$H&em zV z^88Q?rYx-`C5s#UuG_`{0ZBbO_rZ+=r6VS5z#{r83!TR`{BwTGB^oPj zb^|A&=1T>`njwO&Rv=tsuKBjQn6P9-w!Ikt4trL zKTp4}@nV;zv$VA2mZRX(V}h=g!so_7HRPzu-9lP@sLJmi9BQpKVtAnhH&MW?Vy5=u z%C7awieOhGpYx~BEb~w2UPZ@1L-u$c2bWY;`O5Jo=CaIg199x$*-a%SuDXcrRxqKR zAQF>ZDA|x^-ane?KU#=|^vst6pJ5v)Bo&b~cVPd4vy1^3_2ODK)G556-ugwIjE7NR zU|`#>JkcGD&TNepKl~Rn_?#RZ9AGeS0MLQ@p#Fs|x5*vOt5>hSKQX8UkjOe)A*1ER z4GkgP!Bei_49EO)62VnwVSj}d4M!9W?^v%;Kw>F|KTPQjZjB*iz$KWqV~NS<3g1ij z{`ze&JsmAlD6%f+>REA|dHEb0Q^PP@yPSaLzEF zx%cDZ;+zZ}9@zMP*p9hez#iRP6DcZrzU80WB{wqwgr%1Ww_f9xzZQ9F4H*4cQ{Uwi zi2L34W--_0)K}LvH?XCTHqx-(- z8^$SR7c(1kiNgQlGUPv~ai$J4jqW8`hK3C!a0FBi*`r^5j7g8zGG0;W# z3T~!r)n2kl9WuFOf6+hsN0siw&(F+b7QIUb7AS@)l^cacFdv!!bq9($xwwjf8)@t2Qnq74KEA%kw{2`D&jLFqQMQ~8GIR&I zX^HoStNBSzhy}gw!x=J@UqM=cB_f#hNh0nT`LI_iDgJ=%5YGmOyeb64aCKv&8Wa?n zWKBnGbHtT4rK5qbDc*68Qkb8ZGvtr(=a>e}6lysy5QT&fs<=RfBdYBT1bf^gxN`qH4tlu5e|h{pt81aHtu zj;FU&b?wg?RTpe+N&H6$>MpK$;aWIJ(byiYK@i6(9DJdPly$I8>4a7#d!OwAyF$J3Zs-Svt1WBQyl9JL$s_le$z8H+q2#Q=sj1v_tTxl^UiAb~tvvUZ{kyul z?IEHu&UK#7gU#O^6cnE7xiaS3Ay|0KJ2THnk7$bc0JWbUig9p8fZCG>fAQ;r_^>F; z1>=`#lSpdY(U1+H6iype`1X|8`Y=beS00Eu@zXYXw)g7<@D$kj$nfo(?c3W45=95} z_#uMZj4B{ml;&auCfc9%O!+UR-F;%V^1_iqJ-FankYX%82Ns1UHaFk!Vbe>UR7@Bf zxWzp5Lqc}5u|3I`rA33L(5Q(OaYk5fKUp4l0NPQnlttym3obTmLEt6n#?uMfkFU&sns$si_;i$Kmw%;vjyeRO>#lVp{TO zu-Wr+aE}JNlJQF?-i=_vE~|u`AYAppcb|Wh^nB`P5&9b|{Y}9umCV;(E6(>>r`Q)(?9NM$U^#>9f0mNis_*rweoY62D$uXQC!_o3W5Ht<0p8tGTN1US z>|T>xwkzt{eZ0L_PLU&mo=|CpbV9Kck#^Ap*8A9BCh&c|1Rr(~xhyEjmtOj_z0FCt z7hbJRj*x^+LF@Iw@&*G=CJpkmVWAv!ptm#c3@0D~Jn{Hvlh4&!CG!gFx+J3SZhqdx z^t864B8|O`jEoLh_u}H>I%|qHdR1}J;(XZ1$o2-7D^PGzA?DiS1cFSE;9{#(qw>o? zHJYYw6@2e1&%BdS-!x~;bt<>hSpqkxbvQ2oauA$kC1n9-Cc^U=*5)|5vm5DsA65bTGL}cZY>Kb_%gz4lV{@ z5tT9Ir2p$wZFxiqqJp`NT+0}JECKhIJHM}0Jf>TAxc=2MbOjVH9I`bg@1mQIeYOXS zkJd%=P1Hx;IX@P++HDcL+->L=l2Tvs_S-7`NR$<5I(?c0HgwO&Pu~auX?R^$7#tOS zMnJ&CP)4Lu1RYfEViiBqU7Q6f*G)v4j9gIWsI^sw3zL#BJY^i@^zR8vbSIzb<8aza ztIx;7XN9E{0e&|xujaChK+riY09zwN;$FW`%~oIn0wKDdhc}LbaZx;KFi9{+nrvh6eU>Z%&&q?qkG+M6& zm8q|vhX;%Ox@>AXfFIqLJUM_S$Wxt$6je@F;PdkGo)Kv$)66?3(}~Z(!c#hymt*sy zfrW)dP1=@}_0P}j`Ct>llYhMcE3RAiF&z#Rb_vheCLSmF3)DK3NpQi@i-Yo`+l4v+Agp0z-tQmdKrNu8G#)PAP-3G++4D^@sccN-VdYU~etV z9AsR-%@XIhDqeKpsGJ=MA$0&fpP}!D{BwLWkVm)M75f-BuhV;;+EdPoj*d0}j_C2? zp(3_NHMIBtwB3t|sI}v}#_*IvH&|3I|Yk-!{bK6p0~<^u2PqY}pi1Pel@ML^}aRP_M|__pXM8!50MNk25*NuV^f)}>dM*a)8aPiPQ zK%7m!N4MaGjPZ zSLl$ImR_XW0}W^&EPSrous4oTC=_3K3FR|6Lit+p+4rC|Vh|;CdnRg!VunXPpyH5D zx%{$rlp7*x*y$Gt81Ctag#W!8IX|bskE5JWss36LmIXwJJc=fUt;lssGf&n(%Pgje zf*1hVMy5_qOjLfFRQs5&Ahb|{l@fXns;rscxzr9x`^N#|c;`$SKOA*LQ9f3|Qu@|4 zK*S4{BUnMkll@Zsfg?Zi$Gxh(Xy0Ic7JrZw8v{1`Bf=Z6OSHs(zgVp@^x0jMFB*RE z;_siG9WG)qO${Cn)pfmoeMlO_yrptd$Hd|=1=vF5?^8*0LG&&@W)M8~*Lxu9M!Efb zH~SoOq#*0_!avPy{0x50bE>HoZsfZl=)4hZR?Eq+we{3X{be4y`>E z@xpysN-LRHM^fnV_7=?v1ZC*p&+v(#C4aTnb#mpR{XhX$TUTdiiVg(4hOO@vT(j@; zZ%SCQIT~vJ*8yUB?KI{E7%sfvOKHALTrn` ztjGt?o|J^2CPib)SOZJW$jhjnP0nW{Atn-NB^fSP_lEO+J528Iz@LI1Usz5SHdufu zql%-nwx4`vZjolYViImEM?H1a&K+{+PJj6;`EC~`up1-Be&#+wd!xz6ED|(OSqI97 zXo=sh*#OntG9%dGnsQ&RMo7Jj)h?1s>+VR>tOZTx#ig?~k9)x>=1Uz74OW>t7`6ly zs%~l4d+Ur152tM!r87ldN;_YeucEBHUYQo&9JEVFz<^##S2wO}h5hC#v zGx49V$ibGgH{u)QhCaq+(p}r8w*rSV zGh*R<-lEo;C!HMf_$?^qo(#5yp1Oj*P}Fk1=p@h&5pNc=S4|NN%X8_?_yCzTNG=ku+#V)`0O%hs?5%7Nvj`rr!_j9s!4P_vC!*U1CzX@QDA3dW8+vdpcyHCr*mKPd4KhBMMmlmJ{ zfGl-l!i0PvjXUB6K<G~z)vc7h9xp!nccJ|`Y84>A5J!ga44QXONt@7b`T|w3K~Jy%oullX zH8eGKh?8FXqq!jq()gU}iQ3V7+~F-?b(wj9%Ec1?T|ts|>*w#ihhEAWxD-Y>+pw8x z67@{)+x^VOI!hhVPdNVc5}BBH;}*=X5#$4}Ywzw zjkA*eLX6KB@*}I5-{cW3*hRrcft#S}UoO7$0(mwrK3?Yv`a1AhSU{kuZhGg@r{Jl@ zqBL%Z4Cu#n%H6DKoNUlQ>rBPY_1gv zHiX4qk~vQk1sX0C-B6=Gmg+)Cfr0!w_BDz!Vs@V^ean67sQ&YecxN#7p}hW-2G)7{*F0HTyQ*fOW=^F34p zPXfE+it0w$y(cS;D&77&=@VM?hU?LvAycaIq!*HrBwDIa5_t|?J4|iXw;QXt+4l6m z8xdHIuJ(hCg0+MtCgA-|4PN9-v(Hr15MAk<;D6Jqz5@N#qd6c|)w~s8WYjwXc8|3K zJb*x_MqK`ld-b5PG#~A+q(D*so2qG_f%C=Qi5%hpx>De)xr?nrH@QK98dfJmfc|$q z`O~F|IZ{tjm2*J$uLp3!P(cdRO29gSK%{K|c}^4^aC@I`@%e9|;8OVybad6(uZZa9 SD1gnJz!d`%bS28+{{I06Yp4kT literal 0 HcmV?d00001 diff --git a/images/logo_stereolabs.svg b/images/logo_stereolabs.svg deleted file mode 100644 index 1fbc6c18..00000000 --- a/images/logo_stereolabs.svg +++ /dev/null @@ -1 +0,0 @@ -Artboard 1 \ No newline at end of file diff --git a/tutorials/README.md b/tutorials/README.md index 7ece0db7..af275668 100644 --- a/tutorials/README.md +++ b/tutorials/README.md @@ -1,4 +1,4 @@ -![](../images/logo_stereolabs.svg | width=100) +![](../images/Picto+STEREOLABS_Black.png) # Tutorials A series of tutorials are provided to better understand how to use the ZED node in the ROS environment : diff --git a/tutorials/zed_depth_sub_tutorial/README.md b/tutorials/zed_depth_sub_tutorial/README.md index dc03058e..eabe7121 100644 --- a/tutorials/zed_depth_sub_tutorial/README.md +++ b/tutorials/zed_depth_sub_tutorial/README.md @@ -1,4 +1,4 @@ -![](../../images/logo_stereolabs.svg | width=100) +![](../../images/Picto+STEREOLABS_Black.png) # Depth subscription tutorial diff --git a/tutorials/zed_tracking_sub_tutorial/README.md b/tutorials/zed_tracking_sub_tutorial/README.md index db58515c..30fb8c54 100644 --- a/tutorials/zed_tracking_sub_tutorial/README.md +++ b/tutorials/zed_tracking_sub_tutorial/README.md @@ -1,4 +1,4 @@ -![](../../images/logo_stereolabs.svg | width=100) +![](../../images/Picto+STEREOLABS_Black.png) # Positional Tracking tutorial diff --git a/tutorials/zed_video_sub_tutorial/README.md b/tutorials/zed_video_sub_tutorial/README.md index 6b4da070..daae522a 100644 --- a/tutorials/zed_video_sub_tutorial/README.md +++ b/tutorials/zed_video_sub_tutorial/README.md @@ -1,4 +1,4 @@ -![](../../images/logo_stereolabs.svg | width=100) +![](../../images/Picto+STEREOLABS_Black.png) # ZED video subscription tutorial diff --git a/zed_display_rviz/README.md b/zed_display_rviz/README.md index bbd3d5ef..ce3d320b 100644 --- a/zed_display_rviz/README.md +++ b/zed_display_rviz/README.md @@ -1,4 +1,4 @@ -![](../images/logo_stereolabs.svg | width=100) +![](../images/Picto+STEREOLABS_Black.png) # Stereolabs ZED Camera - ROS Display example diff --git a/zed_wrapper/README.md b/zed_wrapper/README.md index 6fafb74f..b2528bad 100644 --- a/zed_wrapper/README.md +++ b/zed_wrapper/README.md @@ -1,4 +1,4 @@ -![](../images/logo_stereolabs.svg | width=100) +![](../images/Picto+STEREOLABS_Black.png) # Stereolabs ZED Camera - ROS Integration diff --git a/zed_wrapper/launch/README.md b/zed_wrapper/launch/README.md index 0911963a..de18165d 100644 --- a/zed_wrapper/launch/README.md +++ b/zed_wrapper/launch/README.md @@ -1,4 +1,4 @@ -![](../images/logo_stereolabs.svg | width=100) +![](../images/Picto+STEREOLABS_Black.png) # Launch Files From bc2f8ab67d023d0afdfc0ef2d8c8a37394b27b8a Mon Sep 17 00:00:00 2001 From: Myzhar Date: Wed, 12 Sep 2018 10:34:01 +0200 Subject: [PATCH 35/55] Added features from `devel` branch: * Floor alignment * Odometry path * Pose path * pose frame fix * odom frame fix * depth range in dynamic reconf --- zed_display_rviz/rviz/zed.rviz | 8 +- zed_display_rviz/rviz/zedm.rviz | 80 +- zed_wrapper/cfg/Zed.cfg | 11 +- zed_wrapper/launch/zed_camera.launch | 4 + zed_wrapper/launch/zed_camera_nodelet.launch | 3 + .../nodelet/include/zed_wrapper_nodelet.hpp | 372 +-- .../src/nodelet/src/zed_wrapper_nodelet.cpp | 2003 +++++++++-------- zed_wrapper/src/tools/include/sl_tools.h | 26 +- zed_wrapper/src/tools/src/sl_tools.cpp | 76 +- 9 files changed, 1418 insertions(+), 1165 deletions(-) diff --git a/zed_display_rviz/rviz/zed.rviz b/zed_display_rviz/rviz/zed.rviz index 45111e58..731c6572 100644 --- a/zed_display_rviz/rviz/zed.rviz +++ b/zed_display_rviz/rviz/zed.rviz @@ -142,7 +142,7 @@ Visualization Manager: Decay Time: 0 Depth Map Topic: /zed/depth/depth_registered Depth Map Transport Hint: raw - Enabled: false + Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 4096 @@ -160,7 +160,7 @@ Visualization Manager: Topic Filter: true Use Fixed Frame: true Use rainbow: true - Value: false + Value: true - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: @@ -173,7 +173,7 @@ Visualization Manager: Color: 255; 255; 255 Color Transformer: RGB8 Decay Time: 0 - Enabled: true + Enabled: false Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 4096 @@ -190,7 +190,7 @@ Visualization Manager: Unreliable: true Use Fixed Frame: true Use rainbow: true - Value: true + Value: false - Class: rviz/Camera Enabled: true Image Rendering: background and overlay diff --git a/zed_display_rviz/rviz/zedm.rviz b/zed_display_rviz/rviz/zedm.rviz index 6e423132..c59d4960 100644 --- a/zed_display_rviz/rviz/zedm.rviz +++ b/zed_display_rviz/rviz/zedm.rviz @@ -5,13 +5,13 @@ Panels: Property Tree Widget: Expanded: - /Global Options1 + - /RobotModel1/Status1 - /RobotModel1/Links1 + - /TF1 - /TF1/Frames1 - - /DepthCloud1 - /DepthCloud1/Occlusion Compensation1 - - /Odometry1/Covariance1/Position1 Splitter Ratio: 0.5 - Tree Height: 393 + Tree Height: 487 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -98,6 +98,8 @@ Visualization Manager: Frame Timeout: 5 Frames: All Enabled: false + imu_link: + Value: true map: Value: true odom: @@ -114,13 +116,15 @@ Visualization Manager: Value: false Marker Scale: 0.5 Name: TF - Show Arrows: true + Show Arrows: false Show Axes: true Show Names: true Tree: map: odom: zed_camera_center: + imu_link: + {} zed_left_camera_frame: zed_left_camera_optical_frame: {} @@ -184,6 +188,8 @@ Visualization Manager: Odometry: true PointCloud2: true Pose: true + Pose Odometry: true + Pose Path: true RobotModel: true TF: true Value: false @@ -235,11 +241,11 @@ Visualization Manager: y_scale: 1 z_scale: 1 Class: rviz_imu_plugin/Imu - Enabled: false + Enabled: true Name: Imu Topic: /zed/imu/data Unreliable: false - Value: false + Value: true fixed_frame_orientation: true - Alpha: 1 Axes Length: 1 @@ -253,9 +259,32 @@ Visualization Manager: Shaft Length: 0.300000012 Shaft Radius: 0.0199999996 Shape: Arrow - Topic: /zed/map + Topic: /zed/pose Unreliable: false Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.0299999993 + Head Length: 0.0199999996 + Length: 0.300000012 + Line Style: Lines + Line Width: 0.0299999993 + Name: Pose Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 25; 255; 0 + Pose Style: Arrows + Radius: 0.0299999993 + Shaft Diameter: 0.00999999978 + Shaft Length: 0.0500000007 + Topic: /zed/path_map + Unreliable: true + Value: true - Angle Tolerance: 0 Class: rviz/Odometry Covariance: @@ -290,6 +319,29 @@ Visualization Manager: Topic: /zed/odom Unreliable: false Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 255; 25; 0 + Enabled: true + Head Diameter: 0.0299999993 + Head Length: 0.0199999996 + Length: 0.300000012 + Line Style: Lines + Line Width: 0.0299999993 + Name: Pose Odometry + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 25; 0 + Pose Style: Arrows + Radius: 0.0299999993 + Shaft Diameter: 0.00999999978 + Shaft Length: 0.0500000007 + Topic: /zed/path_odom + Unreliable: true + Value: true Enabled: true Global Options: Background Color: 48; 48; 48 @@ -315,25 +367,25 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 3.77481484 + Distance: 1.35755372 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 0.861115396 - Y: 1.21251762 - Z: 0.619552732 + X: 0.763631225 + Y: 1.1376406 + Z: 0.689015388 Focal Shape Fixed Size: false Focal Shape Size: 0.0500000007 Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 - Pitch: 0.0147975748 + Pitch: -0.0252024569 Target Frame: Value: Orbit (rviz) - Yaw: 4.01910114 + Yaw: 1.47410023 Saved: ~ Window Geometry: Camera: @@ -343,7 +395,7 @@ Window Geometry: Height: 1056 Hide Left Dock: false Hide Right Dock: false - QMainWindow State: 000000ff00000000fd00000004000000000000016a00000394fc020000000efb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000218000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000002400000010f0000000000000000fb0000000a0049006d006100670065000000028b000000c40000000000000000fb0000000a0049006d006100670065010000028a000000c50000000000000000fb0000000a0049006d00610067006500000002b30000009c0000000000000000fb0000000a0049006d006100670065010000028b000000c40000000000000000fb0000000c00430061006d0065007200610100000246000001760000001600ffffff000000010000010f00000394fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000394000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f00000040fc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000004ba0000039400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd00000004000000000000016a00000394fc020000000efb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000276000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000002400000010f0000000000000000fb0000000a0049006d006100670065000000028b000000c40000000000000000fb0000000a0049006d006100670065010000028a000000c50000000000000000fb0000000a0049006d00610067006500000002b30000009c0000000000000000fb0000000a0049006d006100670065010000028b000000c40000000000000000fb0000000c00430061006d00650072006101000002a4000001180000001600ffffff000000010000010f00000394fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000394000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f00000040fc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000004ba0000039400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: diff --git a/zed_wrapper/cfg/Zed.cfg b/zed_wrapper/cfg/Zed.cfg index 816893f5..44250529 100755 --- a/zed_wrapper/cfg/Zed.cfg +++ b/zed_wrapper/cfg/Zed.cfg @@ -5,10 +5,11 @@ from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() -gen.add("confidence", int_t, 0, "Confidence threshold, the lower the better", 80, 1, 100) -gen.add("exposure", int_t, 1, "Exposure value when manual controlled", 100, 0, 100); -gen.add("gain", int_t, 2, "Gain value when manual controlled", 50, 0, 100); -gen.add("auto_exposure", bool_t, 3, "Enable/Disable auto control of exposure and gain", True); -gen.add("mat_resize_factor", double_t, 4, "Image/Measures resize factor", 1.0, 0.1, 1.0); +gen.add("confidence", int_t, 0, "Confidence threshold, the lower the better", 80, 1, 100) +gen.add("exposure", int_t, 1, "Exposure value when manual controlled", 100, 0, 100); +gen.add("gain", int_t, 2, "Gain value when manual controlled", 50, 0, 100); +gen.add("auto_exposure", bool_t, 3, "Enable/Disable auto control of exposure and gain", True); +gen.add("mat_resize_factor", double_t, 4, "Image/Measures resize factor", 1.0, 0.1, 1.0); +gen.add("max_depth", double_t, 5, "Maximum Depth Range", 3.5, 0.5, 20.0); exit(gen.generate(PACKAGE, "zed_wrapper", "Zed")) diff --git a/zed_wrapper/launch/zed_camera.launch b/zed_wrapper/launch/zed_camera.launch index 88fa9dfc..eb12d2d4 100644 --- a/zed_wrapper/launch/zed_camera.launch +++ b/zed_wrapper/launch/zed_camera.launch @@ -99,6 +99,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + $(arg initial_pose) @@ -137,6 +138,9 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + + diff --git a/zed_wrapper/launch/zed_camera_nodelet.launch b/zed_wrapper/launch/zed_camera_nodelet.launch index 6a1c9dd7..abacab90 100644 --- a/zed_wrapper/launch/zed_camera_nodelet.launch +++ b/zed_wrapper/launch/zed_camera_nodelet.launch @@ -100,6 +100,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + $(arg initial_pose) @@ -138,6 +139,8 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + diff --git a/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp b/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp index 783c8fd7..f72b8ba5 100644 --- a/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp +++ b/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp @@ -25,6 +25,7 @@ ** This sample is a wrapper for the ZED library in order to use the ZED Camera with ROS. ** ** A set of parameters can be specified in the launch file. ** ****************************************************************************************************/ +#include "sl_tools.h" #include @@ -35,6 +36,7 @@ #include #include #include +#include #include #include @@ -63,14 +65,6 @@ namespace zed_wrapper { */ virtual ~ZEDWrapperNodelet(); - /* \brief Image to ros message conversion - * \param img : the image to publish - * \param encodingType : the sensor_msgs::image_encodings encoding type - * \param frameId : the id of the reference frame of the image - * \param t : the ros::Time to stamp the image - */ - static sensor_msgs::ImagePtr imageToROSmsg(cv::Mat img, const std::string encodingType, std::string frameId, ros::Time t); - private: /* \brief Initialization function called by the Nodelet base class */ @@ -78,51 +72,58 @@ namespace zed_wrapper { /* \brief ZED camera polling thread function */ - void device_poll(); + void device_poll_thread_func(); /* \brief Pointcloud publishing function */ - void pointcloud_thread(); + void pointcloud_thread_func(); protected: /* \brief Publish the pose of the camera in "Map" frame with a ros Publisher - * \param poseBaseTransform : Transformation representing the camera pose from odom frame to map frame * \param t : the ros::Time to stamp the image */ - void publishPose(tf2::Transform poseBaseTransform, ros::Time t); + void publishPose(ros::Time t); /* \brief Publish the pose of the camera in "Odom" frame with a ros Publisher - * \param odom_base_transform : Transformation representing the camera pose from base frame to odom frame + * \param base2odomTransf : Transformation representing the camera pose + * from base frame to odom frame * \param t : the ros::Time to stamp the image */ - void publishOdom(tf2::Transform baseToOdomTransform, ros::Time t); + void publishOdom(tf2::Transform base2odomTransf, ros::Time t); /* \brief Publish the pose of the camera in "Map" frame as a transformation - * \param base_transform : Transformation representing the camera pose from odom frame to map frame + * \param baseTransform : Transformation representing the camera pose from + * odom frame to map frame * \param t : the ros::Time to stamp the image */ void publishPoseFrame(tf2::Transform baseTransform, ros::Time t); - /* \brief Publish the odometry of the camera in "Odom" frame as a transformation - * \param base_transform : Transformation representing the camera pose from base frame to odom frame + /* \brief Publish the odometry of the camera in "Odom" frame as a + * transformation + * \param odomTransf : Transformation representing the camera pose from + * base frame to odom frame * \param t : the ros::Time to stamp the image */ - void publishOdomFrame(tf2::Transform baseToOdomTransform, ros::Time t); + void publishOdomFrame(tf2::Transform odomTransf, ros::Time t); /* \brief Publish the pose of the imu in "Odom" frame as a transformation - * \param base_transform : Transformation representing the imu pose from base frame to odom frame + * \param imuTransform : Transformation representing the imu pose from base + * frame to odom framevoid * \param t : the ros::Time to stamp the image */ - void publishImuFrame(tf2::Transform baseTransform); + void publishImuFrame(tf2::Transform imuTransform, ros::Time t); /* \brief Publish a cv::Mat image with a ros Publisher * \param img : the image to publish - * \param pub_img : the publisher object to use (different image publishers exist) - * \param img_frame_id : the id of the reference frame of the image (different image frames exist) + * \param pub_img : the publisher object to use (different image publishers + * exist) + * \param img_frame_id : the id of the reference frame of the image (different + * image frames exist) * \param t : the ros::Time to stamp the image */ - void publishImage(cv::Mat img, image_transport::Publisher& pubImg, string imgFrameId, ros::Time t); + void publishImage(cv::Mat img, image_transport::Publisher& pubImg, + string imgFrameId, ros::Time t); /* \brief Publish a cv::Mat depth image with a ros Publisher * \param depth : the depth image to publish @@ -137,8 +138,6 @@ namespace zed_wrapper { void publishConf(cv::Mat conf, ros::Time t); /* \brief Publish a pointCloud with a ros Publisher - * \param width : the width of the point cloud - * \param height : the height of the point cloud */ void publishPointCloud(); @@ -147,7 +146,8 @@ namespace zed_wrapper { * \param pub_cam_info : the publisher object to use * \param t : the ros::Time to stamp the message */ - void publishCamInfo(sensor_msgs::CameraInfoPtr camInfoMsg, ros::Publisher pubCamInfo, ros::Time t); + void publishCamInfo(sensor_msgs::CameraInfoPtr camInfoMsg, + ros::Publisher pubCamInfo, ros::Time t); /* \brief Publish a cv::Mat disparity image with a ros Publisher * \param disparity : the disparity image to publish @@ -155,33 +155,50 @@ namespace zed_wrapper { */ void publishDisparity(cv::Mat disparity, ros::Time t); - /* \brief Get the information of the ZED cameras and store them in an information message + /* \brief Get the information of the ZED cameras and store them in an + * information message * \param zed : the sl::zed::Camera* pointer to an instance - * \param left_cam_info_msg : the information message to fill with the left camera informations - * \param right_cam_info_msg : the information message to fill with the right camera informations + * \param left_cam_info_msg : the information message to fill with the left + * camera informations + * \param right_cam_info_msg : the information message to fill with the right + * camera informations * \param left_frame_id : the id of the reference frame of the left camera * \param right_frame_id : the id of the reference frame of the right camera */ - void fillCamInfo(sl::Camera& zed, sensor_msgs::CameraInfoPtr leftCamInfoMsg, sensor_msgs::CameraInfoPtr rightCamInfoMsg, - string leftFrameId, string rightFrameId, bool rawParam = false); + void fillCamInfo(sl::Camera& zed, sensor_msgs::CameraInfoPtr leftCamInfoMsg, + sensor_msgs::CameraInfoPtr rightCamInfoMsg, + string leftFrameId, string rightFrameId, + bool rawParam = false); + + /* \bried Check if FPS and Resolution chosen by user are correct. + * Modifies FPS to match correct value. + */ + void checkResolFps(); /* \brief Callback to handle dynamic reconfigure events in ROS */ void dynamicReconfCallback(zed_wrapper::ZedConfig& config, uint32_t level); + /* \brief Callback to publish Path data with a ROS publisher. + * \param e : the ros::TimerEvent binded to the callback + */ + void pathPubCallback(const ros::TimerEvent& e); + /* \brief Callback to publish IMU raw data with a ROS publisher. * \param e : the ros::TimerEvent binded to the callback */ void imuPubCallback(const ros::TimerEvent& e); /* \brief Service callback to reset_tracking service - * Tracking pose is reinitialized to the value available in the ROS Param server + * Tracking pose is reinitialized to the value available in the ROS Param + * server */ bool on_reset_tracking(zed_wrapper::reset_tracking::Request& req, zed_wrapper::reset_tracking::Response& res); /* \brief Service callback to reset_odometry service - * Odometry is reset to clear drift and odometry frame gets the latest pose + * Odometry is reset to clear drift and odometry frame gets the latest + * pose * from ZED tracking. */ bool on_reset_odometry(zed_wrapper::reset_odometry::Request& req, @@ -201,174 +218,193 @@ namespace zed_wrapper { */ void start_tracking(); - /* \bried Check if FPS and Resolution chosen by user are correct. - * Modifies FPS to match correct value. - */ - void checkResolFps(); + private: // SDK version - int verMajor; - int verMinor; - int verSubMinor; + int mVerMajor; + int mVerMinor; + int mVerSubMinor; // ROS - ros::NodeHandle nh; - ros::NodeHandle nhNs; - std::thread devicePollThread; + ros::NodeHandle mNh; + ros::NodeHandle mNhNs; + std::thread mDevicePollThread; std::thread mPcThread; // Point Cloud thread bool mStopNode; // Publishers - image_transport::Publisher pubRgb; - image_transport::Publisher pubRawRgb; - image_transport::Publisher pubLeft; - image_transport::Publisher pubRawLeft; - image_transport::Publisher pubRight; - image_transport::Publisher pubRawRight; - image_transport::Publisher pubDepth; - image_transport::Publisher pubConfImg; - ros::Publisher pubConfMap; - ros::Publisher pubDisparity; - ros::Publisher pubCloud; - ros::Publisher pubRgbCamInfo; - ros::Publisher pubLeftCamInfo; - ros::Publisher pubRightCamInfo; - ros::Publisher pubRgbCamInfoRaw; - ros::Publisher pubLeftCamInfoRaw; - ros::Publisher pubRightCamInfoRaw; - ros::Publisher pubDepthCamInfo; - ros::Publisher pubPose; - ros::Publisher pubOdom; - ros::Publisher pubImu; - ros::Publisher pubImuRaw; - ros::Timer pubImuTimer; - - // Service - bool trackingActivated; - ros::ServiceServer srvSetInitPose; - ros::ServiceServer srvResetOdometry; - ros::ServiceServer srvResetTracking; + image_transport::Publisher mPubRgb; // + image_transport::Publisher mPubRawRgb; // + image_transport::Publisher mPubLeft; // + image_transport::Publisher mPubRawLeft; // + image_transport::Publisher mPubRight; // + image_transport::Publisher mPubRawRight; // + image_transport::Publisher mPubDepth; // + image_transport::Publisher mPubConfImg; // + + ros::Publisher mPubConfMap; // + ros::Publisher mPubDisparity; // + ros::Publisher mPubCloud; + ros::Publisher mPubRgbCamInfo; // + ros::Publisher mPubLeftCamInfo; // + ros::Publisher mPubRightCamInfo; // + ros::Publisher mPubRgbCamInfoRaw; // + ros::Publisher mPubLeftCamInfoRaw; // + ros::Publisher mPubRightCamInfoRaw; // + ros::Publisher mPubDepthCamInfo; // + ros::Publisher mPubPose; + ros::Publisher mPubOdom; + ros::Publisher mPubOdomPath; + ros::Publisher mPubMapPath; + ros::Publisher mPubImu; + ros::Publisher mPubImuRaw; + //ros::Publisher mPubClock; + + // Timers + ros::Timer mImuTimer; + ros::Timer mPathTimer; + + // Services + ros::ServiceServer mSrvSetInitPose; + ros::ServiceServer mSrvResetOdometry; + ros::ServiceServer mSrvResetTracking; + // Camera info - sensor_msgs::CameraInfoPtr rgbCamInfoMsg; - sensor_msgs::CameraInfoPtr leftCamInfoMsg; - sensor_msgs::CameraInfoPtr rightCamInfoMsg; - sensor_msgs::CameraInfoPtr rgbCamInfoRawMsg; - sensor_msgs::CameraInfoPtr leftCamInfoRawMsg; - sensor_msgs::CameraInfoPtr rightCamInfoRawMsg; - sensor_msgs::CameraInfoPtr depthCamInfoMsg; - - // tf - tf2_ros::TransformBroadcaster transformPoseBroadcaster; - tf2_ros::TransformBroadcaster transformOdomBroadcaster; - tf2_ros::TransformBroadcaster transformImuBroadcaster; - - std::string rgbFrameId; - std::string rgbOptFrameId; - - std::string depthFrameId; - std::string depthOptFrameId; - - std::string disparityFrameId; - std::string disparityOptFrameId; - - std::string confidenceFrameId; - std::string confidenceOptFrameId; - - std::string cloudFrameId; - - std::string mapFrameId; - std::string odometryFrameId; - std::string baseFrameId; - std::string rightCamFrameId; - std::string rightCamOptFrameId; - std::string leftCamFrameId; - std::string leftCamOptFrameId; - std::string imuFrameId; + sensor_msgs::CameraInfoPtr mRgbCamInfoMsg; + sensor_msgs::CameraInfoPtr mLeftCamInfoMsg; + sensor_msgs::CameraInfoPtr mRightCamInfoMsg; + sensor_msgs::CameraInfoPtr mRgbCamInfoRawMsg; + sensor_msgs::CameraInfoPtr mLeftCamInfoRawMsg; + sensor_msgs::CameraInfoPtr mRightCamInfoRawMsg; + sensor_msgs::CameraInfoPtr mDepthCamInfoMsg; + + // ROS TF + tf2_ros::TransformBroadcaster mTransformPoseBroadcaster; + tf2_ros::TransformBroadcaster mTransformOdomBroadcaster; + tf2_ros::TransformBroadcaster mTransformImuBroadcaster; + + std::string mRgbFrameId; + std::string mRgbOptFrameId; + + std::string mDepthFrameId; + std::string mDepthOptFrameId; + + std::string mDisparityFrameId; + std::string mDisparityOptFrameId; + + std::string mConfidenceFrameId; + std::string mConfidenceOptFrameId; + + std::string mCloudFrameId; + std::string mPointCloudFrameId; + + std::string mMapFrameId; + std::string mOdometryFrameId; + std::string mBaseFrameId; + std::string mCameraFrameId; + + std::string mRightCamFrameId; + std::string mRightCamOptFrameId; + std::string mLeftCamFrameId; + std::string mLeftCamOptFrameId; + std::string mImuFrameId; // initialization Transform listener - std::shared_ptr tfBuffer; - std::shared_ptr tfListener; - bool publishTf; - bool cameraFlip; + boost::shared_ptr mTfBuffer; + boost::shared_ptr mTfListener; + + bool mPublishTf; + bool mPublishMapTf; + bool mCameraFlip; // Launch file parameters - int resolution; - int frameRate; - int quality; - int sensingMode; - int gpuId; - int zedId; - int depthStabilization; - std::string odometryDb; - std::string svoFilepath; - double imuPubRate; - bool verbose; + int mCamResol; + int mCamFrameRate; + int mCamQuality; + int mCamSensingMode; + int mGpuId; + int mZedId; + int mDepthStabilization; + std::string mOdometryDb; + std::string mSvoFilepath; + double mImuPubRate; + double mPathPubRate; + int mPathMaxCount; + bool mVerbose; bool mSvoMode = false; - // IMU time - ros::Time imuTime; + bool mTrackingActivated; + bool mTrackingReady; + bool mFloorAlignment = false; - bool poseSmoothing; - bool spatialMemory; - bool initOdomWithPose; + // Last frame time + ros::Time mLastFrameTime; //Tracking variables - sl::Transform initialPoseSl; - std::vector initialTrackPose; - - tf2::Transform odomToMapTransform; - tf2::Transform baseToOdomTransform; - - // zed object - sl::InitParameters param; - sl::Camera zed; - unsigned int serial_number; - int userCamModel; // Camera model set by ROS Param - sl::MODEL realCamModel; // Camera model requested to SDK + sl::Pose mLastZedPose; // Sensor to Map transform + sl::Transform mInitialPoseSl; + std::vector mInitialTrackPose; + std::vector mOdomPath; + std::vector mMapPath; + + // TF Transforms + tf2::Transform mOdom2MapTransf; + tf2::Transform mBase2OdomTransf; + + // Zed object + sl::InitParameters mZedParams; + sl::Camera mZed; + unsigned int mZedSerialNumber; + int mZedUserCamModel; // Camera model set by ROS Param + sl::MODEL mZedRealCamModel; // Camera model requested to SDK + + // Dynamic Parameters + int mCamConfidence; + int mCamExposure; + int mCamGain; + double mCamMatResizeFactor; + double mCamMaxDepth; + bool mCamAutoExposure; // flags - double matResizeFactor; - int confidence; - int exposure; - int gain; - bool autoExposure; - bool triggerAutoExposure; - bool computeDepth; - bool grabbing = false; - int openniDepthMode = 0; // 16 bit UC data in mm else 32F in m, for more info http://www.ros.org/reps/rep-0118.html - - // Frame and Mat - int camWidth; - int camHeight; - int matWidth; - int matHeight; - cv::Mat leftImRGB; - cv::Mat rightImRGB; - cv::Mat confImRGB; - cv::Mat confMapFloat; - - // Mutex - std::mutex dataMutex; + bool mTriggerAutoExposure; + bool mComputeDepth; + bool mOpenniDepthMode; // 16 bit UC data in mm else 32F in m, for more info -> http://www.ros.org/reps/rep-0118.html + bool mPoseSmoothing; + bool mSpatialMemory; + bool mInitOdomWithPose; + bool mResetOdom = false; + + // OpenCV Mat + int mCamWidth; + int mCamHeight; + int mMatWidth; + int mMatHeight; + cv::Mat mCvLeftImRGB; + cv::Mat mCvRightImRGB; + cv::Mat mCvConfImRGB; + cv::Mat mCvConfMapFloat; + + // Thread Sync + std::mutex mCamDataMutex; std::mutex mPcMutex; std::condition_variable mPcDataReadyCondVar; bool mPcDataReady; // Point cloud variables - sl::Mat cloud; + sl::Mat mCloud; sensor_msgs::PointCloud2 mPointcloudMsg; - string pointCloudFrameId = ""; - ros::Time pointCloudTime; + ros::Time mPointCloudTime; // Dynamic reconfigure - boost::shared_ptr> server; + boost::shared_ptr> mDynRecServer; // Coordinate Changing indices and signs - unsigned int xIdx, yIdx, zIdx; - int xSign, ySign, zSign; - + int mIdxX, mIdxY, mIdxZ; + int mSignX, mSignY, mSignZ; }; // class ZEDROSWrapperNodelet } // namespace diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index 80cc0689..bf7e1cd3 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -18,7 +18,6 @@ // /////////////////////////////////////////////////////////////////////////// #include "zed_wrapper_nodelet.hpp" -#include "sl_tools.h" #include @@ -26,23 +25,16 @@ #include #endif +#include #include +#include #include #include #include #include #include - #include -// >>>>> Backward compatibility -#define COORDINATE_SYSTEM_IMAGE static_cast(0) -#define COORDINATE_SYSTEM_RIGHT_HANDED_Z_UP \ - static_cast(3) -#define COORDINATE_SYSTEM_RIGHT_HANDED_Z_UP_X_FWD \ - static_cast(5) -// <<<<< Backward compatibility - using namespace std; namespace zed_wrapper { @@ -50,8 +42,8 @@ namespace zed_wrapper { ZEDWrapperNodelet::ZEDWrapperNodelet() : Nodelet() {} ZEDWrapperNodelet::~ZEDWrapperNodelet() { - if (devicePollThread.joinable()) { - devicePollThread.join(); + if (mDevicePollThread.joinable()) { + mDevicePollThread.join(); } if (mPcThread.joinable()) { @@ -65,814 +57,816 @@ namespace zed_wrapper { mPcDataReady = false; #ifndef NDEBUG + if (ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug)) { ros::console::notifyLoggerLevelsChanged(); } #endif - // Launch file parameters - resolution = sl::RESOLUTION_HD720; - quality = sl::DEPTH_MODE_PERFORMANCE; - sensingMode = sl::SENSING_MODE_STANDARD; - frameRate = 30; - gpuId = -1; - zedId = 0; - serial_number = 0; - odometryDb = ""; - imuPubRate = 100.0; - initialTrackPose.resize(6); - for (int i = 0; i < 6; i++) { - initialTrackPose[i] = 0.0f; + mCamResol = sl::RESOLUTION_HD720; + mCamQuality = sl::DEPTH_MODE_PERFORMANCE; + mCamSensingMode = sl::SENSING_MODE_STANDARD; + mCamFrameRate = 30; + mGpuId = -1; + mZedId = 0; + mZedSerialNumber = 0; + mOdometryDb = ""; + mImuPubRate = 100.0; + mPathPubRate = 1.0; + mInitialTrackPose.resize(6); + mOpenniDepthMode = false; + mTrackingReady = false; + + for (size_t i = 0; i < 6; i++) { + mInitialTrackPose[i] = 0.0f; } - matResizeFactor = 1.0; - - verbose = true; - - nh = getMTNodeHandle(); - nhNs = getMTPrivateNodeHandle(); + mCamMatResizeFactor = 1.0; + mVerbose = true; + mNh = getMTNodeHandle(); + mNhNs = getMTPrivateNodeHandle(); // Set default coordinate frames - nhNs.param("pose_frame", mapFrameId, "pose_frame"); - nhNs.param("odometry_frame", odometryFrameId, "odometry_frame"); - nhNs.param("base_frame", baseFrameId, "base_frame"); - nhNs.param("imu_frame", imuFrameId, "imu_link"); - - nhNs.param("left_camera_frame", leftCamFrameId, - "left_camera_frame"); - nhNs.param("left_camera_optical_frame", leftCamOptFrameId, - "left_camera_optical_frame"); - - nhNs.param("right_camera_frame", rightCamFrameId, - "right_camera_frame"); - nhNs.param("right_camera_optical_frame", rightCamOptFrameId, - "right_camera_optical_frame"); - - depthFrameId = leftCamFrameId; - depthOptFrameId = leftCamOptFrameId; + mNhNs.param("pose_frame", mMapFrameId, "map"); + mNhNs.param("odometry_frame", mOdometryFrameId, "odom"); + mNhNs.param("base_frame", mBaseFrameId, "base_link"); + mNhNs.param("camera_frame", mCameraFrameId, "zed_camera_center"); + mNhNs.param("imu_frame", mImuFrameId, "imu_link"); + mNhNs.param("left_camera_frame", mLeftCamFrameId, + "left_camera_frame"); + mNhNs.param("left_camera_optical_frame", mLeftCamOptFrameId, + "left_camera_optical_frame"); + mNhNs.param("right_camera_frame", mRightCamFrameId, + "right_camera_frame"); + mNhNs.param("right_camera_optical_frame", mRightCamOptFrameId, + "right_camera_optical_frame"); + mDepthFrameId = mLeftCamFrameId; + mDepthOptFrameId = mLeftCamOptFrameId; // Note: Depth image frame id must match color image frame id - cloudFrameId = depthOptFrameId; - rgbFrameId = depthFrameId; - rgbOptFrameId = cloudFrameId; - - disparityFrameId = depthFrameId; - disparityOptFrameId = depthOptFrameId; - - confidenceFrameId = depthFrameId; - confidenceOptFrameId = depthOptFrameId; + mCloudFrameId = mDepthOptFrameId; + mRgbFrameId = mDepthFrameId; + mRgbOptFrameId = mCloudFrameId; + mDisparityFrameId = mDepthFrameId; + mDisparityOptFrameId = mDepthOptFrameId; + mConfidenceFrameId = mDepthFrameId; + mConfidenceOptFrameId = mDepthOptFrameId; // Get parameters from launch file - nhNs.getParam("resolution", resolution); - nhNs.getParam("frame_rate", frameRate); - + mNhNs.getParam("resolution", mCamResol); + mNhNs.getParam("frame_rate", mCamFrameRate); checkResolFps(); + mNhNs.getParam("verbose", mVerbose); + mNhNs.getParam("quality", mCamQuality); + mNhNs.getParam("sensing_mode", mCamSensingMode); + mNhNs.getParam("openni_depth_mode", mOpenniDepthMode); + mNhNs.getParam("gpu_id", mGpuId); + mNhNs.getParam("zed_id", mZedId); + mNhNs.getParam("depth_stabilization", mDepthStabilization); - nhNs.getParam("verbose", verbose); - nhNs.getParam("quality", quality); - nhNs.getParam("sensing_mode", sensingMode); - nhNs.getParam("openni_depth_mode", openniDepthMode); - nhNs.getParam("gpu_id", gpuId); - nhNs.getParam("zed_id", zedId); - nhNs.getParam("depth_stabilization", depthStabilization); int tmp_sn = 0; - nhNs.getParam("serial_number", tmp_sn); + mNhNs.getParam("serial_number", tmp_sn); + if (tmp_sn > 0) { - serial_number = tmp_sn; + mZedSerialNumber = static_cast(tmp_sn); } - nhNs.getParam("camera_model", userCamModel); - // Publish odometry tf - nhNs.param("publish_tf", publishTf, true); + mNhNs.getParam("camera_model", mZedUserCamModel); - nhNs.param("camera_flip", cameraFlip, false); + // Publish odometry tf + mNhNs.param("publish_tf", mPublishTf, true); + mNhNs.param("publish_map_tf", mPublishMapTf, true); + mNhNs.param("camera_flip", mCameraFlip, false); - if (serial_number > 0) { - NODELET_INFO_STREAM("SN : " << serial_number); + if (mZedSerialNumber > 0) { + NODELET_INFO_STREAM("SN : " << mZedSerialNumber); } // Print order frames - NODELET_INFO_STREAM("pose_frame \t\t -> " << mapFrameId); - NODELET_INFO_STREAM("odometry_frame \t\t -> " << odometryFrameId); - NODELET_INFO_STREAM("base_frame \t\t -> " << baseFrameId); - NODELET_INFO_STREAM("imu_link \t\t -> " << imuFrameId); - NODELET_INFO_STREAM("left_camera_frame \t -> " << leftCamFrameId); - NODELET_INFO_STREAM("left_camera_optical_frame -> " << leftCamOptFrameId); - NODELET_INFO_STREAM("right_camera_frame \t -> " << rightCamFrameId); - NODELET_INFO_STREAM("right_camera_optical_frame -> " << rightCamOptFrameId); - NODELET_INFO_STREAM("depth_frame \t\t -> " << depthFrameId); - NODELET_INFO_STREAM("depth_optical_frame \t -> " << depthOptFrameId); - NODELET_INFO_STREAM("disparity_frame \t -> " << disparityFrameId); - NODELET_INFO_STREAM("disparity_optical_frame -> " << disparityOptFrameId); - - // Status of map TF - NODELET_INFO_STREAM("Publish " << mapFrameId << " [" - << (publishTf ? "TRUE" : "FALSE") << "]"); - NODELET_INFO_STREAM("Camera Flip [" << (cameraFlip ? "TRUE" : "FALSE") << "]"); + NODELET_INFO_STREAM("pose_frame \t\t -> " << mMapFrameId); + NODELET_INFO_STREAM("odometry_frame \t\t -> " << mOdometryFrameId); + NODELET_INFO_STREAM("base_frame \t\t -> " << mBaseFrameId); + NODELET_INFO_STREAM("camera_frame \t\t -> " << mCameraFrameId); + NODELET_INFO_STREAM("imu_link \t\t -> " << mImuFrameId); + NODELET_INFO_STREAM("left_camera_frame \t -> " << mLeftCamFrameId); + NODELET_INFO_STREAM("left_camera_optical_frame -> " << mLeftCamOptFrameId); + NODELET_INFO_STREAM("right_camera_frame \t -> " << mRightCamFrameId); + NODELET_INFO_STREAM("right_camera_optical_frame -> " << mRightCamOptFrameId); + NODELET_INFO_STREAM("depth_frame \t\t -> " << mDepthFrameId); + NODELET_INFO_STREAM("depth_optical_frame \t -> " << mDepthOptFrameId); + NODELET_INFO_STREAM("disparity_frame \t -> " << mDisparityFrameId); + NODELET_INFO_STREAM("disparity_optical_frame -> " << mDisparityOptFrameId); + + NODELET_INFO_STREAM("Camera Flip [" << (mCameraFlip ? "TRUE" : "FALSE") << "]"); // Status of odometry TF - // NODELET_INFO_STREAM("Publish " << odometry_frame_id << " [" << (publish_tf - // ? "TRUE" : "FALSE") << "]"); + NODELET_INFO_STREAM("Broadcasting " << mOdometryFrameId << " [" << (mPublishTf ? "TRUE" : "FALSE") << "]"); + // Status of map TF + NODELET_INFO_STREAM("Broadcasting " << mMapFrameId << " [" << ((mPublishTf && mPublishMapTf) ? "TRUE" : "FALSE") << "]"); std::string img_topic = "image_rect_color"; std::string img_raw_topic = "image_raw_color"; - // Set the default topic names string left_topic = "left/" + img_topic; string left_raw_topic = "left/" + img_raw_topic; string left_cam_info_topic = "left/camera_info"; string left_cam_info_raw_topic = "left/camera_info_raw"; - string right_topic = "right/" + img_topic; string right_raw_topic = "right/" + img_raw_topic; string right_cam_info_topic = "right/camera_info"; string right_cam_info_raw_topic = "right/camera_info_raw"; - string rgb_topic = "rgb/" + img_topic; string rgb_raw_topic = "rgb/" + img_raw_topic; string rgb_cam_info_topic = "rgb/camera_info"; string rgb_cam_info_raw_topic = "rgb/camera_info_raw"; - + string depth_topic = "depth/"; - if (openniDepthMode) { + if (mOpenniDepthMode) { NODELET_INFO_STREAM("Openni depth mode activated"); depth_topic += "depth_raw_registered"; } else { depth_topic += "depth_registered"; } - string depth_cam_info_topic = "depth/camera_info"; - string disparity_topic = "disparity/disparity_image"; - string point_cloud_topic = "point_cloud/cloud_registered"; - string conf_img_topic = "confidence/confidence_image"; string conf_map_topic = "confidence/confidence_map"; - - string pose_topic = "map"; + string pose_topic = "pose"; string odometry_topic = "odom"; + string odom_path_topic = "path_odom"; + string map_path_topic = "path_map"; string imu_topic = "imu/data"; string imu_topic_raw = "imu/data_raw"; - - nhNs.getParam("rgb_topic", rgb_topic); - nhNs.getParam("rgb_raw_topic", rgb_raw_topic); - nhNs.getParam("rgb_cam_info_topic", rgb_cam_info_topic); - nhNs.getParam("rgb_cam_info_raw_topic", rgb_cam_info_raw_topic); - - nhNs.getParam("left_topic", left_topic); - nhNs.getParam("left_raw_topic", left_raw_topic); - nhNs.getParam("left_cam_info_topic", left_cam_info_topic); - nhNs.getParam("left_cam_info_raw_topic", left_cam_info_raw_topic); - - nhNs.getParam("right_topic", right_topic); - nhNs.getParam("right_raw_topic", right_raw_topic); - nhNs.getParam("right_cam_info_topic", right_cam_info_topic); - nhNs.getParam("right_cam_info_raw_topic", right_cam_info_raw_topic); - - nhNs.getParam("depth_topic", depth_topic); - nhNs.getParam("depth_cam_info_topic", depth_cam_info_topic); - - nhNs.getParam("disparity_topic", disparity_topic); - - nhNs.getParam("confidence_img_topic", conf_img_topic); - nhNs.getParam("confidence_map_topic", conf_map_topic); - - nhNs.getParam("point_cloud_topic", point_cloud_topic); - - nhNs.getParam("pose_topic", pose_topic); - nhNs.getParam("odometry_topic", odometry_topic); - - nhNs.getParam("imu_topic", imu_topic); - nhNs.getParam("imu_topic_raw", imu_topic_raw); - nhNs.getParam("imu_pub_rate", imuPubRate); + mNhNs.getParam("rgb_topic", rgb_topic); + mNhNs.getParam("rgb_raw_topic", rgb_raw_topic); + mNhNs.getParam("rgb_cam_info_topic", rgb_cam_info_topic); + mNhNs.getParam("rgb_cam_info_raw_topic", rgb_cam_info_raw_topic); + mNhNs.getParam("left_topic", left_topic); + mNhNs.getParam("left_raw_topic", left_raw_topic); + mNhNs.getParam("left_cam_info_topic", left_cam_info_topic); + mNhNs.getParam("left_cam_info_raw_topic", left_cam_info_raw_topic); + mNhNs.getParam("right_topic", right_topic); + mNhNs.getParam("right_raw_topic", right_raw_topic); + mNhNs.getParam("right_cam_info_topic", right_cam_info_topic); + mNhNs.getParam("right_cam_info_raw_topic", right_cam_info_raw_topic); + mNhNs.getParam("depth_topic", depth_topic); + mNhNs.getParam("depth_cam_info_topic", depth_cam_info_topic); + mNhNs.getParam("disparity_topic", disparity_topic); + mNhNs.getParam("confidence_img_topic", conf_img_topic); + mNhNs.getParam("confidence_map_topic", conf_map_topic); + mNhNs.getParam("point_cloud_topic", point_cloud_topic); + mNhNs.getParam("pose_topic", pose_topic); + mNhNs.getParam("odometry_topic", odometry_topic); + mNhNs.getParam("imu_topic", imu_topic); + mNhNs.getParam("imu_topic_raw", imu_topic_raw); + mNhNs.getParam("imu_pub_rate", mImuPubRate); + mNhNs.getParam("path_pub_rate", mPathPubRate); + mNhNs.getParam("path_max_count", mPathMaxCount); + if (mPathMaxCount < 2 && mPathMaxCount != -1) { + mPathMaxCount = 2; + } // Create camera info - sensor_msgs::CameraInfoPtr rgb_cam_info_ms_g(new sensor_msgs::CameraInfo()); + sensor_msgs::CameraInfoPtr rgb_cam_info_msg_(new sensor_msgs::CameraInfo()); sensor_msgs::CameraInfoPtr left_cam_info_msg_(new sensor_msgs::CameraInfo()); sensor_msgs::CameraInfoPtr right_cam_info_msg_(new sensor_msgs::CameraInfo()); - sensor_msgs::CameraInfoPtr rgb_cam_info_raw_msg_( - new sensor_msgs::CameraInfo()); - sensor_msgs::CameraInfoPtr left_cam_info_raw_ms_g( - new sensor_msgs::CameraInfo()); - sensor_msgs::CameraInfoPtr right_cam_info_raw_msg_( - new sensor_msgs::CameraInfo()); + sensor_msgs::CameraInfoPtr rgb_cam_info_raw_msg_(new sensor_msgs::CameraInfo()); + sensor_msgs::CameraInfoPtr left_cam_info_raw_msg_(new sensor_msgs::CameraInfo()); + sensor_msgs::CameraInfoPtr right_cam_info_raw_msg_(new sensor_msgs::CameraInfo()); sensor_msgs::CameraInfoPtr depth_cam_info_msg_(new sensor_msgs::CameraInfo()); - - rgbCamInfoMsg = rgb_cam_info_ms_g; - leftCamInfoMsg = left_cam_info_msg_; - rightCamInfoMsg = right_cam_info_msg_; - rgbCamInfoRawMsg = rgb_cam_info_raw_msg_; - leftCamInfoRawMsg = left_cam_info_raw_ms_g; - rightCamInfoRawMsg = right_cam_info_raw_msg_; - depthCamInfoMsg = depth_cam_info_msg_; + mRgbCamInfoMsg = rgb_cam_info_msg_; + mLeftCamInfoMsg = left_cam_info_msg_; + mRightCamInfoMsg = right_cam_info_msg_; + mRgbCamInfoRawMsg = rgb_cam_info_raw_msg_; + mLeftCamInfoRawMsg = left_cam_info_raw_msg_; + mRightCamInfoRawMsg = right_cam_info_raw_msg_; + mDepthCamInfoMsg = depth_cam_info_msg_; // SVO - nhNs.param("svo_filepath", svoFilepath, std::string()); + mNhNs.param("svo_filepath", mSvoFilepath, std::string()); // Initialize tf2 transformation - nhNs.getParam("initial_tracking_pose", initialTrackPose); - set_pose(initialTrackPose[0], initialTrackPose[1], initialTrackPose[2], - initialTrackPose[3], initialTrackPose[4], initialTrackPose[5]); + mNhNs.getParam("initial_tracking_pose", mInitialTrackPose); + set_pose(mInitialTrackPose[0], mInitialTrackPose[1], mInitialTrackPose[2], + mInitialTrackPose[3], mInitialTrackPose[4], mInitialTrackPose[5]); // Initialization transformation listener - tfBuffer.reset(new tf2_ros::Buffer); - tfListener.reset(new tf2_ros::TransformListener(*tfBuffer)); + mTfBuffer.reset(new tf2_ros::Buffer); + mTfListener.reset(new tf2_ros::TransformListener(*mTfBuffer)); // Try to initialize the ZED - if (!svoFilepath.empty()) { - param.svo_input_filename = svoFilepath.c_str(); + if (!mSvoFilepath.empty()) { + mZedParams.svo_input_filename = mSvoFilepath.c_str(); + mZedParams.svo_real_time_mode = true; + // mPubClock = mNh.advertise("/clock", 1); + // NODELET_INFO("Advertised on topic /clock"); mSvoMode = true; } else { - param.camera_fps = frameRate; - param.camera_resolution = static_cast(resolution); - if (serial_number == 0) { - param.camera_linux_id = zedId; + mZedParams.camera_fps = mCamFrameRate; + mZedParams.camera_resolution = static_cast(mCamResol); + + if (mZedSerialNumber == 0) { + mZedParams.camera_linux_id = mZedId; } else { bool waiting_for_camera = true; - while (waiting_for_camera) { - if (!nhNs.ok()) { + while (waiting_for_camera) { + // Ctrl+C check + if (!mNhNs.ok()) { mStopNode = true; // Stops other threads - zed.close(); + mZed.close(); NODELET_DEBUG("ZED pool thread finished"); return; } - sl::DeviceProperties prop = sl_tools::getZEDFromSN(serial_number); + sl::DeviceProperties prop = sl_tools::getZEDFromSN(mZedSerialNumber); + if (prop.id < -1 || prop.camera_state == sl::CAMERA_STATE::CAMERA_STATE_NOT_AVAILABLE) { - std::string msg = "ZED SN" + to_string(serial_number) + + std::string msg = "ZED SN" + to_string(mZedSerialNumber) + " not detected ! Please connect this ZED"; NODELET_INFO_STREAM(msg.c_str()); std::this_thread::sleep_for(std::chrono::milliseconds(2000)); } else { waiting_for_camera = false; - param.camera_linux_id = prop.id; + mZedParams.camera_linux_id = prop.id; } } } } - std::string ver = sl_tools::getSDKVersion(verMajor, verMinor, verSubMinor); + std::string ver = sl_tools::getSDKVersion(mVerMajor, mVerMinor, mVerSubMinor); NODELET_INFO_STREAM("SDK version : " << ver); - if (verMajor < 2) { - NODELET_WARN_STREAM("Please consider to upgrade to latest SDK version to " - "get better performances"); - param.coordinate_system = COORDINATE_SYSTEM_IMAGE; - NODELET_INFO_STREAM("Camera coordinate system : COORDINATE_SYSTEM_IMAGE"); - xIdx = 2; - yIdx = 0; - zIdx = 1; - xSign = 1; - ySign = -1; - zSign = -1; - } else if (verMajor == 2 && verMinor < 5) { - NODELET_WARN_STREAM("Please consider to upgrade to latest SDK version to " - "get latest features"); - param.coordinate_system = COORDINATE_SYSTEM_RIGHT_HANDED_Z_UP; - NODELET_INFO_STREAM( - "Camera coordinate system : COORDINATE_SYSTEM_RIGHT_HANDED_Z_UP"); - xIdx = 1; - yIdx = 0; - zIdx = 2; - xSign = 1; - ySign = -1; - zSign = 1; - } else { - param.coordinate_system = COORDINATE_SYSTEM_RIGHT_HANDED_Z_UP_X_FWD; - NODELET_INFO_STREAM( - "Camera coordinate system : COORDINATE_SYSTEM_RIGHT_HANDED_Z_UP_X_FWD"); - xIdx = 0; - yIdx = 1; - zIdx = 2; - xSign = 1; - ySign = 1; - zSign = 1; - } - - param.coordinate_units = sl::UNIT_METER; +#if (ZED_SDK_MAJOR_VERSION<2) + NODELET_WARN_STREAM("Please consider to upgrade to latest SDK version to " + "get better performances"); + + mZedParams.coordinate_system = sl::COORDINATE_SYSTEM_IMAGE; + + NODELET_INFO_STREAM("Camera coordinate system : COORDINATE_SYSTEM_IMAGE"); + mIdxX = 2; + mIdxY = 0; + mIdxZ = 1; + mSignX = 1; + mSignY = -1; + mSignZ = -1; +#elif (ZED_SDK_MAJOR_VERSION==2 && ZED_SDK_MINOR_VERSION<5) + NODELET_WARN_STREAM("Please consider to upgrade to latest SDK version to " + "get latest features"); + + mZedParams.coordinate_system = sl::COORDINATE_SYSTEM_RIGHT_HANDED_Z_UP; + + NODELET_INFO_STREAM("Camera coordinate system : COORDINATE_SYSTEM_RIGHT_HANDED_Z_UP"); + mIdxX = 1; + mIdxY = 0; + mIdxZ = 2; + mSignX = 1; + mSignY = -1; + mSignZ = 1; +#else + mZedParams.coordinate_system = sl::COORDINATE_SYSTEM_RIGHT_HANDED_Z_UP_X_FWD; + + NODELET_INFO_STREAM("Camera coordinate system : COORDINATE_SYSTEM_RIGHT_HANDED_Z_UP_X_FWD"); + mIdxX = 0; + mIdxY = 1; + mIdxZ = 2; + mSignX = 1; + mSignY = 1; + mSignZ = 1; +#endif - param.depth_mode = static_cast(quality); - param.sdk_verbose = verbose; - param.sdk_gpu_id = gpuId; - param.depth_stabilization = depthStabilization; - param.camera_image_flip = cameraFlip; + mZedParams.coordinate_units = sl::UNIT_METER; + mZedParams.depth_mode = static_cast(mCamQuality); + mZedParams.sdk_verbose = mVerbose; + mZedParams.sdk_gpu_id = mGpuId; + mZedParams.depth_stabilization = mDepthStabilization; + mZedParams.camera_image_flip = mCameraFlip; sl::ERROR_CODE err = sl::ERROR_CODE_CAMERA_NOT_DETECTED; + while (err != sl::SUCCESS) { - err = zed.open(param); + err = mZed.open(mZedParams); NODELET_INFO_STREAM(toString(err)); std::this_thread::sleep_for(std::chrono::milliseconds(2000)); - if (!nhNs.ok()) { + if (!mNhNs.ok()) { mStopNode = true; // Stops other threads - zed.close(); + mZed.close(); NODELET_DEBUG("ZED pool thread finished"); return; } } - realCamModel = zed.getCameraInformation().camera_model; - + mZedRealCamModel = mZed.getCameraInformation().camera_model; std::string camModelStr = "LAST"; - if (realCamModel == sl::MODEL_ZED) { + + if (mZedRealCamModel == sl::MODEL_ZED) { camModelStr = "ZED"; - if (userCamModel != 0) { + + if (mZedUserCamModel != 0) { NODELET_WARN("Camera model does not match user parameter. Please modify " "the value of the parameter 'camera_model' to 0"); } - } else if (realCamModel == sl::MODEL_ZED_M) { + } else if (mZedRealCamModel == sl::MODEL_ZED_M) { camModelStr = "ZED M"; - if (userCamModel != 1) { + + if (mZedUserCamModel != 1) { NODELET_WARN("Camera model does not match user parameter. Please modify " "the value of the parameter 'camera_model' to 1"); } } - NODELET_INFO_STREAM("CAMERA MODEL : " << realCamModel); - - serial_number = zed.getCameraInformation().serial_number; + NODELET_INFO_STREAM("CAMERA MODEL : " << mZedRealCamModel); + mZedSerialNumber = mZed.getCameraInformation().serial_number; // Dynamic Reconfigure parameters - server = - boost::make_shared>(); + mDynRecServer = boost::make_shared>(); dynamic_reconfigure::Server::CallbackType f; f = boost::bind(&ZEDWrapperNodelet::dynamicReconfCallback, this, _1, _2); - server->setCallback(f); + mDynRecServer->setCallback(f); - nhNs.getParam("mat_resize_factor", matResizeFactor); + mNhNs.getParam("mat_resize_factor", mCamMatResizeFactor); - if (matResizeFactor < 0.1) { - matResizeFactor = 0.1; + if (mCamMatResizeFactor < 0.1) { + mCamMatResizeFactor = 0.1; NODELET_WARN_STREAM( "Minimum allowed values for 'mat_resize_factor' is 0.1"); } - if (matResizeFactor > 1.0) { - matResizeFactor = 1.0; + + if (mCamMatResizeFactor > 1.0) { + mCamMatResizeFactor = 1.0; NODELET_WARN_STREAM( "Maximum allowed values for 'mat_resize_factor' is 1.0"); } - nhNs.getParam("confidence", confidence); - nhNs.getParam("exposure", exposure); - nhNs.getParam("gain", gain); - nhNs.getParam("auto_exposure", autoExposure); - if (autoExposure) { - triggerAutoExposure = true; + mNhNs.getParam("confidence", mCamConfidence); + mNhNs.getParam("max_depth", mCamMaxDepth); + mNhNs.getParam("exposure", mCamExposure); + mNhNs.getParam("gain", mCamGain); + mNhNs.getParam("auto_exposure", mCamAutoExposure); + + if (mCamAutoExposure) { + mTriggerAutoExposure = true; } // Create all the publishers // Image publishers - image_transport::ImageTransport it_zed(nh); - pubRgb = it_zed.advertise(rgb_topic, 1); // rgb - NODELET_INFO_STREAM("Advertized on topic " << rgb_topic); - pubRawRgb = it_zed.advertise(rgb_raw_topic, 1); // rgb raw - NODELET_INFO_STREAM("Advertized on topic " << rgb_raw_topic); - pubLeft = it_zed.advertise(left_topic, 1); // left - NODELET_INFO_STREAM("Advertized on topic " << left_topic); - pubRawLeft = it_zed.advertise(left_raw_topic, 1); // left raw - NODELET_INFO_STREAM("Advertized on topic " << left_raw_topic); - pubRight = it_zed.advertise(right_topic, 1); // right - NODELET_INFO_STREAM("Advertized on topic " << right_topic); - pubRawRight = it_zed.advertise(right_raw_topic, 1); // right raw - NODELET_INFO_STREAM("Advertized on topic " << right_raw_topic); - pubDepth = it_zed.advertise(depth_topic, 1); // depth - NODELET_INFO_STREAM("Advertized on topic " << depth_topic); - pubConfImg = it_zed.advertise(conf_img_topic, 1); // confidence image - NODELET_INFO_STREAM("Advertized on topic " << conf_img_topic); + image_transport::ImageTransport it_zed(mNh); + mPubRgb = it_zed.advertise(rgb_topic, 1); // rgb + NODELET_INFO_STREAM("Advertised on topic " << rgb_topic); + mPubRawRgb = it_zed.advertise(rgb_raw_topic, 1); // rgb raw + NODELET_INFO_STREAM("Advertised on topic " << rgb_raw_topic); + mPubLeft = it_zed.advertise(left_topic, 1); // left + NODELET_INFO_STREAM("Advertised on topic " << left_topic); + mPubRawLeft = it_zed.advertise(left_raw_topic, 1); // left raw + NODELET_INFO_STREAM("Advertised on topic " << left_raw_topic); + mPubRight = it_zed.advertise(right_topic, 1); // right + NODELET_INFO_STREAM("Advertised on topic " << right_topic); + mPubRawRight = it_zed.advertise(right_raw_topic, 1); // right raw + NODELET_INFO_STREAM("Advertised on topic " << right_raw_topic); + mPubDepth = it_zed.advertise(depth_topic, 1); // depth + NODELET_INFO_STREAM("Advertised on topic " << depth_topic); + mPubConfImg = it_zed.advertise(conf_img_topic, 1); // confidence image + NODELET_INFO_STREAM("Advertised on topic " << conf_img_topic); // Confidence Map publisher - pubConfMap = - nh.advertise(conf_map_topic, 1); // confidence map - NODELET_INFO_STREAM("Advertized on topic " << conf_map_topic); + mPubConfMap = mNh.advertise(conf_map_topic, 1); // confidence map + NODELET_INFO_STREAM("Advertised on topic " << conf_map_topic); // Disparity publisher - pubDisparity = nh.advertise(disparity_topic, 1); - NODELET_INFO_STREAM("Advertized on topic " << disparity_topic); + mPubDisparity = mNh.advertise(disparity_topic, 1); + NODELET_INFO_STREAM("Advertised on topic " << disparity_topic); // PointCloud publisher - pubCloud = nh.advertise(point_cloud_topic, 1); - NODELET_INFO_STREAM("Advertized on topic " << point_cloud_topic); + mPubCloud = mNh.advertise(point_cloud_topic, 1); + NODELET_INFO_STREAM("Advertised on topic " << point_cloud_topic); // Camera info publishers - pubRgbCamInfo = - nh.advertise(rgb_cam_info_topic, 1); // rgb - NODELET_INFO_STREAM("Advertized on topic " << rgb_cam_info_topic); - pubLeftCamInfo = - nh.advertise(left_cam_info_topic, 1); // left - NODELET_INFO_STREAM("Advertized on topic " << left_cam_info_topic); - pubRightCamInfo = - nh.advertise(right_cam_info_topic, 1); // right - NODELET_INFO_STREAM("Advertized on topic " << right_cam_info_topic); - pubDepthCamInfo = - nh.advertise(depth_cam_info_topic, 1); // depth - NODELET_INFO_STREAM("Advertized on topic " << depth_cam_info_topic); + mPubRgbCamInfo = mNh.advertise(rgb_cam_info_topic, 1); // rgb + NODELET_INFO_STREAM("Advertised on topic " << rgb_cam_info_topic); + mPubLeftCamInfo = mNh.advertise(left_cam_info_topic, 1); // left + NODELET_INFO_STREAM("Advertised on topic " << left_cam_info_topic); + mPubRightCamInfo = mNh.advertise(right_cam_info_topic, 1); // right + NODELET_INFO_STREAM("Advertised on topic " << right_cam_info_topic); + mPubDepthCamInfo = mNh.advertise(depth_cam_info_topic, 1); // depth + NODELET_INFO_STREAM("Advertised on topic " << depth_cam_info_topic); + // Raw - pubRgbCamInfoRaw = nh.advertise( - rgb_cam_info_raw_topic, 1); // raw rgb - NODELET_INFO_STREAM("Advertized on topic " << rgb_cam_info_raw_topic); - pubLeftCamInfoRaw = nh.advertise( - left_cam_info_raw_topic, 1); // raw left - NODELET_INFO_STREAM("Advertized on topic " << left_cam_info_raw_topic); - pubRightCamInfoRaw = nh.advertise( - right_cam_info_raw_topic, 1); // raw right - NODELET_INFO_STREAM("Advertized on topic " << right_cam_info_raw_topic); + mPubRgbCamInfoRaw = mNh.advertise(rgb_cam_info_raw_topic, 1); // raw rgb + NODELET_INFO_STREAM("Advertised on topic " << rgb_cam_info_raw_topic); + mPubLeftCamInfoRaw = mNh.advertise(left_cam_info_raw_topic, 1); // raw left + NODELET_INFO_STREAM("Advertised on topic " << left_cam_info_raw_topic); + mPubRightCamInfoRaw = mNh.advertise(right_cam_info_raw_topic, 1); // raw right + NODELET_INFO_STREAM("Advertised on topic " << right_cam_info_raw_topic); // Odometry and Map publisher - pubPose = nh.advertise(pose_topic, 1); - NODELET_INFO_STREAM("Advertized on topic " << pose_topic); - pubOdom = nh.advertise(odometry_topic, 1); - NODELET_INFO_STREAM("Advertized on topic " << odometry_topic); + mPubPose = mNh.advertise(pose_topic, 1); + NODELET_INFO_STREAM("Advertised on topic " << pose_topic); + mPubOdom = mNh.advertise(odometry_topic, 1); + NODELET_INFO_STREAM("Advertised on topic " << odometry_topic); + + // Camera Path + if (mPathPubRate > 0) { + mPubOdomPath = mNh.advertise(odom_path_topic, 1, true); + NODELET_INFO_STREAM("Advertised on topic " << odom_path_topic); + mPubMapPath = mNh.advertise(map_path_topic, 1, true); + NODELET_INFO_STREAM("Advertised on topic " << map_path_topic); + + mPathTimer = mNhNs.createTimer(ros::Duration(1.0 / mPathPubRate), + &ZEDWrapperNodelet::pathPubCallback, this); + + if (mPathMaxCount != -1) { + NODELET_DEBUG_STREAM("Path vectors reserved " << mPathMaxCount << " poses."); + mOdomPath.reserve(mPathMaxCount); + mMapPath.reserve(mPathMaxCount); + + NODELET_DEBUG_STREAM("Path vector sizes: " << mOdomPath.size() << " " << mMapPath.size()); + } + } // Imu publisher - if (imuPubRate > 0 && realCamModel == sl::MODEL_ZED_M) { - pubImu = nh.advertise(imu_topic, 500); - NODELET_INFO_STREAM("Advertized on topic " << imu_topic << " @ " - << imuPubRate << " Hz"); - - pubImuRaw = nh.advertise(imu_topic_raw, 500); - NODELET_INFO_STREAM("Advertized on topic " << imu_topic_raw << " @ " - << imuPubRate << " Hz"); - - imuTime = ros::Time::now(); - pubImuTimer = nhNs.createTimer(ros::Duration(1.0 / imuPubRate), - &ZEDWrapperNodelet::imuPubCallback, this); - } else if (imuPubRate > 0 && realCamModel == sl::MODEL_ZED) { + if (mImuPubRate > 0 && mZedRealCamModel == sl::MODEL_ZED_M) { + mPubImu = mNh.advertise(imu_topic, 500); + NODELET_INFO_STREAM("Advertised on topic " << imu_topic << " @ " + << mImuPubRate << " Hz"); + mPubImuRaw = mNh.advertise(imu_topic_raw, 500); + NODELET_INFO_STREAM("Advertised on topic " << imu_topic_raw << " @ " + << mImuPubRate << " Hz"); + mLastFrameTime = ros::Time::now(); + mImuTimer = mNhNs.createTimer(ros::Duration(1.0 / mImuPubRate), + &ZEDWrapperNodelet::imuPubCallback, this); + } else if (mImuPubRate > 0 && mZedRealCamModel == sl::MODEL_ZED) { NODELET_WARN_STREAM( "'imu_pub_rate' set to " - << imuPubRate << " Hz" + << mImuPubRate << " Hz" << " but ZED camera model does not support IMU data publishing."); } - // Service - srvSetInitPose = nh.advertiseService("set_initial_pose", - &ZEDWrapperNodelet::on_set_pose, this); - srvResetOdometry = nh.advertiseService( - "reset_odometry", &ZEDWrapperNodelet::on_reset_odometry, this); - srvResetTracking = nh.advertiseService( - "reset_tracking", &ZEDWrapperNodelet::on_reset_tracking, this); - + // Services + mSrvSetInitPose = mNh.advertiseService("set_initial_pose", &ZEDWrapperNodelet::on_set_pose, this); + mSrvResetOdometry = mNh.advertiseService("reset_odometry", &ZEDWrapperNodelet::on_reset_odometry, this); + mSrvResetTracking = mNh.advertiseService("reset_tracking", &ZEDWrapperNodelet::on_reset_tracking, this); + // Start Pointcloud thread - mPcThread = std::thread(&ZEDWrapperNodelet::pointcloud_thread, this); + mPcThread = std::thread(&ZEDWrapperNodelet::pointcloud_thread_func, this); // Start pool thread - devicePollThread = std::thread(&ZEDWrapperNodelet::device_poll, this); + mDevicePollThread = std::thread(&ZEDWrapperNodelet::device_poll_thread_func, this); } void ZEDWrapperNodelet::checkResolFps() { - switch (resolution) { + switch (mCamResol) { case sl::RESOLUTION_HD2K: - if (frameRate != 15) { + if (mCamFrameRate != 15) { NODELET_WARN_STREAM("Wrong FrameRate (" - << frameRate + << mCamFrameRate << ") for the resolution HD2K. Set to 15 FPS."); - frameRate = 15; + mCamFrameRate = 15; } + break; case sl::RESOLUTION_HD1080: - if (frameRate == 15 || frameRate == 30) { + if (mCamFrameRate == 15 || mCamFrameRate == 30) { break; } - if (frameRate > 15 && frameRate < 30) { + if (mCamFrameRate > 15 && mCamFrameRate < 30) { NODELET_WARN_STREAM("Wrong FrameRate (" - << frameRate + << mCamFrameRate << ") for the resolution HD1080. Set to 15 FPS."); - frameRate = 15; - } else if (frameRate > 30) { + mCamFrameRate = 15; + } else if (mCamFrameRate > 30) { NODELET_WARN_STREAM("Wrong FrameRate (" - << frameRate + << mCamFrameRate << ") for the resolution HD1080. Set to 30 FPS."); - frameRate = 30; + mCamFrameRate = 30; } else { NODELET_WARN_STREAM("Wrong FrameRate (" - << frameRate + << mCamFrameRate << ") for the resolution HD1080. Set to 15 FPS."); - frameRate = 15; + mCamFrameRate = 15; } + break; case sl::RESOLUTION_HD720: - if (frameRate == 15 || frameRate == 30 || frameRate == 60) { + if (mCamFrameRate == 15 || mCamFrameRate == 30 || mCamFrameRate == 60) { break; } - if (frameRate > 15 && frameRate < 30) { + if (mCamFrameRate > 15 && mCamFrameRate < 30) { NODELET_WARN_STREAM("Wrong FrameRate (" - << frameRate + << mCamFrameRate << ") for the resolution HD720. Set to 15 FPS."); - frameRate = 15; - } else if (frameRate > 30 && frameRate < 60) { + mCamFrameRate = 15; + } else if (mCamFrameRate > 30 && mCamFrameRate < 60) { NODELET_WARN_STREAM("Wrong FrameRate (" - << frameRate + << mCamFrameRate << ") for the resolution HD720. Set to 30 FPS."); - frameRate = 30; - } else if (frameRate > 60) { + mCamFrameRate = 30; + } else if (mCamFrameRate > 60) { NODELET_WARN_STREAM("Wrong FrameRate (" - << frameRate + << mCamFrameRate << ") for the resolution HD720. Set to 60 FPS."); - frameRate = 60; + mCamFrameRate = 60; } else { NODELET_WARN_STREAM("Wrong FrameRate (" - << frameRate + << mCamFrameRate << ") for the resolution HD720. Set to 15 FPS."); - frameRate = 15; + mCamFrameRate = 15; } + break; case sl::RESOLUTION_VGA: - if (frameRate == 15 || frameRate == 30 || frameRate == 60 || - frameRate == 100) { + if (mCamFrameRate == 15 || mCamFrameRate == 30 || mCamFrameRate == 60 || + mCamFrameRate == 100) { break; } - if (frameRate > 15 && frameRate < 30) { + if (mCamFrameRate > 15 && mCamFrameRate < 30) { NODELET_WARN_STREAM("Wrong FrameRate (" - << frameRate + << mCamFrameRate << ") for the resolution VGA. Set to 15 FPS."); - frameRate = 15; - } else if (frameRate > 30 && frameRate < 60) { + mCamFrameRate = 15; + } else if (mCamFrameRate > 30 && mCamFrameRate < 60) { NODELET_WARN_STREAM("Wrong FrameRate (" - << frameRate + << mCamFrameRate << ") for the resolution VGA. Set to 30 FPS."); - frameRate = 30; - } else if (frameRate > 60 && frameRate < 100) { + mCamFrameRate = 30; + } else if (mCamFrameRate > 60 && mCamFrameRate < 100) { NODELET_WARN_STREAM("Wrong FrameRate (" - << frameRate + << mCamFrameRate << ") for the resolution VGA. Set to 60 FPS."); - frameRate = 60; - } else if (frameRate > 100) { + mCamFrameRate = 60; + } else if (mCamFrameRate > 100) { NODELET_WARN_STREAM("Wrong FrameRate (" - << frameRate + << mCamFrameRate << ") for the resolution VGA. Set to 100 FPS."); - frameRate = 100; + mCamFrameRate = 100; } else { NODELET_WARN_STREAM("Wrong FrameRate (" - << frameRate + << mCamFrameRate << ") for the resolution VGA. Set to 15 FPS."); - frameRate = 15; + mCamFrameRate = 15; } + break; default: NODELET_WARN_STREAM("Invalid resolution. Set to HD720 @ 30 FPS"); - resolution = 2; - frameRate = 30; + mCamResol = 2; + mCamFrameRate = 30; } } - sensor_msgs::ImagePtr - ZEDWrapperNodelet::imageToROSmsg(cv::Mat img, const std::string encodingType, - std::string frameId, ros::Time t) { - sensor_msgs::ImagePtr ptr = boost::make_shared(); - sensor_msgs::Image& imgMessage = *ptr; - imgMessage.header.stamp = t; - imgMessage.header.frame_id = frameId; - imgMessage.height = img.rows; - imgMessage.width = img.cols; - imgMessage.encoding = encodingType; - int num = 1; // for endianness detection - imgMessage.is_bigendian = !(*(char*)&num == 1); - imgMessage.step = img.cols * img.elemSize(); - size_t size = imgMessage.step * img.rows; - imgMessage.data.resize(size); - - if (img.isContinuous()) { - memcpy((char*)(&imgMessage.data[0]), img.data, size); - } else { - uchar* opencvData = img.data; - uchar* rosData = (uchar*)(&imgMessage.data[0]); - - #pragma omp parallel for - for (unsigned int i = 0; i < img.rows; i++) { - memcpy(rosData, opencvData, imgMessage.step); - rosData += imgMessage.step; - opencvData += img.step; - } - } - return ptr; - } - void ZEDWrapperNodelet::set_pose(float xt, float yt, float zt, float rr, float pr, float yr) { // ROS pose tf2::Quaternion q; q.setRPY(rr, pr, yr); - tf2::Vector3 orig(xt, yt, zt); - - baseToOdomTransform.setOrigin(orig); - baseToOdomTransform.setRotation(q); - - odomToMapTransform.setIdentity(); - + mBase2OdomTransf.setOrigin(orig); + mBase2OdomTransf.setRotation(q); + mOdom2MapTransf.setIdentity(); // SL pose sl::float4 q_vec; q_vec[0] = q.x(); q_vec[1] = q.y(); q_vec[2] = q.z(); q_vec[3] = q.w(); - sl::Orientation r(q_vec); - - initialPoseSl.setTranslation(sl::Translation(xt, yt, zt)); - initialPoseSl.setOrientation(r); + mInitialPoseSl.setTranslation(sl::Translation(xt, yt, zt)); + mInitialPoseSl.setOrientation(r); } bool ZEDWrapperNodelet::on_set_pose( zed_wrapper::set_initial_pose::Request& req, zed_wrapper::set_initial_pose::Response& res) { - initialTrackPose.resize(6); - - initialTrackPose[0] = req.x; - initialTrackPose[1] = req.y; - initialTrackPose[2] = req.z; - initialTrackPose[3] = req.R; - initialTrackPose[4] = req.P; - initialTrackPose[5] = req.Y; - - set_pose(initialTrackPose[0], initialTrackPose[1], initialTrackPose[2], - initialTrackPose[3], initialTrackPose[4], initialTrackPose[5]); - - if (trackingActivated) { - zed.resetTracking(initialPoseSl); + mInitialTrackPose.resize(6); + mInitialTrackPose[0] = req.x; + mInitialTrackPose[1] = req.y; + mInitialTrackPose[2] = req.z; + mInitialTrackPose[3] = req.R; + mInitialTrackPose[4] = req.P; + mInitialTrackPose[5] = req.Y; + set_pose(mInitialTrackPose[0], mInitialTrackPose[1], mInitialTrackPose[2], + mInitialTrackPose[3], mInitialTrackPose[4], mInitialTrackPose[5]); + + if (mTrackingActivated) { + mZed.resetTracking(mInitialPoseSl); } res.done = true; - return true; } bool ZEDWrapperNodelet::on_reset_tracking( zed_wrapper::reset_tracking::Request& req, zed_wrapper::reset_tracking::Response& res) { - if (!trackingActivated) { + if (!mTrackingActivated) { res.reset_done = false; return false; } - nhNs.getParam("initial_tracking_pose", initialTrackPose); + mNhNs.getParam("initial_tracking_pose", mInitialTrackPose); - if (initialTrackPose.size() != 6) { - NODELET_WARN_STREAM("Invalid Initial Pose size (" << initialTrackPose.size() + if (mInitialTrackPose.size() != 6) { + NODELET_WARN_STREAM("Invalid Initial Pose size (" << mInitialTrackPose.size() << "). Using Identity"); - initialPoseSl.setIdentity(); - odomToMapTransform.setIdentity(); - baseToOdomTransform.setIdentity(); + mInitialPoseSl.setIdentity(); + mOdom2MapTransf.setIdentity(); + mBase2OdomTransf.setIdentity(); } else { - set_pose(initialTrackPose[0], initialTrackPose[1], initialTrackPose[2], - initialTrackPose[3], initialTrackPose[4], initialTrackPose[5]); + set_pose(mInitialTrackPose[0], mInitialTrackPose[1], mInitialTrackPose[2], + mInitialTrackPose[3], mInitialTrackPose[4], mInitialTrackPose[5]); } - zed.resetTracking(initialPoseSl); + if (mZed.resetTracking(mInitialPoseSl) == sl::SUCCESS) { + return true; + } - return true; + return false; } bool ZEDWrapperNodelet::on_reset_odometry( zed_wrapper::reset_odometry::Request& req, zed_wrapper::reset_odometry::Response& res) { - initOdomWithPose = true; - + mResetOdom = true; res.reset_done = true; - return true; } void ZEDWrapperNodelet::start_tracking() { NODELET_INFO_STREAM("Starting Tracking"); + mNhNs.getParam("odometry_DB", mOdometryDb); + mNhNs.getParam("pose_smoothing", mPoseSmoothing); + mNhNs.getParam("spatial_memory", mSpatialMemory); + mNhNs.getParam("floor_alignment", mFloorAlignment); - nhNs.getParam("odometry_DB", odometryDb); - nhNs.getParam("pose_smoothing", poseSmoothing); - NODELET_INFO_STREAM("Pose Smoothing : " << poseSmoothing); - nhNs.getParam("spatial_memory", spatialMemory); - NODELET_INFO_STREAM("Spatial Memory : " << spatialMemory); - if (realCamModel == sl::MODEL_ZED_M) { - nhNs.getParam("init_odom_with_imu", initOdomWithPose); + if (mZedRealCamModel == sl::MODEL_ZED_M) { + mNhNs.getParam("init_odom_with_imu", mInitOdomWithPose); NODELET_INFO_STREAM( - "Init Odometry with first IMU data : " << initOdomWithPose); + "Init Odometry with first IMU data : " << mInitOdomWithPose); } else { - initOdomWithPose = false; + mInitOdomWithPose = false; } - if (initialTrackPose.size() != 6) { - NODELET_WARN_STREAM("Invalid Initial Pose size (" << initialTrackPose.size() + if (mInitialTrackPose.size() != 6) { + NODELET_WARN_STREAM("Invalid Initial Pose size (" << mInitialTrackPose.size() << "). Using Identity"); - initialPoseSl.setIdentity(); - odomToMapTransform.setIdentity(); - odomToMapTransform.setIdentity(); + mInitialPoseSl.setIdentity(); + mOdom2MapTransf.setIdentity(); + mBase2OdomTransf.setIdentity(); } else { - set_pose(initialTrackPose[0], initialTrackPose[1], initialTrackPose[2], - initialTrackPose[3], initialTrackPose[4], initialTrackPose[5]); + set_pose(mInitialTrackPose[0], mInitialTrackPose[1], mInitialTrackPose[2], + mInitialTrackPose[3], mInitialTrackPose[4], mInitialTrackPose[5]); } - if (odometryDb != "" && !sl_tools::file_exist(odometryDb)) { - odometryDb = ""; + if (mOdometryDb != "" && !sl_tools::file_exist(mOdometryDb)) { + mOdometryDb = ""; NODELET_WARN("odometry_DB path doesn't exist or is unreachable."); } // Tracking parameters sl::TrackingParameters trackParams; - trackParams.area_file_path = odometryDb.c_str(); - trackParams.enable_pose_smoothing = poseSmoothing; - trackParams.enable_spatial_memory = spatialMemory; - - trackParams.initial_world_transform = initialPoseSl; - - zed.enableTracking(trackParams); - trackingActivated = true; + trackParams.area_file_path = mOdometryDb.c_str(); + trackParams.enable_pose_smoothing = mPoseSmoothing; + NODELET_INFO_STREAM("Pose Smoothing : " << trackParams.enable_pose_smoothing); + trackParams.enable_spatial_memory = mSpatialMemory; + NODELET_INFO_STREAM("Spatial Memory : " << trackParams.enable_spatial_memory); + trackParams.initial_world_transform = mInitialPoseSl; + trackParams.set_floor_as_origin = mFloorAlignment; + NODELET_INFO_STREAM("Floor Alignment : " << trackParams.set_floor_as_origin); + mZed.enableTracking(trackParams); + mTrackingActivated = true; + NODELET_INFO("Tracking ENABLED"); } - void ZEDWrapperNodelet::publishOdom(tf2::Transform odom_base_transform, - ros::Time t) { + void ZEDWrapperNodelet::publishOdom(tf2::Transform base2odomTransf, ros::Time t) { nav_msgs::Odometry odom; odom.header.stamp = t; - odom.header.frame_id = odometryFrameId; // odom_frame - odom.child_frame_id = baseFrameId; // base_frame + odom.header.frame_id = mOdometryFrameId; // odom_frame + odom.child_frame_id = mBaseFrameId; // camera_frame // conversion from Tranform to message - geometry_msgs::Transform base2 = tf2::toMsg(odom_base_transform); + geometry_msgs::Transform base2odom = tf2::toMsg(base2odomTransf); // Add all value in odometry message - odom.pose.pose.position.x = base2.translation.x; - odom.pose.pose.position.y = base2.translation.y; - odom.pose.pose.position.z = base2.translation.z; - odom.pose.pose.orientation.x = base2.rotation.x; - odom.pose.pose.orientation.y = base2.rotation.y; - odom.pose.pose.orientation.z = base2.rotation.z; - odom.pose.pose.orientation.w = base2.rotation.w; + odom.pose.pose.position.x = base2odom.translation.x; + odom.pose.pose.position.y = base2odom.translation.y; + odom.pose.pose.position.z = base2odom.translation.z; + odom.pose.pose.orientation.x = base2odom.rotation.x; + odom.pose.pose.orientation.y = base2odom.rotation.y; + odom.pose.pose.orientation.z = base2odom.rotation.z; + odom.pose.pose.orientation.w = base2odom.rotation.w; // Publish odometry message - pubOdom.publish(odom); + mPubOdom.publish(odom); } + + void ZEDWrapperNodelet::publishPose(ros::Time t) { + tf2::Transform base_pose; + base_pose.setIdentity(); - void ZEDWrapperNodelet::publishOdomFrame(tf2::Transform baseTransform, - ros::Time t) { - geometry_msgs::TransformStamped transformStamped; - transformStamped.header.stamp = t; - transformStamped.header.frame_id = odometryFrameId; - transformStamped.child_frame_id = baseFrameId; - // conversion from Tranform to message - transformStamped.transform = tf2::toMsg(baseTransform); - // Publish transformation - transformOdomBroadcaster.sendTransform(transformStamped); - } + if (mPublishMapTf) { + // Look up the transformation from base frame to map + try { + // Save the transformation from base to frame + geometry_msgs::TransformStamped b2m = + mTfBuffer->lookupTransform(mMapFrameId, mBaseFrameId, ros::Time(0)); + // Get the TF2 transformation + tf2::fromMsg(b2m.transform, base_pose); + } catch (tf2::TransformException& ex) { + NODELET_WARN_THROTTLE( + 10.0, "The tf from '%s' to '%s' does not seem to be available, " + "will assume it as identity!", + mBaseFrameId.c_str(), mMapFrameId.c_str()); + NODELET_DEBUG("Transform error: %s", ex.what()); + } + } else { + // Look up the transformation from base frame to odom frame + try { + // Save the transformation from base to frame + geometry_msgs::TransformStamped b2o = + mTfBuffer->lookupTransform(mOdometryFrameId, mBaseFrameId, ros::Time(0)); + // Get the TF2 transformation + tf2::fromMsg(b2o.transform, base_pose); + } catch (tf2::TransformException& ex) { + NODELET_WARN_THROTTLE( + 10.0, "The tf from '%s' to '%s' does not seem to be available, " + "will assume it as identity!", + mBaseFrameId.c_str(), mOdometryFrameId.c_str()); + NODELET_DEBUG("Transform error: %s", ex.what()); + } + } - void ZEDWrapperNodelet::publishPose(tf2::Transform poseBaseTransform, - ros::Time t) { geometry_msgs::PoseStamped pose; - pose.header.stamp = t; - pose.header.frame_id = mapFrameId; // map_frame + + pose.header.stamp = mLastFrameTime; + pose.header.frame_id = mPublishMapTf ? mMapFrameId : mOdometryFrameId; // frame // conversion from Tranform to message - geometry_msgs::Transform base2 = tf2::toMsg(poseBaseTransform); + geometry_msgs::Transform base2frame = tf2::toMsg(base_pose); // Add all value in Pose message - pose.pose.position.x = base2.translation.x; - pose.pose.position.y = base2.translation.y; - pose.pose.position.z = base2.translation.z; - pose.pose.orientation.x = base2.rotation.x; - pose.pose.orientation.y = base2.rotation.y; - pose.pose.orientation.z = base2.rotation.z; - pose.pose.orientation.w = base2.rotation.w; - // Publish odometry message - pubPose.publish(pose); + pose.pose.position.x = base2frame.translation.x; + pose.pose.position.y = base2frame.translation.y; + pose.pose.position.z = base2frame.translation.z; + pose.pose.orientation.x = base2frame.rotation.x; + pose.pose.orientation.y = base2frame.rotation.y; + pose.pose.orientation.z = base2frame.rotation.z; + pose.pose.orientation.w = base2frame.rotation.w; + + // Publish pose stamped message + mPubPose.publish(pose); + } + + void ZEDWrapperNodelet::publishOdomFrame(tf2::Transform odomTransf, ros::Time t) { + geometry_msgs::TransformStamped transformStamped; + transformStamped.header.stamp = t; + transformStamped.header.frame_id = mOdometryFrameId; + transformStamped.child_frame_id = mBaseFrameId; + // conversion from Tranform to message + transformStamped.transform = tf2::toMsg(odomTransf); + // Publish transformation + mTransformOdomBroadcaster.sendTransform(transformStamped); } - void ZEDWrapperNodelet::publishPoseFrame(tf2::Transform baseTransform, - ros::Time t) { + void ZEDWrapperNodelet::publishPoseFrame(tf2::Transform baseTransform, ros::Time t) { geometry_msgs::TransformStamped transformStamped; transformStamped.header.stamp = t; - transformStamped.header.frame_id = mapFrameId; - transformStamped.child_frame_id = odometryFrameId; + transformStamped.header.frame_id = mMapFrameId; + transformStamped.child_frame_id = mOdometryFrameId; // conversion from Tranform to message transformStamped.transform = tf2::toMsg(baseTransform); // Publish transformation - transformPoseBroadcaster.sendTransform(transformStamped); + mTransformPoseBroadcaster.sendTransform(transformStamped); } - void ZEDWrapperNodelet::publishImuFrame(tf2::Transform baseTransform) { + void ZEDWrapperNodelet::publishImuFrame(tf2::Transform imuTransform, ros::Time t) { geometry_msgs::TransformStamped transformStamped; - transformStamped.header.stamp = imuTime; - transformStamped.header.frame_id = baseFrameId; - transformStamped.child_frame_id = imuFrameId; + transformStamped.header.stamp = t; + transformStamped.header.frame_id = mCameraFrameId; + transformStamped.child_frame_id = mImuFrameId; // conversion from Tranform to message - transformStamped.transform = tf2::toMsg(baseTransform); + transformStamped.transform = tf2::toMsg(imuTransform); // Publish transformation - transformImuBroadcaster.sendTransform(transformStamped); + mTransformImuBroadcaster.sendTransform(transformStamped); } void ZEDWrapperNodelet::publishImage(cv::Mat img, image_transport::Publisher& pubImg, string imgFrameId, ros::Time t) { pubImg.publish( - imageToROSmsg(img, sensor_msgs::image_encodings::BGR8, imgFrameId, t)); + sl_tools::imageToROSmsg(img, sensor_msgs::image_encodings::BGR8, imgFrameId, t)); } void ZEDWrapperNodelet::publishDepth(cv::Mat depth, ros::Time t) { string encoding; - if (openniDepthMode) { + + if (mOpenniDepthMode) { depth *= 1000.0f; depth.convertTo(depth, CV_16UC1); // in mm, rounded encoding = sensor_msgs::image_encodings::TYPE_16UC1; @@ -880,26 +874,25 @@ namespace zed_wrapper { encoding = sensor_msgs::image_encodings::TYPE_32FC1; } - pubDepth.publish(imageToROSmsg(depth, encoding, depthOptFrameId, t)); + mPubDepth.publish(sl_tools::imageToROSmsg(depth, encoding, mDepthOptFrameId, t)); } void ZEDWrapperNodelet::publishDisparity(cv::Mat disparity, ros::Time t) { sl::CameraInformation zedParam = - zed.getCameraInformation(sl::Resolution(matWidth, matHeight)); - sensor_msgs::ImagePtr disparity_image = imageToROSmsg( - disparity, sensor_msgs::image_encodings::TYPE_32FC1, disparityFrameId, t); - + mZed.getCameraInformation(sl::Resolution(mMatWidth, mMatHeight)); + sensor_msgs::ImagePtr disparity_image = sl_tools::imageToROSmsg( + disparity, sensor_msgs::image_encodings::TYPE_32FC1, mDisparityFrameId, t); stereo_msgs::DisparityImage msg; msg.image = *disparity_image; msg.header = msg.image.header; msg.f = zedParam.calibration_parameters.left_cam.fx; msg.T = zedParam.calibration_parameters.T.x; - msg.min_disparity = msg.f * msg.T / zed.getDepthMaxRangeValue(); - msg.max_disparity = msg.f * msg.T / zed.getDepthMinRangeValue(); - pubDisparity.publish(msg); + msg.min_disparity = msg.f * msg.T / mZed.getDepthMaxRangeValue(); + msg.max_disparity = msg.f * msg.T / mZed.getDepthMinRangeValue(); + mPubDisparity.publish(msg); } - void ZEDWrapperNodelet::pointcloud_thread() { + void ZEDWrapperNodelet::pointcloud_thread_func() { std::unique_lock lock(mPcMutex); while (!mStopNode) { while (!mPcDataReady) { // loop to avoid spurious wakeups @@ -923,17 +916,17 @@ namespace zed_wrapper { void ZEDWrapperNodelet::publishPointCloud() { // Initialize Point Cloud message // https://github.com/ros/common_msgs/blob/jade-devel/sensor_msgs/include/sensor_msgs/point_cloud2_iterator.h - int ptsCount = matWidth * matHeight; - mPointcloudMsg.header.stamp = pointCloudTime; - if (mPointcloudMsg.width != matWidth || mPointcloudMsg.height != matHeight) { - mPointcloudMsg.header.frame_id = pointCloudFrameId; // Set the header values of the ROS message + int ptsCount = mMatWidth * mMatHeight; + mPointcloudMsg.header.stamp = mPointCloudTime; + if (mPointcloudMsg.width != mMatWidth || mPointcloudMsg.height != mMatHeight) { + mPointcloudMsg.header.frame_id = mPointCloudFrameId; // Set the header values of the ROS message mPointcloudMsg.is_bigendian = false; mPointcloudMsg.is_dense = false; - mPointcloudMsg.width = matWidth; - mPointcloudMsg.height = matHeight; + mPointcloudMsg.width = mMatWidth; + mPointcloudMsg.height = mMatHeight; sensor_msgs::PointCloud2Modifier modifier(mPointcloudMsg); modifier.setPointCloud2Fields(4, @@ -943,21 +936,21 @@ namespace zed_wrapper { "rgb", 1, sensor_msgs::PointField::FLOAT32); } - sl::Vector4* cpu_cloud = cloud.getPtr(); + sl::Vector4* cpu_cloud = mCloud.getPtr(); // Data copy float* ptCloudPtr = (float*)(&mPointcloudMsg.data[0]); #pragma omp parallel for for (size_t i = 0; i < ptsCount; ++i) { - ptCloudPtr[i * 4 + 0] = xSign * cpu_cloud[i][xIdx]; - ptCloudPtr[i * 4 + 1] = ySign * cpu_cloud[i][yIdx]; - ptCloudPtr[i * 4 + 2] = zSign * cpu_cloud[i][zIdx]; + ptCloudPtr[i * 4 + 0] = mSignX * cpu_cloud[i][mIdxX]; + ptCloudPtr[i * 4 + 1] = mSignY * cpu_cloud[i][mIdxY]; + ptCloudPtr[i * 4 + 2] = mSignZ * cpu_cloud[i][mIdxZ]; ptCloudPtr[i * 4 + 3] = cpu_cloud[i][3]; } // Pointcloud publishing - pubCloud.publish(mPointcloudMsg); + mPubCloud.publish(mPointcloudMsg); } void ZEDWrapperNodelet::publishCamInfo(sensor_msgs::CameraInfoPtr camInfoMsg, @@ -969,447 +962,560 @@ namespace zed_wrapper { seq++; } - void ZEDWrapperNodelet::fillCamInfo( - sl::Camera& zed, sensor_msgs::CameraInfoPtr left_cam_info_msg, - sensor_msgs::CameraInfoPtr right_cam_info_msg, string leftFrameId, - string rightFrameId, bool rawParam /*= false*/) { + void ZEDWrapperNodelet::fillCamInfo(sl::Camera& zed, sensor_msgs::CameraInfoPtr leftCamInfoMsg, + sensor_msgs::CameraInfoPtr rightCamInfoMsg, string leftFrameId, + string rightFrameId, bool rawParam /*= false*/) { sl::CalibrationParameters zedParam; - if (rawParam) - zedParam = zed.getCameraInformation(sl::Resolution(matWidth, matHeight)) + if (rawParam) { + zedParam = zed.getCameraInformation(sl::Resolution(mMatWidth, mMatHeight)) .calibration_parameters_raw; - else - zedParam = zed.getCameraInformation(sl::Resolution(matWidth, matHeight)) + } else { + zedParam = zed.getCameraInformation(sl::Resolution(mMatWidth, mMatHeight)) .calibration_parameters; + } float baseline = zedParam.T[0]; - - left_cam_info_msg->distortion_model = + leftCamInfoMsg->distortion_model = sensor_msgs::distortion_models::PLUMB_BOB; - right_cam_info_msg->distortion_model = + rightCamInfoMsg->distortion_model = sensor_msgs::distortion_models::PLUMB_BOB; - - left_cam_info_msg->D.resize(5); - right_cam_info_msg->D.resize(5); - left_cam_info_msg->D[0] = zedParam.left_cam.disto[0]; // k1 - left_cam_info_msg->D[1] = zedParam.left_cam.disto[1]; // k2 - left_cam_info_msg->D[2] = zedParam.left_cam.disto[4]; // k3 - left_cam_info_msg->D[3] = zedParam.left_cam.disto[2]; // p1 - left_cam_info_msg->D[4] = zedParam.left_cam.disto[3]; // p2 - right_cam_info_msg->D[0] = zedParam.right_cam.disto[0]; // k1 - right_cam_info_msg->D[1] = zedParam.right_cam.disto[1]; // k2 - right_cam_info_msg->D[2] = zedParam.right_cam.disto[4]; // k3 - right_cam_info_msg->D[3] = zedParam.right_cam.disto[2]; // p1 - right_cam_info_msg->D[4] = zedParam.right_cam.disto[3]; // p2 - - left_cam_info_msg->K.fill(0.0); - right_cam_info_msg->K.fill(0.0); - left_cam_info_msg->K[0] = zedParam.left_cam.fx; - left_cam_info_msg->K[2] = zedParam.left_cam.cx; - left_cam_info_msg->K[4] = zedParam.left_cam.fy; - left_cam_info_msg->K[5] = zedParam.left_cam.cy; - left_cam_info_msg->K[8] = 1.0; - right_cam_info_msg->K[0] = zedParam.right_cam.fx; - right_cam_info_msg->K[2] = zedParam.right_cam.cx; - right_cam_info_msg->K[4] = zedParam.right_cam.fy; - right_cam_info_msg->K[5] = zedParam.right_cam.cy; - right_cam_info_msg->K[8] = 1.0; - - left_cam_info_msg->R.fill(0.0); - right_cam_info_msg->R.fill(0.0); - for (int i = 0; i < 3; i++) { + leftCamInfoMsg->D.resize(5); + rightCamInfoMsg->D.resize(5); + leftCamInfoMsg->D[0] = zedParam.left_cam.disto[0]; // k1 + leftCamInfoMsg->D[1] = zedParam.left_cam.disto[1]; // k2 + leftCamInfoMsg->D[2] = zedParam.left_cam.disto[4]; // k3 + leftCamInfoMsg->D[3] = zedParam.left_cam.disto[2]; // p1 + leftCamInfoMsg->D[4] = zedParam.left_cam.disto[3]; // p2 + rightCamInfoMsg->D[0] = zedParam.right_cam.disto[0]; // k1 + rightCamInfoMsg->D[1] = zedParam.right_cam.disto[1]; // k2 + rightCamInfoMsg->D[2] = zedParam.right_cam.disto[4]; // k3 + rightCamInfoMsg->D[3] = zedParam.right_cam.disto[2]; // p1 + rightCamInfoMsg->D[4] = zedParam.right_cam.disto[3]; // p2 + leftCamInfoMsg->K.fill(0.0); + rightCamInfoMsg->K.fill(0.0); + leftCamInfoMsg->K[0] = static_cast(zedParam.left_cam.fx); + leftCamInfoMsg->K[2] = static_cast(zedParam.left_cam.cx); + leftCamInfoMsg->K[4] = static_cast(zedParam.left_cam.fy); + leftCamInfoMsg->K[5] = static_cast(zedParam.left_cam.cy); + leftCamInfoMsg->K[8] = 1.0; + rightCamInfoMsg->K[0] = static_cast(zedParam.right_cam.fx); + rightCamInfoMsg->K[2] = static_cast(zedParam.right_cam.cx); + rightCamInfoMsg->K[4] = static_cast(zedParam.right_cam.fy); + rightCamInfoMsg->K[5] = static_cast(zedParam.right_cam.cy); + rightCamInfoMsg->K[8] = 1.0; + leftCamInfoMsg->R.fill(0.0); + rightCamInfoMsg->R.fill(0.0); + + for (size_t i = 0; i < 3; i++) { // identity - right_cam_info_msg->R[i + i * 3] = 1; - left_cam_info_msg->R[i + i * 3] = 1; + rightCamInfoMsg->R[i + i * 3] = 1; + leftCamInfoMsg->R[i + i * 3] = 1; } if (rawParam) { cv::Mat R_ = sl_tools::convertRodrigues(zedParam.R); - float* p = (float*)R_.data; - for (int i = 0; i < 9; i++) { - right_cam_info_msg->R[i] = p[i]; + float* p = (float*)(R_.data); + + for (size_t i = 0; i < 9; i++) { + rightCamInfoMsg->R[i] = static_cast(p[i]); } } - left_cam_info_msg->P.fill(0.0); - right_cam_info_msg->P.fill(0.0); - left_cam_info_msg->P[0] = zedParam.left_cam.fx; - left_cam_info_msg->P[2] = zedParam.left_cam.cx; - left_cam_info_msg->P[5] = zedParam.left_cam.fy; - left_cam_info_msg->P[6] = zedParam.left_cam.cy; - left_cam_info_msg->P[10] = 1.0; + leftCamInfoMsg->P.fill(0.0); + rightCamInfoMsg->P.fill(0.0); + leftCamInfoMsg->P[0] = static_cast(zedParam.left_cam.fx); + leftCamInfoMsg->P[2] = static_cast(zedParam.left_cam.cx); + leftCamInfoMsg->P[5] = static_cast(zedParam.left_cam.fy); + leftCamInfoMsg->P[6] = static_cast(zedParam.left_cam.cy); + leftCamInfoMsg->P[10] = 1.0; // http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html - right_cam_info_msg->P[3] = (-1 * zedParam.left_cam.fx * baseline); - - right_cam_info_msg->P[0] = zedParam.right_cam.fx; - right_cam_info_msg->P[2] = zedParam.right_cam.cx; - right_cam_info_msg->P[5] = zedParam.right_cam.fy; - right_cam_info_msg->P[6] = zedParam.right_cam.cy; - right_cam_info_msg->P[10] = 1.0; - - left_cam_info_msg->width = right_cam_info_msg->width = matWidth; - left_cam_info_msg->height = right_cam_info_msg->height = matHeight; - - left_cam_info_msg->header.frame_id = leftFrameId; - right_cam_info_msg->header.frame_id = rightFrameId; + rightCamInfoMsg->P[3] = static_cast(-1 * zedParam.left_cam.fx * baseline); + rightCamInfoMsg->P[0] = static_cast(zedParam.right_cam.fx); + rightCamInfoMsg->P[2] = static_cast(zedParam.right_cam.cx); + rightCamInfoMsg->P[5] = static_cast(zedParam.right_cam.fy); + rightCamInfoMsg->P[6] = static_cast(zedParam.right_cam.cy); + rightCamInfoMsg->P[10] = 1.0; + leftCamInfoMsg->width = rightCamInfoMsg->width = static_cast(mMatWidth); + leftCamInfoMsg->height = rightCamInfoMsg->height = static_cast(mMatHeight); + leftCamInfoMsg->header.frame_id = leftFrameId; + rightCamInfoMsg->header.frame_id = rightFrameId; } void ZEDWrapperNodelet::dynamicReconfCallback(zed_wrapper::ZedConfig& config, uint32_t level) { switch (level) { case 0: - confidence = config.confidence; - NODELET_INFO("Reconfigure confidence : %d", confidence); + mCamConfidence = config.confidence; + NODELET_INFO("Reconfigure confidence : %d", mCamConfidence); break; + case 1: - exposure = config.exposure; - NODELET_INFO("Reconfigure exposure : %d", exposure); + mCamExposure = config.exposure; + NODELET_INFO("Reconfigure exposure : %d", mCamExposure); break; + case 2: - gain = config.gain; - NODELET_INFO("Reconfigure gain : %d", gain); + mCamGain = config.gain; + NODELET_INFO("Reconfigure gain : %d", mCamGain); break; + case 3: - autoExposure = config.auto_exposure; - if (autoExposure) { - triggerAutoExposure = true; + mCamAutoExposure = config.auto_exposure; + + if (mCamAutoExposure) { + mTriggerAutoExposure = true; } + NODELET_INFO("Reconfigure auto control of exposure and gain : %s", - autoExposure ? "Enable" : "Disable"); + mCamAutoExposure ? "Enable" : "Disable"); break; - case 4: - matResizeFactor = config.mat_resize_factor; - NODELET_INFO("Reconfigure mat_resize_factor: %g", matResizeFactor); - - dataMutex.lock(); - - matWidth = static_cast(camWidth * matResizeFactor); - matHeight = static_cast(camHeight * matResizeFactor); - NODELET_DEBUG_STREAM("Data Mat size : " << matWidth << "x" << matHeight); + case 4: + mCamMatResizeFactor = config.mat_resize_factor; + NODELET_INFO("Reconfigure mat_resize_factor: %g", mCamMatResizeFactor); + mCamDataMutex.lock(); + mMatWidth = static_cast(mCamWidth * mCamMatResizeFactor); + mMatHeight = static_cast(mCamHeight * mCamMatResizeFactor); + NODELET_DEBUG_STREAM("Data Mat size : " << mMatWidth << "x" << mMatHeight); // Update Camera Info - fillCamInfo(zed, leftCamInfoMsg, rightCamInfoMsg, leftCamOptFrameId, - rightCamOptFrameId); - fillCamInfo(zed, leftCamInfoRawMsg, rightCamInfoRawMsg, leftCamOptFrameId, - rightCamOptFrameId, true); - rgbCamInfoMsg = depthCamInfoMsg = leftCamInfoMsg; // the reference camera is + fillCamInfo(mZed, mLeftCamInfoMsg, mRightCamInfoMsg, mLeftCamOptFrameId, + mRightCamOptFrameId); + fillCamInfo(mZed, mLeftCamInfoRawMsg, mRightCamInfoRawMsg, mLeftCamOptFrameId, + mRightCamOptFrameId, true); + mRgbCamInfoMsg = mDepthCamInfoMsg = mLeftCamInfoMsg; // the reference camera is // the Left one (next to // the ZED logo) - rgbCamInfoRawMsg = leftCamInfoRawMsg; - - dataMutex.unlock(); + mRgbCamInfoRawMsg = mLeftCamInfoRawMsg; + mCamDataMutex.unlock(); + break; + case 5: + mCamMaxDepth = config.max_depth; + NODELET_INFO("Reconfigure max depth : %g", mCamMaxDepth); break; } } + void ZEDWrapperNodelet::pathPubCallback(const ros::TimerEvent& e) { + uint32_t mapPathSub = mPubMapPath.getNumSubscribers(); + uint32_t odomPathSub = mPubOdomPath.getNumSubscribers(); + + tf2::Transform base_to_odom; + base_to_odom.setIdentity(); + tf2::Transform base_to_map; + base_to_map.setIdentity(); + + // Look up the transformation from base frame to odom + try { + // Save the transformation from base to frame + geometry_msgs::TransformStamped b2o = + mTfBuffer->lookupTransform(mOdometryFrameId, mBaseFrameId, ros::Time(0)); + // Get the TF2 transformation + tf2::fromMsg(b2o.transform, base_to_odom); + } catch (tf2::TransformException& ex) { + NODELET_WARN_THROTTLE( + 10.0, "The tf from '%s' to '%s' does not seem to be available, " + "will assume it as identity!", + mBaseFrameId.c_str(), mOdometryFrameId.c_str()); + NODELET_DEBUG("Transform error: %s", ex.what()); + + } + + if (mPublishMapTf) { + // Look up the transformation from base frame to map + try { + // Save the transformation from base to frame + geometry_msgs::TransformStamped b2m = + mTfBuffer->lookupTransform(mMapFrameId, mBaseFrameId, ros::Time(0)); + // Get the TF2 transformation + tf2::fromMsg(b2m.transform, base_to_map); + } catch (tf2::TransformException& ex) { + NODELET_WARN_THROTTLE( + 10.0, "The tf from '%s' to '%s' does not seem to be available, " + "will assume it as identity!", + mBaseFrameId.c_str(), mOdometryFrameId.c_str()); + NODELET_DEBUG("Transform error: %s", ex.what()); + } + } + + + geometry_msgs::PoseStamped odomPose; + geometry_msgs::PoseStamped mapPose; + + odomPose.header.stamp = mLastFrameTime; + odomPose.header.frame_id = mOdometryFrameId; // odom_frame + // conversion from Tranform to message + geometry_msgs::Transform base2odom = tf2::toMsg(base_to_odom); + // Add all value in Pose message + odomPose.pose.position.x = base2odom.translation.x; + odomPose.pose.position.y = base2odom.translation.y; + odomPose.pose.position.z = base2odom.translation.z; + odomPose.pose.orientation.x = base2odom.rotation.x; + odomPose.pose.orientation.y = base2odom.rotation.y; + odomPose.pose.orientation.z = base2odom.rotation.z; + odomPose.pose.orientation.w = base2odom.rotation.w; + + if (mPublishMapTf) { + mapPose.header.stamp = mLastFrameTime; + mapPose.header.frame_id = mMapFrameId; // map_frame + // conversion from Tranform to message + geometry_msgs::Transform base2map = tf2::toMsg(base_to_map); + // Add all value in Pose message + mapPose.pose.position.x = base2map.translation.x; + mapPose.pose.position.y = base2map.translation.y; + mapPose.pose.position.z = base2map.translation.z; + mapPose.pose.orientation.x = base2map.rotation.x; + mapPose.pose.orientation.y = base2map.rotation.y; + mapPose.pose.orientation.z = base2map.rotation.z; + mapPose.pose.orientation.w = base2map.rotation.w; + } + + // Circular vector + if (mPathMaxCount != -1) { + if (mOdomPath.size() == mPathMaxCount) { + NODELET_DEBUG("Path vectors full: rotating "); + std::rotate(mOdomPath.begin(), mOdomPath.begin() + 1, mOdomPath.end()); + std::rotate(mMapPath.begin(), mMapPath.begin() + 1, mMapPath.end()); + + mMapPath[mPathMaxCount - 1] = mapPose; + mOdomPath[mPathMaxCount - 1] = odomPose; + } else { + //NODELET_DEBUG_STREAM("Path vectors adding last available poses"); + mMapPath.push_back(mapPose); + mOdomPath.push_back(odomPose); + } + } else { + //NODELET_DEBUG_STREAM("No limit path vectors, adding last available poses"); + mMapPath.push_back(mapPose); + mOdomPath.push_back(odomPose); + } + + if (mapPathSub > 0 && mPublishMapTf) { + nav_msgs::Path mapPath; + mapPath.header.frame_id = mMapFrameId; + mapPath.header.stamp = mLastFrameTime; + mapPath.poses = mMapPath; + + mPubMapPath.publish(mapPath); + } + + if (odomPathSub > 0) { + nav_msgs::Path odomPath; + odomPath.header.frame_id = mPublishMapTf ? mMapFrameId : mOdometryFrameId; + odomPath.header.stamp = mLastFrameTime; + odomPath.poses = mOdomPath; + + mPubOdomPath.publish(odomPath); + } + + } + void ZEDWrapperNodelet::imuPubCallback(const ros::TimerEvent& e) { - int imu_SubNumber = pubImu.getNumSubscribers(); - int imu_RawSubNumber = pubImuRaw.getNumSubscribers(); + uint32_t imu_SubNumber = mPubImu.getNumSubscribers(); + uint32_t imu_RawSubNumber = mPubImuRaw.getNumSubscribers(); if (imu_SubNumber < 1 && imu_RawSubNumber < 1) { return; } - // ros::Time t = - // sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_IMAGE)); - ros::Time t; if (mSvoMode) { t = ros::Time::now(); } else { - t = sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_IMAGE)); + t = sl_tools::slTime2Ros(mZed.getTimestamp(sl::TIME_REFERENCE_IMAGE)); } sl::IMUData imu_data; - zed.getIMUData(imu_data, sl::TIME_REFERENCE_CURRENT); + mZed.getIMUData(imu_data, sl::TIME_REFERENCE_CURRENT); if (imu_SubNumber > 0) { sensor_msgs::Imu imu_msg; - imu_msg.header.stamp = imuTime; // t; - imu_msg.header.frame_id = imuFrameId; - - imu_msg.orientation.x = xSign * imu_data.getOrientation()[xIdx]; - imu_msg.orientation.y = ySign * imu_data.getOrientation()[yIdx]; - imu_msg.orientation.z = zSign * imu_data.getOrientation()[zIdx]; + imu_msg.header.stamp = mLastFrameTime; // t; + imu_msg.header.frame_id = mImuFrameId; + imu_msg.orientation.x = mSignX * imu_data.getOrientation()[mIdxX]; + imu_msg.orientation.y = mSignY * imu_data.getOrientation()[mIdxY]; + imu_msg.orientation.z = mSignZ * imu_data.getOrientation()[mIdxZ]; imu_msg.orientation.w = imu_data.getOrientation()[3]; - - imu_msg.angular_velocity.x = xSign * imu_data.angular_velocity[xIdx]; - imu_msg.angular_velocity.y = ySign * imu_data.angular_velocity[yIdx]; - imu_msg.angular_velocity.z = zSign * imu_data.angular_velocity[zIdx]; - - imu_msg.linear_acceleration.x = xSign * imu_data.linear_acceleration[xIdx]; - imu_msg.linear_acceleration.y = ySign * imu_data.linear_acceleration[yIdx]; - imu_msg.linear_acceleration.z = zSign * imu_data.linear_acceleration[zIdx]; + imu_msg.angular_velocity.x = mSignX * imu_data.angular_velocity[mIdxX]; + imu_msg.angular_velocity.y = mSignY * imu_data.angular_velocity[mIdxY]; + imu_msg.angular_velocity.z = mSignZ * imu_data.angular_velocity[mIdxZ]; + imu_msg.linear_acceleration.x = mSignX * imu_data.linear_acceleration[mIdxX]; + imu_msg.linear_acceleration.y = mSignY * imu_data.linear_acceleration[mIdxY]; + imu_msg.linear_acceleration.z = mSignZ * imu_data.linear_acceleration[mIdxZ]; for (int i = 0; i < 3; i += 3) { imu_msg.orientation_covariance[i * 3 + 0] = - imu_data.orientation_covariance.r[i * 3 + xIdx]; + imu_data.orientation_covariance.r[i * 3 + mIdxX]; imu_msg.orientation_covariance[i * 3 + 1] = - imu_data.orientation_covariance.r[i * 3 + yIdx]; + imu_data.orientation_covariance.r[i * 3 + mIdxY]; imu_msg.orientation_covariance[i * 3 + 2] = - imu_data.orientation_covariance.r[i * 3 + zIdx]; - + imu_data.orientation_covariance.r[i * 3 + mIdxZ]; imu_msg.linear_acceleration_covariance[i * 3 + 0] = - imu_data.linear_acceleration_convariance.r[i * 3 + xIdx]; + imu_data.linear_acceleration_convariance.r[i * 3 + mIdxX]; imu_msg.linear_acceleration_covariance[i * 3 + 1] = - imu_data.linear_acceleration_convariance.r[i * 3 + yIdx]; + imu_data.linear_acceleration_convariance.r[i * 3 + mIdxY]; imu_msg.linear_acceleration_covariance[i * 3 + 2] = - imu_data.linear_acceleration_convariance.r[i * 3 + zIdx]; - + imu_data.linear_acceleration_convariance.r[i * 3 + mIdxZ]; imu_msg.angular_velocity_covariance[i * 3 + 0] = - imu_data.angular_velocity_convariance.r[i * 3 + xIdx]; + imu_data.angular_velocity_convariance.r[i * 3 + mIdxX]; imu_msg.angular_velocity_covariance[i * 3 + 1] = - imu_data.angular_velocity_convariance.r[i * 3 + yIdx]; + imu_data.angular_velocity_convariance.r[i * 3 + mIdxY]; imu_msg.angular_velocity_covariance[i * 3 + 2] = - imu_data.angular_velocity_convariance.r[i * 3 + zIdx]; + imu_data.angular_velocity_convariance.r[i * 3 + mIdxZ]; } - pubImu.publish(imu_msg); + mPubImu.publish(imu_msg); } if (imu_RawSubNumber > 0) { sensor_msgs::Imu imu_raw_msg; - imu_raw_msg.header.stamp = imuTime; // t; - imu_raw_msg.header.frame_id = imuFrameId; - - imu_raw_msg.angular_velocity.x = xSign * imu_data.angular_velocity[xIdx]; - imu_raw_msg.angular_velocity.y = ySign * imu_data.angular_velocity[yIdx]; - imu_raw_msg.angular_velocity.z = zSign * imu_data.angular_velocity[zIdx]; - + imu_raw_msg.header.stamp = mLastFrameTime; // t; + imu_raw_msg.header.frame_id = mImuFrameId; + imu_raw_msg.angular_velocity.x = mSignX * imu_data.angular_velocity[mIdxX]; + imu_raw_msg.angular_velocity.y = mSignY * imu_data.angular_velocity[mIdxY]; + imu_raw_msg.angular_velocity.z = mSignZ * imu_data.angular_velocity[mIdxZ]; imu_raw_msg.linear_acceleration.x = - xSign * imu_data.linear_acceleration[xIdx]; + mSignX * imu_data.linear_acceleration[mIdxX]; imu_raw_msg.linear_acceleration.y = - ySign * imu_data.linear_acceleration[yIdx]; + mSignY * imu_data.linear_acceleration[mIdxY]; imu_raw_msg.linear_acceleration.z = - zSign * imu_data.linear_acceleration[zIdx]; + mSignZ * imu_data.linear_acceleration[mIdxZ]; for (int i = 0; i < 3; i += 3) { imu_raw_msg.linear_acceleration_covariance[i * 3 + 0] = - imu_data.linear_acceleration_convariance.r[i * 3 + xIdx]; + imu_data.linear_acceleration_convariance.r[i * 3 + mIdxX]; imu_raw_msg.linear_acceleration_covariance[i * 3 + 1] = - imu_data.linear_acceleration_convariance.r[i * 3 + yIdx]; + imu_data.linear_acceleration_convariance.r[i * 3 + mIdxY]; imu_raw_msg.linear_acceleration_covariance[i * 3 + 2] = - imu_data.linear_acceleration_convariance.r[i * 3 + zIdx]; - + imu_data.linear_acceleration_convariance.r[i * 3 + mIdxZ]; imu_raw_msg.angular_velocity_covariance[i * 3 + 0] = - imu_data.angular_velocity_convariance.r[i * 3 + xIdx]; + imu_data.angular_velocity_convariance.r[i * 3 + mIdxX]; imu_raw_msg.angular_velocity_covariance[i * 3 + 1] = - imu_data.angular_velocity_convariance.r[i * 3 + yIdx]; + imu_data.angular_velocity_convariance.r[i * 3 + mIdxY]; imu_raw_msg.angular_velocity_covariance[i * 3 + 2] = - imu_data.angular_velocity_convariance.r[i * 3 + zIdx]; + imu_data.angular_velocity_convariance.r[i * 3 + mIdxZ]; } imu_raw_msg.orientation_covariance[0] = -1; // Orientation data is not available in "data_raw" -> See ROS REP145 // http://www.ros.org/reps/rep-0145.html#topics - - pubImuRaw.publish(imu_raw_msg); + mPubImuRaw.publish(imu_raw_msg); } // Publish IMU tf only if enabled - if (publishTf) { - // Camera to map transform from TF buffer - tf2::Transform base_to_map; + if (mPublishTf) { + // Camera to pose transform from TF buffer + tf2::Transform cam_to_pose; + + std::string poseFrame; // Look up the transformation from base frame to map link try { + poseFrame = mPublishMapTf ? mMapFrameId : mOdometryFrameId; + // Save the transformation from base to frame - geometry_msgs::TransformStamped b2m = - tfBuffer->lookupTransform(mapFrameId, baseFrameId, ros::Time(0)); + geometry_msgs::TransformStamped c2p = + mTfBuffer->lookupTransform(poseFrame, mCameraFrameId, ros::Time(0)); // Get the TF2 transformation - tf2::fromMsg(b2m.transform, base_to_map); + tf2::fromMsg(c2p.transform, cam_to_pose); } catch (tf2::TransformException& ex) { NODELET_WARN_THROTTLE( 10.0, "The tf from '%s' to '%s' does not seem to be available. " "IMU TF not published!", - baseFrameId.c_str(), mapFrameId.c_str()); + mCameraFrameId.c_str(), mMapFrameId.c_str()); NODELET_DEBUG_THROTTLE(1.0, "Transform error: %s", ex.what()); return; } // IMU Quaternion in Map frame tf2::Quaternion imu_q; - imu_q.setX(xSign * imu_data.getOrientation()[xIdx]); - imu_q.setY(ySign * imu_data.getOrientation()[yIdx]); - imu_q.setZ(zSign * imu_data.getOrientation()[zIdx]); + imu_q.setX(mSignX * imu_data.getOrientation()[mIdxX]); + imu_q.setY(mSignY * imu_data.getOrientation()[mIdxY]); + imu_q.setZ(mSignZ * imu_data.getOrientation()[mIdxZ]); imu_q.setW(imu_data.getOrientation()[3]); - // Pose Quaternion from ZED Camera - tf2::Quaternion map_q = base_to_map.getRotation(); - + tf2::Quaternion map_q = cam_to_pose.getRotation(); // Difference between IMU and ZED Quaternion tf2::Quaternion delta_q = imu_q * map_q.inverse(); - tf2::Transform imu_pose; imu_pose.setIdentity(); imu_pose.setRotation(delta_q); - // Note, the frame is published, but its values will only change if someone // has subscribed to IMU - publishImuFrame(imu_pose); // publish the imu Frame + publishImuFrame(imu_pose, mLastFrameTime); // publish the imu Frame } } - void ZEDWrapperNodelet::device_poll() { - ros::Rate loop_rate(frameRate); - - // ros::Time old_t = - // sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); - // imuTime = old_t; + void ZEDWrapperNodelet::device_poll_thread_func() { + ros::Rate loop_rate(mCamFrameRate); ros::Time t_old; if (mSvoMode) { t_old = ros::Time::now(); } else { - t_old = sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); + t_old = sl_tools::slTime2Ros(mZed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); } - ros::Time old_t = ros::Time::now(); + ros::Time old_t = t_old; + mLastFrameTime = old_t; sl::ERROR_CODE grab_status; - trackingActivated = false; - + mTrackingActivated = false; // Get the parameters of the ZED images - camWidth = zed.getResolution().width; - camHeight = zed.getResolution().height; - NODELET_DEBUG_STREAM("Camera Frame size : " << camWidth << "x" << camHeight); - - matWidth = static_cast(camWidth * matResizeFactor); - matHeight = static_cast(camHeight * matResizeFactor); - NODELET_DEBUG_STREAM("Data Mat size : " << matWidth << "x" << matHeight); - - cv::Size cvSize(matWidth, matWidth); - leftImRGB = cv::Mat(cvSize, CV_8UC3); - rightImRGB = cv::Mat(cvSize, CV_8UC3); - confImRGB = cv::Mat(cvSize, CV_8UC3); - confMapFloat = cv::Mat(cvSize, CV_32FC1); - + mCamWidth = mZed.getResolution().width; + mCamHeight = mZed.getResolution().height; + NODELET_DEBUG_STREAM("Camera Frame size : " << mCamWidth << "x" << mCamHeight); + mMatWidth = static_cast(mCamWidth * mCamMatResizeFactor); + mMatHeight = static_cast(mCamHeight * mCamMatResizeFactor); + NODELET_DEBUG_STREAM("Data Mat size : " << mMatWidth << "x" << mMatHeight); + cv::Size cvSize(mMatWidth, mMatWidth); + mCvLeftImRGB = cv::Mat(cvSize, CV_8UC3); + mCvRightImRGB = cv::Mat(cvSize, CV_8UC3); + mCvConfImRGB = cv::Mat(cvSize, CV_8UC3); + mCvConfMapFloat = cv::Mat(cvSize, CV_32FC1); // Create and fill the camera information messages - fillCamInfo(zed, leftCamInfoMsg, rightCamInfoMsg, leftCamOptFrameId, - rightCamOptFrameId); - fillCamInfo(zed, leftCamInfoRawMsg, rightCamInfoRawMsg, leftCamOptFrameId, - rightCamOptFrameId, true); - rgbCamInfoMsg = depthCamInfoMsg = leftCamInfoMsg; // the reference camera is + fillCamInfo(mZed, mLeftCamInfoMsg, mRightCamInfoMsg, mLeftCamOptFrameId, + mRightCamOptFrameId); + fillCamInfo(mZed, mLeftCamInfoRawMsg, mRightCamInfoRawMsg, mLeftCamOptFrameId, + mRightCamOptFrameId, true); + mRgbCamInfoMsg = mDepthCamInfoMsg = mLeftCamInfoMsg; // the reference camera is // the Left one (next to the // ZED logo) - rgbCamInfoRawMsg = leftCamInfoRawMsg; - + mRgbCamInfoRawMsg = mLeftCamInfoRawMsg; sl::RuntimeParameters runParams; - runParams.sensing_mode = static_cast(sensingMode); + runParams.sensing_mode = static_cast(mCamSensingMode); + sl::Mat leftZEDMat, rightZEDMat, depthZEDMat, disparityZEDMat, confImgZEDMat, confMapZEDMat; - sl::Mat leftZEDMat, rightZEDMat, depthZEDMat, disparityZEDMat, confImgZEDMat, - confMapZEDMat; // Main loop - while (nhNs.ok()) { + while (mNhNs.ok()) { // Check for subscribers - int rgb_SubNumber = pubRgb.getNumSubscribers(); - int rgb_raw_SubNumber = pubRawRgb.getNumSubscribers(); - int left_SubNumber = pubLeft.getNumSubscribers(); - int left_raw_SubNumber = pubRawLeft.getNumSubscribers(); - int right_SubNumber = pubRight.getNumSubscribers(); - int right_raw_SubNumber = pubRawRight.getNumSubscribers(); - int depth_SubNumber = pubDepth.getNumSubscribers(); - int disparity_SubNumber = pubDisparity.getNumSubscribers(); - int cloud_SubNumber = pubCloud.getNumSubscribers(); - int pose_SubNumber = pubPose.getNumSubscribers(); - int odom_SubNumber = pubOdom.getNumSubscribers(); - int conf_img_SubNumber = pubConfImg.getNumSubscribers(); - int conf_map_SubNumber = pubConfMap.getNumSubscribers(); - int imu_SubNumber = pubImu.getNumSubscribers(); - int imu_RawSubNumber = pubImuRaw.getNumSubscribers(); - bool runLoop = (rgb_SubNumber + rgb_raw_SubNumber + left_SubNumber + - left_raw_SubNumber + right_SubNumber + right_raw_SubNumber + - depth_SubNumber + disparity_SubNumber + cloud_SubNumber + - pose_SubNumber + odom_SubNumber + conf_img_SubNumber + - conf_map_SubNumber + imu_SubNumber + imu_RawSubNumber) > 0; + uint32_t rgbSubnumber = mPubRgb.getNumSubscribers(); + uint32_t rgbRawSubnumber = mPubRawRgb.getNumSubscribers(); + uint32_t leftSubnumber = mPubLeft.getNumSubscribers(); + uint32_t leftRawSubnumber = mPubRawLeft.getNumSubscribers(); + uint32_t rightSubnumber = mPubRight.getNumSubscribers(); + uint32_t rightRawSubnumber = mPubRawRight.getNumSubscribers(); + uint32_t depthSubnumber = mPubDepth.getNumSubscribers(); + uint32_t disparitySubnumber = mPubDisparity.getNumSubscribers(); + uint32_t cloudSubnumber = mPubCloud.getNumSubscribers(); + uint32_t poseSubnumber = mPubPose.getNumSubscribers(); + uint32_t odomSubnumber = mPubOdom.getNumSubscribers(); + uint32_t confImgSubnumber = mPubConfImg.getNumSubscribers(); + uint32_t confMapSubnumber = mPubConfMap.getNumSubscribers(); + uint32_t imuSubnumber = mPubImu.getNumSubscribers(); + uint32_t imuRawsubnumber = mPubImuRaw.getNumSubscribers(); + uint32_t pathSubNumber = mPubMapPath.getNumSubscribers() + mPubOdomPath.getNumSubscribers(); + bool runLoop = ((rgbSubnumber + rgbRawSubnumber + leftSubnumber + + leftRawSubnumber + rightSubnumber + rightRawSubnumber + + depthSubnumber + disparitySubnumber + cloudSubnumber + + poseSubnumber + odomSubnumber + confImgSubnumber + + confMapSubnumber + imuSubnumber + imuRawsubnumber + pathSubNumber) > 0); runParams.enable_point_cloud = false; - if (cloud_SubNumber > 0) { + + if (cloudSubnumber > 0) { runParams.enable_point_cloud = true; } + // Run the loop only if there is some subscribers if (runLoop) { - if ((depthStabilization || pose_SubNumber > 0 || odom_SubNumber > 0 || - cloud_SubNumber > 0 || depth_SubNumber > 0) && - !trackingActivated) { // Start the tracking + bool startTracking = (mDepthStabilization || poseSubnumber > 0 || odomSubnumber > 0 || + cloudSubnumber > 0 || depthSubnumber > 0 || pathSubNumber > 0); + + if ((startTracking) && !mTrackingActivated) { // Start the tracking start_tracking(); - } else if (!depthStabilization && pose_SubNumber == 0 && - odom_SubNumber == 0 && - trackingActivated) { // Stop the tracking - zed.disableTracking(); - trackingActivated = false; + } else if (!mDepthStabilization && poseSubnumber == 0 && + odomSubnumber == 0 && + mTrackingActivated) { // Stop the tracking + mZed.disableTracking(); + mTrackingActivated = false; } - computeDepth = (depth_SubNumber + disparity_SubNumber + cloud_SubNumber + - pose_SubNumber + odom_SubNumber + conf_img_SubNumber + - conf_map_SubNumber) > 0; // Detect if one of the - // subscriber need to have the - // depth information + + // Detect if one of the subscriber need to have the depth information + mComputeDepth = ((depthSubnumber + disparitySubnumber + cloudSubnumber + + poseSubnumber + odomSubnumber + confImgSubnumber + + confMapSubnumber) > 0); // Timestamp ros::Time t; if (mSvoMode) { t = ros::Time::now(); } else { - t = sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_IMAGE)); + t = sl_tools::slTime2Ros(mZed.getTimestamp(sl::TIME_REFERENCE_IMAGE)); } - grabbing = true; - if (computeDepth) { - int actual_confidence = zed.getConfidenceThreshold(); - if (actual_confidence != confidence) { - zed.setConfidenceThreshold(confidence); + if (mComputeDepth) { + int actual_confidence = mZed.getConfidenceThreshold(); + + if (actual_confidence != mCamConfidence) { + mZed.setConfidenceThreshold(mCamConfidence); } + + double actual_max_depth = static_cast(mZed.getDepthMaxRangeValue()); + + if (actual_max_depth != mCamMaxDepth) { + mZed.setDepthMaxRangeValue(static_cast(mCamMaxDepth)); + } + runParams.enable_depth = true; // Ask to compute the depth } else { runParams.enable_depth = false; } - grab_status = zed.grab(runParams); // Ask to not compute the depth - - grabbing = false; + grab_status = mZed.grab(runParams); // Ask to not compute the depth // cout << toString(grab_status) << endl; - if (grab_status != - sl::ERROR_CODE::SUCCESS) { // Detect if a error occurred (for example: + if (grab_status != sl::ERROR_CODE::SUCCESS) { + // Detect if a error occurred (for example: // the zed have been disconnected) and // re-initialize the ZED - - if (grab_status == sl::ERROR_CODE_NOT_A_NEW_FRAME) { - NODELET_DEBUG_THROTTLE(1.0, "Wait for a new image to proceed"); - } else { + if (grab_status != sl::ERROR_CODE_NOT_A_NEW_FRAME) { NODELET_INFO_STREAM_ONCE(toString(grab_status)); } + // if ( mSvoMode && mPubClock.getNumSubscribers() > 0) { + // rosgraph_msgs::Clock clkMsg; + // clkMsg.clock = sl_tools::slTime2Ros(mZed.getTimestamp(sl::TIME_REFERENCE_IMAGE)); + + // mPubClock.publish(clkMsg); + // } + std::this_thread::sleep_for(std::chrono::milliseconds(2)); if ((t - old_t).toSec() > 5 && !mSvoMode) { - zed.close(); - + mZed.close(); NODELET_INFO("Re-opening the ZED"); sl::ERROR_CODE err = sl::ERROR_CODE_CAMERA_NOT_DETECTED; + while (err != sl::SUCCESS) { - if (!nhNs.ok()) { + if (!mNhNs.ok()) { mStopNode = true; - zed.close(); + mZed.close(); NODELET_DEBUG("ZED pool thread finished"); return; } - int id = sl_tools::checkCameraReady(serial_number); + int id = sl_tools::checkCameraReady(mZedSerialNumber); + if (id > 0) { - param.camera_linux_id = id; - err = zed.open(param); // Try to initialize the ZED + mZedParams.camera_linux_id = id; + err = mZed.open(mZedParams); // Try to initialize the ZED NODELET_INFO_STREAM(toString(err)); } else { - NODELET_INFO("Waiting for the ZED to be re-connected"); + NODELET_INFO_STREAM("Waiting for the ZED (S/N " << mZedSerialNumber << ") to be re-connected"); } + std::this_thread::sleep_for(std::chrono::milliseconds(2000)); } - trackingActivated = false; - if (depthStabilization || pose_SubNumber > 0 || - odom_SubNumber > 0) { // Start the tracking + + mTrackingActivated = false; + + startTracking = mDepthStabilization || poseSubnumber > 0 || odomSubnumber > 0; + + if (startTracking) { // Start the tracking start_tracking(); } } + continue; } @@ -1418,131 +1524,128 @@ namespace zed_wrapper { if (mSvoMode) { t_old = ros::Time::now(); } else { - t_old = sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); + t_old = sl_tools::slTime2Ros(mZed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); } old_t = t_old; - if (autoExposure) { + if (mCamAutoExposure) { // getCameraSettings() can't check status of auto exposure // triggerAutoExposure is used to execute setCameraSettings() only once - if (triggerAutoExposure) { - zed.setCameraSettings(sl::CAMERA_SETTINGS_EXPOSURE, 0, true); - triggerAutoExposure = false; + if (mTriggerAutoExposure) { + mZed.setCameraSettings(sl::CAMERA_SETTINGS_EXPOSURE, 0, true); + mTriggerAutoExposure = false; } } else { int actual_exposure = - zed.getCameraSettings(sl::CAMERA_SETTINGS_EXPOSURE); - if (actual_exposure != exposure) { - zed.setCameraSettings(sl::CAMERA_SETTINGS_EXPOSURE, exposure); + mZed.getCameraSettings(sl::CAMERA_SETTINGS_EXPOSURE); + + if (actual_exposure != mCamExposure) { + mZed.setCameraSettings(sl::CAMERA_SETTINGS_EXPOSURE, mCamExposure); } - int actual_gain = zed.getCameraSettings(sl::CAMERA_SETTINGS_GAIN); - if (actual_gain != gain) { - zed.setCameraSettings(sl::CAMERA_SETTINGS_GAIN, gain); + int actual_gain = mZed.getCameraSettings(sl::CAMERA_SETTINGS_GAIN); + + if (actual_gain != mCamGain) { + mZed.setCameraSettings(sl::CAMERA_SETTINGS_GAIN, mCamGain); } } - dataMutex.lock(); + mCamDataMutex.lock(); // Publish the left == rgb image if someone has subscribed to - if (left_SubNumber > 0 || rgb_SubNumber > 0) { + if (leftSubnumber > 0 || rgbSubnumber > 0) { // Retrieve RGBA Left image - zed.retrieveImage(leftZEDMat, sl::VIEW_LEFT, sl::MEM_CPU, matWidth, - matHeight); - cv::cvtColor(sl_tools::toCVMat(leftZEDMat), leftImRGB, CV_RGBA2RGB); - if (left_SubNumber > 0) { - publishCamInfo(leftCamInfoMsg, pubLeftCamInfo, t); - publishImage(leftImRGB, pubLeft, leftCamOptFrameId, t); + mZed.retrieveImage(leftZEDMat, sl::VIEW_LEFT, sl::MEM_CPU, mMatWidth, mMatHeight); + cv::cvtColor(sl_tools::toCVMat(leftZEDMat), mCvLeftImRGB, CV_RGBA2RGB); + + if (leftSubnumber > 0) { + publishCamInfo(mLeftCamInfoMsg, mPubLeftCamInfo, t); + publishImage(mCvLeftImRGB, mPubLeft, mLeftCamOptFrameId, t); } - if (rgb_SubNumber > 0) { - publishCamInfo(rgbCamInfoMsg, pubRgbCamInfo, t); - publishImage(leftImRGB, pubRgb, depthOptFrameId, - t); // rgb is the left image + + if (rgbSubnumber > 0) { + publishCamInfo(mRgbCamInfoMsg, mPubRgbCamInfo, t); + publishImage(mCvLeftImRGB, mPubRgb, mDepthOptFrameId, t); // rgb is the left image } } // Publish the left_raw == rgb_raw image if someone has subscribed to - if (left_raw_SubNumber > 0 || rgb_raw_SubNumber > 0) { + if (leftRawSubnumber > 0 || rgbRawSubnumber > 0) { // Retrieve RGBA Left image - zed.retrieveImage(leftZEDMat, sl::VIEW_LEFT_UNRECTIFIED, sl::MEM_CPU, - matWidth, matHeight); - cv::cvtColor(sl_tools::toCVMat(leftZEDMat), leftImRGB, CV_RGBA2RGB); - if (left_raw_SubNumber > 0) { - publishCamInfo(leftCamInfoRawMsg, pubLeftCamInfoRaw, t); - publishImage(leftImRGB, pubRawLeft, leftCamOptFrameId, t); + mZed.retrieveImage(leftZEDMat, sl::VIEW_LEFT_UNRECTIFIED, sl::MEM_CPU, mMatWidth, mMatHeight); + cv::cvtColor(sl_tools::toCVMat(leftZEDMat), mCvLeftImRGB, CV_RGBA2RGB); + + if (leftRawSubnumber > 0) { + publishCamInfo(mLeftCamInfoRawMsg, mPubLeftCamInfoRaw, t); + publishImage(mCvLeftImRGB, mPubRawLeft, mLeftCamOptFrameId, t); } - if (rgb_raw_SubNumber > 0) { - publishCamInfo(rgbCamInfoRawMsg, pubRgbCamInfoRaw, t); - publishImage(leftImRGB, pubRawRgb, depthOptFrameId, t); + + if (rgbRawSubnumber > 0) { + publishCamInfo(mRgbCamInfoRawMsg, mPubRgbCamInfoRaw, t); + publishImage(mCvLeftImRGB, mPubRawRgb, mDepthOptFrameId, t); } } // Publish the right image if someone has subscribed to - if (right_SubNumber > 0) { + if (rightSubnumber > 0) { // Retrieve RGBA Right image - zed.retrieveImage(rightZEDMat, sl::VIEW_RIGHT, sl::MEM_CPU, matWidth, - matHeight); - cv::cvtColor(sl_tools::toCVMat(rightZEDMat), rightImRGB, CV_RGBA2RGB); - publishCamInfo(rightCamInfoMsg, pubRightCamInfo, t); - publishImage(rightImRGB, pubRight, rightCamOptFrameId, t); + mZed.retrieveImage(rightZEDMat, sl::VIEW_RIGHT, sl::MEM_CPU, mMatWidth, mMatHeight); + cv::cvtColor(sl_tools::toCVMat(rightZEDMat), mCvRightImRGB, CV_RGBA2RGB); + publishCamInfo(mRightCamInfoMsg, mPubRightCamInfo, t); + publishImage(mCvRightImRGB, mPubRight, mRightCamOptFrameId, t); } // Publish the right image if someone has subscribed to - if (right_raw_SubNumber > 0) { + if (rightRawSubnumber > 0) { // Retrieve RGBA Right image - zed.retrieveImage(rightZEDMat, sl::VIEW_RIGHT_UNRECTIFIED, sl::MEM_CPU, - matWidth, matHeight); - cv::cvtColor(sl_tools::toCVMat(rightZEDMat), rightImRGB, CV_RGBA2RGB); - publishCamInfo(rightCamInfoRawMsg, pubRightCamInfoRaw, t); - publishImage(rightImRGB, pubRawRight, rightCamOptFrameId, t); + mZed.retrieveImage(rightZEDMat, sl::VIEW_RIGHT_UNRECTIFIED, sl::MEM_CPU, mMatWidth, mMatHeight); + cv::cvtColor(sl_tools::toCVMat(rightZEDMat), mCvRightImRGB, CV_RGBA2RGB); + publishCamInfo(mRightCamInfoRawMsg, mPubRightCamInfoRaw, t); + publishImage(mCvRightImRGB, mPubRawRight, mRightCamOptFrameId, t); } // Publish the depth image if someone has subscribed to - if (depth_SubNumber > 0 || disparity_SubNumber > 0) { - zed.retrieveMeasure(depthZEDMat, sl::MEASURE_DEPTH, sl::MEM_CPU, - matWidth, matHeight); - publishCamInfo(depthCamInfoMsg, pubDepthCamInfo, t); + if (depthSubnumber > 0 || disparitySubnumber > 0) { + mZed.retrieveMeasure(depthZEDMat, sl::MEASURE_DEPTH, sl::MEM_CPU, mMatWidth, mMatHeight); + publishCamInfo(mDepthCamInfoMsg, mPubDepthCamInfo, t); publishDepth(sl_tools::toCVMat(depthZEDMat), t); // in meters } // Publish the disparity image if someone has subscribed to - if (disparity_SubNumber > 0) { - zed.retrieveMeasure(disparityZEDMat, sl::MEASURE_DISPARITY, sl::MEM_CPU, - matWidth, matHeight); + if (disparitySubnumber > 0) { + mZed.retrieveMeasure(disparityZEDMat, sl::MEASURE_DISPARITY, sl::MEM_CPU, mMatWidth, mMatHeight); // Need to flip sign, but cause of this is not sure cv::Mat disparity = sl_tools::toCVMat(disparityZEDMat) * -1.0; publishDisparity(disparity, t); } // Publish the confidence image if someone has subscribed to - if (conf_img_SubNumber > 0) { - zed.retrieveImage(confImgZEDMat, sl::VIEW_CONFIDENCE, sl::MEM_CPU, - matWidth, matHeight); - cv::cvtColor(sl_tools::toCVMat(confImgZEDMat), confImRGB, CV_RGBA2RGB); - publishImage(confImRGB, pubConfImg, confidenceOptFrameId, t); + if (confImgSubnumber > 0) { + mZed.retrieveImage(confImgZEDMat, sl::VIEW_CONFIDENCE, sl::MEM_CPU, mMatWidth, mMatHeight); + cv::cvtColor(sl_tools::toCVMat(confImgZEDMat), mCvConfImRGB, CV_RGBA2RGB); + publishImage(mCvConfImRGB, mPubConfImg, mConfidenceOptFrameId, t); } // Publish the confidence map if someone has subscribed to - if (conf_map_SubNumber > 0) { - zed.retrieveMeasure(confMapZEDMat, sl::MEASURE_CONFIDENCE, sl::MEM_CPU, - matWidth, matHeight); - confMapFloat = sl_tools::toCVMat(confMapZEDMat); - pubConfMap.publish(imageToROSmsg( - confMapFloat, sensor_msgs::image_encodings::TYPE_32FC1, - confidenceOptFrameId, t)); + if (confMapSubnumber > 0) { + mZed.retrieveMeasure(confMapZEDMat, sl::MEASURE_CONFIDENCE, sl::MEM_CPU, mMatWidth, mMatHeight); + mCvConfMapFloat = sl_tools::toCVMat(confMapZEDMat); + mPubConfMap.publish(sl_tools::imageToROSmsg( + mCvConfMapFloat, sensor_msgs::image_encodings::TYPE_32FC1, + mConfidenceOptFrameId, t)); } // Publish the point cloud if someone has subscribed to - if (cloud_SubNumber > 0) { + if (cloudSubnumber > 0) { // Run the point cloud conversion asynchronously to avoid slowing down // all the program // Retrieve raw pointCloud data if latest Pointcloud is ready std::unique_lock lock(mPcMutex, std::defer_lock); if (lock.try_lock()) { - zed.retrieveMeasure(cloud, sl::MEASURE_XYZBGRA, sl::MEM_CPU, matWidth, matHeight); + mZed.retrieveMeasure(mCloud, sl::MEASURE_XYZBGRA, sl::MEM_CPU, mMatWidth, mMatHeight); - pointCloudFrameId = depthFrameId; - pointCloudTime = t; + mPointCloudFrameId = mDepthFrameId; + mPointCloudTime = t; // Signal Pointcloud thread that a new pointcloud is ready mPcDataReady = true; @@ -1551,133 +1654,141 @@ namespace zed_wrapper { } } - dataMutex.unlock(); - + mCamDataMutex.unlock(); + // Transform from base to sensor tf2::Transform sensor_to_base_transf; + // Look up the transformation from base frame to camera link try { // Save the transformation from base to frame geometry_msgs::TransformStamped s2b = - tfBuffer->lookupTransform(baseFrameId, depthFrameId, t); + mTfBuffer->lookupTransform(mBaseFrameId, mDepthFrameId, t); // Get the TF2 transformation tf2::fromMsg(s2b.transform, sensor_to_base_transf); - } catch (tf2::TransformException& ex) { NODELET_WARN_THROTTLE( 10.0, "The tf from '%s' to '%s' does not seem to be available, " "will assume it as identity!", - depthFrameId.c_str(), baseFrameId.c_str()); + mDepthFrameId.c_str(), mBaseFrameId.c_str()); NODELET_DEBUG("Transform error: %s", ex.what()); sensor_to_base_transf.setIdentity(); } // Publish the odometry if someone has subscribed to - if (pose_SubNumber > 0 || odom_SubNumber > 0 || cloud_SubNumber > 0 || - depth_SubNumber > - - - 0 || imu_SubNumber > 0 || imu_RawSubNumber > 0) { - if (!initOdomWithPose) { + if (poseSubnumber > 0 || odomSubnumber > 0 || cloudSubnumber > 0 || + depthSubnumber > 0 || imuSubnumber > 0 || imuRawsubnumber > 0 || pathSubNumber > 0) { + if (!mInitOdomWithPose) { sl::Pose deltaOdom; - zed.getPosition(deltaOdom, sl::REFERENCE_FRAME_CAMERA); - - // Transform ZED delta odom pose in TF2 Transformation - geometry_msgs::Transform deltaTransf; - - sl::Translation translation = deltaOdom.getTranslation(); - sl::Orientation quat = deltaOdom.getOrientation(); - - deltaTransf.translation.x = xSign * translation(xIdx); - deltaTransf.translation.y = ySign * translation(yIdx); - deltaTransf.translation.z = zSign * translation(zIdx); - - deltaTransf.rotation.x = xSign * quat(xIdx); - deltaTransf.rotation.y = ySign * quat(yIdx); - deltaTransf.rotation.z = zSign * quat(zIdx); - deltaTransf.rotation.w = quat(3); - - tf2::Transform deltaOdomTf; - tf2::fromMsg(deltaTransf, deltaOdomTf); - - // delta odom from sensor to base frame - tf2::Transform deltaOdomTf_base = sensor_to_base_transf * - deltaOdomTf * - sensor_to_base_transf.inverse(); - - // Propagate Odom transform in time - baseToOdomTransform = baseToOdomTransform * deltaOdomTf_base; - - // Publish odometry message - publishOdom(baseToOdomTransform, t); + sl::TRACKING_STATE status = mZed.getPosition(deltaOdom, sl::REFERENCE_FRAME_CAMERA); + + if (status == sl::TRACKING_STATE_OK || status == sl::TRACKING_STATE_SEARCHING || status == sl::TRACKING_STATE_FPS_TOO_LOW) { + // Transform ZED delta odom pose in TF2 Transformation + geometry_msgs::Transform deltaTransf; + sl::Translation translation = deltaOdom.getTranslation(); + sl::Orientation quat = deltaOdom.getOrientation(); + deltaTransf.translation.x = mSignX * translation(mIdxX); + deltaTransf.translation.y = mSignY * translation(mIdxY); + deltaTransf.translation.z = mSignZ * translation(mIdxZ); + deltaTransf.rotation.x = mSignX * quat(mIdxX); + deltaTransf.rotation.y = mSignY * quat(mIdxY); + deltaTransf.rotation.z = mSignZ * quat(mIdxZ); + deltaTransf.rotation.w = quat(3); + tf2::Transform deltaOdomTf; + tf2::fromMsg(deltaTransf, deltaOdomTf); + // delta odom from sensor to base frame + tf2::Transform deltaOdomTf_base = + sensor_to_base_transf * deltaOdomTf * sensor_to_base_transf.inverse(); + + // Propagate Odom transform in time + mBase2OdomTransf = mBase2OdomTransf * deltaOdomTf_base; + // Publish odometry message + publishOdom(mBase2OdomTransf, t); + mTrackingReady = true; + } else { + NODELET_DEBUG_STREAM("ODOM -> Tracking Status: " << static_cast(status)); + } } } // Publish the zed camera pose if someone has subscribed to - if (pose_SubNumber > 0 || odom_SubNumber > 0 || cloud_SubNumber > 0 || - depth_SubNumber > 0 || imu_SubNumber > 0 || imu_RawSubNumber > 0) { - sl::Pose zed_pose; // Sensor to Map transform - zed.getPosition(zed_pose, sl::REFERENCE_FRAME_WORLD); - - // Transform ZED pose in TF2 Transformation - geometry_msgs::Transform sens2mapTransf; - - sl::Translation translation = zed_pose.getTranslation(); - sl::Orientation quat = zed_pose.getOrientation(); - - sens2mapTransf.translation.x = xSign * translation(xIdx); - sens2mapTransf.translation.y = ySign * translation(yIdx); - sens2mapTransf.translation.z = zSign * translation(zIdx); - - sens2mapTransf.rotation.x = xSign * quat(xIdx); - sens2mapTransf.rotation.y = ySign * quat(yIdx); - sens2mapTransf.rotation.z = zSign * quat(zIdx); - sens2mapTransf.rotation.w = quat(3); - - tf2::Transform sens_to_map_transf; - tf2::fromMsg(sens2mapTransf, sens_to_map_transf); + if (poseSubnumber > 0 || odomSubnumber > 0 || cloudSubnumber > 0 || + depthSubnumber > 0 || imuSubnumber > 0 || imuRawsubnumber > 0 || pathSubNumber > 0) { + + static sl::TRACKING_STATE oldStatus; + sl::TRACKING_STATE status = mZed.getPosition(mLastZedPose, sl::REFERENCE_FRAME_WORLD); + + if (status == sl::TRACKING_STATE_OK || status == sl::TRACKING_STATE_SEARCHING /*|| status == sl::TRACKING_STATE_FPS_TOO_LOW*/) { + // Transform ZED pose in TF2 Transformation + geometry_msgs::Transform sens2mapTransf; + sl::Translation translation = mLastZedPose.getTranslation(); + sl::Orientation quat = mLastZedPose.getOrientation(); + sens2mapTransf.translation.x = mSignX * translation(mIdxX); + sens2mapTransf.translation.y = mSignY * translation(mIdxY); + sens2mapTransf.translation.z = mSignZ * translation(mIdxZ); + sens2mapTransf.rotation.x = mSignX * quat(mIdxX); + sens2mapTransf.rotation.y = mSignY * quat(mIdxY); + sens2mapTransf.rotation.z = mSignZ * quat(mIdxZ); + sens2mapTransf.rotation.w = quat(3); + tf2::Transform sens_to_map_transf; + tf2::fromMsg(sens2mapTransf, sens_to_map_transf); + // Transformation from camera sensor to base frame + /*tf2::Transform base_to_map_transform = + sensor_to_base_transf * sens_to_map_transf * sensor_to_base_transf.inverse();*/ + + tf2::Transform base_to_map_transform = (sensor_to_base_transf * sens_to_map_transf.inverse()).inverse(); + + bool initOdom = false; + + if (!(mFloorAlignment)) { + initOdom = mInitOdomWithPose; + } else { + initOdom = (status == sl::TRACKING_STATE_OK) & mInitOdomWithPose; + } - // Transformation from camera sensor to base frame - tf2::Transform base_to_map_transform = sensor_to_base_transf * - sens_to_map_transf * - sensor_to_base_transf.inverse(); + if (initOdom || mResetOdom) { + // Propagate Odom transform in time + mBase2OdomTransf = base_to_map_transform; + base_to_map_transform.setIdentity(); - if (initOdomWithPose) { - // Propagate Odom transform in time - baseToOdomTransform = base_to_map_transform; - base_to_map_transform.setIdentity(); + if (odomSubnumber > 0) { + // Publish odometry message + publishOdom(mBase2OdomTransf, t); + } - if (odom_SubNumber > 0) { - // Publish odometry message - publishOdom(baseToOdomTransform, t); + mInitOdomWithPose = false; + mResetOdom = false; + } else { + // Transformation from map to odometry frame + mOdom2MapTransf = + base_to_map_transform * mBase2OdomTransf.inverse(); } - initOdomWithPose = false; + // Publish Pose message + publishPose(t); + mTrackingReady = true; } else { - // Transformation from map to odometry frame - odomToMapTransform = - base_to_map_transform * baseToOdomTransform.inverse(); + NODELET_DEBUG_STREAM("MAP -> Tracking Status: " << static_cast(status)); } - // Publish Pose message - publishPose(odomToMapTransform, t); + oldStatus = status; } // Publish pose tf only if enabled - if (publishTf) { + if (mPublishTf) { // Note, the frame is published, but its values will only change if // someone has subscribed to odom - publishOdomFrame(baseToOdomTransform, - t); // publish the base Frame in odometry frame - // Note, the frame is published, but its values will only change if - // someone has subscribed to map - publishPoseFrame(odomToMapTransform, - t); // publish the odometry Frame in map frame - - imuTime = t; + publishOdomFrame(mBase2OdomTransf, t); // publish the base Frame in odometry frame + if (mPublishMapTf) { + // Note, the frame is published, but its values will only change if + // someone has subscribed to map + publishPoseFrame(mOdom2MapTransf, t); // publish the odometry Frame in map frame + } + mLastFrameTime = t; } static int rateWarnCount = 0; + if (!loop_rate.sleep()) { rateWarnCount++; @@ -1697,34 +1808,34 @@ namespace zed_wrapper { rateWarnCount = 0; } } else { - NODELET_DEBUG_THROTTLE(1.0, "No topics subscribed by users"); + NODELET_DEBUG_THROTTLE(5.0, "No topics subscribed by users"); // Publish odometry tf only if enabled - if (publishTf) { + if (mPublishTf) { ros::Time t; if (mSvoMode) { t = ros::Time::now(); } else { - t = sl_tools::slTime2Ros(zed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); + t = sl_tools::slTime2Ros(mZed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); } - publishOdomFrame(baseToOdomTransform, - t); // publish the base Frame in odometry frame - publishPoseFrame(odomToMapTransform, - t); // publish the odometry Frame in map frame + publishOdomFrame(mBase2OdomTransf, t); // publish the base Frame in odometry frame + + if (mPublishMapTf) { + publishPoseFrame(mOdom2MapTransf, t); // publish the odometry Frame in map frame + } } + std::this_thread::sleep_for( std::chrono::milliseconds(10)); // No subscribers, we just wait - loop_rate.reset(); } } // while loop mStopNode = true; // Stops other threads - zed.close(); + mZed.close(); NODELET_DEBUG("ZED pool thread finished"); } - } // namespace diff --git a/zed_wrapper/src/tools/include/sl_tools.h b/zed_wrapper/src/tools/include/sl_tools.h index ba6470ce..d372141b 100644 --- a/zed_wrapper/src/tools/include/sl_tools.h +++ b/zed_wrapper/src/tools/include/sl_tools.h @@ -21,10 +21,11 @@ // /////////////////////////////////////////////////////////////////////////// -#include -#include #include #include +#include +#include +#include namespace sl_tools { @@ -62,18 +63,17 @@ namespace sl_tools { */ ros::Time slTime2Ros(sl::timeStamp t); - inline sl::uchar4 depackColor4(float colorIn) { - sl::uchar4 out; - uint32_t color_uint = *(uint32_t*) & colorIn; - unsigned char* color_uchar = (unsigned char*) &color_uint; - for (int c = 0; c < 3; c++) { - out[c] = static_cast(color_uchar[c]); - } - out.w = 255; - return out; - } + /* \brief Image to ros message conversion + * \param img : the image to publish + * \param encodingType : the sensor_msgs::image_encodings encoding type + * \param frameId : the id of the reference frame of the image + * \param t : the ros::Time to stamp the image + */ + sensor_msgs::ImagePtr imageToROSmsg(cv::Mat img, + const std::string encodingType, + std::string frameId, ros::Time t); + - } // namespace #endif // SL_TOOLS_H diff --git a/zed_wrapper/src/tools/src/sl_tools.cpp b/zed_wrapper/src/tools/src/sl_tools.cpp index 45ef83a2..eecb72ad 100644 --- a/zed_wrapper/src/tools/src/sl_tools.cpp +++ b/zed_wrapper/src/tools/src/sl_tools.cpp @@ -20,30 +20,38 @@ #include "sl_tools.h" +#include #include #include -#include + +#include namespace sl_tools { int checkCameraReady(unsigned int serial_number) { int id = -1; auto f = sl::Camera::getDeviceList(); + for (auto& it : f) - if (it.serial_number == serial_number && it.camera_state == sl::CAMERA_STATE::CAMERA_STATE_AVAILABLE) { + if (it.serial_number == serial_number && + it.camera_state == sl::CAMERA_STATE::CAMERA_STATE_AVAILABLE) { id = it.id; } + return id; } sl::DeviceProperties getZEDFromSN(unsigned int serial_number) { sl::DeviceProperties prop; auto f = sl::Camera::getDeviceList(); + for (auto& it : f) { - if (it.serial_number == serial_number && it.camera_state == sl::CAMERA_STATE::CAMERA_STATE_AVAILABLE) { + if (it.serial_number == serial_number && + it.camera_state == sl::CAMERA_STATE::CAMERA_STATE_AVAILABLE) { prop = it; } } + return prop; } @@ -53,33 +61,44 @@ namespace sl_tools { } int cvType; + switch (mat.getDataType()) { case sl::MAT_TYPE_32F_C1: cvType = CV_32FC1; break; + case sl::MAT_TYPE_32F_C2: cvType = CV_32FC2; break; + case sl::MAT_TYPE_32F_C3: cvType = CV_32FC3; break; + case sl::MAT_TYPE_32F_C4: cvType = CV_32FC4; break; + case sl::MAT_TYPE_8U_C1: cvType = CV_8UC1; break; + case sl::MAT_TYPE_8U_C2: cvType = CV_8UC2; break; + case sl::MAT_TYPE_8U_C3: cvType = CV_8UC3; break; + case sl::MAT_TYPE_8U_C4: cvType = CV_8UC4; break; } - return cv::Mat((int) mat.getHeight(), (int) mat.getWidth(), cvType, mat.getPtr(sl::MEM_CPU), mat.getStepBytes(sl::MEM_CPU)); + + return cv::Mat((int)mat.getHeight(), (int)mat.getWidth(), cvType, + mat.getPtr(sl::MEM_CPU), + mat.getStepBytes(sl::MEM_CPU)); } cv::Mat convertRodrigues(sl::float3 r) { @@ -93,11 +112,9 @@ namespace sl_tools { double s = sin(theta); double c1 = 1. - c; double itheta = theta ? 1. / theta : 0.; - r *= itheta; - cv::Mat rrt = cv::Mat::eye(3, 3, CV_32F); - float* p = (float*) rrt.data; + float* p = (float*)rrt.data; p[0] = r.x * r.x; p[1] = r.x * r.y; p[2] = r.x * r.z; @@ -107,9 +124,8 @@ namespace sl_tools { p[6] = r.x * r.z; p[7] = r.y * r.z; p[8] = r.z * r.z; - cv::Mat r_x = cv::Mat::eye(3, 3, CV_32F); - p = (float*) r_x.data; + p = (float*)r_x.data; p[0] = 0; p[1] = -r.z; p[2] = r.y; @@ -119,10 +135,10 @@ namespace sl_tools { p[6] = -r.y; p[7] = r.x; p[8] = 0; - // R = cos(theta)*I + (1 - cos(theta))*r*rT + sin(theta)*[r_x] R = c * cv::Mat::eye(3, 3, CV_32F) + c1 * rrt + s * r_x; } + return R; } @@ -133,11 +149,10 @@ namespace sl_tools { std::string getSDKVersion(int& major, int& minor, int& sub_minor) { std::string ver = sl::Camera::getSDKVersion().c_str(); - std::vector strings; std::istringstream f(ver); std::string s; - + while (getline(f, s, '.')) { strings.push_back(s); } @@ -161,10 +176,41 @@ namespace sl_tools { } ros::Time slTime2Ros(sl::timeStamp t) { - uint32_t sec = static_cast(t / 1000000000); + uint32_t sec = static_cast(t / 1000000000); uint32_t nsec = static_cast(t % 1000000000); - ros::Time time(sec, nsec); - return time; + return ros::Time(sec, nsec); + } + + sensor_msgs::ImagePtr imageToROSmsg(cv::Mat img, const std::string encodingType, + std::string frameId, ros::Time t) { + sensor_msgs::ImagePtr ptr = boost::make_shared(); + sensor_msgs::Image& imgMessage = *ptr; + imgMessage.header.stamp = t; + imgMessage.header.frame_id = frameId; + imgMessage.height = static_cast(img.rows); + imgMessage.width = static_cast(img.cols); + imgMessage.encoding = encodingType; + int num = 1; // for endianness detection + imgMessage.is_bigendian = !(*(char*)&num == 1); + imgMessage.step = static_cast(img.step); + size_t size = imgMessage.step * img.rows; + imgMessage.data.resize(size); + + if (img.isContinuous()) { + memcpy((char*)(&imgMessage.data[0]), img.data, size); + } else { + uchar* opencvData = img.data; + uchar* rosData = (uchar*)(&imgMessage.data[0]); + + #pragma omp parallel for + for (unsigned int i = 0; i < img.rows; i++) { + memcpy(rosData, opencvData, imgMessage.step); + rosData += imgMessage.step; + opencvData += img.step; + } + } + + return ptr; } } // namespace From add1ad9fa4dd36cad63e1ad1219cb7a935d76b26 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Wed, 12 Sep 2018 10:36:47 +0200 Subject: [PATCH 36/55] Added missing "max_depth" param in launch files --- zed_wrapper/launch/zed_camera.launch | 1 + zed_wrapper/launch/zed_camera_nodelet.launch | 1 + 2 files changed, 2 insertions(+) diff --git a/zed_wrapper/launch/zed_camera.launch b/zed_wrapper/launch/zed_camera.launch index eb12d2d4..f0373270 100644 --- a/zed_wrapper/launch/zed_camera.launch +++ b/zed_wrapper/launch/zed_camera.launch @@ -93,6 +93,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + diff --git a/zed_wrapper/launch/zed_camera_nodelet.launch b/zed_wrapper/launch/zed_camera_nodelet.launch index abacab90..fa02dbf7 100644 --- a/zed_wrapper/launch/zed_camera_nodelet.launch +++ b/zed_wrapper/launch/zed_camera_nodelet.launch @@ -94,6 +94,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + From 7a513b149f4a0955280460569efc92c0746c6b02 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Wed, 12 Sep 2018 10:51:32 +0200 Subject: [PATCH 37/55] Added check on SDK version for Floor Alignment --- zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index bf7e1cd3..dbd0d7a0 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -742,8 +742,15 @@ namespace zed_wrapper { trackParams.enable_spatial_memory = mSpatialMemory; NODELET_INFO_STREAM("Spatial Memory : " << trackParams.enable_spatial_memory); trackParams.initial_world_transform = mInitialPoseSl; - trackParams.set_floor_as_origin = mFloorAlignment; - NODELET_INFO_STREAM("Floor Alignment : " << trackParams.set_floor_as_origin); + + if (mFloorAlignment && + ((ZED_SDK_MAJOR_VERSION < 2) || (ZED_SDK_MAJOR_VERSION == 2 && ZED_SDK_MINOR_VERSION < 6))) { + NODELET_WARN("Floor Alignment is available starting from SDK v2.6"); + } else { + trackParams.set_floor_as_origin = mFloorAlignment; + NODELET_INFO_STREAM("Floor Alignment : " << trackParams.set_floor_as_origin); + } + mZed.enableTracking(trackParams); mTrackingActivated = true; NODELET_INFO("Tracking ENABLED"); From 6e9a80949894ccf09c4950a3e074546fcd6ea07e Mon Sep 17 00:00:00 2001 From: Myzhar Date: Wed, 12 Sep 2018 11:08:36 +0200 Subject: [PATCH 38/55] Better Rviz plugin organization --- zed_display_rviz/rviz/zed.rviz | 472 +++++++++++++++++++---------- zed_display_rviz/rviz/zedm.rviz | 520 +++++++++++++++++++------------- 2 files changed, 612 insertions(+), 380 deletions(-) diff --git a/zed_display_rviz/rviz/zed.rviz b/zed_display_rviz/rviz/zed.rviz index 731c6572..092f9894 100644 --- a/zed_display_rviz/rviz/zed.rviz +++ b/zed_display_rviz/rviz/zed.rviz @@ -1,15 +1,18 @@ Panels: - Class: rviz/Displays - Help Height: 75 + Help Height: 78 Name: Displays Property Tree Widget: Expanded: + - /Global Options1 - /RobotModel1/Links1 - /TF1/Frames1 - - /Odometry1/Shape1 - - /Confidence1 + - /Video1/Camera view1 + - /Video1/Camera view1/Visibility1 + - /Depth1/DepthCloud1 + - /Pose1 Splitter Ratio: 0.5 - Tree Height: 441 + Tree Height: 485 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -28,7 +31,7 @@ Panels: Experimental: false Name: Time SyncMode: 0 - SyncSource: Camera + SyncSource: Camera view Visualization Manager: Class: "" Displays: @@ -36,7 +39,7 @@ Visualization Manager: Cell Size: 1 Class: rviz/Grid Color: 160; 160; 164 - Enabled: false + Enabled: true Line Style: Line Width: 0.0299999993 Value: Lines @@ -49,7 +52,7 @@ Visualization Manager: Plane: XY Plane Cell Count: 10 Reference Frame: - Value: false + Value: true - Alpha: 1 Class: rviz/RobotModel Collision Enabled: false @@ -60,6 +63,10 @@ Visualization Manager: Expand Link Details: false Expand Tree: false Link Tree Style: Links in Alphabetic Order + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false zed_camera_center: Alpha: 1 Show Axes: false @@ -89,9 +96,11 @@ Visualization Manager: Visual Enabled: true - Class: rviz/TF Enabled: true - Frame Timeout: 15 + Frame Timeout: 5 Frames: All Enabled: false + imu_link: + Value: true map: Value: true odom: @@ -106,15 +115,17 @@ Visualization Manager: Value: false zed_right_camera_optical_frame: Value: false - Marker Scale: 1 + Marker Scale: 0.5 Name: TF - Show Arrows: true + Show Arrows: false Show Axes: true Show Names: true Tree: map: odom: zed_camera_center: + imu_link: + {} zed_left_camera_frame: zed_left_camera_optical_frame: {} @@ -123,162 +134,281 @@ Visualization Manager: {} Update Interval: 0 Value: true - - Alpha: 1 - Auto Size: - Auto Size Factor: 1 - Value: true - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/DepthCloud - Color: 255; 255; 255 - Color Image Topic: /zed/rgb/image_raw_color - Color Transformer: RGB8 - Color Transport Hint: raw - Decay Time: 0 - Depth Map Topic: /zed/depth/depth_registered - Depth Map Transport Hint: raw + - Class: rviz/Group + Displays: + - Class: rviz/Camera + Enabled: true + Image Rendering: background and overlay + Image Topic: /zed/rgb/image_rect_color + Name: Camera view + Overlay Alpha: 0.5 + Queue Size: 2 + Transport Hint: raw + Unreliable: true + Value: true + Visibility: + Depth: + Confidence image: true + Confidence map: true + Depth map: true + DepthCloud: true + PointCloud2: true + Value: false + Grid: true + Pose: + Odometry: true + Odometry Path: true + Pose: true + Pose Path: true + Value: false + RobotModel: false + TF: true + Value: true + Video: + Camera view: true + Left camera: true + Right camera: true + Value: true + Zoom Factor: 1 + - Class: rviz/Image + Enabled: false + Image Topic: /zed/left/image_rect_color + Max Value: 10 + Median window: 5 + Min Value: 0 + Name: Left camera + Normalize Range: false + Queue Size: 1 + Transport Hint: raw + Unreliable: true + Value: false + - Class: rviz/Image + Enabled: false + Image Topic: /zed/right/image_rect_color + Max Value: 10 + Median window: 5 + Min Value: 0 + Name: Right camera + Normalize Range: false + Queue Size: 1 + Transport Hint: raw + Unreliable: true + Value: false Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: DepthCloud - Occlusion Compensation: - Occlusion Time-Out: 30 - Value: false - Position Transformer: XYZ - Queue Size: 5 - Selectable: true - Size (Pixels): 1 - Style: Points - Topic Filter: true - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: RGB8 - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: PointCloud2 - Position Transformer: XYZ - Queue Size: 1 - Selectable: false - Size (Pixels): 1 - Size (m): 0.00999999978 - Style: Points - Topic: /zed/point_cloud/cloud_registered - Unreliable: true - Use Fixed Frame: true - Use rainbow: true - Value: false - - Class: rviz/Camera + Name: Video + - Class: rviz/Group + Displays: + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 0.240854248 + Min Value: -1.55063653 + Value: true + Axis: X + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 1 + Selectable: false + Size (Pixels): 1 + Size (m): 0.00999999978 + Style: Points + Topic: /zed/point_cloud/cloud_registered + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Auto Size: + Auto Size Factor: 1 + Value: true + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/DepthCloud + Color: 255; 255; 255 + Color Image Topic: /zed/rgb/image_rect_color + Color Transformer: RGB8 + Color Transport Hint: raw + Decay Time: 0 + Depth Map Topic: /zed/depth/depth_registered + Depth Map Transport Hint: raw + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: DepthCloud + Occlusion Compensation: + Occlusion Time-Out: 30 + Value: false + Position Transformer: XYZ + Queue Size: 2 + Selectable: true + Size (Pixels): 1 + Style: Points + Topic Filter: true + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Image + Enabled: false + Image Topic: /zed/depth/depth_registered + Max Value: 10 + Median window: 5 + Min Value: 0 + Name: Depth map + Normalize Range: false + Queue Size: 1 + Transport Hint: raw + Unreliable: true + Value: false + - Class: rviz/Image + Enabled: false + Image Topic: /zed/confidence/confidence_image + Max Value: 10 + Median window: 5 + Min Value: 0 + Name: Confidence image + Normalize Range: false + Queue Size: 1 + Transport Hint: raw + Unreliable: true + Value: false + - Class: rviz/Image + Enabled: false + Image Topic: /zed/confidence/confidence_map + Max Value: 100 + Median window: 5 + Min Value: 0 + Name: Confidence map + Normalize Range: false + Queue Size: 1 + Transport Hint: raw + Unreliable: true + Value: false Enabled: true - Image Rendering: background and overlay - Image Topic: /zed/rgb/image_rect_color - Name: Camera - Overlay Alpha: 0.5 - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - Visibility: - Confidence: true - DepthCloud: true - Grid: true - Odometry: true - PointCloud2: true - Pose: true - RobotModel: true - TF: true - Value: false - Zoom Factor: 1 - - Angle Tolerance: 0 - Class: rviz/Odometry - Covariance: - Orientation: - Alpha: 0.5 - Color: 255; 255; 127 - Color Style: Unique - Frame: Local - Offset: 1 - Scale: 1 + Name: Depth + - Class: rviz/Group + Displays: + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 255; 25; 0 + Enabled: true + Head Diameter: 0.0299999993 + Head Length: 0.0199999996 + Length: 0.300000012 + Line Style: Lines + Line Width: 0.0299999993 + Name: Odometry Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 25; 0 + Pose Style: Arrows + Radius: 0.0299999993 + Shaft Diameter: 0.00999999978 + Shaft Length: 0.0500000007 + Topic: /zed/path_odom + Unreliable: true Value: true - Position: - Alpha: 0.300000012 - Color: 204; 51; 204 - Scale: 1 + - Angle Tolerance: 0 + Class: rviz/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.300000012 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Keep: 1 + Name: Odometry + Position Tolerance: 0 + Shape: + Alpha: 1 + Axes Length: 0.100000001 + Axes Radius: 0.00999999978 + Color: 255; 25; 0 + Head Length: 0.100000001 + Head Radius: 0.0500000007 + Shaft Length: 0.300000012 + Shaft Radius: 0.0199999996 + Value: Arrow + Topic: /zed/odom + Unreliable: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.0299999993 + Head Length: 0.0199999996 + Length: 0.300000012 + Line Style: Lines + Line Width: 0.0299999993 + Name: Pose Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 25; 255; 0 + Pose Style: Arrows + Radius: 0.0299999993 + Shaft Diameter: 0.00999999978 + Shaft Length: 0.0500000007 + Topic: /zed/path_map + Unreliable: true + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.100000001 + Class: rviz/Pose + Color: 0; 255; 0 + Enabled: true + Head Length: 0.100000001 + Head Radius: 0.0500000007 + Name: Pose + Shaft Length: 0.300000012 + Shaft Radius: 0.0199999996 + Shape: Arrow + Topic: /zed/pose + Unreliable: false Value: true - Value: true - Enabled: true - Keep: 1 - Name: Odometry - Position Tolerance: 0 - Shape: - Alpha: 1 - Axes Length: 1 - Axes Radius: 0.100000001 - Color: 25; 255; 0 - Head Length: 0.100000001 - Head Radius: 0.100000001 - Shaft Length: 0.300000012 - Shaft Radius: 0.0199999996 - Value: Arrow - Topic: /zed/odom - Unreliable: false - Value: true - - Alpha: 1 - Axes Length: 1 - Axes Radius: 0.100000001 - Class: rviz/Pose - Color: 255; 25; 0 Enabled: true - Head Length: 0.100000001 - Head Radius: 0.100000001 Name: Pose - Shaft Length: 0.300000012 - Shaft Radius: 0.0199999996 - Shape: Arrow - Topic: /zed/map - Unreliable: false - Value: true - - Class: rviz/Image - Enabled: false - Image Topic: /zed/confidence/confidence_image - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Confidence - Normalize Range: true - Queue Size: 1 - Transport Hint: raw - Unreliable: true - Value: false Enabled: true Global Options: Background Color: 48; 48; 48 Default Light: true Fixed Frame: map - Frame Rate: 30 + Frame Rate: 60 Name: root Tools: - Class: rviz/Interact @@ -298,37 +428,45 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 1.89739549 + Distance: 1.35755372 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 1.17609167 - Y: 0.259650975 - Z: 0.122633442 + X: 0.763631225 + Y: 1.1376406 + Z: 0.689015388 Focal Shape Fixed Size: false Focal Shape Size: 0.0500000007 Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 - Pitch: 0.310398072 - Target Frame: zed_left_camera + Pitch: 0.0447975472 + Target Frame: Value: Orbit (rviz) - Yaw: 2.44542289 + Yaw: 1.85410023 Saved: ~ Window Geometry: - Camera: + Camera view: + collapsed: false + Confidence image: + collapsed: false + Confidence map: collapsed: false - Confidence: + Depth map: collapsed: false Displays: collapsed: false Height: 1056 Hide Left Dock: false - Hide Right Dock: true - QMainWindow State: 000000ff00000000fd00000004000000000000016a00000396fc020000000ffb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000245000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000002400000010f0000000000000000fb0000000a0049006d006100670065000000028b000000c40000000000000000fb0000000a0049006d006100670065010000028a000000c50000000000000000fb0000000a0049006d00610067006500000002b30000009c0000000000000000fb0000000a0049006d006100670065010000028b000000c40000000000000000fb0000000c00430061006d00650072006101000002730000014b0000001600fffffffb000000140043006f006e0066006900640065006e0063006502000001c60000011c0000016a000000ca000000010000010f00000327fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000327000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000005cf0000039600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Hide Right Dock: false + Left camera: + collapsed: false + QMainWindow State: 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 + Right camera: + collapsed: false Selection: collapsed: false Time: @@ -336,7 +474,7 @@ Window Geometry: Tool Properties: collapsed: false Views: - collapsed: true + collapsed: false Width: 1855 X: 65 Y: 24 diff --git a/zed_display_rviz/rviz/zedm.rviz b/zed_display_rviz/rviz/zedm.rviz index c59d4960..a2e40b67 100644 --- a/zed_display_rviz/rviz/zedm.rviz +++ b/zed_display_rviz/rviz/zedm.rviz @@ -5,13 +5,13 @@ Panels: Property Tree Widget: Expanded: - /Global Options1 - - /RobotModel1/Status1 - /RobotModel1/Links1 - - /TF1 - /TF1/Frames1 - - /DepthCloud1/Occlusion Compensation1 + - /Video1/Camera view1 + - /Video1/Camera view1/Visibility1 + - /Depth1/DepthCloud1 Splitter Ratio: 0.5 - Tree Height: 487 + Tree Height: 485 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -30,7 +30,7 @@ Panels: Experimental: false Name: Time SyncMode: 0 - SyncSource: DepthCloud + SyncSource: Camera view Visualization Manager: Class: "" Displays: @@ -133,215 +133,299 @@ Visualization Manager: {} Update Interval: 0 Value: true - - Alpha: 1 - Auto Size: - Auto Size Factor: 1 - Value: true - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/DepthCloud - Color: 255; 255; 255 - Color Image Topic: /zed/rgb/image_rect_color - Color Transformer: RGB8 - Color Transport Hint: raw - Decay Time: 0 - Depth Map Topic: /zed/depth/depth_registered - Depth Map Transport Hint: raw - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: DepthCloud - Occlusion Compensation: - Occlusion Time-Out: 30 - Value: false - Position Transformer: XYZ - Queue Size: 1 - Selectable: true - Size (Pixels): 1 - Style: Points - Topic Filter: true - Use Fixed Frame: true - Use rainbow: true - Value: true - - Class: rviz/Camera - Enabled: true - Image Rendering: background and overlay - Image Topic: /zed/rgb/image_rect_color - Name: Camera - Overlay Alpha: 0.5 - Queue Size: 2 - Transport Hint: raw - Unreliable: true - Value: true - Visibility: - DepthCloud: true - Grid: true - Imu: true - Odometry: true - PointCloud2: true - Pose: true - Pose Odometry: true - Pose Path: true - RobotModel: true - TF: true - Value: false - Zoom Factor: 1 - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 0.240854248 - Min Value: -1.55063653 - Value: true - Axis: X - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: RGB8 - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: PointCloud2 - Position Transformer: XYZ - Queue Size: 1 - Selectable: false - Size (Pixels): 1 - Size (m): 0.00999999978 - Style: Points - Topic: /zed/point_cloud/cloud_registered - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - - Acceleration properties: - Acc. vector alpha: 1 - Acc. vector color: 255; 0; 0 - Acc. vector scale: 1 - Derotate acceleration: false - Enable acceleration: false - Axes properties: - Axes scale: 1 - Enable axes: true - Box properties: - Box alpha: 1 - Box color: 255; 0; 0 - Enable box: false - x_scale: 1 - y_scale: 1 - z_scale: 1 - Class: rviz_imu_plugin/Imu - Enabled: true - Name: Imu - Topic: /zed/imu/data - Unreliable: false - Value: true - fixed_frame_orientation: true - - Alpha: 1 - Axes Length: 1 - Axes Radius: 0.100000001 - Class: rviz/Pose - Color: 0; 255; 0 + - Class: rviz/Group + Displays: + - Class: rviz/Camera + Enabled: true + Image Rendering: background and overlay + Image Topic: /zed/rgb/image_rect_color + Name: Camera view + Overlay Alpha: 0.5 + Queue Size: 2 + Transport Hint: raw + Unreliable: true + Value: true + Visibility: + Depth: + Confidence image: true + Confidence map: true + Depth map: true + DepthCloud: true + PointCloud2: true + Value: false + Grid: true + Pose: + Imu: true + Odometry: true + Odometry Path: true + Pose: true + Pose Path: true + Value: false + RobotModel: false + TF: true + Value: true + Video: + Camera view: true + Left camera: true + Right camera: true + Value: true + Zoom Factor: 1 + - Class: rviz/Image + Enabled: false + Image Topic: /zed/left/image_rect_color + Max Value: 10 + Median window: 5 + Min Value: 0 + Name: Left camera + Normalize Range: false + Queue Size: 1 + Transport Hint: raw + Unreliable: true + Value: false + - Class: rviz/Image + Enabled: false + Image Topic: /zed/right/image_rect_color + Max Value: 10 + Median window: 5 + Min Value: 0 + Name: Right camera + Normalize Range: false + Queue Size: 1 + Transport Hint: raw + Unreliable: true + Value: false Enabled: true - Head Length: 0.100000001 - Head Radius: 0.0500000007 - Name: Pose - Shaft Length: 0.300000012 - Shaft Radius: 0.0199999996 - Shape: Arrow - Topic: /zed/pose - Unreliable: false - Value: true - - Alpha: 1 - Buffer Length: 1 - Class: rviz/Path - Color: 25; 255; 0 + Name: Video + - Class: rviz/Group + Displays: + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 0.240854248 + Min Value: -1.55063653 + Value: true + Axis: X + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 1 + Selectable: false + Size (Pixels): 1 + Size (m): 0.00999999978 + Style: Points + Topic: /zed/point_cloud/cloud_registered + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Auto Size: + Auto Size Factor: 1 + Value: true + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/DepthCloud + Color: 255; 255; 255 + Color Image Topic: /zed/rgb/image_rect_color + Color Transformer: RGB8 + Color Transport Hint: raw + Decay Time: 0 + Depth Map Topic: /zed/depth/depth_registered + Depth Map Transport Hint: raw + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: DepthCloud + Occlusion Compensation: + Occlusion Time-Out: 30 + Value: false + Position Transformer: XYZ + Queue Size: 2 + Selectable: true + Size (Pixels): 1 + Style: Points + Topic Filter: true + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Image + Enabled: false + Image Topic: /zed/depth/depth_registered + Max Value: 10 + Median window: 5 + Min Value: 0 + Name: Depth map + Normalize Range: false + Queue Size: 1 + Transport Hint: raw + Unreliable: true + Value: false + - Class: rviz/Image + Enabled: false + Image Topic: /zed/confidence/confidence_image + Max Value: 10 + Median window: 5 + Min Value: 0 + Name: Confidence image + Normalize Range: false + Queue Size: 1 + Transport Hint: raw + Unreliable: true + Value: false + - Class: rviz/Image + Enabled: false + Image Topic: /zed/confidence/confidence_map + Max Value: 100 + Median window: 5 + Min Value: 0 + Name: Confidence map + Normalize Range: false + Queue Size: 1 + Transport Hint: raw + Unreliable: true + Value: false Enabled: true - Head Diameter: 0.0299999993 - Head Length: 0.0199999996 - Length: 0.300000012 - Line Style: Lines - Line Width: 0.0299999993 - Name: Pose Path - Offset: - X: 0 - Y: 0 - Z: 0 - Pose Color: 25; 255; 0 - Pose Style: Arrows - Radius: 0.0299999993 - Shaft Diameter: 0.00999999978 - Shaft Length: 0.0500000007 - Topic: /zed/path_map - Unreliable: true - Value: true - - Angle Tolerance: 0 - Class: rviz/Odometry - Covariance: - Orientation: - Alpha: 0.5 - Color: 255; 255; 127 - Color Style: Unique - Frame: Local - Offset: 1 - Scale: 1 + Name: Depth + - Class: rviz/Group + Displays: + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 255; 25; 0 + Enabled: true + Head Diameter: 0.0299999993 + Head Length: 0.0199999996 + Length: 0.300000012 + Line Style: Lines + Line Width: 0.0299999993 + Name: Odometry Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 25; 0 + Pose Style: Arrows + Radius: 0.0299999993 + Shaft Diameter: 0.00999999978 + Shaft Length: 0.0500000007 + Topic: /zed/path_odom + Unreliable: true Value: true - Position: - Alpha: 0.300000012 - Color: 204; 51; 204 - Scale: 1 + - Angle Tolerance: 0 + Class: rviz/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.300000012 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Keep: 1 + Name: Odometry + Position Tolerance: 0 + Shape: + Alpha: 1 + Axes Length: 0.100000001 + Axes Radius: 0.00999999978 + Color: 255; 25; 0 + Head Length: 0.100000001 + Head Radius: 0.0500000007 + Shaft Length: 0.300000012 + Shaft Radius: 0.0199999996 + Value: Arrow + Topic: /zed/odom + Unreliable: false Value: true - Value: true - Enabled: true - Keep: 1 - Name: Odometry - Position Tolerance: 0 - Shape: - Alpha: 1 - Axes Length: 0.100000001 - Axes Radius: 0.00999999978 - Color: 255; 25; 0 - Head Length: 0.100000001 - Head Radius: 0.0500000007 - Shaft Length: 0.300000012 - Shaft Radius: 0.0199999996 - Value: Arrow - Topic: /zed/odom - Unreliable: false - Value: true - - Alpha: 1 - Buffer Length: 1 - Class: rviz/Path - Color: 255; 25; 0 + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.0299999993 + Head Length: 0.0199999996 + Length: 0.300000012 + Line Style: Lines + Line Width: 0.0299999993 + Name: Pose Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 25; 255; 0 + Pose Style: Arrows + Radius: 0.0299999993 + Shaft Diameter: 0.00999999978 + Shaft Length: 0.0500000007 + Topic: /zed/path_map + Unreliable: true + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.100000001 + Class: rviz/Pose + Color: 0; 255; 0 + Enabled: true + Head Length: 0.100000001 + Head Radius: 0.0500000007 + Name: Pose + Shaft Length: 0.300000012 + Shaft Radius: 0.0199999996 + Shape: Arrow + Topic: /zed/pose + Unreliable: false + Value: true + - Acceleration properties: + Acc. vector alpha: 1 + Acc. vector color: 255; 0; 0 + Acc. vector scale: 1 + Derotate acceleration: false + Enable acceleration: false + Axes properties: + Axes scale: 1 + Enable axes: true + Box properties: + Box alpha: 1 + Box color: 255; 0; 0 + Enable box: false + x_scale: 1 + y_scale: 1 + z_scale: 1 + Class: rviz_imu_plugin/Imu + Enabled: true + Name: Imu + Topic: /zed/imu/data + Unreliable: false + Value: true + fixed_frame_orientation: true Enabled: true - Head Diameter: 0.0299999993 - Head Length: 0.0199999996 - Length: 0.300000012 - Line Style: Lines - Line Width: 0.0299999993 - Name: Pose Odometry - Offset: - X: 0 - Y: 0 - Z: 0 - Pose Color: 255; 25; 0 - Pose Style: Arrows - Radius: 0.0299999993 - Shaft Diameter: 0.00999999978 - Shaft Length: 0.0500000007 - Topic: /zed/path_odom - Unreliable: true - Value: true + Name: Pose Enabled: true Global Options: Background Color: 48; 48; 48 @@ -382,20 +466,30 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 - Pitch: -0.0252024569 + Pitch: 0.0447975472 Target Frame: Value: Orbit (rviz) - Yaw: 1.47410023 + Yaw: 1.85410023 Saved: ~ Window Geometry: - Camera: + Camera view: + collapsed: false + Confidence image: + collapsed: false + Confidence map: + collapsed: false + Depth map: collapsed: false Displays: collapsed: false Height: 1056 Hide Left Dock: false Hide Right Dock: false - QMainWindow State: 000000ff00000000fd00000004000000000000016a00000394fc020000000efb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000276000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000002400000010f0000000000000000fb0000000a0049006d006100670065000000028b000000c40000000000000000fb0000000a0049006d006100670065010000028a000000c50000000000000000fb0000000a0049006d00610067006500000002b30000009c0000000000000000fb0000000a0049006d006100670065010000028b000000c40000000000000000fb0000000c00430061006d00650072006101000002a4000001180000001600ffffff000000010000010f00000394fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000394000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f00000040fc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000004ba0000039400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Left camera: + collapsed: false + QMainWindow State: 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 + Right camera: + collapsed: false Selection: collapsed: false Time: From c0b7510074438a3b925dc1968553f3025bf8966e Mon Sep 17 00:00:00 2001 From: Myzhar Date: Wed, 12 Sep 2018 12:29:04 +0200 Subject: [PATCH 39/55] Fixed init odometry with first valid pose when IMU is not available --- zed_display_rviz/rviz/zedm.rviz | 22 ++++++++----------- .../src/nodelet/src/zed_wrapper_nodelet.cpp | 13 +++++------ 2 files changed, 14 insertions(+), 21 deletions(-) diff --git a/zed_display_rviz/rviz/zedm.rviz b/zed_display_rviz/rviz/zedm.rviz index a2e40b67..de69505f 100644 --- a/zed_display_rviz/rviz/zedm.rviz +++ b/zed_display_rviz/rviz/zedm.rviz @@ -9,6 +9,7 @@ Panels: - /TF1/Frames1 - /Video1/Camera view1 - /Video1/Camera view1/Visibility1 + - /Depth1 - /Depth1/DepthCloud1 Splitter Ratio: 0.5 Tree Height: 485 @@ -98,8 +99,6 @@ Visualization Manager: Frame Timeout: 5 Frames: All Enabled: false - imu_link: - Value: true map: Value: true odom: @@ -116,15 +115,13 @@ Visualization Manager: Value: false Marker Scale: 0.5 Name: TF - Show Arrows: false + Show Arrows: true Show Axes: true Show Names: true Tree: map: odom: zed_camera_center: - imu_link: - {} zed_left_camera_frame: zed_left_camera_optical_frame: {} @@ -165,7 +162,6 @@ Visualization Manager: TF: true Value: true Video: - Camera view: true Left camera: true Right camera: true Value: true @@ -258,7 +254,7 @@ Visualization Manager: Occlusion Time-Out: 30 Value: false Position Transformer: XYZ - Queue Size: 2 + Queue Size: 1 Selectable: true Size (Pixels): 1 Style: Points @@ -451,25 +447,25 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 1.35755372 + Distance: 18.398035 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 0.763631225 - Y: 1.1376406 - Z: 0.689015388 + X: -0.646270275 + Y: 1.53709924 + Z: -0.526653945 Focal Shape Fixed Size: false Focal Shape Size: 0.0500000007 Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 - Pitch: 0.0447975472 + Pitch: 0.289797693 Target Frame: Value: Orbit (rviz) - Yaw: 1.85410023 + Yaw: 1.33909941 Saved: ~ Window Geometry: Camera view: diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index dbd0d7a0..11355c6f 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -709,14 +709,8 @@ namespace zed_wrapper { mNhNs.getParam("pose_smoothing", mPoseSmoothing); mNhNs.getParam("spatial_memory", mSpatialMemory); mNhNs.getParam("floor_alignment", mFloorAlignment); - - if (mZedRealCamModel == sl::MODEL_ZED_M) { - mNhNs.getParam("init_odom_with_imu", mInitOdomWithPose); - NODELET_INFO_STREAM( - "Init Odometry with first IMU data : " << mInitOdomWithPose); - } else { - mInitOdomWithPose = false; - } + mNhNs.getParam("init_odom_with_imu", mInitOdomWithPose); + NODELET_INFO_STREAM("Init Odometry with first valid pose data : " << mInitOdomWithPose); if (mInitialTrackPose.size() != 6) { NODELET_WARN_STREAM("Invalid Initial Pose size (" << mInitialTrackPose.size() @@ -1754,6 +1748,9 @@ namespace zed_wrapper { } if (initOdom || mResetOdom) { + + ROS_INFO("Odometry aligned to last tracking pose"); + // Propagate Odom transform in time mBase2OdomTransf = base_to_map_transform; base_to_map_transform.setIdentity(); From d22831600ad42c689ca98bef5c5159f1a0cafac2 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Wed, 12 Sep 2018 16:29:52 +0200 Subject: [PATCH 40/55] Debug info --- zed_wrapper/launch/zed_camera.launch | 2 +- .../src/nodelet/src/zed_wrapper_nodelet.cpp | 24 ++++++++++++++----- 2 files changed, 19 insertions(+), 7 deletions(-) diff --git a/zed_wrapper/launch/zed_camera.launch b/zed_wrapper/launch/zed_camera.launch index f0373270..fe7df9be 100644 --- a/zed_wrapper/launch/zed_camera.launch +++ b/zed_wrapper/launch/zed_camera.launch @@ -132,7 +132,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - + diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index 11355c6f..d3a8fdc1 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -631,10 +631,15 @@ namespace zed_wrapper { // ROS pose tf2::Quaternion q; q.setRPY(rr, pr, yr); - tf2::Vector3 orig(xt, yt, zt); - mBase2OdomTransf.setOrigin(orig); - mBase2OdomTransf.setRotation(q); + //tf2::Vector3 orig(xt, yt, zt); + // mBase2OdomTransf.setOrigin(orig); + // mBase2OdomTransf.setRotation(q); + // mOdom2MapTransf.setIdentity(); + + mBase2OdomTransf.setIdentity(); + mBase2OdomTransf.setIdentity(); mOdom2MapTransf.setIdentity(); + // SL pose sl::float4 q_vec; q_vec[0] = q.x(); @@ -1707,7 +1712,7 @@ namespace zed_wrapper { publishOdom(mBase2OdomTransf, t); mTrackingReady = true; } else { - NODELET_DEBUG_STREAM("ODOM -> Tracking Status: " << static_cast(status)); + NODELET_DEBUG_STREAM("ODOM -> Tracking Status: " << sl::toString(status)); } } } @@ -1719,11 +1724,18 @@ namespace zed_wrapper { static sl::TRACKING_STATE oldStatus; sl::TRACKING_STATE status = mZed.getPosition(mLastZedPose, sl::REFERENCE_FRAME_WORLD); + sl::Translation translation = mLastZedPose.getTranslation(); + sl::Orientation quat = mLastZedPose.getOrientation(); + + NODELET_DEBUG("POSE [%s] - %.2f,%.2f,%.2f %.2f,%.2f,%.2f,%.2f", + sl::toString(status).c_str(), + translation(mIdxX), translation(mIdxY), translation(mIdxZ), + quat(mIdxX), quat(mIdxY), quat(mIdxZ), quat(3)); + if (status == sl::TRACKING_STATE_OK || status == sl::TRACKING_STATE_SEARCHING /*|| status == sl::TRACKING_STATE_FPS_TOO_LOW*/) { // Transform ZED pose in TF2 Transformation geometry_msgs::Transform sens2mapTransf; - sl::Translation translation = mLastZedPose.getTranslation(); - sl::Orientation quat = mLastZedPose.getOrientation(); + sens2mapTransf.translation.x = mSignX * translation(mIdxX); sens2mapTransf.translation.y = mSignY * translation(mIdxY); sens2mapTransf.translation.z = mSignZ * translation(mIdxZ); From b3b47b712116e7d7f8f13eaf5c012219067e2d84 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Thu, 13 Sep 2018 10:51:35 +0200 Subject: [PATCH 41/55] Added covariance * added covariance to odom message * added a pose with covariance message --- zed_display_rviz/rviz/zed.rviz | 20 +--- zed_display_rviz/rviz/zedm.rviz | 82 ++++++++++---- zed_wrapper/launch/zed_camera.launch | 2 +- .../nodelet/include/zed_wrapper_nodelet.hpp | 4 +- .../src/nodelet/src/zed_wrapper_nodelet.cpp | 104 +++++++++++++----- 5 files changed, 149 insertions(+), 63 deletions(-) diff --git a/zed_display_rviz/rviz/zed.rviz b/zed_display_rviz/rviz/zed.rviz index 092f9894..1e92abb7 100644 --- a/zed_display_rviz/rviz/zed.rviz +++ b/zed_display_rviz/rviz/zed.rviz @@ -1,6 +1,6 @@ Panels: - Class: rviz/Displays - Help Height: 78 + Help Height: 0 Name: Displays Property Tree Widget: Expanded: @@ -9,10 +9,9 @@ Panels: - /TF1/Frames1 - /Video1/Camera view1 - /Video1/Camera view1/Visibility1 - - /Depth1/DepthCloud1 - /Pose1 - Splitter Ratio: 0.5 - Tree Height: 485 + Splitter Ratio: 0.409937888 + Tree Height: 459 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -63,10 +62,6 @@ Visualization Manager: Expand Link Details: false Expand Tree: false Link Tree Style: Links in Alphabetic Order - imu_link: - Alpha: 1 - Show Axes: false - Show Trail: false zed_camera_center: Alpha: 1 Show Axes: false @@ -99,8 +94,6 @@ Visualization Manager: Frame Timeout: 5 Frames: All Enabled: false - imu_link: - Value: true map: Value: true odom: @@ -124,8 +117,6 @@ Visualization Manager: map: odom: zed_camera_center: - imu_link: - {} zed_left_camera_frame: zed_left_camera_optical_frame: {} @@ -165,7 +156,6 @@ Visualization Manager: TF: true Value: true Video: - Camera view: true Left camera: true Right camera: true Value: true @@ -269,7 +259,7 @@ Visualization Manager: - Class: rviz/Image Enabled: false Image Topic: /zed/depth/depth_registered - Max Value: 10 + Max Value: 5 Median window: 5 Min Value: 0 Name: Depth map @@ -464,7 +454,7 @@ Window Geometry: Hide Right Dock: false Left camera: collapsed: false - QMainWindow State: 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 + QMainWindow State: 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 Right camera: collapsed: false Selection: diff --git a/zed_display_rviz/rviz/zedm.rviz b/zed_display_rviz/rviz/zedm.rviz index de69505f..b10f54f8 100644 --- a/zed_display_rviz/rviz/zedm.rviz +++ b/zed_display_rviz/rviz/zedm.rviz @@ -9,10 +9,19 @@ Panels: - /TF1/Frames1 - /Video1/Camera view1 - /Video1/Camera view1/Visibility1 - - /Depth1 - /Depth1/DepthCloud1 + - /Pose1 + - /Pose1/Odometry1 + - /Pose1/Odometry1/Covariance1 + - /Pose1/Odometry1/Covariance1/Position1 + - /Pose1/Odometry1/Covariance1/Orientation1 + - /Pose1/Pose1 + - /Pose1/PoseWithCovariance1 + - /Pose1/PoseWithCovariance1/Covariance1 + - /Pose1/PoseWithCovariance1/Covariance1/Position1 + - /Pose1/PoseWithCovariance1/Covariance1/Orientation1 Splitter Ratio: 0.5 - Tree Height: 485 + Tree Height: 421 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -99,6 +108,8 @@ Visualization Manager: Frame Timeout: 5 Frames: All Enabled: false + imu_link: + Value: true map: Value: true odom: @@ -122,6 +133,8 @@ Visualization Manager: map: odom: zed_camera_center: + imu_link: + {} zed_left_camera_frame: zed_left_camera_optical_frame: {} @@ -157,6 +170,7 @@ Visualization Manager: Odometry Path: true Pose: true Pose Path: true + PoseWithCovariance: true Value: false RobotModel: false TF: true @@ -298,7 +312,7 @@ Visualization Manager: Transport Hint: raw Unreliable: true Value: false - Enabled: true + Enabled: false Name: Depth - Class: rviz/Group Displays: @@ -306,7 +320,7 @@ Visualization Manager: Buffer Length: 1 Class: rviz/Path Color: 255; 25; 0 - Enabled: true + Enabled: false Head Diameter: 0.0299999993 Head Length: 0.0199999996 Length: 0.300000012 @@ -324,22 +338,22 @@ Visualization Manager: Shaft Length: 0.0500000007 Topic: /zed/path_odom Unreliable: true - Value: true + Value: false - Angle Tolerance: 0 Class: rviz/Odometry Covariance: Orientation: Alpha: 0.5 Color: 255; 255; 127 - Color Style: Unique + Color Style: RGB Frame: Local - Offset: 1 - Scale: 1 + Offset: 0.150000006 + Scale: 20 Value: true Position: Alpha: 0.300000012 Color: 204; 51; 204 - Scale: 1 + Scale: 10 Value: true Value: true Enabled: true @@ -363,7 +377,7 @@ Visualization Manager: Buffer Length: 1 Class: rviz/Path Color: 25; 255; 0 - Enabled: true + Enabled: false Head Diameter: 0.0299999993 Head Length: 0.0199999996 Length: 0.300000012 @@ -381,13 +395,13 @@ Visualization Manager: Shaft Length: 0.0500000007 Topic: /zed/path_map Unreliable: true - Value: true + Value: false - Alpha: 1 Axes Length: 1 Axes Radius: 0.100000001 Class: rviz/Pose Color: 0; 255; 0 - Enabled: true + Enabled: false Head Length: 0.100000001 Head Radius: 0.0500000007 Name: Pose @@ -396,6 +410,36 @@ Visualization Manager: Shape: Arrow Topic: /zed/pose Unreliable: false + Value: false + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.100000001 + Class: rviz/PoseWithCovariance + Color: 25; 255; 0 + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 0.150000006 + Scale: 100 + Value: true + Position: + Alpha: 0.300000012 + Color: 204; 51; 204 + Scale: 100 + Value: true + Value: true + Enabled: true + Head Length: 0.100000001 + Head Radius: 0.0500000007 + Name: PoseWithCovariance + Shaft Length: 0.300000012 + Shaft Radius: 0.0199999996 + Shape: Arrow + Topic: /zed/pose_with_covariance + Unreliable: false Value: true - Acceleration properties: Acc. vector alpha: 1 @@ -447,25 +491,25 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 18.398035 + Distance: 1.48717809 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: -0.646270275 - Y: 1.53709924 - Z: -0.526653945 + X: -0.149202153 + Y: -0.131090492 + Z: 0.699279904 Focal Shape Fixed Size: false Focal Shape Size: 0.0500000007 Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 - Pitch: 0.289797693 + Pitch: 0.465398431 Target Frame: Value: Orbit (rviz) - Yaw: 1.33909941 + Yaw: 0.965398073 Saved: ~ Window Geometry: Camera view: @@ -483,7 +527,7 @@ Window Geometry: Hide Right Dock: false Left camera: collapsed: false - QMainWindow State: 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 + QMainWindow State: 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 Right camera: collapsed: false Selection: diff --git a/zed_wrapper/launch/zed_camera.launch b/zed_wrapper/launch/zed_camera.launch index fe7df9be..92c730fc 100644 --- a/zed_wrapper/launch/zed_camera.launch +++ b/zed_wrapper/launch/zed_camera.launch @@ -99,7 +99,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - + $(arg initial_pose) diff --git a/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp b/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp index f72b8ba5..e734c14d 100644 --- a/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp +++ b/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp @@ -88,9 +88,10 @@ namespace zed_wrapper { /* \brief Publish the pose of the camera in "Odom" frame with a ros Publisher * \param base2odomTransf : Transformation representing the camera pose * from base frame to odom frame + * \param slPose : latest odom pose from ZED SDK * \param t : the ros::Time to stamp the image */ - void publishOdom(tf2::Transform base2odomTransf, ros::Time t); + void publishOdom(tf2::Transform base2odomTransf, sl::Pose& slPose, ros::Time t); /* \brief Publish the pose of the camera in "Map" frame as a transformation * \param baseTransform : Transformation representing the camera pose from @@ -255,6 +256,7 @@ namespace zed_wrapper { ros::Publisher mPubRightCamInfoRaw; // ros::Publisher mPubDepthCamInfo; // ros::Publisher mPubPose; + ros::Publisher mPubPoseCov; ros::Publisher mPubOdom; ros::Publisher mPubOdomPath; ros::Publisher mPubMapPath; diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index d3a8fdc1..4f86b624 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -193,6 +193,7 @@ namespace zed_wrapper { string conf_img_topic = "confidence/confidence_image"; string conf_map_topic = "confidence/confidence_map"; string pose_topic = "pose"; + string pose_cov_topic = "pose_with_covariance"; string odometry_topic = "odom"; string odom_path_topic = "path_odom"; string map_path_topic = "path_map"; @@ -465,6 +466,8 @@ namespace zed_wrapper { // Odometry and Map publisher mPubPose = mNh.advertise(pose_topic, 1); NODELET_INFO_STREAM("Advertised on topic " << pose_topic); + mPubPoseCov = mNh.advertise(pose_cov_topic, 1); + NODELET_INFO_STREAM("Advertised on topic " << pose_cov_topic); mPubOdom = mNh.advertise(odometry_topic, 1); NODELET_INFO_STREAM("Advertised on topic " << odometry_topic); @@ -755,7 +758,7 @@ namespace zed_wrapper { NODELET_INFO("Tracking ENABLED"); } - void ZEDWrapperNodelet::publishOdom(tf2::Transform base2odomTransf, ros::Time t) { + void ZEDWrapperNodelet::publishOdom(tf2::Transform base2odomTransf, sl::Pose& slPose, ros::Time t) { nav_msgs::Odometry odom; odom.header.stamp = t; odom.header.frame_id = mOdometryFrameId; // odom_frame @@ -770,6 +773,18 @@ namespace zed_wrapper { odom.pose.pose.orientation.y = base2odom.rotation.y; odom.pose.pose.orientation.z = base2odom.rotation.z; odom.pose.pose.orientation.w = base2odom.rotation.w; + + // >>>>> Odometry pose covariance if available +#if ((ZED_SDK_MAJOR_VERSION>2) || (ZED_SDK_MAJOR_VERSION==2 && ZED_SDK_MINOR_VERSION>=6)) + if (!mSpatialMemory) { + for (size_t i = 0; i < odom.pose.covariance.size(); i++) { + // odom.pose.covariance[i] = static_cast(slPose.pose_covariance[i]); // TODO USE THIS WHEN STEP BY STEP COVARIANCE WILL BE AVAILABLE IN CAMERA_FRAME + odom.pose.covariance[i] = static_cast(mLastZedPose.pose_covariance[i]); + } + } +#endif + // <<<<< Odometry pose covariance if available + // Publish odometry message mPubOdom.publish(odom); } @@ -810,25 +825,56 @@ namespace zed_wrapper { } } - geometry_msgs::PoseStamped pose; + std_msgs::Header header; + header.stamp = mLastFrameTime; + header.frame_id = mPublishMapTf ? mMapFrameId : mOdometryFrameId; // frame - pose.header.stamp = mLastFrameTime; - pose.header.frame_id = mPublishMapTf ? mMapFrameId : mOdometryFrameId; // frame // conversion from Tranform to message geometry_msgs::Transform base2frame = tf2::toMsg(base_pose); + // Add all value in Pose message - pose.pose.position.x = base2frame.translation.x; - pose.pose.position.y = base2frame.translation.y; - pose.pose.position.z = base2frame.translation.z; - pose.pose.orientation.x = base2frame.rotation.x; - pose.pose.orientation.y = base2frame.rotation.y; - pose.pose.orientation.z = base2frame.rotation.z; - pose.pose.orientation.w = base2frame.rotation.w; - - // Publish pose stamped message - mPubPose.publish(pose); + geometry_msgs::Pose pose; + pose.position.x = base2frame.translation.x; + pose.position.y = base2frame.translation.y; + pose.position.z = base2frame.translation.z; + pose.orientation.x = base2frame.rotation.x; + pose.orientation.y = base2frame.rotation.y; + pose.orientation.z = base2frame.rotation.z; + pose.orientation.w = base2frame.rotation.w; + + if (mPubPose.getNumSubscribers() > 0) { + + geometry_msgs::PoseStamped poseNoCov; + + poseNoCov.header = header; + poseNoCov.pose = pose; + + // Publish pose stamped message + mPubPose.publish(poseNoCov); + } + + if (mPubPoseCov.getNumSubscribers() > 0) { + geometry_msgs::PoseWithCovarianceStamped poseCov; + + poseCov.header = header; + poseCov.pose.pose = pose; + + // >>>>> Odometry pose covariance if available +#if ((ZED_SDK_MAJOR_VERSION>2) || (ZED_SDK_MAJOR_VERSION==2 && ZED_SDK_MINOR_VERSION>=6)) + if (!mSpatialMemory) { + for (size_t i = 0; i < poseCov.pose.covariance.size(); i++) { + // odom.pose.covariance[i] = static_cast(slPose.pose_covariance[i]); // TODO USE THIS WHEN STEP BY STEP COVARIANCE WILL BE AVAILABLE IN CAMERA_FRAME + poseCov.pose.covariance[i] = static_cast(mLastZedPose.pose_covariance[i]); + } + } +#endif + // <<<<< Odometry pose covariance if available + + // Publish pose with covariance stamped message + mPubPoseCov.publish(poseCov); + } } - + void ZEDWrapperNodelet::publishOdomFrame(tf2::Transform odomTransf, ros::Time t) { geometry_msgs::TransformStamped transformStamped; transformStamped.header.stamp = t; @@ -1404,6 +1450,7 @@ namespace zed_wrapper { uint32_t disparitySubnumber = mPubDisparity.getNumSubscribers(); uint32_t cloudSubnumber = mPubCloud.getNumSubscribers(); uint32_t poseSubnumber = mPubPose.getNumSubscribers(); + uint32_t poseCovSubnumber = mPubPoseCov.getNumSubscribers(); uint32_t odomSubnumber = mPubOdom.getNumSubscribers(); uint32_t confImgSubnumber = mPubConfImg.getNumSubscribers(); uint32_t confMapSubnumber = mPubConfMap.getNumSubscribers(); @@ -1413,7 +1460,7 @@ namespace zed_wrapper { bool runLoop = ((rgbSubnumber + rgbRawSubnumber + leftSubnumber + leftRawSubnumber + rightSubnumber + rightRawSubnumber + depthSubnumber + disparitySubnumber + cloudSubnumber + - poseSubnumber + odomSubnumber + confImgSubnumber + + poseSubnumber + poseCovSubnumber + odomSubnumber + confImgSubnumber + confMapSubnumber + imuSubnumber + imuRawsubnumber + pathSubNumber) > 0); runParams.enable_point_cloud = false; @@ -1424,12 +1471,12 @@ namespace zed_wrapper { // Run the loop only if there is some subscribers if (runLoop) { - bool startTracking = (mDepthStabilization || poseSubnumber > 0 || odomSubnumber > 0 || - cloudSubnumber > 0 || depthSubnumber > 0 || pathSubNumber > 0); + bool startTracking = (mDepthStabilization || poseSubnumber > 0 || poseCovSubnumber > 0 || + odomSubnumber > 0 || cloudSubnumber > 0 || depthSubnumber > 0 || pathSubNumber > 0); if ((startTracking) && !mTrackingActivated) { // Start the tracking start_tracking(); - } else if (!mDepthStabilization && poseSubnumber == 0 && + } else if (!mDepthStabilization && poseSubnumber == 0 && poseCovSubnumber == 0 && odomSubnumber == 0 && mTrackingActivated) { // Stop the tracking mZed.disableTracking(); @@ -1438,7 +1485,7 @@ namespace zed_wrapper { // Detect if one of the subscriber need to have the depth information mComputeDepth = ((depthSubnumber + disparitySubnumber + cloudSubnumber + - poseSubnumber + odomSubnumber + confImgSubnumber + + poseSubnumber + poseCovSubnumber + odomSubnumber + confImgSubnumber + confMapSubnumber) > 0); // Timestamp @@ -1515,7 +1562,8 @@ namespace zed_wrapper { mTrackingActivated = false; - startTracking = mDepthStabilization || poseSubnumber > 0 || odomSubnumber > 0; + startTracking = mDepthStabilization || poseSubnumber > 0 || poseCovSubnumber > 0 || + odomSubnumber > 0; if (startTracking) { // Start the tracking start_tracking(); @@ -1661,7 +1709,7 @@ namespace zed_wrapper { } mCamDataMutex.unlock(); - + // Transform from base to sensor tf2::Transform sensor_to_base_transf; @@ -1680,9 +1728,9 @@ namespace zed_wrapper { NODELET_DEBUG("Transform error: %s", ex.what()); sensor_to_base_transf.setIdentity(); } - + // Publish the odometry if someone has subscribed to - if (poseSubnumber > 0 || odomSubnumber > 0 || cloudSubnumber > 0 || + if (poseSubnumber > 0 || poseCovSubnumber > 0 || odomSubnumber > 0 || cloudSubnumber > 0 || depthSubnumber > 0 || imuSubnumber > 0 || imuRawsubnumber > 0 || pathSubNumber > 0) { if (!mInitOdomWithPose) { sl::Pose deltaOdom; @@ -1709,7 +1757,7 @@ namespace zed_wrapper { // Propagate Odom transform in time mBase2OdomTransf = mBase2OdomTransf * deltaOdomTf_base; // Publish odometry message - publishOdom(mBase2OdomTransf, t); + publishOdom(mBase2OdomTransf, deltaOdom, t); mTrackingReady = true; } else { NODELET_DEBUG_STREAM("ODOM -> Tracking Status: " << sl::toString(status)); @@ -1718,7 +1766,7 @@ namespace zed_wrapper { } // Publish the zed camera pose if someone has subscribed to - if (poseSubnumber > 0 || odomSubnumber > 0 || cloudSubnumber > 0 || + if (poseSubnumber > 0 || odomSubnumber > 0 || poseCovSubnumber > 0 || cloudSubnumber > 0 || depthSubnumber > 0 || imuSubnumber > 0 || imuRawsubnumber > 0 || pathSubNumber > 0) { static sl::TRACKING_STATE oldStatus; @@ -1769,7 +1817,7 @@ namespace zed_wrapper { if (odomSubnumber > 0) { // Publish odometry message - publishOdom(mBase2OdomTransf, t); + publishOdom(mBase2OdomTransf, mLastZedPose, t); } mInitOdomWithPose = false; @@ -1790,6 +1838,8 @@ namespace zed_wrapper { oldStatus = status; } + + // Publish pose tf only if enabled if (mPublishTf) { // Note, the frame is published, but its values will only change if From dcf9b27cedcd58a3900d8bd7747628aeacd4774a Mon Sep 17 00:00:00 2001 From: Myzhar Date: Thu, 13 Sep 2018 12:32:53 +0200 Subject: [PATCH 42/55] Minor change --- zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index 4f86b624..d1e80feb 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -218,6 +218,7 @@ namespace zed_wrapper { mNhNs.getParam("confidence_map_topic", conf_map_topic); mNhNs.getParam("point_cloud_topic", point_cloud_topic); mNhNs.getParam("pose_topic", pose_topic); + pose_cov_topic = pose_topic + "_with_covariance"; mNhNs.getParam("odometry_topic", odometry_topic); mNhNs.getParam("imu_topic", imu_topic); mNhNs.getParam("imu_topic_raw", imu_topic_raw); From c443709d429b628b17c8397d5a9c8506683f78ae Mon Sep 17 00:00:00 2001 From: Myzhar Date: Fri, 14 Sep 2018 10:17:55 +0200 Subject: [PATCH 43/55] Manually merged `no_opencv` modifications --- zed_wrapper/CMakeLists.txt | 9 - zed_wrapper/README.md | 1 - zed_wrapper/package.xml | 1 - .../nodelet/include/zed_wrapper_nodelet.hpp | 25 +-- .../src/nodelet/src/zed_wrapper_nodelet.cpp | 112 +++++++----- zed_wrapper/src/tools/include/sl_tools.h | 13 +- zed_wrapper/src/tools/src/sl_tools.cpp | 168 ++++++++++-------- 7 files changed, 166 insertions(+), 163 deletions(-) diff --git a/zed_wrapper/CMakeLists.txt b/zed_wrapper/CMakeLists.txt index cb569fcf..cf8a81a7 100644 --- a/zed_wrapper/CMakeLists.txt +++ b/zed_wrapper/CMakeLists.txt @@ -27,11 +27,6 @@ if ( CMAKE_SYSTEM_NAME2 MATCHES "aarch64" ) # Jetson TX SET(CUDA_USE_STATIC_CUDA_RUNTIME OFF) endif() -find_package(OpenCV 3 COMPONENTS core highgui imgproc) -checkPackage("OPENCV_CORE" "OpenCV core not found, install it from the tutorial at:\n https://www.stereolabs.com/documentation/overview/getting-started/getting-started.html") -checkPackage("OPENCV_HIGHGUI" "OpenCV highgui not found, install it from the tutorial at:\n https://www.stereolabs.com/documentation/overview/getting-started/getting-started.html") -checkPackage("OPENCV_IMGPROC" "OpenCV imgproc not found, install it from the tutorial at:\n https://www.stereolabs.com/documentation/overview/getting-started/getting-started.html") - find_package(CUDA) checkPackage("CUDA" "CUDA not found, install it from:\n https://developer.nvidia.com/cuda-downloads") @@ -85,7 +80,6 @@ catkin_package( rosconsole sensor_msgs stereo_msgs - opencv3 image_transport dynamic_reconfigure tf2_ros @@ -111,14 +105,12 @@ include_directories( ${catkin_INCLUDE_DIRS} ${CUDA_INCLUDE_DIRS} ${ZED_INCLUDE_DIRS} - ${OpenCV_INCLUDE_DIRS} ${CMAKE_CURRENT_SOURCE_DIR}/src/tools/include ${CMAKE_CURRENT_SOURCE_DIR}/src/nodelet/include ) link_directories(${ZED_LIBRARY_DIR}) link_directories(${CUDA_LIBRARY_DIRS}) -link_directories(${OpenCV_LIBRARY_DIRS}) ############################################################################### @@ -136,7 +128,6 @@ set(LINK_LIBRARIES ${catkin_LIBRARIES} ${ZED_LIBRARIES} ${CUDA_LIBRARIES} ${CUDA_NPP_LIBRARIES_ZED} - ${OpenCV_LIBS} ) add_library(ZEDWrapper ${TOOLS_SRC} ${NODELET_SRC}) diff --git a/zed_wrapper/README.md b/zed_wrapper/README.md index b2528bad..cbddf841 100644 --- a/zed_wrapper/README.md +++ b/zed_wrapper/README.md @@ -27,7 +27,6 @@ The zed_ros_wrapper is a catkin package. It depends on the following ROS package - rosconsole - sensor_msgs - stereo_msgs - - opencv3 - image_transport - dynamic_reconfigure - urdf diff --git a/zed_wrapper/package.xml b/zed_wrapper/package.xml index 9ab9bace..19e34df7 100644 --- a/zed_wrapper/package.xml +++ b/zed_wrapper/package.xml @@ -17,7 +17,6 @@ rosconsole sensor_msgs stereo_msgs - opencv3 image_transport dynamic_reconfigure nodelet diff --git a/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp b/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp index e734c14d..b55233f4 100644 --- a/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp +++ b/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp @@ -44,8 +44,6 @@ #include #include -#include - #include #include #include @@ -115,7 +113,7 @@ namespace zed_wrapper { */ void publishImuFrame(tf2::Transform imuTransform, ros::Time t); - /* \brief Publish a cv::Mat image with a ros Publisher + /* \brief Publish a sl::Mat image with a ros Publisher * \param img : the image to publish * \param pub_img : the publisher object to use (different image publishers * exist) @@ -123,20 +121,19 @@ namespace zed_wrapper { * image frames exist) * \param t : the ros::Time to stamp the image */ - void publishImage(cv::Mat img, image_transport::Publisher& pubImg, - string imgFrameId, ros::Time t); + void publishImage(sl::Mat img, image_transport::Publisher& pubImg, string imgFrameId, ros::Time t); - /* \brief Publish a cv::Mat depth image with a ros Publisher + /* \brief Publish a sl::Mat depth image with a ros Publisher * \param depth : the depth image to publish * \param t : the ros::Time to stamp the depth image */ - void publishDepth(cv::Mat depth, ros::Time t); + void publishDepth(sl::Mat depth, ros::Time t); - /* \brief Publish a cv::Mat confidence image with a ros Publisher + /* \brief Publish a sl::Mat confidence image with a ros Publisher * \param conf : the confidence image to publish * \param t : the ros::Time to stamp the depth image */ - void publishConf(cv::Mat conf, ros::Time t); + void publishConf(sl::Mat conf, ros::Time t); /* \brief Publish a pointCloud with a ros Publisher */ @@ -150,11 +147,11 @@ namespace zed_wrapper { void publishCamInfo(sensor_msgs::CameraInfoPtr camInfoMsg, ros::Publisher pubCamInfo, ros::Time t); - /* \brief Publish a cv::Mat disparity image with a ros Publisher + /* \brief Publish a sl::Mat disparity image with a ros Publisher * \param disparity : the disparity image to publish * \param t : the ros::Time to stamp the depth image */ - void publishDisparity(cv::Mat disparity, ros::Time t); + void publishDisparity(sl::Mat disparity, ros::Time t); /* \brief Get the information of the ZED cameras and store them in an * information message @@ -380,15 +377,11 @@ namespace zed_wrapper { bool mInitOdomWithPose; bool mResetOdom = false; - // OpenCV Mat + // Mat int mCamWidth; int mCamHeight; int mMatWidth; int mMatHeight; - cv::Mat mCvLeftImRGB; - cv::Mat mCvRightImRGB; - cv::Mat mCvConfImRGB; - cv::Mat mCvConfMapFloat; // Thread Sync std::mutex mCamDataMutex; diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index d1e80feb..29a5c446 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -19,8 +19,6 @@ /////////////////////////////////////////////////////////////////////////// #include "zed_wrapper_nodelet.hpp" -#include - #ifndef NDEBUG #include #endif @@ -162,7 +160,8 @@ namespace zed_wrapper { // Status of odometry TF NODELET_INFO_STREAM("Broadcasting " << mOdometryFrameId << " [" << (mPublishTf ? "TRUE" : "FALSE") << "]"); // Status of map TF - NODELET_INFO_STREAM("Broadcasting " << mMapFrameId << " [" << ((mPublishTf && mPublishMapTf) ? "TRUE" : "FALSE") << "]"); + NODELET_INFO_STREAM("Broadcasting " << mMapFrameId << " [" << ((mPublishTf && + mPublishMapTf) ? "TRUE" : "FALSE") << "]"); std::string img_topic = "image_rect_color"; std::string img_raw_topic = "image_raw_color"; @@ -909,32 +908,55 @@ namespace zed_wrapper { mTransformImuBroadcaster.sendTransform(transformStamped); } - void ZEDWrapperNodelet::publishImage(cv::Mat img, + void ZEDWrapperNodelet::publishImage(sl::Mat img, image_transport::Publisher& pubImg, string imgFrameId, ros::Time t) { - pubImg.publish( - sl_tools::imageToROSmsg(img, sensor_msgs::image_encodings::BGR8, imgFrameId, t)); + pubImg.publish(sl_tools::imageToROSmsg(img, imgFrameId, t)); } - void ZEDWrapperNodelet::publishDepth(cv::Mat depth, ros::Time t) { - string encoding; + void ZEDWrapperNodelet::publishDepth(sl::Mat depth, ros::Time t) { - if (mOpenniDepthMode) { - depth *= 1000.0f; - depth.convertTo(depth, CV_16UC1); // in mm, rounded - encoding = sensor_msgs::image_encodings::TYPE_16UC1; - } else { - encoding = sensor_msgs::image_encodings::TYPE_32FC1; + if (!mOpenniDepthMode) { + mPubDepth.publish(sl_tools::imageToROSmsg(depth, mDepthOptFrameId, t)); + return; + } + + // OPENNI CONVERSION (meter -> millimeters - float32 -> uint16) + sensor_msgs::ImagePtr depthMessage = boost::make_shared(); + + depthMessage->header.stamp = t; + depthMessage->header.frame_id = mDepthOptFrameId; + depthMessage->height = depth.getHeight(); + depthMessage->width = depth.getWidth(); + + int num = 1; // for endianness detection + depthMessage->is_bigendian = !(*(char*)&num == 1); + + depthMessage->step = depthMessage->width * sizeof(uint16_t); + depthMessage->encoding = sensor_msgs::image_encodings::MONO16; + + size_t size = depthMessage->step * depthMessage->height; + depthMessage->data.resize(size); + + uint16_t* data = (uint16_t*)(&depthMessage->data[0]); + + int dataSize = depthMessage->width * depthMessage->height; + sl::float1* depthDataPtr = depth.getPtr(); + + for (int i = 0; i < dataSize; i++) { + *(data++) = static_cast(std::round(*(depthDataPtr++) * 1000)); // in mm, rounded } - mPubDepth.publish(sl_tools::imageToROSmsg(depth, encoding, mDepthOptFrameId, t)); + mPubDepth.publish(depthMessage); } - void ZEDWrapperNodelet::publishDisparity(cv::Mat disparity, ros::Time t) { + void ZEDWrapperNodelet::publishDisparity(sl::Mat disparity, ros::Time t) { + sl::CameraInformation zedParam = mZed.getCameraInformation(sl::Resolution(mMatWidth, mMatHeight)); - sensor_msgs::ImagePtr disparity_image = sl_tools::imageToROSmsg( - disparity, sensor_msgs::image_encodings::TYPE_32FC1, mDisparityFrameId, t); + + sensor_msgs::ImagePtr disparity_image = sl_tools::imageToROSmsg(disparity, mDisparityFrameId, t); + stereo_msgs::DisparityImage msg; msg.image = *disparity_image; msg.header = msg.image.header; @@ -1067,11 +1089,10 @@ namespace zed_wrapper { } if (rawParam) { - cv::Mat R_ = sl_tools::convertRodrigues(zedParam.R); - float* p = (float*)(R_.data); - - for (size_t i = 0; i < 9; i++) { - rightCamInfoMsg->R[i] = static_cast(p[i]); + std::vector R_ = sl_tools::convertRodrigues(zedParam.R); + float* p = R_.data(); + for (int i = 0; i < 9; i++) { + rightCamInfoMsg->R[i] = p[i]; } } @@ -1420,11 +1441,7 @@ namespace zed_wrapper { mMatWidth = static_cast(mCamWidth * mCamMatResizeFactor); mMatHeight = static_cast(mCamHeight * mCamMatResizeFactor); NODELET_DEBUG_STREAM("Data Mat size : " << mMatWidth << "x" << mMatHeight); - cv::Size cvSize(mMatWidth, mMatWidth); - mCvLeftImRGB = cv::Mat(cvSize, CV_8UC3); - mCvRightImRGB = cv::Mat(cvSize, CV_8UC3); - mCvConfImRGB = cv::Mat(cvSize, CV_8UC3); - mCvConfMapFloat = cv::Mat(cvSize, CV_32FC1); + // Create and fill the camera information messages fillCamInfo(mZed, mLeftCamInfoMsg, mRightCamInfoMsg, mLeftCamOptFrameId, mRightCamOptFrameId); @@ -1611,16 +1628,15 @@ namespace zed_wrapper { if (leftSubnumber > 0 || rgbSubnumber > 0) { // Retrieve RGBA Left image mZed.retrieveImage(leftZEDMat, sl::VIEW_LEFT, sl::MEM_CPU, mMatWidth, mMatHeight); - cv::cvtColor(sl_tools::toCVMat(leftZEDMat), mCvLeftImRGB, CV_RGBA2RGB); if (leftSubnumber > 0) { publishCamInfo(mLeftCamInfoMsg, mPubLeftCamInfo, t); - publishImage(mCvLeftImRGB, mPubLeft, mLeftCamOptFrameId, t); + publishImage(leftZEDMat, mPubLeft, mLeftCamOptFrameId, t); } if (rgbSubnumber > 0) { publishCamInfo(mRgbCamInfoMsg, mPubRgbCamInfo, t); - publishImage(mCvLeftImRGB, mPubRgb, mDepthOptFrameId, t); // rgb is the left image + publishImage(leftZEDMat, mPubRgb, mDepthOptFrameId, t); // rgb is the left image } } @@ -1628,16 +1644,15 @@ namespace zed_wrapper { if (leftRawSubnumber > 0 || rgbRawSubnumber > 0) { // Retrieve RGBA Left image mZed.retrieveImage(leftZEDMat, sl::VIEW_LEFT_UNRECTIFIED, sl::MEM_CPU, mMatWidth, mMatHeight); - cv::cvtColor(sl_tools::toCVMat(leftZEDMat), mCvLeftImRGB, CV_RGBA2RGB); if (leftRawSubnumber > 0) { publishCamInfo(mLeftCamInfoRawMsg, mPubLeftCamInfoRaw, t); - publishImage(mCvLeftImRGB, mPubRawLeft, mLeftCamOptFrameId, t); + publishImage(leftZEDMat, mPubRawLeft, mLeftCamOptFrameId, t); } if (rgbRawSubnumber > 0) { publishCamInfo(mRgbCamInfoRawMsg, mPubRgbCamInfoRaw, t); - publishImage(mCvLeftImRGB, mPubRawRgb, mDepthOptFrameId, t); + publishImage(leftZEDMat, mPubRawRgb, mDepthOptFrameId, t); } } @@ -1645,49 +1660,46 @@ namespace zed_wrapper { if (rightSubnumber > 0) { // Retrieve RGBA Right image mZed.retrieveImage(rightZEDMat, sl::VIEW_RIGHT, sl::MEM_CPU, mMatWidth, mMatHeight); - cv::cvtColor(sl_tools::toCVMat(rightZEDMat), mCvRightImRGB, CV_RGBA2RGB); + publishCamInfo(mRightCamInfoMsg, mPubRightCamInfo, t); - publishImage(mCvRightImRGB, mPubRight, mRightCamOptFrameId, t); + publishImage(rightZEDMat, mPubRight, mRightCamOptFrameId, t); } // Publish the right image if someone has subscribed to if (rightRawSubnumber > 0) { // Retrieve RGBA Right image mZed.retrieveImage(rightZEDMat, sl::VIEW_RIGHT_UNRECTIFIED, sl::MEM_CPU, mMatWidth, mMatHeight); - cv::cvtColor(sl_tools::toCVMat(rightZEDMat), mCvRightImRGB, CV_RGBA2RGB); + publishCamInfo(mRightCamInfoRawMsg, mPubRightCamInfoRaw, t); - publishImage(mCvRightImRGB, mPubRawRight, mRightCamOptFrameId, t); + publishImage(rightZEDMat, mPubRawRight, mRightCamOptFrameId, t); } // Publish the depth image if someone has subscribed to if (depthSubnumber > 0 || disparitySubnumber > 0) { mZed.retrieveMeasure(depthZEDMat, sl::MEASURE_DEPTH, sl::MEM_CPU, mMatWidth, mMatHeight); publishCamInfo(mDepthCamInfoMsg, mPubDepthCamInfo, t); - publishDepth(sl_tools::toCVMat(depthZEDMat), t); // in meters + publishDepth(depthZEDMat, t); // in meters } // Publish the disparity image if someone has subscribed to if (disparitySubnumber > 0) { mZed.retrieveMeasure(disparityZEDMat, sl::MEASURE_DISPARITY, sl::MEM_CPU, mMatWidth, mMatHeight); // Need to flip sign, but cause of this is not sure - cv::Mat disparity = sl_tools::toCVMat(disparityZEDMat) * -1.0; - publishDisparity(disparity, t); + publishDisparity(disparityZEDMat, t); } // Publish the confidence image if someone has subscribed to if (confImgSubnumber > 0) { mZed.retrieveImage(confImgZEDMat, sl::VIEW_CONFIDENCE, sl::MEM_CPU, mMatWidth, mMatHeight); - cv::cvtColor(sl_tools::toCVMat(confImgZEDMat), mCvConfImRGB, CV_RGBA2RGB); - publishImage(mCvConfImRGB, mPubConfImg, mConfidenceOptFrameId, t); + publishImage(confImgZEDMat, mPubConfImg, mConfidenceOptFrameId, t); } // Publish the confidence map if someone has subscribed to if (confMapSubnumber > 0) { mZed.retrieveMeasure(confMapZEDMat, sl::MEASURE_CONFIDENCE, sl::MEM_CPU, mMatWidth, mMatHeight); - mCvConfMapFloat = sl_tools::toCVMat(confMapZEDMat); - mPubConfMap.publish(sl_tools::imageToROSmsg( - mCvConfMapFloat, sensor_msgs::image_encodings::TYPE_32FC1, - mConfidenceOptFrameId, t)); + + + mPubConfMap.publish(sl_tools::imageToROSmsg(confMapZEDMat, mConfidenceOptFrameId, t)); } // Publish the point cloud if someone has subscribed to @@ -1737,7 +1749,8 @@ namespace zed_wrapper { sl::Pose deltaOdom; sl::TRACKING_STATE status = mZed.getPosition(deltaOdom, sl::REFERENCE_FRAME_CAMERA); - if (status == sl::TRACKING_STATE_OK || status == sl::TRACKING_STATE_SEARCHING || status == sl::TRACKING_STATE_FPS_TOO_LOW) { + if (status == sl::TRACKING_STATE_OK || status == sl::TRACKING_STATE_SEARCHING || + status == sl::TRACKING_STATE_FPS_TOO_LOW) { // Transform ZED delta odom pose in TF2 Transformation geometry_msgs::Transform deltaTransf; sl::Translation translation = deltaOdom.getTranslation(); @@ -1781,7 +1794,8 @@ namespace zed_wrapper { translation(mIdxX), translation(mIdxY), translation(mIdxZ), quat(mIdxX), quat(mIdxY), quat(mIdxZ), quat(3)); - if (status == sl::TRACKING_STATE_OK || status == sl::TRACKING_STATE_SEARCHING /*|| status == sl::TRACKING_STATE_FPS_TOO_LOW*/) { + if (status == sl::TRACKING_STATE_OK || + status == sl::TRACKING_STATE_SEARCHING /*|| status == sl::TRACKING_STATE_FPS_TOO_LOW*/) { // Transform ZED pose in TF2 Transformation geometry_msgs::Transform sens2mapTransf; diff --git a/zed_wrapper/src/tools/include/sl_tools.h b/zed_wrapper/src/tools/include/sl_tools.h index d372141b..d8fb0b4f 100644 --- a/zed_wrapper/src/tools/include/sl_tools.h +++ b/zed_wrapper/src/tools/include/sl_tools.h @@ -21,7 +21,6 @@ // /////////////////////////////////////////////////////////////////////////// -#include #include #include #include @@ -39,12 +38,7 @@ namespace sl_tools { */ sl::DeviceProperties getZEDFromSN(unsigned int serial_number); - /* \brief Convert an sl:Mat to a cv::Mat - * \param mat : the sl::Mat to convert - */ - cv::Mat toCVMat(sl::Mat& mat); - - cv::Mat convertRodrigues(sl::float3 r); + std::vector convertRodrigues(sl::float3 r); /* \brief Test if a file exist * \param name : the path to the file @@ -65,13 +59,10 @@ namespace sl_tools { /* \brief Image to ros message conversion * \param img : the image to publish - * \param encodingType : the sensor_msgs::image_encodings encoding type * \param frameId : the id of the reference frame of the image * \param t : the ros::Time to stamp the image */ - sensor_msgs::ImagePtr imageToROSmsg(cv::Mat img, - const std::string encodingType, - std::string frameId, ros::Time t); + sensor_msgs::ImagePtr imageToROSmsg(sl::Mat img, std::string frameId, ros::Time t); } // namespace diff --git a/zed_wrapper/src/tools/src/sl_tools.cpp b/zed_wrapper/src/tools/src/sl_tools.cpp index eecb72ad..cd4cd713 100644 --- a/zed_wrapper/src/tools/src/sl_tools.cpp +++ b/zed_wrapper/src/tools/src/sl_tools.cpp @@ -24,6 +24,8 @@ #include #include +#include + #include namespace sl_tools { @@ -55,66 +57,30 @@ namespace sl_tools { return prop; } - cv::Mat toCVMat(sl::Mat& mat) { - if (mat.getMemoryType() == sl::MEM_GPU) { - mat.updateCPUfromGPU(); - } - - int cvType; - - switch (mat.getDataType()) { - case sl::MAT_TYPE_32F_C1: - cvType = CV_32FC1; - break; - - case sl::MAT_TYPE_32F_C2: - cvType = CV_32FC2; - break; - - case sl::MAT_TYPE_32F_C3: - cvType = CV_32FC3; - break; - - case sl::MAT_TYPE_32F_C4: - cvType = CV_32FC4; - break; - - case sl::MAT_TYPE_8U_C1: - cvType = CV_8UC1; - break; - - case sl::MAT_TYPE_8U_C2: - cvType = CV_8UC2; - break; - - case sl::MAT_TYPE_8U_C3: - cvType = CV_8UC3; - break; - - case sl::MAT_TYPE_8U_C4: - cvType = CV_8UC4; - break; - } - - return cv::Mat((int)mat.getHeight(), (int)mat.getWidth(), cvType, - mat.getPtr(sl::MEM_CPU), - mat.getStepBytes(sl::MEM_CPU)); - } + std::vector convertRodrigues(sl::float3 r) { + float theta = sqrt(r.x * r.x + r.y * r.y + r.z * r.z); - cv::Mat convertRodrigues(sl::float3 r) { - double theta = sqrt(r.x * r.x + r.y * r.y + r.z * r.z); - cv::Mat R = cv::Mat::eye(3, 3, CV_32F); + std::vector R = {1.0f, 0.0f, 0.0f, + 0.0f, 1.0f, 0.0f, + 0.0f, 0.0f, 1.0f + }; if (theta < DBL_EPSILON) { return R; } else { - double c = cos(theta); - double s = sin(theta); - double c1 = 1. - c; - double itheta = theta ? 1. / theta : 0.; + float c = cos(theta); + float s = sin(theta); + float c1 = 1.f - c; + float itheta = theta ? 1.f / theta : 0.f; + r *= itheta; - cv::Mat rrt = cv::Mat::eye(3, 3, CV_32F); - float* p = (float*)rrt.data; + + std::vector rrt = {1.0f, 0.0f, 0.0f, + 0.0f, 1.0f, 0.0f, + 0.0f, 0.0f, 1.0f + }; + + float* p = rrt.data(); p[0] = r.x * r.x; p[1] = r.x * r.y; p[2] = r.x * r.z; @@ -124,8 +90,12 @@ namespace sl_tools { p[6] = r.x * r.z; p[7] = r.y * r.z; p[8] = r.z * r.z; - cv::Mat r_x = cv::Mat::eye(3, 3, CV_32F); - p = (float*)r_x.data; + + std::vector r_x = {1.0f, 0.0f, 0.0f, + 0.0f, 1.0f, 0.0f, + 0.0f, 0.0f, 1.0f + }; + p = r_x.data(); p[0] = 0; p[1] = -r.z; p[2] = r.y; @@ -135,13 +105,33 @@ namespace sl_tools { p[6] = -r.y; p[7] = r.x; p[8] = 0; + // R = cos(theta)*I + (1 - cos(theta))*r*rT + sin(theta)*[r_x] - R = c * cv::Mat::eye(3, 3, CV_32F) + c1 * rrt + s * r_x; + + sl::Matrix3f eye; + eye.setIdentity(); + + sl::Matrix3f sl_R(R.data()); + sl::Matrix3f sl_rrt(rrt.data()); + sl::Matrix3f sl_r_x(r_x.data()); + + sl_R = eye * c + sl_rrt * c1 + sl_r_x * s; + + R[0] = sl_R.r00; + R[1] = sl_R.r01; + R[2] = sl_R.r02; + R[3] = sl_R.r10; + R[4] = sl_R.r11; + R[5] = sl_R.r12; + R[6] = sl_R.r20; + R[7] = sl_R.r21; + R[8] = sl_R.r22; } return R; } + bool file_exist(const std::string& name) { struct stat buffer; return (stat(name.c_str(), &buffer) == 0); @@ -181,33 +171,59 @@ namespace sl_tools { return ros::Time(sec, nsec); } - sensor_msgs::ImagePtr imageToROSmsg(cv::Mat img, const std::string encodingType, - std::string frameId, ros::Time t) { + sensor_msgs::ImagePtr imageToROSmsg(sl::Mat img, std::string frameId, ros::Time t) { + sensor_msgs::ImagePtr ptr = boost::make_shared(); sensor_msgs::Image& imgMessage = *ptr; + imgMessage.header.stamp = t; imgMessage.header.frame_id = frameId; - imgMessage.height = static_cast(img.rows); - imgMessage.width = static_cast(img.cols); - imgMessage.encoding = encodingType; + imgMessage.height = img.getHeight(); + imgMessage.width = img.getWidth(); + int num = 1; // for endianness detection imgMessage.is_bigendian = !(*(char*)&num == 1); - imgMessage.step = static_cast(img.step); - size_t size = imgMessage.step * img.rows; + + imgMessage.step = img.getStepBytes(); + + size_t size = imgMessage.step * imgMessage.height; imgMessage.data.resize(size); - if (img.isContinuous()) { - memcpy((char*)(&imgMessage.data[0]), img.data, size); - } else { - uchar* opencvData = img.data; - uchar* rosData = (uchar*)(&imgMessage.data[0]); - - #pragma omp parallel for - for (unsigned int i = 0; i < img.rows; i++) { - memcpy(rosData, opencvData, imgMessage.step); - rosData += imgMessage.step; - opencvData += img.step; - } + sl::MAT_TYPE dataType = img.getDataType(); + + switch (dataType) { + case sl::MAT_TYPE_32F_C1: /**< float 1 channel.*/ + imgMessage.encoding = sensor_msgs::image_encodings::TYPE_32FC1; + memcpy((char*)(&imgMessage.data[0]), img.getPtr(), size); + break; + case sl::MAT_TYPE_32F_C2: /**< float 2 channels.*/ + imgMessage.encoding = sensor_msgs::image_encodings::TYPE_32FC2; + memcpy((char*)(&imgMessage.data[0]), img.getPtr(), size); + break; + case sl::MAT_TYPE_32F_C3: /**< float 3 channels.*/ + imgMessage.encoding = sensor_msgs::image_encodings::TYPE_32FC3; + memcpy((char*)(&imgMessage.data[0]), img.getPtr(), size); + break; + case sl::MAT_TYPE_32F_C4: /**< float 4 channels.*/ + imgMessage.encoding = sensor_msgs::image_encodings::TYPE_32FC4; + memcpy((char*)(&imgMessage.data[0]), img.getPtr(), size); + break; + case sl::MAT_TYPE_8U_C1: /**< unsigned char 1 channel.*/ + imgMessage.encoding = sensor_msgs::image_encodings::MONO8; + memcpy((char*)(&imgMessage.data[0]), img.getPtr(), size); + break; + case sl::MAT_TYPE_8U_C2: /**< unsigned char 2 channels.*/ + imgMessage.encoding = sensor_msgs::image_encodings::TYPE_8UC2; + memcpy((char*)(&imgMessage.data[0]), img.getPtr(), size); + break; + case sl::MAT_TYPE_8U_C3: /**< unsigned char 3 channels.*/ + imgMessage.encoding = sensor_msgs::image_encodings::BGR8; + memcpy((char*)(&imgMessage.data[0]), img.getPtr(), size); + break; + case sl::MAT_TYPE_8U_C4: /**< unsigned char 4 channels.*/ + imgMessage.encoding = sensor_msgs::image_encodings::BGRA8; + memcpy((char*)(&imgMessage.data[0]), img.getPtr(), size); + break; } return ptr; From 7a31aa7a18e9a25100edc6d09798907817090593 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Fri, 14 Sep 2018 10:40:45 +0200 Subject: [PATCH 44/55] Updated the version of the packages Added missing Copyright information --- examples/zed_nodelet_example/package.xml | 2 +- examples/zed_rtabmap_example/package.xml | 2 +- tutorials/zed_depth_sub_tutorial/package.xml | 2 +- .../src/zed_depth_sub_tutorial.cpp | 23 +++++++++++++-- .../zed_tracking_sub_tutorial/package.xml | 2 +- .../src/zed_tracking_sub_tutorial.cpp | 29 +++++++++++++++---- tutorials/zed_video_sub_tutorial/package.xml | 2 +- .../src/zed_video_sub_tutorial.cpp | 23 +++++++++++++-- zed_display_rviz/package.xml | 2 +- zed_wrapper/package.xml | 2 +- .../src/nodelet/src/zed_wrapper_nodelet.cpp | 1 + 11 files changed, 74 insertions(+), 16 deletions(-) diff --git a/examples/zed_nodelet_example/package.xml b/examples/zed_nodelet_example/package.xml index 75908476..c4ef8a49 100644 --- a/examples/zed_nodelet_example/package.xml +++ b/examples/zed_nodelet_example/package.xml @@ -1,7 +1,7 @@ zed_nodelet_example - 1.0.0 + 2.6.0 "zed_nodelet_example" is a ROS package to illustrate how to load the ZEDWrapperNodelet with an external nodelet manager and use the intraprocess communication. diff --git a/examples/zed_rtabmap_example/package.xml b/examples/zed_rtabmap_example/package.xml index 822cb27a..56fb99ff 100644 --- a/examples/zed_rtabmap_example/package.xml +++ b/examples/zed_rtabmap_example/package.xml @@ -1,7 +1,7 @@ zed_rtabmap_example - 1.0.0 + 2.6.0 "zed_rtabmap_example" is a ROS package to show how to use the ROS wrapper with "RTAB-MAP" diff --git a/tutorials/zed_depth_sub_tutorial/package.xml b/tutorials/zed_depth_sub_tutorial/package.xml index 6b0989da..7a54f007 100644 --- a/tutorials/zed_depth_sub_tutorial/package.xml +++ b/tutorials/zed_depth_sub_tutorial/package.xml @@ -1,6 +1,6 @@ zed_depth_sub_tutorial - 1.0.0 + 2.6.0 This package is a tutorial showing how to subscribe to ZED depth streams diff --git a/tutorials/zed_depth_sub_tutorial/src/zed_depth_sub_tutorial.cpp b/tutorials/zed_depth_sub_tutorial/src/zed_depth_sub_tutorial.cpp index 6b057cbd..1494fce7 100644 --- a/tutorials/zed_depth_sub_tutorial/src/zed_depth_sub_tutorial.cpp +++ b/tutorials/zed_depth_sub_tutorial/src/zed_depth_sub_tutorial.cpp @@ -1,10 +1,29 @@ -#include -#include +/////////////////////////////////////////////////////////////////////////// +// +// Copyright (c) 2018, STEREOLABS. +// +// All rights reserved. +// +// 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. +// +/////////////////////////////////////////////////////////////////////////// /** * This tutorial demonstrates simple receipt of ZED depth messages over the ROS system. */ +#include +#include /** * Subscriber callback diff --git a/tutorials/zed_tracking_sub_tutorial/package.xml b/tutorials/zed_tracking_sub_tutorial/package.xml index 09160220..3220734c 100644 --- a/tutorials/zed_tracking_sub_tutorial/package.xml +++ b/tutorials/zed_tracking_sub_tutorial/package.xml @@ -1,6 +1,6 @@ zed_tracking_sub_tutorial - 1.0.0 + 2.6.0 This package is a tutorial showing how to subscribe to ZED positional tracking data streams diff --git a/tutorials/zed_tracking_sub_tutorial/src/zed_tracking_sub_tutorial.cpp b/tutorials/zed_tracking_sub_tutorial/src/zed_tracking_sub_tutorial.cpp index f60dd41f..0d06e646 100644 --- a/tutorials/zed_tracking_sub_tutorial/src/zed_tracking_sub_tutorial.cpp +++ b/tutorials/zed_tracking_sub_tutorial/src/zed_tracking_sub_tutorial.cpp @@ -1,3 +1,27 @@ +/////////////////////////////////////////////////////////////////////////// +// +// Copyright (c) 2018, STEREOLABS. +// +// All rights reserved. +// +// 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. +// +/////////////////////////////////////////////////////////////////////////// + +/** + * This tutorial demonstrates simple receipt of ZED odom and pose messages over the ROS system. + */ + #include #include #include @@ -9,11 +33,6 @@ #define RAD2DEG 57.295779513 -/** - * This tutorial demonstrates simple receipt of ZED odom and pose messages over the ROS system. - */ - - /** * Subscriber callbacks */ diff --git a/tutorials/zed_video_sub_tutorial/package.xml b/tutorials/zed_video_sub_tutorial/package.xml index 2c7c7a56..b52e5fee 100644 --- a/tutorials/zed_video_sub_tutorial/package.xml +++ b/tutorials/zed_video_sub_tutorial/package.xml @@ -1,6 +1,6 @@ zed_video_sub_tutorial - 1.0.0 + 2.6.0 This package is a tutorial showing how to subscribe to ZED Video streams diff --git a/tutorials/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp b/tutorials/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp index 4f0c38b8..7c3c9fac 100644 --- a/tutorials/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp +++ b/tutorials/zed_video_sub_tutorial/src/zed_video_sub_tutorial.cpp @@ -1,11 +1,30 @@ -#include -#include +/////////////////////////////////////////////////////////////////////////// +// +// Copyright (c) 2018, STEREOLABS. +// +// All rights reserved. +// +// 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. +// +/////////////////////////////////////////////////////////////////////////// /** * This tutorial demonstrates how to receive the Left and Right rectified images * from the ZED node */ +#include +#include /** * Subscriber callbacks. The argument of the callback is a constant pointer to the received message diff --git a/zed_display_rviz/package.xml b/zed_display_rviz/package.xml index 468d24b1..0a79068f 100644 --- a/zed_display_rviz/package.xml +++ b/zed_display_rviz/package.xml @@ -1,7 +1,7 @@ zed_display_rviz - 1.0.0 + 2.6.0 "zed_display" is a ROS package to visualize in Rviz the information from the "zed_wrapper" node diff --git a/zed_wrapper/package.xml b/zed_wrapper/package.xml index 19e34df7..2c480020 100644 --- a/zed_wrapper/package.xml +++ b/zed_wrapper/package.xml @@ -1,7 +1,7 @@ zed_wrapper - 1.0.0 + 2.6.0 zed_wrapper is a ROS wrapper for the ZED library for interfacing with the ZED camera. diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index 29a5c446..c6ad560a 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -17,6 +17,7 @@ // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. // /////////////////////////////////////////////////////////////////////////// + #include "zed_wrapper_nodelet.hpp" #ifndef NDEBUG From a6887e53b02d336f06aa7b4f3adad150ce25235a Mon Sep 17 00:00:00 2001 From: Myzhar Date: Fri, 14 Sep 2018 10:44:51 +0200 Subject: [PATCH 45/55] Updated email in package.xml --- examples/zed_nodelet_example/package.xml | 2 +- examples/zed_rtabmap_example/package.xml | 2 +- tutorials/zed_depth_sub_tutorial/package.xml | 2 +- tutorials/zed_tracking_sub_tutorial/package.xml | 2 +- tutorials/zed_video_sub_tutorial/package.xml | 2 +- zed_display_rviz/package.xml | 2 +- zed_wrapper/package.xml | 3 ++- 7 files changed, 8 insertions(+), 7 deletions(-) diff --git a/examples/zed_nodelet_example/package.xml b/examples/zed_nodelet_example/package.xml index c4ef8a49..7071e4dd 100644 --- a/examples/zed_nodelet_example/package.xml +++ b/examples/zed_nodelet_example/package.xml @@ -5,7 +5,7 @@ "zed_nodelet_example" is a ROS package to illustrate how to load the ZEDWrapperNodelet with an external nodelet manager and use the intraprocess communication. - STEREOLABS + STEREOLABS BSD catkin diff --git a/examples/zed_rtabmap_example/package.xml b/examples/zed_rtabmap_example/package.xml index 56fb99ff..34c59f56 100644 --- a/examples/zed_rtabmap_example/package.xml +++ b/examples/zed_rtabmap_example/package.xml @@ -5,7 +5,7 @@ "zed_rtabmap_example" is a ROS package to show how to use the ROS wrapper with "RTAB-MAP" - STEREOLABS + STEREOLABS BSD catkin diff --git a/tutorials/zed_depth_sub_tutorial/package.xml b/tutorials/zed_depth_sub_tutorial/package.xml index 7a54f007..4de7c1f4 100644 --- a/tutorials/zed_depth_sub_tutorial/package.xml +++ b/tutorials/zed_depth_sub_tutorial/package.xml @@ -4,7 +4,7 @@ This package is a tutorial showing how to subscribe to ZED depth streams - STEREOLABS + STEREOLABS BSD catkin diff --git a/tutorials/zed_tracking_sub_tutorial/package.xml b/tutorials/zed_tracking_sub_tutorial/package.xml index 3220734c..c060169c 100644 --- a/tutorials/zed_tracking_sub_tutorial/package.xml +++ b/tutorials/zed_tracking_sub_tutorial/package.xml @@ -4,7 +4,7 @@ This package is a tutorial showing how to subscribe to ZED positional tracking data streams - STEREOLABS + STEREOLABS BSD catkin diff --git a/tutorials/zed_video_sub_tutorial/package.xml b/tutorials/zed_video_sub_tutorial/package.xml index b52e5fee..d8ac4282 100644 --- a/tutorials/zed_video_sub_tutorial/package.xml +++ b/tutorials/zed_video_sub_tutorial/package.xml @@ -4,7 +4,7 @@ This package is a tutorial showing how to subscribe to ZED Video streams - STEREOLABS + STEREOLABS BSD catkin diff --git a/zed_display_rviz/package.xml b/zed_display_rviz/package.xml index 0a79068f..d5c24807 100644 --- a/zed_display_rviz/package.xml +++ b/zed_display_rviz/package.xml @@ -5,7 +5,7 @@ "zed_display" is a ROS package to visualize in Rviz the information from the "zed_wrapper" node - STEREOLABS + STEREOLABS BSD catkin diff --git a/zed_wrapper/package.xml b/zed_wrapper/package.xml index 2c480020..cc7e6ca0 100644 --- a/zed_wrapper/package.xml +++ b/zed_wrapper/package.xml @@ -5,7 +5,7 @@ zed_wrapper is a ROS wrapper for the ZED library for interfacing with the ZED camera. -STEREOLABS + STEREOLABS BSD catkin @@ -23,6 +23,7 @@ urdf message_generation + robot_state_publisher message_runtime From e48fe04985962dbbdbafe876a537a0b5336eb182 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Fri, 14 Sep 2018 10:47:00 +0200 Subject: [PATCH 46/55] Changed email adresses. ROS doesn't accept "support at stereolabs.com" --- examples/zed_nodelet_example/package.xml | 2 +- examples/zed_rtabmap_example/package.xml | 2 +- tutorials/zed_depth_sub_tutorial/package.xml | 2 +- tutorials/zed_tracking_sub_tutorial/package.xml | 2 +- tutorials/zed_video_sub_tutorial/package.xml | 2 +- zed_display_rviz/package.xml | 2 +- zed_wrapper/package.xml | 2 +- 7 files changed, 7 insertions(+), 7 deletions(-) diff --git a/examples/zed_nodelet_example/package.xml b/examples/zed_nodelet_example/package.xml index 7071e4dd..f274822a 100644 --- a/examples/zed_nodelet_example/package.xml +++ b/examples/zed_nodelet_example/package.xml @@ -5,7 +5,7 @@ "zed_nodelet_example" is a ROS package to illustrate how to load the ZEDWrapperNodelet with an external nodelet manager and use the intraprocess communication. - STEREOLABS + STEREOLABS BSD catkin diff --git a/examples/zed_rtabmap_example/package.xml b/examples/zed_rtabmap_example/package.xml index 34c59f56..6e552beb 100644 --- a/examples/zed_rtabmap_example/package.xml +++ b/examples/zed_rtabmap_example/package.xml @@ -5,7 +5,7 @@ "zed_rtabmap_example" is a ROS package to show how to use the ROS wrapper with "RTAB-MAP" - STEREOLABS + STEREOLABS BSD catkin diff --git a/tutorials/zed_depth_sub_tutorial/package.xml b/tutorials/zed_depth_sub_tutorial/package.xml index 4de7c1f4..7a54f007 100644 --- a/tutorials/zed_depth_sub_tutorial/package.xml +++ b/tutorials/zed_depth_sub_tutorial/package.xml @@ -4,7 +4,7 @@ This package is a tutorial showing how to subscribe to ZED depth streams - STEREOLABS + STEREOLABS BSD catkin diff --git a/tutorials/zed_tracking_sub_tutorial/package.xml b/tutorials/zed_tracking_sub_tutorial/package.xml index c060169c..3220734c 100644 --- a/tutorials/zed_tracking_sub_tutorial/package.xml +++ b/tutorials/zed_tracking_sub_tutorial/package.xml @@ -4,7 +4,7 @@ This package is a tutorial showing how to subscribe to ZED positional tracking data streams - STEREOLABS + STEREOLABS BSD catkin diff --git a/tutorials/zed_video_sub_tutorial/package.xml b/tutorials/zed_video_sub_tutorial/package.xml index d8ac4282..b52e5fee 100644 --- a/tutorials/zed_video_sub_tutorial/package.xml +++ b/tutorials/zed_video_sub_tutorial/package.xml @@ -4,7 +4,7 @@ This package is a tutorial showing how to subscribe to ZED Video streams - STEREOLABS + STEREOLABS BSD catkin diff --git a/zed_display_rviz/package.xml b/zed_display_rviz/package.xml index d5c24807..690430df 100644 --- a/zed_display_rviz/package.xml +++ b/zed_display_rviz/package.xml @@ -5,7 +5,7 @@ "zed_display" is a ROS package to visualize in Rviz the information from the "zed_wrapper" node - STEREOLABS + STEREOLABS BSD catkin diff --git a/zed_wrapper/package.xml b/zed_wrapper/package.xml index cc7e6ca0..f92ff988 100644 --- a/zed_wrapper/package.xml +++ b/zed_wrapper/package.xml @@ -5,7 +5,7 @@ zed_wrapper is a ROS wrapper for the ZED library for interfacing with the ZED camera. - STEREOLABS + STEREOLABS BSD catkin From 735c3aec0369534d853a85bf6700841f72cd4b83 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Fri, 14 Sep 2018 11:07:04 +0200 Subject: [PATCH 47/55] Added `zer_ros` meta-package --- zed_ros/CMakeLists.txt | 4 ++++ zed_ros/package.xml | 22 ++++++++++++++++++++++ 2 files changed, 26 insertions(+) create mode 100644 zed_ros/CMakeLists.txt create mode 100644 zed_ros/package.xml diff --git a/zed_ros/CMakeLists.txt b/zed_ros/CMakeLists.txt new file mode 100644 index 00000000..b983ecce --- /dev/null +++ b/zed_ros/CMakeLists.txt @@ -0,0 +1,4 @@ +cmake_minimum_required(VERSION 2.8.3) +project(zed_ros) +find_package(catkin REQUIRED) +catkin_metapackage() diff --git a/zed_ros/package.xml b/zed_ros/package.xml new file mode 100644 index 00000000..8c1e7a6a --- /dev/null +++ b/zed_ros/package.xml @@ -0,0 +1,22 @@ + + + zed_ros + 2.6.0 + Stereolabs zed-ros-wrapper support meta package + + STEREOLABS + BSD + + http://stereolabs.com/rc_visard + https://github.com/stereolabs/zed-ros-wrapper + https://github.com/stereolabs/zed-ros-wrapper/issues + + catkin + + zed_wrapper + zed_display_rviz + + + + + From b9c321c2a7eb8d2b1a0a175bcf5bf4b48fe41f1a Mon Sep 17 00:00:00 2001 From: Myzhar Date: Fri, 14 Sep 2018 11:07:04 +0200 Subject: [PATCH 48/55] Added `zed_ros` meta-package --- zed_ros/CMakeLists.txt | 4 ++++ zed_ros/package.xml | 22 ++++++++++++++++++++++ 2 files changed, 26 insertions(+) create mode 100644 zed_ros/CMakeLists.txt create mode 100644 zed_ros/package.xml diff --git a/zed_ros/CMakeLists.txt b/zed_ros/CMakeLists.txt new file mode 100644 index 00000000..b983ecce --- /dev/null +++ b/zed_ros/CMakeLists.txt @@ -0,0 +1,4 @@ +cmake_minimum_required(VERSION 2.8.3) +project(zed_ros) +find_package(catkin REQUIRED) +catkin_metapackage() diff --git a/zed_ros/package.xml b/zed_ros/package.xml new file mode 100644 index 00000000..8c1e7a6a --- /dev/null +++ b/zed_ros/package.xml @@ -0,0 +1,22 @@ + + + zed_ros + 2.6.0 + Stereolabs zed-ros-wrapper support meta package + + STEREOLABS + BSD + + http://stereolabs.com/rc_visard + https://github.com/stereolabs/zed-ros-wrapper + https://github.com/stereolabs/zed-ros-wrapper/issues + + catkin + + zed_wrapper + zed_display_rviz + + + + + From b21717cec038f227ddc069377b7e15e64ed69c6b Mon Sep 17 00:00:00 2001 From: Myzhar Date: Fri, 14 Sep 2018 17:53:59 +0200 Subject: [PATCH 49/55] Minor fixes --- zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp | 1 + zed_wrapper/src/tools/include/sl_tools.h | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index c6ad560a..31e6e600 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -1153,6 +1153,7 @@ namespace zed_wrapper { mMatWidth = static_cast(mCamWidth * mCamMatResizeFactor); mMatHeight = static_cast(mCamHeight * mCamMatResizeFactor); NODELET_DEBUG_STREAM("Data Mat size : " << mMatWidth << "x" << mMatHeight); + // Update Camera Info fillCamInfo(mZed, mLeftCamInfoMsg, mRightCamInfoMsg, mLeftCamOptFrameId, mRightCamOptFrameId); diff --git a/zed_wrapper/src/tools/include/sl_tools.h b/zed_wrapper/src/tools/include/sl_tools.h index d8fb0b4f..3d0db999 100644 --- a/zed_wrapper/src/tools/include/sl_tools.h +++ b/zed_wrapper/src/tools/include/sl_tools.h @@ -57,7 +57,7 @@ namespace sl_tools { */ ros::Time slTime2Ros(sl::timeStamp t); - /* \brief Image to ros message conversion + /* \brief sl::Mat to ros message conversion * \param img : the image to publish * \param frameId : the id of the reference frame of the image * \param t : the ros::Time to stamp the image From 0cbcb88b75200f90b082fdada2ce3acae15cec70 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Mon, 17 Sep 2018 16:25:57 +0200 Subject: [PATCH 50/55] Param init_odom_with_imu renamed to init_odom_with_first_valid_pose --- zed_wrapper/launch/zed_camera.launch | 2 +- zed_wrapper/launch/zed_camera_nodelet.launch | 2 +- zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/zed_wrapper/launch/zed_camera.launch b/zed_wrapper/launch/zed_camera.launch index 92c730fc..a979c35b 100644 --- a/zed_wrapper/launch/zed_camera.launch +++ b/zed_wrapper/launch/zed_camera.launch @@ -132,7 +132,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - + diff --git a/zed_wrapper/launch/zed_camera_nodelet.launch b/zed_wrapper/launch/zed_camera_nodelet.launch index fa02dbf7..c0ab8f4b 100644 --- a/zed_wrapper/launch/zed_camera_nodelet.launch +++ b/zed_wrapper/launch/zed_camera_nodelet.launch @@ -133,7 +133,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - + diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index 31e6e600..ff3e1e97 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -718,7 +718,7 @@ namespace zed_wrapper { mNhNs.getParam("pose_smoothing", mPoseSmoothing); mNhNs.getParam("spatial_memory", mSpatialMemory); mNhNs.getParam("floor_alignment", mFloorAlignment); - mNhNs.getParam("init_odom_with_imu", mInitOdomWithPose); + mNhNs.getParam("init_odom_with_first_valid_pose", mInitOdomWithPose); NODELET_INFO_STREAM("Init Odometry with first valid pose data : " << mInitOdomWithPose); if (mInitialTrackPose.size() != 6) { From 78402933004486e5518824cbae19a19fc75b437b Mon Sep 17 00:00:00 2001 From: Myzhar Date: Wed, 19 Sep 2018 10:03:45 +0200 Subject: [PATCH 51/55] Improved solution to issue #276 https://github.com/stereolabs/zed-ros-wrapper/issues/276 * fixed crash due to IMU thread --- .../nodelet/include/zed_wrapper_nodelet.hpp | 4 +- .../src/nodelet/src/zed_wrapper_nodelet.cpp | 130 ++++++++++-------- 2 files changed, 74 insertions(+), 60 deletions(-) diff --git a/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp b/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp index b55233f4..a93783a5 100644 --- a/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp +++ b/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp @@ -340,7 +340,8 @@ namespace zed_wrapper { bool mFloorAlignment = false; // Last frame time - ros::Time mLastFrameTime; + ros::Time mPrevFrameTimestamp; + ros::Time mFrameTimestamp; //Tracking variables sl::Pose mLastZedPose; // Sensor to Map transform @@ -384,6 +385,7 @@ namespace zed_wrapper { int mMatHeight; // Thread Sync + std::mutex mCloseZedMutex; std::mutex mCamDataMutex; std::mutex mPcMutex; std::condition_variable mPcDataReadyCondVar; diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index ff3e1e97..6636514b 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -278,7 +278,11 @@ namespace zed_wrapper { // Ctrl+C check if (!mNhNs.ok()) { mStopNode = true; // Stops other threads + + std::lock_guard lock(mCloseZedMutex); + NODELET_DEBUG("Closing ZED"); mZed.close(); + NODELET_DEBUG("ZED pool thread finished"); return; } @@ -356,7 +360,11 @@ namespace zed_wrapper { if (!mNhNs.ok()) { mStopNode = true; // Stops other threads + + std::lock_guard lock(mCloseZedMutex); + NODELET_DEBUG("Closing ZED"); mZed.close(); + NODELET_DEBUG("ZED pool thread finished"); return; } @@ -499,7 +507,7 @@ namespace zed_wrapper { mPubImuRaw = mNh.advertise(imu_topic_raw, 500); NODELET_INFO_STREAM("Advertised on topic " << imu_topic_raw << " @ " << mImuPubRate << " Hz"); - mLastFrameTime = ros::Time::now(); + mFrameTimestamp = ros::Time::now(); mImuTimer = mNhNs.createTimer(ros::Duration(1.0 / mImuPubRate), &ZEDWrapperNodelet::imuPubCallback, this); } else if (mImuPubRate > 0 && mZedRealCamModel == sl::MODEL_ZED) { @@ -827,7 +835,7 @@ namespace zed_wrapper { } std_msgs::Header header; - header.stamp = mLastFrameTime; + header.stamp = mFrameTimestamp; header.frame_id = mPublishMapTf ? mMapFrameId : mOdometryFrameId; // frame // conversion from Tranform to message @@ -1219,7 +1227,7 @@ namespace zed_wrapper { geometry_msgs::PoseStamped odomPose; geometry_msgs::PoseStamped mapPose; - odomPose.header.stamp = mLastFrameTime; + odomPose.header.stamp = mFrameTimestamp; odomPose.header.frame_id = mOdometryFrameId; // odom_frame // conversion from Tranform to message geometry_msgs::Transform base2odom = tf2::toMsg(base_to_odom); @@ -1233,7 +1241,7 @@ namespace zed_wrapper { odomPose.pose.orientation.w = base2odom.rotation.w; if (mPublishMapTf) { - mapPose.header.stamp = mLastFrameTime; + mapPose.header.stamp = mFrameTimestamp; mapPose.header.frame_id = mMapFrameId; // map_frame // conversion from Tranform to message geometry_msgs::Transform base2map = tf2::toMsg(base_to_map); @@ -1270,7 +1278,7 @@ namespace zed_wrapper { if (mapPathSub > 0 && mPublishMapTf) { nav_msgs::Path mapPath; mapPath.header.frame_id = mMapFrameId; - mapPath.header.stamp = mLastFrameTime; + mapPath.header.stamp = mFrameTimestamp; mapPath.poses = mMapPath; mPubMapPath.publish(mapPath); @@ -1279,7 +1287,7 @@ namespace zed_wrapper { if (odomPathSub > 0) { nav_msgs::Path odomPath; odomPath.header.frame_id = mPublishMapTf ? mMapFrameId : mOdometryFrameId; - odomPath.header.stamp = mLastFrameTime; + odomPath.header.stamp = mFrameTimestamp; odomPath.poses = mOdomPath; mPubOdomPath.publish(odomPath); @@ -1288,6 +1296,12 @@ namespace zed_wrapper { } void ZEDWrapperNodelet::imuPubCallback(const ros::TimerEvent& e) { + + std::lock_guard lock(mCloseZedMutex); + if (!mZed.isOpened()) { + return; + } + uint32_t imu_SubNumber = mPubImu.getNumSubscribers(); uint32_t imu_RawSubNumber = mPubImuRaw.getNumSubscribers(); @@ -1307,7 +1321,7 @@ namespace zed_wrapper { if (imu_SubNumber > 0) { sensor_msgs::Imu imu_msg; - imu_msg.header.stamp = mLastFrameTime; // t; + imu_msg.header.stamp = mFrameTimestamp; // t; imu_msg.header.frame_id = mImuFrameId; imu_msg.orientation.x = mSignX * imu_data.getOrientation()[mIdxX]; imu_msg.orientation.y = mSignY * imu_data.getOrientation()[mIdxY]; @@ -1346,7 +1360,7 @@ namespace zed_wrapper { if (imu_RawSubNumber > 0) { sensor_msgs::Imu imu_raw_msg; - imu_raw_msg.header.stamp = mLastFrameTime; // t; + imu_raw_msg.header.stamp = mFrameTimestamp; // t; imu_raw_msg.header.frame_id = mImuFrameId; imu_raw_msg.angular_velocity.x = mSignX * imu_data.angular_velocity[mIdxX]; imu_raw_msg.angular_velocity.y = mSignY * imu_data.angular_velocity[mIdxY]; @@ -1418,22 +1432,22 @@ namespace zed_wrapper { imu_pose.setRotation(delta_q); // Note, the frame is published, but its values will only change if someone // has subscribed to IMU - publishImuFrame(imu_pose, mLastFrameTime); // publish the imu Frame + publishImuFrame(imu_pose, mFrameTimestamp); // publish the imu Frame } } void ZEDWrapperNodelet::device_poll_thread_func() { ros::Rate loop_rate(mCamFrameRate); - ros::Time t_old; + // Timestamp initialization if (mSvoMode) { - t_old = ros::Time::now(); + mFrameTimestamp = ros::Time::now(); } else { - t_old = sl_tools::slTime2Ros(mZed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); + mFrameTimestamp = sl_tools::slTime2Ros(mZed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); } - ros::Time old_t = t_old; - mLastFrameTime = old_t; + mPrevFrameTimestamp = mFrameTimestamp; + sl::ERROR_CODE grab_status; mTrackingActivated = false; // Get the parameters of the ZED images @@ -1508,14 +1522,6 @@ namespace zed_wrapper { poseSubnumber + poseCovSubnumber + odomSubnumber + confImgSubnumber + confMapSubnumber) > 0); - // Timestamp - ros::Time t; - if (mSvoMode) { - t = ros::Time::now(); - } else { - t = sl_tools::slTime2Ros(mZed.getTimestamp(sl::TIME_REFERENCE_IMAGE)); - } - if (mComputeDepth) { int actual_confidence = mZed.getConfidenceThreshold(); @@ -1554,22 +1560,28 @@ namespace zed_wrapper { std::this_thread::sleep_for(std::chrono::milliseconds(2)); - if ((t - old_t).toSec() > 5 && !mSvoMode) { + if ((ros::Time::now() - mPrevFrameTimestamp).toSec() > 5 && !mSvoMode) { + mCloseZedMutex.lock(); mZed.close(); - NODELET_INFO("Re-opening the ZED"); + mCloseZedMutex.unlock(); + sl::ERROR_CODE err = sl::ERROR_CODE_CAMERA_NOT_DETECTED; while (err != sl::SUCCESS) { if (!mNhNs.ok()) { mStopNode = true; + + std::lock_guard lock(mCloseZedMutex); + NODELET_DEBUG("Closing ZED"); mZed.close(); + NODELET_DEBUG("ZED pool thread finished"); return; } int id = sl_tools::checkCameraReady(mZedSerialNumber); - if (id > 0) { + if (id >= 0) { mZedParams.camera_linux_id = id; err = mZed.open(mZedParams); // Try to initialize the ZED NODELET_INFO_STREAM(toString(err)); @@ -1593,14 +1605,14 @@ namespace zed_wrapper { continue; } - // Time update - ros::Time t_old; + mPrevFrameTimestamp = mFrameTimestamp; + + // Timestamp if (mSvoMode) { - t_old = ros::Time::now(); + mFrameTimestamp = ros::Time::now(); } else { - t_old = sl_tools::slTime2Ros(mZed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); + mFrameTimestamp = sl_tools::slTime2Ros(mZed.getTimestamp(sl::TIME_REFERENCE_IMAGE)); } - old_t = t_old; if (mCamAutoExposure) { // getCameraSettings() can't check status of auto exposure @@ -1632,13 +1644,13 @@ namespace zed_wrapper { mZed.retrieveImage(leftZEDMat, sl::VIEW_LEFT, sl::MEM_CPU, mMatWidth, mMatHeight); if (leftSubnumber > 0) { - publishCamInfo(mLeftCamInfoMsg, mPubLeftCamInfo, t); - publishImage(leftZEDMat, mPubLeft, mLeftCamOptFrameId, t); + publishCamInfo(mLeftCamInfoMsg, mPubLeftCamInfo, mFrameTimestamp); + publishImage(leftZEDMat, mPubLeft, mLeftCamOptFrameId, mFrameTimestamp); } if (rgbSubnumber > 0) { - publishCamInfo(mRgbCamInfoMsg, mPubRgbCamInfo, t); - publishImage(leftZEDMat, mPubRgb, mDepthOptFrameId, t); // rgb is the left image + publishCamInfo(mRgbCamInfoMsg, mPubRgbCamInfo, mFrameTimestamp); + publishImage(leftZEDMat, mPubRgb, mDepthOptFrameId, mFrameTimestamp); // rgb is the left image } } @@ -1648,13 +1660,13 @@ namespace zed_wrapper { mZed.retrieveImage(leftZEDMat, sl::VIEW_LEFT_UNRECTIFIED, sl::MEM_CPU, mMatWidth, mMatHeight); if (leftRawSubnumber > 0) { - publishCamInfo(mLeftCamInfoRawMsg, mPubLeftCamInfoRaw, t); - publishImage(leftZEDMat, mPubRawLeft, mLeftCamOptFrameId, t); + publishCamInfo(mLeftCamInfoRawMsg, mPubLeftCamInfoRaw, mFrameTimestamp); + publishImage(leftZEDMat, mPubRawLeft, mLeftCamOptFrameId, mFrameTimestamp); } if (rgbRawSubnumber > 0) { - publishCamInfo(mRgbCamInfoRawMsg, mPubRgbCamInfoRaw, t); - publishImage(leftZEDMat, mPubRawRgb, mDepthOptFrameId, t); + publishCamInfo(mRgbCamInfoRawMsg, mPubRgbCamInfoRaw, mFrameTimestamp); + publishImage(leftZEDMat, mPubRawRgb, mDepthOptFrameId, mFrameTimestamp); } } @@ -1663,8 +1675,8 @@ namespace zed_wrapper { // Retrieve RGBA Right image mZed.retrieveImage(rightZEDMat, sl::VIEW_RIGHT, sl::MEM_CPU, mMatWidth, mMatHeight); - publishCamInfo(mRightCamInfoMsg, mPubRightCamInfo, t); - publishImage(rightZEDMat, mPubRight, mRightCamOptFrameId, t); + publishCamInfo(mRightCamInfoMsg, mPubRightCamInfo, mFrameTimestamp); + publishImage(rightZEDMat, mPubRight, mRightCamOptFrameId, mFrameTimestamp); } // Publish the right image if someone has subscribed to @@ -1672,28 +1684,28 @@ namespace zed_wrapper { // Retrieve RGBA Right image mZed.retrieveImage(rightZEDMat, sl::VIEW_RIGHT_UNRECTIFIED, sl::MEM_CPU, mMatWidth, mMatHeight); - publishCamInfo(mRightCamInfoRawMsg, mPubRightCamInfoRaw, t); - publishImage(rightZEDMat, mPubRawRight, mRightCamOptFrameId, t); + publishCamInfo(mRightCamInfoRawMsg, mPubRightCamInfoRaw, mFrameTimestamp); + publishImage(rightZEDMat, mPubRawRight, mRightCamOptFrameId, mFrameTimestamp); } // Publish the depth image if someone has subscribed to if (depthSubnumber > 0 || disparitySubnumber > 0) { mZed.retrieveMeasure(depthZEDMat, sl::MEASURE_DEPTH, sl::MEM_CPU, mMatWidth, mMatHeight); - publishCamInfo(mDepthCamInfoMsg, mPubDepthCamInfo, t); - publishDepth(depthZEDMat, t); // in meters + publishCamInfo(mDepthCamInfoMsg, mPubDepthCamInfo, mFrameTimestamp); + publishDepth(depthZEDMat, mFrameTimestamp); // in meters } // Publish the disparity image if someone has subscribed to if (disparitySubnumber > 0) { mZed.retrieveMeasure(disparityZEDMat, sl::MEASURE_DISPARITY, sl::MEM_CPU, mMatWidth, mMatHeight); // Need to flip sign, but cause of this is not sure - publishDisparity(disparityZEDMat, t); + publishDisparity(disparityZEDMat, mFrameTimestamp); } // Publish the confidence image if someone has subscribed to if (confImgSubnumber > 0) { mZed.retrieveImage(confImgZEDMat, sl::VIEW_CONFIDENCE, sl::MEM_CPU, mMatWidth, mMatHeight); - publishImage(confImgZEDMat, mPubConfImg, mConfidenceOptFrameId, t); + publishImage(confImgZEDMat, mPubConfImg, mConfidenceOptFrameId, mFrameTimestamp); } // Publish the confidence map if someone has subscribed to @@ -1701,7 +1713,7 @@ namespace zed_wrapper { mZed.retrieveMeasure(confMapZEDMat, sl::MEASURE_CONFIDENCE, sl::MEM_CPU, mMatWidth, mMatHeight); - mPubConfMap.publish(sl_tools::imageToROSmsg(confMapZEDMat, mConfidenceOptFrameId, t)); + mPubConfMap.publish(sl_tools::imageToROSmsg(confMapZEDMat, mConfidenceOptFrameId, mFrameTimestamp)); } // Publish the point cloud if someone has subscribed to @@ -1714,7 +1726,7 @@ namespace zed_wrapper { mZed.retrieveMeasure(mCloud, sl::MEASURE_XYZBGRA, sl::MEM_CPU, mMatWidth, mMatHeight); mPointCloudFrameId = mDepthFrameId; - mPointCloudTime = t; + mPointCloudTime = mFrameTimestamp; // Signal Pointcloud thread that a new pointcloud is ready mPcDataReady = true; @@ -1732,7 +1744,7 @@ namespace zed_wrapper { try { // Save the transformation from base to frame geometry_msgs::TransformStamped s2b = - mTfBuffer->lookupTransform(mBaseFrameId, mDepthFrameId, t); + mTfBuffer->lookupTransform(mBaseFrameId, mDepthFrameId, mFrameTimestamp); // Get the TF2 transformation tf2::fromMsg(s2b.transform, sensor_to_base_transf); } catch (tf2::TransformException& ex) { @@ -1773,7 +1785,7 @@ namespace zed_wrapper { // Propagate Odom transform in time mBase2OdomTransf = mBase2OdomTransf * deltaOdomTf_base; // Publish odometry message - publishOdom(mBase2OdomTransf, deltaOdom, t); + publishOdom(mBase2OdomTransf, deltaOdom, mFrameTimestamp); mTrackingReady = true; } else { NODELET_DEBUG_STREAM("ODOM -> Tracking Status: " << sl::toString(status)); @@ -1834,7 +1846,7 @@ namespace zed_wrapper { if (odomSubnumber > 0) { // Publish odometry message - publishOdom(mBase2OdomTransf, mLastZedPose, t); + publishOdom(mBase2OdomTransf, mLastZedPose, mFrameTimestamp); } mInitOdomWithPose = false; @@ -1846,7 +1858,7 @@ namespace zed_wrapper { } // Publish Pose message - publishPose(t); + publishPose(mFrameTimestamp); mTrackingReady = true; } else { NODELET_DEBUG_STREAM("MAP -> Tracking Status: " << static_cast(status)); @@ -1855,19 +1867,16 @@ namespace zed_wrapper { oldStatus = status; } - - // Publish pose tf only if enabled if (mPublishTf) { // Note, the frame is published, but its values will only change if // someone has subscribed to odom - publishOdomFrame(mBase2OdomTransf, t); // publish the base Frame in odometry frame + publishOdomFrame(mBase2OdomTransf, mFrameTimestamp); // publish the base Frame in odometry frame if (mPublishMapTf) { // Note, the frame is published, but its values will only change if // someone has subscribed to map - publishPoseFrame(mOdom2MapTransf, t); // publish the odometry Frame in map frame + publishPoseFrame(mOdom2MapTransf, mFrameTimestamp); // publish the odometry Frame in map frame } - mLastFrameTime = t; } static int rateWarnCount = 0; @@ -1903,10 +1912,10 @@ namespace zed_wrapper { t = sl_tools::slTime2Ros(mZed.getTimestamp(sl::TIME_REFERENCE_CURRENT)); } - publishOdomFrame(mBase2OdomTransf, t); // publish the base Frame in odometry frame + publishOdomFrame(mBase2OdomTransf, mFrameTimestamp); // publish the base Frame in odometry frame if (mPublishMapTf) { - publishPoseFrame(mOdom2MapTransf, t); // publish the odometry Frame in map frame + publishPoseFrame(mOdom2MapTransf, mFrameTimestamp); // publish the odometry Frame in map frame } } @@ -1917,6 +1926,9 @@ namespace zed_wrapper { } // while loop mStopNode = true; // Stops other threads + + std::lock_guard lock(mCloseZedMutex); + NODELET_DEBUG("Closing ZED"); mZed.close(); NODELET_DEBUG("ZED pool thread finished"); From d96d535c3da71a97a3ed58cbf82f64f3383049d3 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Wed, 19 Sep 2018 16:45:49 +0200 Subject: [PATCH 52/55] Fixes to odometry TF * added missing "publish_map_tf" param to launch files --- zed_display_rviz/rviz/zedm.rviz | 45 +++++------ zed_wrapper/launch/zed_camera.launch | 3 + zed_wrapper/launch/zed_camera_nodelet.launch | 2 + .../nodelet/include/zed_wrapper_nodelet.hpp | 5 ++ .../src/nodelet/src/zed_wrapper_nodelet.cpp | 74 ++++++++++--------- 5 files changed, 70 insertions(+), 59 deletions(-) diff --git a/zed_display_rviz/rviz/zedm.rviz b/zed_display_rviz/rviz/zedm.rviz index b10f54f8..419d2f51 100644 --- a/zed_display_rviz/rviz/zedm.rviz +++ b/zed_display_rviz/rviz/zedm.rviz @@ -11,11 +11,9 @@ Panels: - /Video1/Camera view1/Visibility1 - /Depth1/DepthCloud1 - /Pose1 - - /Pose1/Odometry1 - /Pose1/Odometry1/Covariance1 - /Pose1/Odometry1/Covariance1/Position1 - /Pose1/Odometry1/Covariance1/Orientation1 - - /Pose1/Pose1 - /Pose1/PoseWithCovariance1 - /Pose1/PoseWithCovariance1/Covariance1 - /Pose1/PoseWithCovariance1/Covariance1/Position1 @@ -110,8 +108,6 @@ Visualization Manager: All Enabled: false imu_link: Value: true - map: - Value: true odom: Value: true zed_camera_center: @@ -130,17 +126,16 @@ Visualization Manager: Show Axes: true Show Names: true Tree: - map: - odom: - zed_camera_center: - imu_link: + odom: + zed_camera_center: + imu_link: + {} + zed_left_camera_frame: + zed_left_camera_optical_frame: + {} + zed_right_camera_frame: + zed_right_camera_optical_frame: {} - zed_left_camera_frame: - zed_left_camera_optical_frame: - {} - zed_right_camera_frame: - zed_right_camera_optical_frame: - {} Update Interval: 0 Value: true - Class: rviz/Group @@ -320,7 +315,7 @@ Visualization Manager: Buffer Length: 1 Class: rviz/Path Color: 255; 25; 0 - Enabled: false + Enabled: true Head Diameter: 0.0299999993 Head Length: 0.0199999996 Length: 0.300000012 @@ -338,7 +333,7 @@ Visualization Manager: Shaft Length: 0.0500000007 Topic: /zed/path_odom Unreliable: true - Value: false + Value: true - Angle Tolerance: 0 Class: rviz/Odometry Covariance: @@ -377,7 +372,7 @@ Visualization Manager: Buffer Length: 1 Class: rviz/Path Color: 25; 255; 0 - Enabled: false + Enabled: true Head Diameter: 0.0299999993 Head Length: 0.0199999996 Length: 0.300000012 @@ -395,7 +390,7 @@ Visualization Manager: Shaft Length: 0.0500000007 Topic: /zed/path_map Unreliable: true - Value: false + Value: true - Alpha: 1 Axes Length: 1 Axes Radius: 0.100000001 @@ -470,7 +465,7 @@ Visualization Manager: Global Options: Background Color: 48; 48; 48 Default Light: true - Fixed Frame: map + Fixed Frame: odom Frame Rate: 60 Name: root Tools: @@ -491,25 +486,25 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 1.48717809 + Distance: 1.64165437 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: -0.149202153 - Y: -0.131090492 - Z: 0.699279904 + X: -0.146052256 + Y: -0.190351665 + Z: 0.792743862 Focal Shape Fixed Size: false Focal Shape Size: 0.0500000007 Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 - Pitch: 0.465398431 + Pitch: 0.525398433 Target Frame: Value: Orbit (rviz) - Yaw: 0.965398073 + Yaw: 1.14039791 Saved: ~ Window Geometry: Camera view: diff --git a/zed_wrapper/launch/zed_camera.launch b/zed_wrapper/launch/zed_camera.launch index a979c35b..b6863a56 100644 --- a/zed_wrapper/launch/zed_camera.launch +++ b/zed_wrapper/launch/zed_camera.launch @@ -36,6 +36,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + @@ -62,6 +63,8 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + diff --git a/zed_wrapper/launch/zed_camera_nodelet.launch b/zed_wrapper/launch/zed_camera_nodelet.launch index c0ab8f4b..13b84496 100644 --- a/zed_wrapper/launch/zed_camera_nodelet.launch +++ b/zed_wrapper/launch/zed_camera_nodelet.launch @@ -38,6 +38,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + @@ -64,6 +65,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + diff --git a/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp b/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp index a93783a5..fe44e525 100644 --- a/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp +++ b/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp @@ -212,6 +212,10 @@ namespace zed_wrapper { */ void set_pose(float xt, float yt, float zt, float rr, float pr, float yr); + /* \brief Utility to initialize the most used transforms + */ + void initTransforms(); + /* \bried Start tracking loading the parameters from param server */ void start_tracking(); @@ -353,6 +357,7 @@ namespace zed_wrapper { // TF Transforms tf2::Transform mOdom2MapTransf; tf2::Transform mBase2OdomTransf; + tf2::Transform mSensor2BaseTransf; // Zed object sl::InitParameters mZedParams; diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index 6636514b..4853c19c 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -248,14 +248,15 @@ namespace zed_wrapper { // SVO mNhNs.param("svo_filepath", mSvoFilepath, std::string()); + // Initialization transformation listener + mTfBuffer.reset(new tf2_ros::Buffer); + mTfListener.reset(new tf2_ros::TransformListener(*mTfBuffer)); + // Initialize tf2 transformation mNhNs.getParam("initial_tracking_pose", mInitialTrackPose); set_pose(mInitialTrackPose[0], mInitialTrackPose[1], mInitialTrackPose[2], mInitialTrackPose[3], mInitialTrackPose[4], mInitialTrackPose[5]); - // Initialization transformation listener - mTfBuffer.reset(new tf2_ros::Buffer); - mTfListener.reset(new tf2_ros::TransformListener(*mTfBuffer)); // Try to initialize the ZED if (!mSvoFilepath.empty()) { @@ -638,6 +639,32 @@ namespace zed_wrapper { } } + void ZEDWrapperNodelet::initTransforms() { + // >>>>> Dynamic transforms + mBase2OdomTransf.setIdentity(); + mOdom2MapTransf.setIdentity(); + // <<<<< Dynamic transforms + + // >>>>> Static transforms + // Sensor to Base link + try { + // Save the transformation from base to frame + geometry_msgs::TransformStamped s2b = + mTfBuffer->lookupTransform(mBaseFrameId, mDepthFrameId, mFrameTimestamp); + // Get the TF2 transformation + tf2::fromMsg(s2b.transform, mSensor2BaseTransf); + } catch (tf2::TransformException& ex) { + NODELET_WARN_THROTTLE( + 10.0, "The tf from '%s' to '%s' does not seem to be available, " + "will assume it as identity!", + mDepthFrameId.c_str(), mBaseFrameId.c_str()); + NODELET_DEBUG("Transform error: %s", ex.what()); + mSensor2BaseTransf.setIdentity(); + } + // <<<<< Static transforms + + } + void ZEDWrapperNodelet::set_pose(float xt, float yt, float zt, float rr, float pr, float yr) { // ROS pose @@ -648,9 +675,7 @@ namespace zed_wrapper { // mBase2OdomTransf.setRotation(q); // mOdom2MapTransf.setIdentity(); - mBase2OdomTransf.setIdentity(); - mBase2OdomTransf.setIdentity(); - mOdom2MapTransf.setIdentity(); + initTransforms(); // SL pose sl::float4 q_vec; @@ -698,8 +723,8 @@ namespace zed_wrapper { NODELET_WARN_STREAM("Invalid Initial Pose size (" << mInitialTrackPose.size() << "). Using Identity"); mInitialPoseSl.setIdentity(); - mOdom2MapTransf.setIdentity(); - mBase2OdomTransf.setIdentity(); + + initTransforms(); } else { set_pose(mInitialTrackPose[0], mInitialTrackPose[1], mInitialTrackPose[2], mInitialTrackPose[3], mInitialTrackPose[4], mInitialTrackPose[5]); @@ -733,8 +758,8 @@ namespace zed_wrapper { NODELET_WARN_STREAM("Invalid Initial Pose size (" << mInitialTrackPose.size() << "). Using Identity"); mInitialPoseSl.setIdentity(); - mOdom2MapTransf.setIdentity(); - mBase2OdomTransf.setIdentity(); + + initTransforms(); } else { set_pose(mInitialTrackPose[0], mInitialTrackPose[1], mInitialTrackPose[2], mInitialTrackPose[3], mInitialTrackPose[4], mInitialTrackPose[5]); @@ -770,7 +795,7 @@ namespace zed_wrapper { void ZEDWrapperNodelet::publishOdom(tf2::Transform base2odomTransf, sl::Pose& slPose, ros::Time t) { nav_msgs::Odometry odom; odom.header.stamp = t; - odom.header.frame_id = mOdometryFrameId; // odom_frame + odom.header.frame_id = mOdometryFrameId; odom.child_frame_id = mBaseFrameId; // camera_frame // conversion from Tranform to message geometry_msgs::Transform base2odom = tf2::toMsg(base2odomTransf); @@ -1203,7 +1228,6 @@ namespace zed_wrapper { "will assume it as identity!", mBaseFrameId.c_str(), mOdometryFrameId.c_str()); NODELET_DEBUG("Transform error: %s", ex.what()); - } if (mPublishMapTf) { @@ -1223,12 +1247,11 @@ namespace zed_wrapper { } } - geometry_msgs::PoseStamped odomPose; geometry_msgs::PoseStamped mapPose; odomPose.header.stamp = mFrameTimestamp; - odomPose.header.frame_id = mOdometryFrameId; // odom_frame + odomPose.header.frame_id = mOdometryFrameId; // conversion from Tranform to message geometry_msgs::Transform base2odom = tf2::toMsg(base_to_odom); // Add all value in Pose message @@ -1737,24 +1760,7 @@ namespace zed_wrapper { mCamDataMutex.unlock(); - // Transform from base to sensor - tf2::Transform sensor_to_base_transf; - - // Look up the transformation from base frame to camera link - try { - // Save the transformation from base to frame - geometry_msgs::TransformStamped s2b = - mTfBuffer->lookupTransform(mBaseFrameId, mDepthFrameId, mFrameTimestamp); - // Get the TF2 transformation - tf2::fromMsg(s2b.transform, sensor_to_base_transf); - } catch (tf2::TransformException& ex) { - NODELET_WARN_THROTTLE( - 10.0, "The tf from '%s' to '%s' does not seem to be available, " - "will assume it as identity!", - mDepthFrameId.c_str(), mBaseFrameId.c_str()); - NODELET_DEBUG("Transform error: %s", ex.what()); - sensor_to_base_transf.setIdentity(); - } + // Publish the odometry if someone has subscribed to if (poseSubnumber > 0 || poseCovSubnumber > 0 || odomSubnumber > 0 || cloudSubnumber > 0 || @@ -1780,7 +1786,7 @@ namespace zed_wrapper { tf2::fromMsg(deltaTransf, deltaOdomTf); // delta odom from sensor to base frame tf2::Transform deltaOdomTf_base = - sensor_to_base_transf * deltaOdomTf * sensor_to_base_transf.inverse(); + mSensor2BaseTransf * deltaOdomTf * mSensor2BaseTransf.inverse(); // Propagate Odom transform in time mBase2OdomTransf = mBase2OdomTransf * deltaOdomTf_base; @@ -1826,7 +1832,7 @@ namespace zed_wrapper { /*tf2::Transform base_to_map_transform = sensor_to_base_transf * sens_to_map_transf * sensor_to_base_transf.inverse();*/ - tf2::Transform base_to_map_transform = (sensor_to_base_transf * sens_to_map_transf.inverse()).inverse(); + tf2::Transform base_to_map_transform = (mSensor2BaseTransf * sens_to_map_transf.inverse()).inverse(); bool initOdom = false; From a27f56746f4d97c8ba72c02835cfcbd3d409d757 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Thu, 20 Sep 2018 18:37:19 +0200 Subject: [PATCH 53/55] Fix to path frames for odometry --- zed_display_rviz/rviz/zedm.rviz | 43 ++++++++++--------- .../src/nodelet/src/zed_wrapper_nodelet.cpp | 4 +- 2 files changed, 25 insertions(+), 22 deletions(-) diff --git a/zed_display_rviz/rviz/zedm.rviz b/zed_display_rviz/rviz/zedm.rviz index 419d2f51..a55ffa87 100644 --- a/zed_display_rviz/rviz/zedm.rviz +++ b/zed_display_rviz/rviz/zedm.rviz @@ -108,6 +108,8 @@ Visualization Manager: All Enabled: false imu_link: Value: true + map: + Value: true odom: Value: true zed_camera_center: @@ -126,16 +128,17 @@ Visualization Manager: Show Axes: true Show Names: true Tree: - odom: - zed_camera_center: - imu_link: - {} - zed_left_camera_frame: - zed_left_camera_optical_frame: - {} - zed_right_camera_frame: - zed_right_camera_optical_frame: + map: + odom: + zed_camera_center: + imu_link: {} + zed_left_camera_frame: + zed_left_camera_optical_frame: + {} + zed_right_camera_frame: + zed_right_camera_optical_frame: + {} Update Interval: 0 Value: true - Class: rviz/Group @@ -396,7 +399,7 @@ Visualization Manager: Axes Radius: 0.100000001 Class: rviz/Pose Color: 0; 255; 0 - Enabled: false + Enabled: true Head Length: 0.100000001 Head Radius: 0.0500000007 Name: Pose @@ -405,7 +408,7 @@ Visualization Manager: Shape: Arrow Topic: /zed/pose Unreliable: false - Value: false + Value: true - Alpha: 1 Axes Length: 1 Axes Radius: 0.100000001 @@ -426,7 +429,7 @@ Visualization Manager: Scale: 100 Value: true Value: true - Enabled: true + Enabled: false Head Length: 0.100000001 Head Radius: 0.0500000007 Name: PoseWithCovariance @@ -435,7 +438,7 @@ Visualization Manager: Shape: Arrow Topic: /zed/pose_with_covariance Unreliable: false - Value: true + Value: false - Acceleration properties: Acc. vector alpha: 1 Acc. vector color: 255; 0; 0 @@ -465,7 +468,7 @@ Visualization Manager: Global Options: Background Color: 48; 48; 48 Default Light: true - Fixed Frame: odom + Fixed Frame: map Frame Rate: 60 Name: root Tools: @@ -486,25 +489,25 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 1.64165437 + Distance: 1.97160459 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: -0.146052256 - Y: -0.190351665 - Z: 0.792743862 + X: -0.156546906 + Y: -0.1158977 + Z: 0.691972911 Focal Shape Fixed Size: false Focal Shape Size: 0.0500000007 Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 - Pitch: 0.525398433 + Pitch: 1.04539788 Target Frame: Value: Orbit (rviz) - Yaw: 1.14039791 + Yaw: 3.37540507 Saved: ~ Window Geometry: Camera view: diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index 4853c19c..40336420 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -795,7 +795,7 @@ namespace zed_wrapper { void ZEDWrapperNodelet::publishOdom(tf2::Transform base2odomTransf, sl::Pose& slPose, ros::Time t) { nav_msgs::Odometry odom; odom.header.stamp = t; - odom.header.frame_id = mOdometryFrameId; + odom.header.frame_id = mPublishMapTf ? mMapFrameId : mOdometryFrameId; // frame odom.child_frame_id = mBaseFrameId; // camera_frame // conversion from Tranform to message geometry_msgs::Transform base2odom = tf2::toMsg(base2odomTransf); @@ -1251,7 +1251,7 @@ namespace zed_wrapper { geometry_msgs::PoseStamped mapPose; odomPose.header.stamp = mFrameTimestamp; - odomPose.header.frame_id = mOdometryFrameId; + odomPose.header.frame_id = mPublishMapTf ? mMapFrameId : mOdometryFrameId; // frame // conversion from Tranform to message geometry_msgs::Transform base2odom = tf2::toMsg(base_to_odom); // Add all value in Pose message From 673d6c2b76cd702b7c52c904b64f5e35ace81cc2 Mon Sep 17 00:00:00 2001 From: Myzhar Date: Fri, 21 Sep 2018 12:48:32 +0200 Subject: [PATCH 54/55] Added parameter to disable covariance as requested here: https:// github.com/stereolabs/zed-ros-wrapper/issues/281#issuecomment-423488528 --- zed_wrapper/launch/zed_camera.launch | 2 + zed_wrapper/launch/zed_camera_nodelet.launch | 2 + .../nodelet/include/zed_wrapper_nodelet.hpp | 1 + .../src/nodelet/src/zed_wrapper_nodelet.cpp | 44 +++++++++++-------- 4 files changed, 30 insertions(+), 19 deletions(-) diff --git a/zed_wrapper/launch/zed_camera.launch b/zed_wrapper/launch/zed_camera.launch index b6863a56..3b4de0e9 100644 --- a/zed_wrapper/launch/zed_camera.launch +++ b/zed_wrapper/launch/zed_camera.launch @@ -145,6 +145,8 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + diff --git a/zed_wrapper/launch/zed_camera_nodelet.launch b/zed_wrapper/launch/zed_camera_nodelet.launch index 13b84496..793019e2 100644 --- a/zed_wrapper/launch/zed_camera_nodelet.launch +++ b/zed_wrapper/launch/zed_camera_nodelet.launch @@ -144,6 +144,8 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + diff --git a/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp b/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp index fe44e525..58a75985 100644 --- a/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp +++ b/zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp @@ -382,6 +382,7 @@ namespace zed_wrapper { bool mSpatialMemory; bool mInitOdomWithPose; bool mResetOdom = false; + bool mPublishPoseCovariance = true; // Mat int mCamWidth; diff --git a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp index 40336420..de5cebd9 100644 --- a/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_wrapper/src/nodelet/src/zed_wrapper_nodelet.cpp @@ -132,6 +132,8 @@ namespace zed_wrapper { mNhNs.getParam("camera_model", mZedUserCamModel); + mNhNs.getParam("publish_pose_covariance", mPublishPoseCovariance); + // Publish odometry tf mNhNs.param("publish_tf", mPublishTf, true); mNhNs.param("publish_map_tf", mPublishMapTf, true); @@ -476,8 +478,10 @@ namespace zed_wrapper { // Odometry and Map publisher mPubPose = mNh.advertise(pose_topic, 1); NODELET_INFO_STREAM("Advertised on topic " << pose_topic); - mPubPoseCov = mNh.advertise(pose_cov_topic, 1); - NODELET_INFO_STREAM("Advertised on topic " << pose_cov_topic); + if (mPublishPoseCovariance) { + mPubPoseCov = mNh.advertise(pose_cov_topic, 1); + NODELET_INFO_STREAM("Advertised on topic " << pose_cov_topic); + } mPubOdom = mNh.advertise(odometry_topic, 1); NODELET_INFO_STREAM("Advertised on topic " << odometry_topic); @@ -517,12 +521,12 @@ namespace zed_wrapper { << mImuPubRate << " Hz" << " but ZED camera model does not support IMU data publishing."); } - + // Services mSrvSetInitPose = mNh.advertiseService("set_initial_pose", &ZEDWrapperNodelet::on_set_pose, this); mSrvResetOdometry = mNh.advertiseService("reset_odometry", &ZEDWrapperNodelet::on_reset_odometry, this); mSrvResetTracking = mNh.advertiseService("reset_tracking", &ZEDWrapperNodelet::on_reset_tracking, this); - + // Start Pointcloud thread mPcThread = std::thread(&ZEDWrapperNodelet::pointcloud_thread_func, this); @@ -810,7 +814,7 @@ namespace zed_wrapper { // >>>>> Odometry pose covariance if available #if ((ZED_SDK_MAJOR_VERSION>2) || (ZED_SDK_MAJOR_VERSION==2 && ZED_SDK_MINOR_VERSION>=6)) - if (!mSpatialMemory) { + if (!mSpatialMemory && mPublishPoseCovariance) { for (size_t i = 0; i < odom.pose.covariance.size(); i++) { // odom.pose.covariance[i] = static_cast(slPose.pose_covariance[i]); // TODO USE THIS WHEN STEP BY STEP COVARIANCE WILL BE AVAILABLE IN CAMERA_FRAME odom.pose.covariance[i] = static_cast(mLastZedPose.pose_covariance[i]); @@ -822,7 +826,7 @@ namespace zed_wrapper { // Publish odometry message mPubOdom.publish(odom); } - + void ZEDWrapperNodelet::publishPose(ros::Time t) { tf2::Transform base_pose; base_pose.setIdentity(); @@ -887,25 +891,27 @@ namespace zed_wrapper { mPubPose.publish(poseNoCov); } - if (mPubPoseCov.getNumSubscribers() > 0) { - geometry_msgs::PoseWithCovarianceStamped poseCov; + if (mPublishPoseCovariance) { + if (mPubPoseCov.getNumSubscribers() > 0) { + geometry_msgs::PoseWithCovarianceStamped poseCov; - poseCov.header = header; - poseCov.pose.pose = pose; + poseCov.header = header; + poseCov.pose.pose = pose; - // >>>>> Odometry pose covariance if available + // >>>>> Odometry pose covariance if available #if ((ZED_SDK_MAJOR_VERSION>2) || (ZED_SDK_MAJOR_VERSION==2 && ZED_SDK_MINOR_VERSION>=6)) - if (!mSpatialMemory) { - for (size_t i = 0; i < poseCov.pose.covariance.size(); i++) { - // odom.pose.covariance[i] = static_cast(slPose.pose_covariance[i]); // TODO USE THIS WHEN STEP BY STEP COVARIANCE WILL BE AVAILABLE IN CAMERA_FRAME - poseCov.pose.covariance[i] = static_cast(mLastZedPose.pose_covariance[i]); + if (!mSpatialMemory) { + for (size_t i = 0; i < poseCov.pose.covariance.size(); i++) { + // odom.pose.covariance[i] = static_cast(slPose.pose_covariance[i]); // TODO USE THIS WHEN STEP BY STEP COVARIANCE WILL BE AVAILABLE IN CAMERA_FRAME + poseCov.pose.covariance[i] = static_cast(mLastZedPose.pose_covariance[i]); + } } - } #endif - // <<<<< Odometry pose covariance if available + // <<<<< Odometry pose covariance if available - // Publish pose with covariance stamped message - mPubPoseCov.publish(poseCov); + // Publish pose with covariance stamped message + mPubPoseCov.publish(poseCov); + } } } From 56bb273f5dfc5ae8192b4ec3b92ed8a5acc75279 Mon Sep 17 00:00:00 2001 From: Aymeric Dujardin Date: Fri, 21 Sep 2018 15:14:31 +0200 Subject: [PATCH 55/55] Minor changes README --- README.md | 1 - examples/README.md | 2 -- examples/zed_nodelet_example/README.md | 2 -- examples/zed_rtabmap_example/README.md | 2 -- tutorials/README.md | 2 -- tutorials/zed_depth_sub_tutorial/README.md | 2 -- tutorials/zed_tracking_sub_tutorial/README.md | 2 -- tutorials/zed_video_sub_tutorial/README.md | 2 -- zed_display_rviz/README.md | 2 -- zed_wrapper/README.md | 2 -- 10 files changed, 19 deletions(-) diff --git a/README.md b/README.md index 9795c0ce..ff69d53c 100644 --- a/README.md +++ b/README.md @@ -29,7 +29,6 @@ The zed_ros_wrapper is a catkin package. It depends on the following ROS package - rosconsole - sensor_msgs - stereo_msgs - - opencv3 - image_transport - dynamic_reconfigure - urdf diff --git a/examples/README.md b/examples/README.md index 9c127a03..993d0272 100644 --- a/examples/README.md +++ b/examples/README.md @@ -1,5 +1,3 @@ -![](../images/Picto+STEREOLABS_Black.png) - # Examples How to use the ZED ROS node with other ROS packages diff --git a/examples/zed_nodelet_example/README.md b/examples/zed_nodelet_example/README.md index 0766d27c..70e83c2b 100644 --- a/examples/zed_nodelet_example/README.md +++ b/examples/zed_nodelet_example/README.md @@ -1,5 +1,3 @@ -![](../../images/Picto+STEREOLABS_Black.png) - # Stereolabs ZED Camera - ROS Nodelet example `zed_nodelet_example` is a ROS package to illustrate how to load the `ZEDWrapperNodelet` with an external nodelet manager and use the intraprocess communication to generate a virtual laser scan thanks to the nodelet `depthimage_to_laserscan` diff --git a/examples/zed_rtabmap_example/README.md b/examples/zed_rtabmap_example/README.md index 79283277..98483107 100644 --- a/examples/zed_rtabmap_example/README.md +++ b/examples/zed_rtabmap_example/README.md @@ -1,5 +1,3 @@ -![](../../images/Picto+STEREOLABS_Black.png) - # Stereolabs ZED Camera - RTAB-map example This package shows how to use the ZED Wrapper with [RTAB-map](http://introlab.github.io/rtabmap/) diff --git a/tutorials/README.md b/tutorials/README.md index af275668..dca74947 100644 --- a/tutorials/README.md +++ b/tutorials/README.md @@ -1,5 +1,3 @@ -![](../images/Picto+STEREOLABS_Black.png) - # Tutorials A series of tutorials are provided to better understand how to use the ZED node in the ROS environment : diff --git a/tutorials/zed_depth_sub_tutorial/README.md b/tutorials/zed_depth_sub_tutorial/README.md index eabe7121..7ca8520a 100644 --- a/tutorials/zed_depth_sub_tutorial/README.md +++ b/tutorials/zed_depth_sub_tutorial/README.md @@ -1,5 +1,3 @@ -![](../../images/Picto+STEREOLABS_Black.png) - # Depth subscription tutorial In this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Image to retrieve the depth images published by the ZED node and to get the measured distance at the center of the image diff --git a/tutorials/zed_tracking_sub_tutorial/README.md b/tutorials/zed_tracking_sub_tutorial/README.md index 30fb8c54..66d81cc5 100644 --- a/tutorials/zed_tracking_sub_tutorial/README.md +++ b/tutorials/zed_tracking_sub_tutorial/README.md @@ -1,5 +1,3 @@ -![](../../images/Picto+STEREOLABS_Black.png) - # Positional Tracking tutorial In this tutorial you will learn how to write a simple node that subscribes to messages of type diff --git a/tutorials/zed_video_sub_tutorial/README.md b/tutorials/zed_video_sub_tutorial/README.md index daae522a..94debb33 100644 --- a/tutorials/zed_video_sub_tutorial/README.md +++ b/tutorials/zed_video_sub_tutorial/README.md @@ -1,5 +1,3 @@ -![](../../images/Picto+STEREOLABS_Black.png) - # ZED video subscription tutorial In this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Image to retrieve the Left and Right rectified images published by the ZED node. diff --git a/zed_display_rviz/README.md b/zed_display_rviz/README.md index ce3d320b..54eb06b2 100644 --- a/zed_display_rviz/README.md +++ b/zed_display_rviz/README.md @@ -1,5 +1,3 @@ -![](../images/Picto+STEREOLABS_Black.png) - # Stereolabs ZED Camera - ROS Display example This package lets you visualize in the RViz application all the possible information that can be acquired using a ZED camera. diff --git a/zed_wrapper/README.md b/zed_wrapper/README.md index d31caaf3..e5718c0a 100644 --- a/zed_wrapper/README.md +++ b/zed_wrapper/README.md @@ -1,5 +1,3 @@ -![](../images/Picto+STEREOLABS_Black.png) - # Stereolabs ZED Camera - ROS Integration This package lets you use the ZED stereo camera with ROS. It outputs the camera left and right images, depth map, point cloud, pose information and supports the use of multiple ZED cameras.