From aaee3443aad815f75ad8548fce881b398a5c0c8a Mon Sep 17 00:00:00 2001 From: David Baumert Date: Wed, 26 May 2021 11:00:36 -0700 Subject: [PATCH] Initial upload --- .gitignore | 32 + README.md | 113 ++- Setup/MAP.md | 34 + Setup/README.md | 157 ++++ Setup/TIPS.md | 102 +++ Setup/images/config.png | Bin 0 -> 25208 bytes linux/HoloLens_Localization/CMakeLists.txt | 63 ++ .../include/anchor_localizer/ICP_module.h | 58 ++ .../include/static_calibration/calibration.h | 159 ++++ .../static_calibration/cost_function.h | 224 +++++ .../include/static_calibration/teleop.h | 49 ++ linux/HoloLens_Localization/package.xml | 65 ++ .../scripts/dynamic_adjuster.py | 142 ++++ .../scripts/localizer.py | 86 ++ .../src/anchor_localizer/ICP_module.cpp | 420 ++++++++++ .../src/anchor_localizer/main.cpp | 28 + .../src/static_calibration/calibration.cpp | 789 ++++++++++++++++++ .../src/static_calibration/cost_function.cpp | 53 ++ .../src/static_calibration/main.cpp | 86 ++ .../src/static_calibration/teleop.cpp | 221 +++++ linux/HoloROSBridge/CMakeLists.txt | 202 +++++ linux/HoloROSBridge/include/data_connection.h | 49 ++ linux/HoloROSBridge/include/funcs.h | 26 + linux/HoloROSBridge/package.xml | 59 ++ linux/HoloROSBridge/src/data_connection.cpp | 43 + linux/HoloROSBridge/src/funcs.cpp | 56 ++ .../src/hololens_ros_bridge_node.cpp | 421 ++++++++++ linux/holo_nav_dash/CMakeLists.txt | 14 + linux/holo_nav_dash/README.md | 24 + linux/holo_nav_dash/holo_nav_dash.py | 276 ++++++ linux/holo_nav_dash/package.xml | 18 + linux/holo_nav_dash/requirements.txt | 3 + linux/holo_nav_dash/settings.py | 34 + .../static/images/Logo_RobotHandshake.png | Bin 0 -> 59580 bytes linux/holo_nav_dash/static/js/app.js | 194 +++++ linux/holo_nav_dash/static/js/websocket.js | 164 ++++ linux/holo_nav_dash/static/main.css | 98 +++ linux/holo_nav_dash/templates/favicon.ico | Bin 0 -> 129882 bytes linux/holo_nav_dash/templates/index.html | 116 +++ linux/holo_nav_dash/webSocket.py | 221 +++++ linux/navigation_launcher/CMakeLists.txt | 195 +++++ .../config/costmap_common.yaml | 24 + .../launch/hololensstack.launch | 13 + .../launch/holonavstack.launch | 42 + .../launch/navstack.launch | 31 + linux/navigation_launcher/package.xml | 50 ++ linux/navigation_launcher/params/map.yaml | 6 + linux/navigation_launcher/params/test.png | Bin 0 -> 1409 bytes rviz/pepper.rviz | 267 ++++++ rviz/pepper_nav.rviz | 661 +++++++++++++++ windows/MSRHoloLensSpatialMapping.sln | 51 ++ windows/MSRHoloLensSpatialMapping/AppView.cpp | 231 +++++ windows/MSRHoloLensSpatialMapping/AppView.h | 66 ++ .../Assets/LockScreenLogo.scale-200.png | Bin 0 -> 6366 bytes .../Logo_RobotHandshake_transparent.png | Bin 0 -> 42610 bytes .../Assets/SplashScreen.scale-200.png | Bin 0 -> 158282 bytes .../Assets/Square150x150Logo.scale-200.png | Bin 0 -> 73266 bytes .../Assets/Square44x44Logo.scale-200.png | Bin 0 -> 13981 bytes ...x44Logo.targetsize-24_altform-unplated.png | Bin 0 -> 3405 bytes .../Assets/StoreLogo.png | Bin 0 -> 6374 bytes .../Assets/Wide310x150Logo.scale-200.png | Bin 0 -> 54792 bytes .../Common/CameraResources.cpp | 295 +++++++ .../Common/CameraResources.h | 82 ++ .../Common/DeviceResources.cpp | 361 ++++++++ .../Common/DeviceResources.h | 117 +++ .../Common/DirectXHelper.h | 70 ++ .../Common/StepTimer.h | 200 +++++ .../Content/GetDataFromIBuffer.h | 57 ++ .../Content/RealTimeSurfaceMeshRenderer.cpp | 410 +++++++++ .../Content/RealTimeSurfaceMeshRenderer.h | 102 +++ .../Content/ShaderStructures.h | 66 ++ .../Content/SimpleLightingPixelShader.hlsl | 86 ++ .../Content/SolidColorPixelShader.hlsl | 40 + .../Content/SpatialInputHandler.cpp | 56 ++ .../Content/SpatialInputHandler.h | 42 + .../Content/SurfaceGeometryShader.hlsl | 50 ++ .../Content/SurfaceMesh.cpp | 532 ++++++++++++ .../Content/SurfaceMesh.h | 150 ++++ .../Content/SurfaceVPRTVertexShader.hlsl | 82 ++ .../Content/SurfaceVertexShader.hlsl | 82 ++ .../MSRHoloLensSpatialMapping.cpp | 641 ++++++++++++++ .../MSRHoloLensSpatialMapping.vcxproj | 441 ++++++++++ .../MSRHoloLensSpatialMapping.vcxproj.filters | 150 ++++ .../MSRHoloLensSpatialMapping.vcxproj.user | 27 + .../MSRHoloLensSpatialMappingMain.cpp | 576 +++++++++++++ .../MSRHoloLensSpatialMappingMain.h | 232 +++++ .../Miscellaneous.cpp | 93 +++ .../MSRHoloLensSpatialMapping/Miscellaneous.h | 63 ++ .../Package.appxmanifest | 32 + .../SpatialAnchor.cpp | 87 ++ .../MSRHoloLensSpatialMapping/SpatialAnchor.h | 32 + .../MSRHoloLensSpatialMapping/packages.config | 4 + windows/MSRHoloLensSpatialMapping/pch.cpp | 1 + windows/MSRHoloLensSpatialMapping/pch.h | 30 + 94 files changed, 11801 insertions(+), 24 deletions(-) create mode 100644 .gitignore create mode 100644 Setup/MAP.md create mode 100644 Setup/README.md create mode 100644 Setup/TIPS.md create mode 100644 Setup/images/config.png create mode 100644 linux/HoloLens_Localization/CMakeLists.txt create mode 100644 linux/HoloLens_Localization/include/anchor_localizer/ICP_module.h create mode 100644 linux/HoloLens_Localization/include/static_calibration/calibration.h create mode 100644 linux/HoloLens_Localization/include/static_calibration/cost_function.h create mode 100644 linux/HoloLens_Localization/include/static_calibration/teleop.h create mode 100644 linux/HoloLens_Localization/package.xml create mode 100644 linux/HoloLens_Localization/scripts/dynamic_adjuster.py create mode 100644 linux/HoloLens_Localization/scripts/localizer.py create mode 100644 linux/HoloLens_Localization/src/anchor_localizer/ICP_module.cpp create mode 100644 linux/HoloLens_Localization/src/anchor_localizer/main.cpp create mode 100644 linux/HoloLens_Localization/src/static_calibration/calibration.cpp create mode 100644 linux/HoloLens_Localization/src/static_calibration/cost_function.cpp create mode 100644 linux/HoloLens_Localization/src/static_calibration/main.cpp create mode 100644 linux/HoloLens_Localization/src/static_calibration/teleop.cpp create mode 100644 linux/HoloROSBridge/CMakeLists.txt create mode 100644 linux/HoloROSBridge/include/data_connection.h create mode 100644 linux/HoloROSBridge/include/funcs.h create mode 100644 linux/HoloROSBridge/package.xml create mode 100644 linux/HoloROSBridge/src/data_connection.cpp create mode 100644 linux/HoloROSBridge/src/funcs.cpp create mode 100644 linux/HoloROSBridge/src/hololens_ros_bridge_node.cpp create mode 100644 linux/holo_nav_dash/CMakeLists.txt create mode 100644 linux/holo_nav_dash/README.md create mode 100644 linux/holo_nav_dash/holo_nav_dash.py create mode 100644 linux/holo_nav_dash/package.xml create mode 100644 linux/holo_nav_dash/requirements.txt create mode 100644 linux/holo_nav_dash/settings.py create mode 100644 linux/holo_nav_dash/static/images/Logo_RobotHandshake.png create mode 100644 linux/holo_nav_dash/static/js/app.js create mode 100644 linux/holo_nav_dash/static/js/websocket.js create mode 100644 linux/holo_nav_dash/static/main.css create mode 100644 linux/holo_nav_dash/templates/favicon.ico create mode 100644 linux/holo_nav_dash/templates/index.html create mode 100644 linux/holo_nav_dash/webSocket.py create mode 100644 linux/navigation_launcher/CMakeLists.txt create mode 100644 linux/navigation_launcher/config/costmap_common.yaml create mode 100644 linux/navigation_launcher/launch/hololensstack.launch create mode 100644 linux/navigation_launcher/launch/holonavstack.launch create mode 100644 linux/navigation_launcher/launch/navstack.launch create mode 100644 linux/navigation_launcher/package.xml create mode 100644 linux/navigation_launcher/params/map.yaml create mode 100644 linux/navigation_launcher/params/test.png create mode 100644 rviz/pepper.rviz create mode 100644 rviz/pepper_nav.rviz create mode 100644 windows/MSRHoloLensSpatialMapping.sln create mode 100644 windows/MSRHoloLensSpatialMapping/AppView.cpp create mode 100644 windows/MSRHoloLensSpatialMapping/AppView.h create mode 100644 windows/MSRHoloLensSpatialMapping/Assets/LockScreenLogo.scale-200.png create mode 100644 windows/MSRHoloLensSpatialMapping/Assets/Logo_RobotHandshake_transparent.png create mode 100644 windows/MSRHoloLensSpatialMapping/Assets/SplashScreen.scale-200.png create mode 100644 windows/MSRHoloLensSpatialMapping/Assets/Square150x150Logo.scale-200.png create mode 100644 windows/MSRHoloLensSpatialMapping/Assets/Square44x44Logo.scale-200.png create mode 100644 windows/MSRHoloLensSpatialMapping/Assets/Square44x44Logo.targetsize-24_altform-unplated.png create mode 100644 windows/MSRHoloLensSpatialMapping/Assets/StoreLogo.png create mode 100644 windows/MSRHoloLensSpatialMapping/Assets/Wide310x150Logo.scale-200.png create mode 100644 windows/MSRHoloLensSpatialMapping/Common/CameraResources.cpp create mode 100644 windows/MSRHoloLensSpatialMapping/Common/CameraResources.h create mode 100644 windows/MSRHoloLensSpatialMapping/Common/DeviceResources.cpp create mode 100644 windows/MSRHoloLensSpatialMapping/Common/DeviceResources.h create mode 100644 windows/MSRHoloLensSpatialMapping/Common/DirectXHelper.h create mode 100644 windows/MSRHoloLensSpatialMapping/Common/StepTimer.h create mode 100644 windows/MSRHoloLensSpatialMapping/Content/GetDataFromIBuffer.h create mode 100644 windows/MSRHoloLensSpatialMapping/Content/RealTimeSurfaceMeshRenderer.cpp create mode 100644 windows/MSRHoloLensSpatialMapping/Content/RealTimeSurfaceMeshRenderer.h create mode 100644 windows/MSRHoloLensSpatialMapping/Content/ShaderStructures.h create mode 100644 windows/MSRHoloLensSpatialMapping/Content/SimpleLightingPixelShader.hlsl create mode 100644 windows/MSRHoloLensSpatialMapping/Content/SolidColorPixelShader.hlsl create mode 100644 windows/MSRHoloLensSpatialMapping/Content/SpatialInputHandler.cpp create mode 100644 windows/MSRHoloLensSpatialMapping/Content/SpatialInputHandler.h create mode 100644 windows/MSRHoloLensSpatialMapping/Content/SurfaceGeometryShader.hlsl create mode 100644 windows/MSRHoloLensSpatialMapping/Content/SurfaceMesh.cpp create mode 100644 windows/MSRHoloLensSpatialMapping/Content/SurfaceMesh.h create mode 100644 windows/MSRHoloLensSpatialMapping/Content/SurfaceVPRTVertexShader.hlsl create mode 100644 windows/MSRHoloLensSpatialMapping/Content/SurfaceVertexShader.hlsl create mode 100644 windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMapping.cpp create mode 100644 windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMapping.vcxproj create mode 100644 windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMapping.vcxproj.filters create mode 100644 windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMapping.vcxproj.user create mode 100644 windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMappingMain.cpp create mode 100644 windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMappingMain.h create mode 100644 windows/MSRHoloLensSpatialMapping/Miscellaneous.cpp create mode 100644 windows/MSRHoloLensSpatialMapping/Miscellaneous.h create mode 100644 windows/MSRHoloLensSpatialMapping/Package.appxmanifest create mode 100644 windows/MSRHoloLensSpatialMapping/SpatialAnchor.cpp create mode 100644 windows/MSRHoloLensSpatialMapping/SpatialAnchor.h create mode 100644 windows/MSRHoloLensSpatialMapping/packages.config create mode 100644 windows/MSRHoloLensSpatialMapping/pch.cpp create mode 100644 windows/MSRHoloLensSpatialMapping/pch.h diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..c597d68 --- /dev/null +++ b/.gitignore @@ -0,0 +1,32 @@ +################################################################################ +# This .gitignore file was automatically created by Microsoft(R) Visual Studio. +################################################################################ + +/.vs +/windows/HoloLensBridge/.vs/HoloLensNavigation/v16 +/linux/navigation_launcher/params/left0000_pointcloud.jpg +/linux/navigation_launcher/params/left0000.jpg +/windows/HoloLensBridge/Debug/HoloLensNavigation +/windows/HoloLensBridge/HoloLensNavigation/Debug +/windows/HoloLensBridge/HoloLensNavigation/Release +/windows/HoloLensBridge/packages/Eigen.3.3.3 +/windows/HoloLensBridge/Release/HoloLensNavigation +/windows/HoloLensBridge/HoloLensNavigation/HoloLensNavigation.vcxproj.user +/windows/HoloLensBridge/ARM64/Release/HoloLensNavigation +/windows/HoloLensBridge/HoloLensNavigation/ARM64/Release +/windows/HoloLensBridge/ARM64/Debug/HoloLensNavigation +/windows/HoloLensBridge/HoloLensNavigation/ARM64/Debug +/windows/HoloLensBridge/HoloLensNavigation/x64/Release +/windows/HoloLensBridge/x64/Release/HoloLensNavigation +/linux/navigation_launcher/params/left0000 (copy).jpg +/linux/HoloROSBridge/src/hololens_ros_bridge_node_OLD.cpp +/windows/HoloLensBridge/ARM/Release/HoloLensNavigation +/windows/HoloLensBridge/HoloLensNavigation/ARM/Release +/linux/holo_nav_dash/webSocket.pyc +/linux/holo_nav_dash/settings.pyc +/windows/packages/Eigen.3.3.3 +/windows/bin +/windows/.vs/HoloLensSpatialMapping/v16 +/windows/build +/windows/.vs/MSRHoloLensSpatialMapping/v16 +/windows/.vs diff --git a/README.md b/README.md index 5cd7cec..694f7e3 100644 --- a/README.md +++ b/README.md @@ -1,33 +1,98 @@ -# Project +# HoloLens ROS Navigation Package -> This repo has been populated by an initial template to help get you started. Please -> make sure to update the content to build a great experience for community-building. +## Overview -As the maintainer of this project, please make a few updates: +This is HoloLens bridge example for Robot navigation in ROS system. It contains three modules: -- Improving this README.MD file to provide a great experience -- Updating SUPPORT.MD with content about this project's support experience -- Understanding the security reporting process in SECURITY.MD -- Remove this section from the README +### HoloLensBridge +Universal Windows Platform (UWP) application for HoloLens. Communicates with HoloROSBridge. -## Contributing +### HoloROSBridge +ROS package of HoloLens brigde. +Module for using HoloLens in ROS system. -This project welcomes contributions and suggestions. Most contributions require you to agree to a -Contributor License Agreement (CLA) declaring that you have the right to, and actually do, grant us -the rights to use your contribution. For details, visit https://cla.opensource.microsoft.com. +### HoloLens_Localization +ROS package including HoloLens Localization module, +offline calibration between HoloLens and Robot's head, and online calibration between HoloLens and Robot's base. -When you submit a pull request, a CLA bot will automatically determine whether you need to provide -a CLA and decorate the PR appropriately (e.g., status check, comment). Simply follow the instructions -provided by the bot. You will only need to do this once across all repos using our CLA. +## Prerequisites, installation and build -This project has adopted the [Microsoft Open Source Code of Conduct](https://opensource.microsoft.com/codeofconduct/). -For more information see the [Code of Conduct FAQ](https://opensource.microsoft.com/codeofconduct/faq/) or -contact [opencode@microsoft.com](mailto:opencode@microsoft.com) with any additional questions or comments. +Follow instructions in the [setup instructions](Setup/README.md). -## Trademarks +## Tips -This project may contain trademarks or logos for projects, products, or services. Authorized use of Microsoft -trademarks or logos is subject to and must follow -[Microsoft's Trademark & Brand Guidelines](https://www.microsoft.com/en-us/legal/intellectualproperty/trademarks/usage/general). -Use of Microsoft trademarks or logos in modified versions of this project must not cause confusion or imply Microsoft sponsorship. -Any use of third-party trademarks or logos are subject to those third-party's policies. +General tips aiding in the deployment, handling Pepper, accessing HoloLens, etc can be found [here](/Setup/TIPS.md). + + +## How to use + +### Advance Preparation +Follow instructions how to build and install the map [here](Setup/MAP.md). + +Attach HoloLens to Robot's Head (instructions TODO) + +### Running Process +#### HoloLens Stack +- (HoloLens) Boot HoloLens Bridge + - Launch the HoloLensNavigation application from Device Portal (access the HoloLens ip from browser). Or use alternative methods. +- (ROS) Launch Pepper's stack + - `$ roslaunch pepper_bringup pepper_full.launch nao_ip:= network_interface:=` + - The local ROS computer's network interface name can be found using the terminal command "ifconfig" and looking for the name associated with the active IP address. Do not include the colon after the network interface. + - Ideally start Pepper with life disabled. Use Choregraph or refer to the [tips](/Setup/TIPS.md) document for alternative options. +- (ROS) Launch HoloLens stack + - `$ roslaunch navigation_launcher hololensstack.launch HoloLens_ip:=` + - Note that XTerm needs to be installed for this as the script uses it to interact with the calibration. + +#### Navigation Stack +- (ROS) Launch Navigation program + - ```roslaunch navigation_launcher navstack.launch``` + +#### Calibration +- in the calibration window: + - move Pepper's head into inital/default pose. Use either Choregraph or connect to Pepper via SSH and set the pitch directly: + - ```qicli call ALMotion.setAngles "HeadPitch" 0.0 0.3``` + - ```qicli call ALMotion.setAngles "HeadYaw" 0.0 0.3``` + - press ```space``` to record the initial position. + - move Pepper's head upward. Use either Choregraph or connect to Pepper via SSH and set the pitch directly: + - ```qicli call ALMotion.setAngles "HeadPitch" -0.35 0.3``` + - press ```space``` again to record the new position. + - reset Pepper's head pitch and then rotate to left. Use either Choregraph or connect to Pepper via SSH: + - ```qicli call ALMotion.setAngles "HeadPitch" 0.0 0.3``` + - ```qicli call ALMotion.setAngles "HeadYaw" 0.7 0.3``` + - press ```space``` to record the new position. + - rotate Pepper's head to the right. Use either Choregraph or connect to Pepper via SSH: + - ```qicli call ALMotion.setAngles "HeadYaw" -0.7 0.3``` + - press ```space``` to record the new position. + - press ```c``` to calibrate. + - reset Pepper's head pitch and rotation. Use either Choregraph or connect to Pepper via SSH: + - ```qicli call ALMotion.setAngles "HeadPitch" 0.0 0.3``` + - ```qicli call ALMotion.setAngles "HeadYaw" 0.0 0.3``` + +#### Navigation +- (ROS) Launch rviz + - `$ rosrun rviz rviz` + - add Map and Pepper RobotModel topics. Alternatively, load the [pepper.rviz](rviz/pepper.rviz) rviz configuration file. +- In rviz, select `2D Pose Estimate` and set Pepper's inital position and direction on the map. Try to be as precise as + possible. The script will calculate a pose estimate and localize the Pepper model. +- In rviz, select `2D Nav Goal` and select a destination goal and orientation on the map. +- Pepper navigation will start. + + + +### Running Process (INDIVIDUAL NODES) +- Pepper ROS full stack + - ```$ roslaunch pepper_bringup pepper_full.launch nao_ip:= network_interface:=``` + - example: ```roslaunch pepper_bringup pepper_full.launch nao_ip:=10.1.1.202 network_interface:=enp3s0``` +- HoloLens ROS Bridge + - ```$ rosrun hololens_ros_bridge hololens_ros_bridge_node 1234``` + - example: ```rosrun hololens_ros_bridge hololens_ros_bridge_node 10.1.1.206 1234``` +- ROS map_server + - ```$ rosrun map_server map_server src/navigation_launcher/params/map.yaml``` +- HoloLens Anchor Localizer + - ```$ rosrun hololens_localizer anchor_localizer``` +- Localizer Calibration + - ```$ rosrun hololens_localizer static_calibration [calibrationFileName]``` + - example: ```rosrun hololens_localizer static_calibration odom Head base_footprint calibrationData.bin``` +- Dynamic Adjuster + - ```$ rosrun hololens_localizer dynamic_adjuster.py ``` + - example: ```rosrun hololens_localizer dynamic_adjuster.py``` diff --git a/Setup/MAP.md b/Setup/MAP.md new file mode 100644 index 0000000..ef75581 --- /dev/null +++ b/Setup/MAP.md @@ -0,0 +1,34 @@ +# How to build a map + +## HoloLens Spatial Mapping + +Use the HoloLens device to build a spatial mapping of your environment. Map the floor up to at least your eye level, +and make sure to carefully trace along the floor edges to get accurate readings. + +For visual feedback, compile and run the HoloLensNavigation application and complete the spatial mesh mapping. Alternatively, + compile and run the lighter wieght Microsoft's Holographic spatial mapping sample found +[here](https://github.com/microsoft/Windows-universal-samples/tree/master/Samples/HolographicSpatialMapping). + +## Create a floor plan image from HoloLens' Spatial Map in ROS + +- launch the HoloLensNavigation app on your HoloLens device + - there are different ways to launch the application. Easiest way is to use the Device Portal to launch +application. Alternatively wear the headset and launch from GUI, or launch from VisualStudio. +- launch the ROS map_server + - ```$ rosrun map_server map_server src/navigation_launcher/params/map.yaml``` +- launch the HoloLens bridge in ROS + - ```$ rosrun hololens_ros_bridge hololens_ros_bridge_node 1234``` + - note that ```1234``` is the port number. +- launch the HoloLens localizer in ROS + - ```$ rosrun hololens_localizer anchor_localizer``` +- launch the image saver node in ROS + - ```$ rosrun image_view image_saver image:=/hololens/image``` +- launch rviz in ROS + - ```$ rviz``` + - select "2D Pose Estimate" and then click anywhere on the map view to set initial position in any location and + direction. This instructs image_saver to create a cross-section of the HoloLens' spatial map and save it as + ```left000.jpg``` in the same folder the image_saver was launched. +- open the file ```left0000.jpg``` + - open the file ```left0000.jpg``` with your favorite image editor. + - using the depicted pointcloud outline, create a ROS compliant image map. + - save the modified ```left0000.jpg``` file in the ```navigation_launcher/params/``` folder. diff --git a/Setup/README.md b/Setup/README.md new file mode 100644 index 0000000..fa82cc1 --- /dev/null +++ b/Setup/README.md @@ -0,0 +1,157 @@ +# Prerequisites, installation and build instructions + +## Prerequisites + +### Ubuntu 18.04.5 LTS + +Install v18 LTS from https://releases.ubuntu.com/18.04/. + +Install XTerm + +### ROS Melodic + +http://wiki.ros.org/melodic/Installation/Ubuntu. + +Additional ROS packages required: + +``` +$ sudo apt-get install ros-melodic-driver-base +$ sudo apt-get install ros-melodic-move-base-msgs ros-melodic-octomap ros-melodic-octomap-msgs +$ sudo apt-get install ros-melodic-map-server +$ sudo apt-get install ros-melodic-camera-info-manager ros-melodic-camera-info-manager-py +$ sudo apt-get install ros-melodic-rgbd-launch +$ sudo apt-get install ros-melodic-husky-navigation +``` + +``` +$ sudo apt-get install python-catkin-tools +``` + +Optional: + +``` +$ cd ~/catkin_ws/src/ +$ git clone https://github.com/ros-teleop/teleop_twist_keyboard +$ cd ~/catkin_ws/ +$ catkin_make +``` + +### Ceres Solver + +Install dependecies: + +``` +sudo apt-get install libgoogle-glog-dev +sudo apt-get install libatlas-base-dev +sudo apt-get install libeigen3-dev +``` + +Get Ceres Solver source code, build and install it: + +``` +$ mkdir -p ~/ceres +$ cd ~/ceres/ +wget http://ceres-solver.org/ceres-solver-1.14.0.tar.gz +tar xvf ceres-solver-1.14.0.tar.gz +mkdir ceres-build && cd ceres-build +cmake ../ceres-solver-1.14.0 +make -j3 +sudo make install +``` + +### Pepper + +http://wiki.ros.org/pepper + +``` +$ sudo apt-get install ros-melodic-pepper-.* +$ sudo apt install ros-melodic-naoqi-bridge-msgs ros-melodic-naoqi-libqi ros-melodic-naoqi-driver ros-melodic-naoqi-libqicore +``` + +Download python SDK from https://developer.softbankrobotics.com/pepper-naoqi-25-downloads-linux. + +Extract `pynaoqi-python2.7-2.5.7.1-linux64.tar.gz` to `~/nao` + +Add naoqi python pythonSDK path to .bashrc: +``` +$ echo "export PYTHONPATH=${PYTHONPATH}:~/nao/pynaoqi-python2.7-2.5.7.1-linux64/lib/python2.7/site-packages" >> ~/.bashrc +``` + +Source packages: + +``` +$ cd ~/catkin_ws/src/ +$ git clone https://github.com/ros-naoqi/naoqi_dcm_driver +$ git clone https://github.com/ros-naoqi/naoqi_bridge +$ git clone https://github.com/ros-naoqi/pepper_robot +$ cd ~/catkin_ws/ +$ catkin_make +``` + +Disable audio in boot configuration file (set flag in line 85 from true to false): + +``` +$ sudo gedit /opt/ros/melodic/share/naoqi_driver/share/boot_config.json +``` + +Optional: + +Install Choregraph. + +If Choregraph fails to start, try: +``` +sudo ln -sf /usr/lib/x86_64-linux-gnu/libz.so /opt/'Softbank Robotics'/'Choregraphe Suite 2.5'/lib/libz.so.1 +``` + +## Hololens Navigation Installation + +Copy `HoloROSBridge` to `~/catkin_ws/src/HoloROSBridge` + +Copy `HoloLens_Localization` to `~/catkin_ws/src/HoloLens_Localization` + +Copy `navigation_launcher` to `~/catkin_ws/src/navigation_launcher` + +``` +$ cd ~/catkin_ws/src/HoloLens_Localization/scripts +$ chown $USER:$USER dynamic_adjuster.py +$ chmod +x dynamic_adjuster.py +$ chown $USER:$USER localizer.py +$ chmod +x localizer.py +``` + +## Build + +``` +$ cd ~/catkin_ws/ +$ catkin_make +``` + +## HoloLens Spatial Mapping application (Windows) + +Enable development mode on HoloLens. Pair device with PC. Enable Device Portal. + +Install Visual Studio 2019 with Universal Windows Platform build environment. + +After loading the solution in Visual Studio for the first time, navigate to +```Tools```->```NuGet Package Manager```->```Package Manager Console```. If +you see a message "Some NuGet packages are missing from this solution...", +click on ```Restore``` to download and install the missing ```Eigen``` package. +At the time of development, v3.3.3 of Eigen was used for this solution. + +For HoloLens generation 1: build with "Solution Configure:Release", "Solution Platform: x86" +For HoloLens generation 2: build with "Solution Configure:Release", "Solution Platform: ARM64" + + +If HoloLens device is connected via USB: + +![Config](images/config.png) + +Deploy target: "Device" + +If HoloLens is connected via WiFi, deploy target using Remote Machine settings. + +Deploy information: https://docs.microsoft.com/en-us/windows/mixed-reality/develop/platform-capabilities-and-apis/using-visual-studio + +After launching the application, you can air-tap to toggle between wirefreame and solid model render mode. + + diff --git a/Setup/TIPS.md b/Setup/TIPS.md new file mode 100644 index 0000000..2f51693 --- /dev/null +++ b/Setup/TIPS.md @@ -0,0 +1,102 @@ +# General Tips + +## HoloLens + +### Device Portal + +Enable Device Portal on the HoloLens device in `Settings->For developers` + +Navigate to the HoloLens IP using your web browser and set up a user/password. + +#### Certificate Installation +Navigate to the HoloLens IP using your web browser and download the HoloLens certificate. Convert and install it: + +``` +$ sudo apt-get install ca-certificates -y +$ openssl x509 -outform der -in certificate.pem -out certificate.crt +$ sudo cp certificate.crt /usr/local/share/ca-certificates +$ sudo update-ca-certificates +``` + +#### Change or disable HoloLens sleep settings +Navigate to the HoloLens IP using your web browser and log in with the user/pwd set above. In System->Preferences set sleep +settings. To disable, use the browser's inspect feature and add `0` as a list option, then select `0`. Note you will need +to do this twice if you want to disable sleep for both `battery` and `plugged-in` settings. + +## Pepper + +Using [qicli](http://doc.aldebaran.com/2-5/dev/libqi/guide/qicli.html) commands. + +### Start Pepper with autonomous life disabled + +Disable Pepper autonomous life mode using Choregraph: + +- Connect to Pepper using Choregraph. +- Click on blue heart icon in upper right corner. +- Wake Pepper up by clicking on sunshine icon in upper right corner + + Disable Pepper autonomous life mode using `ssh`: + +``` +$ ssh nao@ + > nao stop + > naoqi-bin --disable-life +``` + +Connect to Pepper again and: +``` +$ ssh nao@ + > qicli call ALMotion.wakeUp +``` + +To make Pepper go to sleep: +``` +$ ssh nao@ + > qicli call ALMotion.rest +``` + +To shut down Pepper: +``` +$ ssh nao@ + > sudo shutdown -h now +``` + +To get the joint names for the body or a chain: +``` +$ ssh nao@ + > qicli call ALMotion.getBodyNames "Body" +``` + +To view Pepper's current joint state: +``` +$ ssh nao@ + > qicli call ALMotion.getSummary +``` + +To change Pepper's head pitch: +``` +$ ssh nao@ + > qicli call ALMotion.setAngles "HeadPitch" 0.0 0.3 +``` + +The `setAngles` call is a non-blocking call. Parameters: +- `names` – The name or names of joints, chains, “Body”, “JointActuators”, “Joints” or “Actuators”. +- `angles` – One or more angles in radians +- `fractionMaxSpeed` – The fraction of maximum speed to use + +Valid Pepper joint names can be found [here](http://doc.aldebaran.com/2-5/family/romeo/joints_romeo.html?highlight=joint) and [here](https://developer.softbankrobotics.com/nao6/nao-documentation/nao-developer-guide/kinematics-data/effector-chain-definitions#nao-chains), +or call `getBodyNames` for a complete list. + +### Pepper RViz configuration file + +location: `/opt/ros/melodic/share/naoqi_driver/share/pepper.rviz` + + +### Miscellaneous + +Enumerate network interfaces on Ubuntu: + +``` +ip l show +ip a show eno1 +``` \ No newline at end of file diff --git a/Setup/images/config.png b/Setup/images/config.png new file mode 100644 index 0000000000000000000000000000000000000000..890f752d39bb8587b25cf1cbc12ebe4158687271 GIT binary patch literal 25208 zcmd3OcRZWx|F|Gs#;oVmS~M=(bC$rYNo2TP$M*ETQypf&h7|iUCUYYyA2C<> zpW~96@qgYj1?0{<{Lk6zFz$2zoUq(_SMu-4vr8J0J70z4L?)~@_FnX-36GKv{qt## zMCb{_emtIm+t+b#XDEDPmkKOay!_ASEIO_RLNHpua%u4=JiU$nslrky&_)o9ok2-=kTWa&;b_S%|Sgw6iDwtGCGT+BH}^i?Zj+5f#tw@*UD8nJbQ;;s8D z8zA}b2XZpW+?4XVnKWhEoT@07>MmujSG?*;L`~S9^M4I{o6Asjy93;#y4$tSi^`h9 zgBW8936>s=!nq7@K-uiO|NVVV!+xF;q$)l@SAD}+ao6;a*RiyFsG#7YOAU_+`UaP z!|6;;Z#E$2e+_q4Orwq12;xH}P2s6XYFtl}#A0Ij#<3FBouRl-9wBrO)V|nW^9Xlt z2&O5@Ub_~8ihY5K<+_$WMmqFN4-oRq$L-TB531y4RG^OP&F0OA=J51S+6pfCBY!RW zUc2tOJm5wj*T{Zv_U=ApA}CNcTIycV?m8-AW1v0f?4N0>0l~#t)hgoYUN<;0$s3eO}#(6EE8M6>R)JDek(_zDcb}{jJDwTc#F2Y6|GOBWbF| z`yP7*0U)+V4J?$71wtQUcAd`UP+FJX>sm?<;UJ}z&>{>24YE(p#gFO8=ruHL(ga3A_ z>XobNqaa;%w5DLcn(_LQ{{9nkm*4`9o~8=j+5DtEV|@{n;@lLn`tmPfIeEj`43!)t z_6v)YhCb8^XgRhjSzAJekPd9PH-JTswq*fDr|CGV`WKQP@ zocT{4xaVD={9bHkJvQnjNlQNDAaWjEKmxKfV(v#;7+dXOs5j2!oypT%*8YWj5mN`X z3OQjIrFha%bfjYXp}K0gylN5Zv#5~R-`0|wcpNEqXqhW`Ep+oXkr^3u)C+Xd#wc^y zThjk{&hdA?MV^R1lmdf71L~H($a}eN3?im|k|%Z%?yY^-&Qea1Btw8fkQRBYdU`fr zN~*0`SLATQa|pJ-TvIYVn6kxYZqopao+k|Ywxziv{EDAu743>8f0;>|5oIBuJ!C8U zB~^>v7qE@W{SMfx`D5qs{>Sx0&Uhs~!ksJ&Fd;KK5izZF9}1vUA`WBcx3QE=h&fTB zBx#iF(%5_g!)jFNx-o0UP(+P-{wv*21u6zgBA7ZvxlO|3e-4m0vc&y z;@FC+`nnX8NVxO2G(L9BsOk~jZ|2T)iJw^4)dGV>7Q@VgSu z&%DLN@Lex;uf4NIPP5)Cn|&=!*{UblGkj;gs-z>d6q(Kq2|h-S3$D=$O5yDd6h#vT@72A(KuBF?l0 z&J?ZmDVB6ZBP94DO14^(;5`c!Pt&XQUS!OMoZFvvj{F_fQyp4Yir+wo<3U4fD$df9a$AI$f%TEwgfoLT zz`S3AHVlr4lo?KQN}R-BSoBCT;cPq^h_2Fy18?0J={)YiZ5L$5A$}E(y%u?bi*u7k zR~@LguKL*+KqUwHJ%P7&lsw^T>sp>q_GtIIVl2xxwdpU2kWix*Zi7{x)PYPU+WcoA zC6m5POIir5cjRT;oa!$&k}kEglfho`vUVl(y_gC_EryTqt&cO?k>AI!d&ZH>0hE2*;^@#7U-l`W5ZaO_PeTf?Wv>Em#373NC(OEM zA=MLQwvoKX!QnSiPjEedx_BvsHtPt!ThwbflK_w5`> zzx;TKf)z%Wob}9tkjqyx8+dw~xN36Zy&DAWXtey!pfUYsl{>tuQ1)_~gXOyw?GfE} z$;mWDjm*9Y8)S>(!afqI{LrPVWo-%ZVcq~P&_A~!>5kq~AB|U>s&;;|n zH{m5;NE`tcMtbdDQ-o!ki$)-kku`VreAulO5~m~1b-YJ`u|Rjgc>xsIo>b7x+(Szs zoTaysw$F=2F;f32Y-_3Jkz(#mKZ@q)`2D>*z8iDJ3wN?8?;;#j}cp%{D zcD*q2rQ<$@wI5Cz9+@zd(6mbf8=B4}7i9$Z2bK|Rt~d%zDQ;8g@rq6*s3c5nIc7n3 ztAA~tqiA%b7c4#2Vmfx|c9x|;%?MwqwdvnZ;xwS6ZtTgRD2VKnrS=tLRqEP9c8Wzm z1+3Bn$w(?AT2b$Ja{}Y*Wmo1z7Trg{geK)yBIKG-`ci?`A{#f3X_+h^Ib3H&xu4Kj zE`;`w{|17A<6!oEsIkuDN-5I&RaFtdxJR#M#f^Bv&yGvELy7hczk?Vvy$Y^fR&z$q z+9TJG^o;vlw4dS&E3utdFyuM)#e-cJ+MepN^9F6xZe>z#KXds^!PrEHRkN}PVeW3D zPH&ks0|wpM>K8#@x&hDt*H_k{q)xZDznl0^eMy<=W6IVqPtwPK+}Rw_7xlwYEPE_x zyowYvPVW@QV1b1lI24~`%EK3i?#kJ6ddbKQ`6iTJRY%L@h5=u*y@hSeJfO}ET2iR% z_+og_LtmU}s@d3cNq8N*0&dn9+4wsa=V^K#^@3F(lQjpf#b6JqWFCzdZ#s4JX=v)! z4%2>+dq1#x;{dbq3aCndBAk9}&c3)`0hE1O;-bsNyz%7h2J1G|Nnr=euRGzZ2PwJ0 zVM@KThTB2W67GP_Rn!`3e3U@0-n#9WDM~Ps*IPp_l_>=;?KbS(6zQ<9i8b>GO@Z*g zR}5yuE9x5_|GV+YIpWP`_=UCziZ8bg_`H)T{yTPxI?SD;{Y=8xeUH>XP7i(%8Zf%K z((TQK@N8XIUOw{HE5)=;=L^f#K+Cg-W&Hx4cBpqaHTBPOcU+j99HB%g?s?q^Kl{K^ zAz)m}0h$O-<{I&B`!Kay7e65ZK_);bqs84q%Ubp{^9`A^ z4~`ZYICsPQe>z0Sk4`P2>Dz(&m*h_rcNUrPixoVc_3t*EkO_pc=O$s|D--=f!7}Da zr@`hpZrj!wk!x$=z=U;JQf|@Z#{}0RlbT=|G$A_S_v)utGtq=f59E>;Z5;g>v_x+r z8xaD()O0%4OT48PTGfG7&eX2Vv`oB%tdvTK4gj1j1ZINjo~J8d6bJ;p)JvK&{eVdG ziQe@am5+HQwn;Ps&7B`};};l=E8^bt#K+ds7v zbkp_p$E#HJG9Mmv!dB0kbS4c>lm8N*`8x-~91B7i7c~Phyn7Cs3ECdDT{Tvc5kj6B zK?#N^)6(0g5|ww?CPvm*n`XbwC0PPf-SB%K$ z%KtOCjw@_65YOyZhYgIgbilLvZ>LDXRKek5s{`~zTX7`mWqWZlMv_in6e%M-X{kB- zpG#9p$7kOA&p9) z2OSplvR~uACz9BlrkZj4Qn*SvPY+Q*p;+CxkI zg<+2~vFe?}G5Z0VL+x7b&GSY*Q;ykX-+2Bb6bnmQigV=hPEWS7RP){rUqYr5Nk8k= z&-b3UEcU6RM*7#=sR7jMmhfQd-^ddD?}d>v6Wn8s&Lc}bjo=B9_6?z>zDCqKdesr#4$Lc-nMY?O;~kxAP+op^MOHR3%Jz^%UvqCv`yRo8o*Y7@o5mrK#1}vh z#VXbqqqZ|oR_!WQ)obQCLb;vyP8cp0huEvmZB(I0`G%5Py6)P!U{?nkoyVF3z4o7& zB-3BwWk+2rp)LjvzqzYF)LhQy=}pAfG8F^H=K!*8Caa3*TCUI5oX$3>nbm;O9_HU4 z&vyt%v`2oJRX51Dv1BS7EGXqz=-#|xXI@k>dp5?!`r?+%Gnq|SzFQN)fPq?2L6AqS zB%*fz8*q2x<+qfqo9g?J4^vw=JzkGTfMx!B{;L{94Xi>*f3d>c!_r6U8vP?JQKM@B zRe8Go*DBJ5KdK2&`qyn8u+m!>RYzId2Im3uvcr$5v2rlTn~k1b%0H841Px^HJcJaD zU9q>wxQ#LJlgbEc7oW0Uel4q`T3H(5-!HGv*&F?vzk90nt|Zfm&e}lRWX0V$xB2d7 z3=6RYE0t{5&hIPi-j95?Rs0P1vNmMGU0Cu!22`XO6?Hy|KfK=(ur< z9yUcixrhN~PTX;w5b+%Vb{?T5=+DQR+C)wEvRD{YP>sQix7XSqJyc{`HZ1dpSA z{e|F`@4hzAJq-F^HLpCxDztf}y4X8$6u%LZI!@Z6&J;8n4T$k6!rbH8W1PPEwHce) zJjQvC<1Y)=JC{&~u+@V@GM&pwub#JZL^ZVkLh*T6SAu`7gX4;_`E=tvf+pOW`-6X$ znf-uZB^)MJ7qPMSa{c{aZgc6#P>`;<+V=k(IJ1eIH-j&qlyIN{d1 z%(#!OY*@?_NVjJwbd_Q4+#)Gc<#CAMJ;;0Iq__uymJj=y66dW>aH7#gLq!wy-!@Ih z?)q4nF6{(#nc|y={mN4-gLS;WnNoG_+r$a4OrWWx(H)E?XQj7GRYTeekM-E^)Tm3j zrXc~^#fo{518(LSPJyKxh^;Ey-Ii_Z{CviDP4|8xV24Ty{Y^bXvy(lc0t<*A)2*h7 z$%_GHZ=PA^B5!sX-$*vp#!5P6xPdI98DBzLQ_Ddn!b$L46kH`O7E^cfdgorMAd~SlnM&W_)Ck07@1iu-Pv0@wU|;^hGR9Mywp*l zK8#t!3hq*#eVxY#GpeMDzuej9b!e|Apqn_aETjUAF9VY*;)(ovHGt7e5|> z2{<-kCqpVsZist8w_|Uf%T|C13Y(x>VcxzYc7>Oa#)~TqthE%pHT;iuqP7^dqKN*d z4@4dNo0R>zc}1gv_sBHgDMI(NI|>$gMQ`$bcpPxX&GrUPI+U2j_WS%c!eKu^@Fr5) zc-`xzv*80T=pP!bf=o=3OobzZgn`aiCgpdk#&ez(mFiDi*6$>E_sMk5=*`ImPNgn5;STKGHQQ}dh@x|ZkFnFzPq8f)!4%>PGZZaZxd%5 zvwml0Bh0oaU&^j!w*%F;H$s3}vS!s%Mo;5wM3BKL>koM|>nheCk8JXb2cg}iKu{&e z5wU^%_74P}f_l=^krOkboy*|?D;bwVv_}reS?)5!$YrC}S5=7ben15UA0!`yr0bYH zhI2dTVI``d1hN0#_Co?6DXEtK8NOaxt5RAD!fH-S<%cN)pDDu}0U>No(?h-A+%!qPNs&qY2rRe-hRaJs4 z92GS^6NO-W5Q{rxi0#qOHlz6VS9R5UeM9kkg*uM`N-83RG0^M2%J{u!;nwxxOO3yE zmO;JuY64E4j3>dz@DYNRl-f~(*H~?sdjf{yzLYY>hw)1HE~BL0R7F_T56ET_dCXP& z0$tF^rB}k38d-W@Y5uINc}76td9~4!pgg4e_SR6(mNDTJQ!}rN76kJAJ^m0453D;k zzGetwMJ~~L72BaOSC%FD0ZvB&^(uXo10PbpP_4i;cfM#1qMh(EGMB{Va7mone#ix}r*N|v2IUI1 zG3#vK;8)t%@B>dNZQ4a4IFJMVfv%0#U*t)fs6OPAULEn{-mO_jpPDT8v=B$igGZCw zkhg|VkL?+CK^EhV%2jDU=v6NCyUG(5o^%asT*;)SYZZ;D1r|A(#nr$KzCZlWDV%H@ z`R*X@^b{|>mtOKi;W1lX@Rt7s?oOlmK=(-6^y}E-+wNz3dhdV$RD9R7UhN-<^~zQm zt_nKF*ToeZCaLZ|N!MoVz)))#*7M*1Ifn8JOF6s^W6-TxmtR}~7G8}WHQNK&r<4%e zzA_VW2uCDNj~2XWlwsEIDXGgj#^y{i+LdFe2`uQmjMx(M$>?VAp?BZ)jls%o)N zjI_jMaZv&wYg`Q{9+or^>0e>r&6WEZtbsehcL2Wb-B26VlWUqf$vdtPz0c~r7W2fe zXjOMSzeuPV=kL&cJKKK5H~BhNs=Leo$Oj~OLa3@&TBHET4n~5(h(Y_WoB<)FAP|I+ zr`AxE9pM(WfGrbDy9K{w>bk;Vn_OD83+|OR#0GqXgFfzGitr!ol_lBd zTP<#&*4HhoW|8FRQb8e zlOT5UQb&w@S2uSRwA4L5r@eH4XvgRGoRE4G<1tG+x$-(vJS|$eSRKODTN0 z!%XQ7L)|}%Rrh*XCUnD+mQ%;>eR3Bi7Ci;>dE`4Npn|wx3a^soxGyHuR!-^_eT$IW z{Njd)x34}hx6;fjUR0m&X0*c1t|z#)u}h4N?O99wF@Z%aig_MHwpSXN@Ck-|jc(fCtxF&nVdtw{DzJKEL@CLBVTEF{7Sp z{i_x=UPBJX;cBk)JMQiyXCuw=EwefSkfJ!9yZG#t60x`*Mi(*R2ZgwT1uwc3EG3R;!(vRi)GA9v;zIj{cTusvak6RYdd$%p~QLUhpL@WCBjC@JgiLvV$sZ zX1AY$LU~VknVO4_$fJ1n0WNmfF$s0gZCjF*35stc)AZCHNn}1Z)(oDRF_6z}$jnSu zg}40UexWLy3BI(}6@2?uIJMKg{i+cw(M`0hoZUVt29h!19+dMTNhJ| z)&K^*C3{RAWigr?RbzFwK9V;h@)$dUHhKxO1K+>3JE(Hq*-C{-mD}|LRiDgM^($*) z6dO}Wez@!vonqpp%7u%@qxIi7v?rTAS}PtB%xAU$_^tP)g2F?KZm#J!H#P;uA9z}8 zqds=v#ZwuQzMu;-2TAhlJJ9jpE;JU(4fzxK!-$jk5IgN=axTCRsIBV z_x-!tOl%-Fe`&D>1xK>q^fRopi6Qvfd|SAAF~%PmiqV^QVNsme1+L6nOQs@5F%B2=(9$fcV1!JEr^!NiEm((c6xR0E zH3EGM21MpdbZ=+RNPCzPdbJJ5?tQ-@*LP`#^|O2IX^dP@*{jky02SGOS^BzU>Q`x`W zViMrwZ`0G@1r#G5e?AET)!Xc+CmC^lYri14$x})^-YV8ioTnG9;=HToKH@+b{(*4Z zr#V#ct;vLepqUp|>k3t>vNWn)obFz`k!ehEh!r^#jQu1S_+z%GDsHiD>HE1bd-Cc8 zSithn7XeFHEu7!k`C0ugyM<>dvK6Ie2}EN^^cpyOhiD3&&i;x=*F(-88EpET$zXT;Xwt5c1|a&qpt;?w*MTIyOkKf ziIsYl%lr0QIvdFTl5UCXTN?$pObhVZksQ?~(19O1#BiUxr#cvUoI`(pM3iNaOXN<_ z%eZ7%?!1AsEn)09QiRhIzlWJ9wf_MN%sYK=;IBO!bq^y?=3LNG@Dakv9{zQt%u;d7 zl0~I%Jzl~0d+S->3iA#4*U$*h|BWZcWy(x7ZrL9{MfC?WWz=xMSt~P_+vMdvZHVcYj56P8Zb-W9*rLFD*V$v#qlVe>c2U z%lBk!Yv)phpDM>K`M==fIJ21bp$hm6*!AlUsn|snDh6+}{Gpk}I`&pR{hf!!4Kv3@ z^p=i#n`ky&S)OI{EOtf80bhERp3*kJ22C@}8EbUL|r{kDJUK!cy;DcH;VX1uW0pugy*E^d1>u^@I-Oj62PocYc*D+FbC% zIx9F~RkgwXaEplkXzF)#JmZg}i2#ZE6#_zmuF>mc7&`Lw4B#8$KrfgCmA3pF&t`%)mHN2)*{Q;07dQVr{rNx%G z6LA>*RXNouOD$P;acRRng?n5CM@+jnUKCc>U7lr?#ONPo55Dtz_ebRY13J!Of$1(D zyQkEJVt%-*2b$^6Hgl3%Be;N;Hhyc@bUw96*e)4l|8x!Y;U}yXcLt;EZ_$2)@y`r} z5uVplO9@-5&uSU{T&JIZ6Xa#{viB#~*Xn>4u5Vm>{hK45JZNL?Ef(0etS$*d^Hw@k zY|;Qu+OMYMu6ZJ~5)II;d@nK7!@afW`V;Qqx`c;j0iV7F7Z(goNcz|}Puq{B_-T#H z*giSO)>2PC=I}-NoH)ev?I3`vKXOh^U;eiszo#g^RzQZ>iFK5|QzCy(^?3t}!Hckk zT+2xer%o2L>P`j_ko42At=CJ6W+|)QVQ#`aS6r~30xP1helAw4Ri5OxgJ()aRX<6i z{H9QtWl0+~6KI-6QAPg+W&pEPH~pSOwBWww+s74#7FisLFB`b5=hL|LcxMXv@F}ZT z3p;GGYzpZ3rBu;A4urNoT_p;9?3#7FXtJ(C?wOTd|GuA^hgm+%sgx|B&MicoLkd#f z$*P9OZ=~y(ZFyupJ>WH8f6+LwiG`^CH)rc#kJql_R+#q^dx}EM3OGq;-hJ^oc57Da zyXc`Dxu32ZPmO(9mVFb&^}SQMjYlEt)0$gk_7UAmH`gp3)^PRMey z^7jb2-*VjfEk{|wY4d=`2D~W|yf=Ei(EdFMIx_nA9+!yeOFSyM^QUOii&R}{F`*{D zNIm+CiCZc5%#z|d&IA+oe~>?N8@G%l*;(n7h@sS%R;|+k2LnHQ`g>sU0>l##wT(=> z3UL%WlrHy4`^tq8MwMJ2+DN}H*xxX#x)BD^9LXwZUJjU4H0N7^9yY1@YdC5kf1})%pXm(TloDN zz8xA^9P`^#e~BK<&HbRIdaOnIGYh34LGMABf`{_m=7qI}9&nZF9a>ct6iogaN6HNJ zHg^9h=;uN084H;r(h{7b=u|q_l5$L3l~tl-RFfA`5dyVyrWAbuaI)YAx9-=g2j3A^ zRUV4%8KyA0)n`g#e@Ec23kP!!rYOJJp7YK&bGe-4ZZ#iJ(IMa|skEH(=&QLVUr5%p zzmaA->uYx>`W4J|lJ}NMqS&JL%sR(`#EgfLA51U%4Bjs_(pOO_LyuFkv6IoLMI;2HTyedM~R zZ+B1~8j<9Ckm(2A6p25A2mRaxSy+-R^SK*V-@al0F#qMj^+A=b+kKx*@%1bwdlK1* zS)OnS_+)&z{}CT4-~B%~=Sq$7h$oy&VxSp`V9J{+!{QpJCL|bSZT@7O(G@)C@q0w3 z%UN{%XDmy60XwK7*K8&R7W3chB7XFCu}%>yK;R#688`pmqu^+H=Wy1>0!igo%@#D} zgdo4COWw~;Lqax0=tiC)=q(vD;4aLBRvp!MIl{EkiphK33@umQwSU%&=1{%m8-!SE ziYfHV0V1*POFZ(Jrnk~=&0oUhM)`6AYUqxUE6SxI5wdsVX6hzpmIJ!w$+Lx;z9F89 zu|8aZ8^QGAH!Jb@QVfFv_Jge&4VkS1>Z&HNF9z~w;;Eqk3MBhEeY=T*j0MC1oHxqz zbnUXp_OrW(Sr}?eQ@=E1^QpozZnZz7hS;D4JY>##*i2K#CTGopCPIpknVw|l9@W*o zpK8LDa$BayO8$FkO+PX>7QoE1x`g< za4rItoj)*5@Y*0XPHmJc#4&QDRs;*qDY53;OXUVOENKN#-n3Fpv`~Y!pSNU?Wor$fS+~Tn*1XaFJtVJ zoA0bt3$srTU@?+7qGMTtLfcZ)X8RYrhYmzc{wKRQ72w^a0;5kOdP*vH8Jo91>88(Q zxJ|!$;x%fhc_CavKj7Dg`Int+d?S!#+4$Oc*^jkDXd(K(*VL)dQV)>wnta$p3+Qnd zts@e)lU`Ar&Ls->sL!eTece0fBJ}u6dU?vo^|01DtHTyxV9*eb0&eqbrNz&Ykb$~( zAzlQT<;@*fR4s0ED4-&QtJLv^x2}67x^5re3e^_>Fmg&^fblGAnz?OOAb0`Pj+p^6 z_dkSS*uXY8X^JvpLWNKc*Zaz-Wdz;Ev_3yuERKF5Ww*W;$ct&UE7v=vv=TY@*$5C* zIiUB*v?@uFl&vX{v-25sh(*WowGhnr?b=W`NDkvqcbbLgmqqREZ|wnArAKkC*il7P|@fP({yf48w=pf)xuV6ju8E@A$vK1&Yw42-0I5Bs)Yg>Ox8aBNJ6p5_ zpdfdK1s8==wHs_B`CMbcF}tV)#MX=`vD>U=*lz$WbS*w{X;a34xC|UdRVJJXcM)osiXk*yE@v*fv9(kImKfD+(P*CTKatFM%Op8&b%^!!x z&Ak^=9Ys-s?Lzz$(s)h@EtNU>sz<(eV;Yn|jm3)P;s2F5O8iz{1=KD?3ReuA|B;ph z`sUBz8}`e!f$tycX$x3Q1VUZ1tI7hYG$}3hF-s~=Dl;6wFn6Kv0P2+t=r>0rfHlCo zyKBOs95Ncjx6SReCCmL1?t<{75Ne-1{2Ql%&IvKF_{i7dB}x5;Ez(B#>@UB);ul}o z77O-6zScO3EKYCU^BTk9A64${Qa|}IhRqW4CAY(d@6?TNZ4F^yn4JDHYZ}lFE*u%p zGPc+8Mndpmx+BjQTJ!Q-V`tT|q=Ce^djP^h zY{DLzIp^SBedQaomH#ilR}UiZZ)=c$(1D*XL%P?OslU3DCipX0^YQ*et6>{{{CC^Y zMlg(=V=j(>eYs^+LQtqQJz~TuO4=#*l z1@3!dPpf6$YY5e{1V#h!A|EzJ>Q5Iebh)Crge#~tS&>KJM; zru7hu5N}us-`?V+CN@gP}5WX!V?9E6IybF`ap(Atfe9vV~34v z{3$=eq|q;>BqPoiU=-NO01O{;BWU;W4qAt}(0NX9vcX89-u?^*a0dBfdSH>ipapGL z723^jlkO0?wN>Y~?-$2K7G{U0;TTq0W({Y=dTTT;f*DXajHgub?{ zCC(Nif}fls|4BTpsils=Jd$EreW^B+D%Q>cQB|0)8bAmZAlmnti25wAxjJH9{zO-j zrJI&|+o6^Vh>-A4+$PhTUnxB|Rp|?zem*26zJ)f}aHz&FBN*8S7G11crEQJV3|{Zj z)HysL>9nyD)l%!0Uyh@vqe;7HwRo5PJO02;I)5^ofzF-hod!zMLn%M3Y9?sb#N+Nt zk)#cSt$OTQ9ca6Kct_Y;J-x+eRW~HQ9Jrz4j74>4(_`k2Q1?}r7Cl;4&O>;Gia58h zGeC=}#{21JN;++l$4i9znlQ*~u-Jw``EoF)EWI^^{v4K+j^Hl9U>^n-I=f#{dqjP_wVC#@IH_Tv%Nc!b z1#Gv$xfm?DaEWQJ=l|1Qc)vJK4AdM|qLf&$4b@WOI_04e{JS=fK&vl~2lyi9|HkPDVn0*IMN zvoT;hA}jct_a`(cC|)t9(gz|~dMq0}yfAeEVn6lJ96?o33;rdJt8wWXu<>mp+C(7w zczi_Mq-{(1?>Vh}A9YwLlS%-Y(cfTMf6|pds}KPx+$LXnN-Ye;h*!uAc`DFwM{=~D zS^)MCtZ>8T^t<{O>7kC5bVgSZwXbGJ0QN;{mz>ZB#gF3CxQZpZ>T3mR3cwvlOUc6S zYzFhkNeg({jNLU$j9-I&Jp|FpQhnKfI@7~9K3O!Vh>e5uZjDyFV%;N$j~OVQAHUehqS^y*7Q@M zJ+WL_C-~2FF6x_1{bD@7m(Dn%BZ!JCZX`7U+~QXa*bHY=cQQN?ot*aF@K6;?AQ$*j z+Sejxx!|Y2x-tiG!qk2UyaT>el&EWoxi+V{DxxKy3%ivZD23vq*;oS2;AnOhbnb)@ z?Cwn`(WZ-DogW{r+GZ*5SPOtb#x93SPcUXg^b1`sq^R*BvnrMx!AEkxvaEPJ?*rDb45ZP}d)PCmU`(Ng+e zNfAVNc~l3vKlk$ks7hbUxgJkU(1)=^E)V@G)k+|mup4+6aF#x~ui64={ z7;o6Hux~X-0H#tU2P$8n&J*eGj|}`#z^WS=R8A;-naMGf%r=w~>00XSKx{$3cd8Th zPWQk*Rdht~P`Yj1OV9CI0+CGd>*mzanY@Blj0sFzB^wi5n5a%cBe7Vwp*R)4Pv1`q z){nH%O`q5#Gc^7@TIyh>G+8%4GO>Wy0Puq^!Q|Ks9stW5Ily0wq^v0z{erAOa%sY> z&R2wG%xdxlmh*UHAs4?3uci*|P1?no>Awv3@q7lVcG2f*F31geB^p;v<|bzW5jq9Y z^*^E;d-KszdkGVQve4r&-Indd%HRf1t1`1C9NndB>m#!(|H@NR9JGS$@muwukhu?2 zVK`5s?MD`@AEbv5F5G3u)XL@R-qr}9oBQev#j*jv@I{d~3oJnaubRJ7x$tIFszpjPb`}Qv069 zS+Iq5g8wzhht)uW^M;Eivg!nNZ-RJoLKEw#!7SyZgHqmPeMW(kX@%BCj*;FX39ilIN2M&lnDLEo&^FuESq~4l%MfRwW%f)|vAB%6Wdt0PS@%G0-MyeklM=HA32cBT4b6vyE0;gTHyOnIrv+#R%At9C9TYg6@Nq^1B{Lsc^h%@i*p3it=EPQ4|8Mc zTdolW&wSMmQd~OHUU-VU@!+R24kCeVJ_i*M*=1XKZ0zfSHB4;3r;iUy~!^>yv!9*k_*?-Y~{U%6_bB+#^c zc+@SsKls;=SW9^uReLlcyo45D+u*4IuyKla37;sI2Mt$b<6gG7!f|;7%cmEakI{X2 z6t4(=_TV2g-aQj~ZII8xv@bImvYDEWp6Usm-~I zS5>&v){M0-AQ$AdnMe%?F5@nWQNwf%+;yyL$p}wH0zH_95J2+CD>b2e#(^D|Mp#RJ zGU01_pC%~WpInyX*G|XXfAJK|YYRi?KX!`8JUoDS`}1*^txp)t-{#5d-N)Wv4pl(j zWVlh5yAlwqEoDA3w5fq$U!S4R42<<#`AJZBIw|Dp!vkD{1!fLweZ?0^ITC zdU5Z!S}uD>Uk25t^9Ei1SmCP0G}&13ZP2iNHqL1W8}Ndp9#iUJYx`6;5@WIb=pT#y z@vcN(KOI<&+iR_~Iox%g+0_mo9udR&kob7>V%?fmrV_J+7qEry*=|r=hqD=SOTHs6 zi`qIz4c=QEqhA(Y2riDIYuO&p!f*FW^u%VX+@cMJMTlfKZ4S;w2?DP&`UHw@g0s+n zPES|`FM^8nPo#xt>p#M*)g@bdBv-ZLX0^9c+4xqr5-#p2FGCsxImToz;Nk;+b%f{> zK2LjBS*260u256m1LC-ZTrTMF5B!BVHlh-x)YA{azM{q!u*Lw1B_x$eXCxjrrYUEG z#$&3KQ^kmVMP~P%qwZ3tvyGEY=4M?tjk_h;!gIk{cA z<;KT9o_10p&hakY=?}Hyd6~U%d$;PIqkH%VrfQr3y#MHuQ&BeTj!0(2bp^Fi|5+{vrF zg}ve0T-?0u9g-bxsg|XdI4~zK=N0F({X804>bggzB9eh<|49_xA*C+{Cu$oEkYR z_`#{LxmlMDcQFFe3}a7ZF~MBx<0+xF*6t@igLH-Sj7X1h)CDtYX09~c;bgfNEf8Lk zH=X%Y?hvfH_&P@My|MgreSC_?XSBK{%D{q|@t}RoLdR(c4r4L7BLs`*Yd&BGPIX- zWA?8dQ@-#*7d2y^l*GEv(B}u zt>X;f}$`IWp1)%{f} zbI9)Iy>rZmn+5!TdNa+>Eq?i%s<9c}JYywA=)%hC z`XkBR4Un$OY>B;mT+<(u1K3E9zg+Hj-RCGgRv;9-o~|IeICF)1ea9!=`C=Y( zJ926`y;*)&OCWN*&nPoON~2++LdOHEN3SbFPxXB{&d^xmFa24irzBC~Ju*Y`fdmDN zhbt89t1NfM=>@-bLF{bcwN0~WSw1Q0_>oiM_` z&J1+eFWE)XSH|HZryW6toSzDF8UM6?=;g++@R^{+Z+LB|V*EcQTrA~wy+^$?ESVI109eDk0yeH=_i~%4FVeUMKX)jMz zctk^}F?~a9bypqIkS(9gFE#fZ$Lyl_&bkDko~pBRVA%~g8P3LRPv(_J$69prE4-$H z|0p}jS&%*HTJ>w^{P}S6j@-v=f9fla8Li)~7rjRDa~HF)Ndh?C*VXzR zzt#S?e||L_a=?%G3C>@GqEz}9 zESUeEW2DqwdMVgLrA={355B44x@Wy!YM>vfxYP;HO9u%*znk8&J9fPE{xYXWR6yt0 z_&kLO8PZ2fTq3hqjq8}Lvv=hP0GhDwMx zn<-TF-CZm?J}j6d;JXzdimzJ7l})7VAyp7I3KQ#l1nP=651@%Cs!Llms!*juH-50+ zt&{CPoo70-AaD7FanpDu_;wrc7HN6&_^;vctGFFgeI<~MGfHCbtCFaYtKR_xcZP8{ zq_elKe3vBU)bUkuDrk+h6jcbndGUYRxXys4nr#~uMMNy1f(bOEJE2pvHJ zN)J_#fT7taej?I)2~9!~kS+uQ8kH_3)KDVQ2@nk>652cAyWf4+``(}Y%QVJ;8k3=%nV!$Tq{O6l3@xU3vWNDhQ1p2%pXdc zxkl*7zuJ;cmAnN0D%x_7q5P51(v8Z8BVOunBnA$+&|1t`SgLKRtzLNQ&1?7Z_ z#BMwrd2F)dCStpy^LdC2^q(CQf1-TdyEpU1Ag=b%-O9#oSgOl9OLCM211HHcA$ZUl zOC9-LHd%~{BgQNb94Me648%0uE0%tBoVT0e_Y_r*@drw>X*k=!z^7pAD^Kg)cijsIZF(31`1l-*Ori z70!tH%Zl|FTI>h1$Q#vQynXU53ksCE?27E`;Hk~-sQnc1<`A=OrCL*;yi8SXy#7OJ z^DfWu$TM`$#N2sXu8(jxZ4NWfYF zq^*WYmgT{ul|ZMGf6ed~K-2$eZ7l>t@ff9k!)) z8(2EKkn^{!&0k#XTh;Fsf-jz{TP)%Ce?jVL0h=J z4f%y?`XUmNaIk*>EQcXAE^{`;o*13h>GvEP8Q|#0PhlnG(c#p{vMw1tU-uPjEcgrA zPrW~zUvmJlnp*O&naT@n;718pG)u7eoypHXUHCq;a0g{kf+cIl_wVbM>7Vm&6QnEh}!%He{NxA)$c@%1 zh}y)vht6;?4$RMud)Kcf3g$&LRS59VF!6n7k4njVWpei-pnB$&t-LZ`HfA^0soT`DE{7e~xrQJB08$W*L z9-Fbl5oY=DC%Ca$T{2;E%R*HM-|XTYy(FGTdA(}t>a^ed4}KVG@hJ0tJ5JHJi3u!qFf`dA+-}op#xMU^O1`49 z&F>K(OVkzf<2@DKd|);a(#*4r8c~5o;~J@d=D%SLX0B~UXISCKk-|7hpU*)DukU@k zy4toDRw)Mh8yPgfQgB129671tel3DaqHHoO*R}d3jb|rW5nTif4WdYx`H6g699|HL z5}EQCMRfb6&b;u)}-)0z2x-=q$LceSVlbfDzUlg*{{ zG+u)iwrk4);OZlD0AEEGxMy;-XqiYFO4-GYTg8P-J$S*BP6SRix++ljlx;^O+Nu3o zqFfh0m+njYPy9)UJSlK>US%u!)6eV&Matg-&(I*hX62hMx7qO5_*XsQi0xguUwHozVb^$U2{RWq06rI z;X8fLqUqUou_QngpZgI1Hj4Db)x1<#8Sec>s-*~T#=?r%yJB%#8>%iMCb{Z`nPWB7 zO4aW;Hgk*@D>I^UV&WBlk@V8tg@x9yf2T~lQ3{sfuVFX`7+Hy$7Q*7?#(bNfeg^9B z7zimhPOGPidle6aMCcD&&hn9bDn-_!&3*$oMLSAyHN*CXU0Z;`vTJC-2Js$GsXpgW zt;bV(<|v;|X&vpawx<0Hhzol%wS`kTDZ^V-g-Wbvcj+i}IO}i$^z#IB=ZcEwU3Kj8 z`gtQiT+_~IQ^u}=1$d%>)wtTrQG|ret1Q0g{wN$|-J>3||#bhp7;CF9iCG@la@%gp;Y%g4}pw`BaGsTW3u zY2)x7P<*}lncNx0SK%t(YKrn6VmOi$-t$L!i01(d9*;NZQ4Z5CNcB6EIn*^1d$==A zuCdNU#rt&v#x&eo&TqL9mi=JuFHW4~h|kYs$h+uhNzp5s)p*gFg>EB_a{3vkTQ5^x zq)SfAYx77Xv5=1)NaKEeq_nK7R#f>cxUYX8P3NLzT}E{@!N1QhM9`i- z(k=v3xeP25&KxBE5rVfB6~#n;!?N}mZN$;58Yx8uyBX?ZUA0mK%4 zkj((LH5?R2F>|Lc*w3`7nsV_H{%VvclfiCnEM+;jq}WPF#ObB8N)-cB$h+ASvhi%a4^D-PjgEj_6^`Rp=9L?Tcm))U2lXxwUs*V1fmq5!3 zr!D{mhCL|%Umo5S76T_zki_gqoc?2b z8fP)SAF)cW5mtjcj*lzO!}_ar(wwjrWF&`NYq_o+GrOs6*&ep3`<_S8al;@ujSjE_ zg-aqfoIH|Up2+j%@4BWQmk}XKb3wyW65Md!@6LaXs|3Bje&loxF>+9y8#5Dfk&V6) zXVf<@0XxDIu=Gne=~cv|PxE#RXqsYuk=S`F2OK-N(EY_h#xbqT3M-6ST1`3&EPSg+ zyQx)yolWDLEfrv?|6KSHJHW!%ZVuuGm-=sZutw(oNO4kDWE^h$|BJn)(S_Nv?tBpxDM>knoO#e9Xdbjefeg)gJasvE zwA^i|96q6#yhSc`UUf6~RrXXjFxIk~-BNJ$r#EanK0?aX(1~)lV0+JG z$$?!r6}_EW1pY4}yzkpKY1#8NBEYI#ofZX&zB%ACS9~>-s|YbA!R-#PynbQi$q~B} zfs?F@P_vhS-J_}r=EfPD?VqPZ0Rk9SW$WAYOMH~>o{hStJ1(O0gr=P{Vd;|_t#Y7^ z1>&ZsadVR*`bIz_Zv3^=w0V}18TIpCPJCQ{b;;IJ-1g6rZgJVzV<<|B&lD!o>C}Ic zOPQ=Tsy{ZUnx)2kes{r`Li+i$4OFGF`F0Mv{B*bE^_j7I2f&yXDe5 z6vc^O-=PvyzC(Ng>gW`+{0GSJ$2~+yDeOOeh@DWVD7%+(&31dA)XYAWv99gi4UBk zwh2ja(l^D)JXzUl@SQJH*yThwg~y=^Dt|C5n}w8(hKHCQQNH;#({xSQ`lQ%;kq$T9 zEhNru(Ho(}hHWD8WKU#GEsV28gcy-{vr|gQG2P!CT?@*h95w8HWnsPM)b!Ize+4U1 zPgps8jwsc!BdVe7oWGM6hw>(;$tLQ`<9uHfMqflWdb?dZe$V6Iyk?eR24(Kp(4l>H zomGZhnJ1^1cBK2uQjre1c7LyAGOY%&N_BmtsxNoBP{wPD^&}=fjaHiI49cb_&b*QEt0;LKt z^itb%S9pA@kR1F1#L#Ot=luQLxZ8t(q^ZH^P;p3MZDSy5ZKsg<7%)si=cQTSh{Dco zgxgeTRm>oni>DY=`{qmg{x&5HP5=fc0@W4}Wh(`oU;r!907_;+;oPGI2X*j1t^eF< zhB(4GlBp0!%h!n(hP`u{IskgQIm+0WF|ZjeBXhpr+{k^8-n;vng)C%W5509oLj2mN zb|;@@R*+g#D*@97Een`9M+(|yormrR(&!Q+A{jBX!n(+EYDk0+$Kzi&RkPm!0tQDX zvdBpjw8~k(rPWvV0LOa~_!dAMGrzC>z~mh;b4@0;SFP;YhNwOo@fwT z8F_jO%cy5-MB>(S#tFYz<{h=_L*oJSsuMU@N>CrH_tdpD#u8v1$k5kfa?URn1dWeP{P4&Y$!E z30g}uUwSeq(Qf)j?9?<~VkFl@e!4|`+kg>CP|apbv(6!)iiUWkNcHI8%KiB^=O37!~6B|)zu^Le7%m0U>=TU zS%=K&^_cIPB1s5sfkwS8Ksjb<$;(o?yy^E#v)G4Oj4Z}4Ij(5OYmZLA+?i?NEvE#o z2#h#&oiyq^$@%-HZd2<cSA9jBp83bw za894%3EmrtIw*SP(Ab%{ei=1-mIAA>*_)i6EBjqIt%*$DaQ=7%)cM?3?;!oQt3kN_b9I&}K@*t+ zIsDldVM*wXY}v;H?RJS(kMOd3t->%>-IqgVL!+j8Ltkgx z;QWnjqQ*Tg?eIakx>HH|@v9IPi)w~9JP7nj_NXB#X>7C0Q;4)ZtI?LUvi*=Mhvf3| z^6vN+9;l2_xF5z+onyq(&~$4wm8?iyIb-@@p|ZsvCSBn9N+Mr|K zEl)DzoJM~UMI+NT5_1>~l4K=HvCM-@Zt|$bFac!2?d1UA6%^MvhicN!)#*Ybj#ICq zktZ+15JZBUeddby+B3MBWy*;ZUk|QJ1k;}tM@lL(_X{6T1O>0}SDf?CS2eG}vVm?9 ztvg{#&pdUu*|zVEjvC3CZ4p$Y^PP)0Q|9CD%KXqBHFTa&>~N6B{8hns{fWh{6%*`& z9p3O@Vz^L8SAhMNmZH3QIK>riurl&dCyT=+lU*Clo*i@wbFWPSRoIf}EW;n3Q=U+`@)j^i(UJs1xIfd;rk zfLpk1_B@o2T;OVdj+zjowvP7Q^STz2&dh>b77vC3l2&F>!J{=;wsS-U zTQBFizil=RN*=uQ_oYsdRpXZQ4jGP)w{6J4bl#Y?NF7+*Y0DV0NlDK>A;Tj!40>wO z^G^oyA#h^5ajK=kh!9G(80=4-FqF;C0Pl}ZtvZaq2-tS+(U}&VVik?$1L2NO z&IU?8yqwIm7CD%80(6&`SogP`p-IG1!!0dVIne!cRd(z>@|G_YK=)Dq9-ae~x_4*- W*PFY?8yC%ZfzB;`%~JLI&;JK12a_rQ literal 0 HcmV?d00001 diff --git a/linux/HoloLens_Localization/CMakeLists.txt b/linux/HoloLens_Localization/CMakeLists.txt new file mode 100644 index 0000000..a122ea5 --- /dev/null +++ b/linux/HoloLens_Localization/CMakeLists.txt @@ -0,0 +1,63 @@ +cmake_minimum_required(VERSION 2.8.3) +project(hololens_localizer) + +add_compile_options(-std=c++11) + +find_package(catkin REQUIRED COMPONENTS + roscpp + rospy + tf +) + +find_package(Eigen3 REQUIRED) +find_package(Boost REQUIRED) +find_package(Ceres REQUIRED) + +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES hololens_localizer +# CATKIN_DEPENDS roscpp rospy +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations + + +include_directories( + include/anchor_localizer + include/static_calibration + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} +) + +message("----------------------" ${INCLUDE_DIRS}) + +add_executable(anchor_localizer + src/anchor_localizer/main.cpp + src/anchor_localizer/ICP_module.cpp + ) + +target_link_libraries(anchor_localizer + ${catkin_LIBRARIES} +) + +add_executable(static_calibration + src/static_calibration/main.cpp + src/static_calibration/cost_function.cpp + src/static_calibration/teleop.cpp + src/static_calibration/calibration.cpp +) + +target_link_libraries(static_calibration + ${catkin_LIBRARIES} + ceres +) + + + diff --git a/linux/HoloLens_Localization/include/anchor_localizer/ICP_module.h b/linux/HoloLens_Localization/include/anchor_localizer/ICP_module.h new file mode 100644 index 0000000..88fcb0c --- /dev/null +++ b/linux/HoloLens_Localization/include/anchor_localizer/ICP_module.h @@ -0,0 +1,58 @@ +#include "ros/ros.h" + +#include +#include + +#include +#include +#include +#include +#include "eigen3/Eigen/Core" +#include "eigen3/Eigen/Geometry" + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + + +namespace bg = boost::geometry; +namespace bgi = boost::geometry::index; + +typedef bg::model::point point; +typedef bg::model::box box; +typedef std::pair value; + +class ICP2D_Module +{ +public: + ICP2D_Module(ros::NodeHandle n); + void start(); + +private: + void callbackPC(const sensor_msgs::PointCloud::ConstPtr& pointcloud); + void callbackMap(const nav_msgs::OccupancyGrid::ConstPtr& subscribedmap); + void callbackInitPose(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& initPose); + + void distFromPlane(geometry_msgs::Point32 pt,geometry_msgs::Point32& ptret,double& dist); + void linearCompute(std::vector ,std::vector,Eigen::Matrix2d& R,Eigen::Vector2d& T); + +#include + Eigen::Vector3d nv, t1, t2; + double h; // plane parameter + ros::Publisher pub, pubpre, pubimg, pubreq, pubarr; + ros::Subscriber sub, submap, subinitpose; + tf::TransformListener listener; + bgi::rtree< value, bgi::quadratic<16> > rtree; + double initx, inity, yaw; + bool bInit; +}; diff --git a/linux/HoloLens_Localization/include/static_calibration/calibration.h b/linux/HoloLens_Localization/include/static_calibration/calibration.h new file mode 100644 index 0000000..88c95e9 --- /dev/null +++ b/linux/HoloLens_Localization/include/static_calibration/calibration.h @@ -0,0 +1,159 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "teleop.h" +#include +#include +#include "cost_function.h" +#include "ceres/ceres.h" +#include "glog/logging.h" + +using ceres::AutoDiffCostFunction; +using ceres::NumericDiffCostFunction; +using ceres::CostFunction; +using ceres::Problem; +using ceres::Solver; +using ceres::Solve; +using namespace Eigen; + +class calibrator +{ +public: + calibrator(std::string holoLinkedFrame, std::string odomFrame, std::string robotFootFrame,std::string fpath); + void run(); +private: + void publish_thread(); + + void setTransform(); + void calibration(std::vector pep_pos, std::vector hol_pos, Matrix3d& R, Vector3d& T); + void horizontalCalibration(std::vector pep_pos, std::vector hol_pos, std::vector verticalVecs, std::vector normVecs, Matrix3d& R, Vector3d& T); + void transition_log(std::vector pep_pos, std::vector hol_pos,std::ofstream& ofs); + void linear_calibration(std::vector pep_pos, std::vector hol_pos, Matrix3d& R, Vector3d& T); + void nonlinear_calibration(std::vector pep_pos, std::vector hol_pos, Matrix3d& R, Vector3d& T); + void horizontal_initialization(std::vector pep_pos, std::vector hol_pos, std::vector verticalVecs, std::vector normVecs, Matrix3d& R, Vector3d& T, double* bestScores); + void nonlinear_horizontal_calibration(std::vector pep_pos, std::vector hol_pos, std::vector verticalVecs, std::vector normVecs, Matrix3d& R, Vector3d& T, double* bestScores); + void poseStampedCB(const geometry_msgs::PoseStamped::ConstPtr& msg); + bool lookupTransform(); + void recordCurrentPosition(); + void calibrate(); + bool setHeadPositionAndRecord(float fPitch, float fYaw); + bool autocalibrate(); + void writeCalibrationData(); + + std::vector m_pep_pos; + std::vector m_hol_pos; + std::vector m_floor2holo; + std::vector m_head2foot; + + geometry_msgs::PoseStamped m_latestPoseStamped; + + Matrix3d R; + Vector3d T; + + tf::StampedTransform m_transform1; + tf::StampedTransform m_transform2; + tf::StampedTransform m_transform3; + tf::StampedTransform m_transform4; + tf::TransformBroadcaster m_tf_br; + tf::StampedTransform m_tf_map_to_odom; + ros::Subscriber m_holo_floor_sub; + ros::NodeHandle m_nh; + + bool m_horizontalCalibMode = false; + + std::string m_holoLinkedFrame; + std::string m_odomFrame; + std::string m_robotFootFrame; + std::string m_fpath; + + tf::TransformListener m_listener; + teleop m_tele; + + int getch() + { + static struct termios oldt, newt; + tcgetattr( STDIN_FILENO, &oldt); // save old settings + newt = oldt; + newt.c_lflag &= ~(ICANON); // disable buffering + tcsetattr( STDIN_FILENO, TCSANOW, &newt); // apply new settings + + int c = getchar(); // read character + + tcsetattr( STDIN_FILENO, TCSANOW, &oldt); // restore old settings + return c; + } + + bool kbhit() + { + termios term; + tcgetattr(0, &term); + + termios term2 = term; + term2.c_lflag &= ~ICANON; + tcsetattr(0, TCSANOW, &term2); + + int byteswaiting; + ioctl(0, FIONREAD, &byteswaiting); + + tcsetattr(0, TCSANOW, &term); + + return byteswaiting > 0; + } + + Matrix4d btTrans2EigMat4d(tf::Transform t) + { + tf::Matrix3x3 btm(t.getRotation()); + Matrix4d m; + m< bool operator()(const T* const x, T* residual) const { + residual[0] = 10.0 - x[0]; + return true; + } +}; + +//e=|AX-XB| +struct simple_costfunctor +{ +public: + simple_costfunctor(Eigen::Matrix4d& A_,Eigen::Matrix4d& B_){A=A_;B=B_;}; + bool operator()(const double* parameters, double* residual)const{ + double tx=parameters[0]; + double ty=parameters[1]; + double tz=parameters[2]; + double rx=parameters[3]; + double ry=parameters[4]; + double rz=parameters[5]; + + Eigen::Matrix3d R=axisRot2R(rx,ry,rz); + Eigen::Matrix4d X; + X.block(0,0,3,3)=R; + X(0,3)=tx; + X(1,3)=ty; + X(2,3)=tz; + X.block(3,0,1,4)<<0,0,0,1; + //std::cout< +#include +#include +#include +#include +#include + +class teleop +{ +public: + teleop(); + + void operation(int c); + void setPepperHeadPitch(float angle); + void setPepperHeadYaw(float angle); + void setPepperHeadPitchYaw(float pitch, float yaw); + +private: + /** + * \brief calls m_bodyPoseClient on the poseName, to execute a body pose + * @return success of actionlib call + */ + bool callBodyPoseClient(const std::string& poseName); + +private: + bool m_fStiffness; + double m_maxHeadYaw; + double m_maxHeadPitch; + ros::Duration m_bodyPoseTimeOut; + ros::Publisher m_movePub; + ros::Publisher m_headPub; + ros::ServiceClient m_stiffnessDisableClient; + ros::ServiceClient m_stiffnessEnableClient; + ros::ServiceClient m_wakeup; + ros::ServiceClient m_rest; + actionlib::SimpleActionClient m_bodyPoseClient; +}; + diff --git a/linux/HoloLens_Localization/package.xml b/linux/HoloLens_Localization/package.xml new file mode 100644 index 0000000..c6b9d96 --- /dev/null +++ b/linux/HoloLens_Localization/package.xml @@ -0,0 +1,65 @@ + + + hololens_localizer + 0.0.0 + The hololens_localizer package + + + + + t-ryish + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + roscpp + rospy + roscpp + rospy + roscpp + rospy + + + + + + + + diff --git a/linux/HoloLens_Localization/scripts/dynamic_adjuster.py b/linux/HoloLens_Localization/scripts/dynamic_adjuster.py new file mode 100644 index 0000000..9a82a58 --- /dev/null +++ b/linux/HoloLens_Localization/scripts/dynamic_adjuster.py @@ -0,0 +1,142 @@ +#!/usr/bin/env python + +# -------------------------------------------------------------------------------------------- +# Copyright (c) Microsoft Corporation. All rights reserved. +# Licensed under the MIT License. +# -------------------------------------------------------------------------------------------- + +import rospy +import socket +import struct +import sys +import tf +import numpy as np +from geometry_msgs.msg import PoseWithCovarianceStamped +from std_msgs.msg import * +import math + + +# ----------------------------------------------------------------------------- +# +if __name__ == '__main__': + rospy.init_node('dynamic_adjuster') + listener=tf.TransformListener() + + if len(sys.argv)<2: + rospy.logerr("usage: dynamic_adjuster.py ") + exit() + + footprintFrame="/" + sys.argv[1] + + print "dynamic_adjuster: footprintframe: " + footprintFrame + + hololensPos = rospy.Publisher('/initialpose_h', PoseWithCovarianceStamped,queue_size=1) + + rate = rospy.Rate(10.0) + br = tf.TransformBroadcaster() + + last_update = rospy.get_time() + firstloop = True + adjuster = True + + while not rospy.is_shutdown(): + + #get transform from map to footprint via hololens + # map -> HoloLens + try: + #if listener.frameExists("/map") and listener.frameExists("/hololens"): + t = listener.getLatestCommonTime('/map', '/hololens') + (trans,rot) = listener.lookupTransform('/map', '/hololens', t) + #else: + # continue + except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException,tf.Exception): + print "tf error /map /hololens" + continue + try: + (trans2,rot2) = listener.lookupTransform('/hololens_p', footprintFrame, rospy.Time(0)) + except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException,tf.Exception): + print "tf error hololens_p footprintframe" + continue + + #position jump check caused by switching spatial anchor + if not firstloop: + if (last_t == t): + continue + + d = (trans[0]-last_trans[0])*(trans[0]-last_trans[0])+(trans[1]-last_trans[1])*(trans[1]-last_trans[1]) + now = rospy.get_time() + + if d > 1.0 and now - last_update < 2.0: + print "dynamic_adjuster: position jumped (ddist , dtime) (" + str(d) + "," + str(now-last_update) + continue + + #compute transform matrix from map to hololens_p + map2holo = np.dot(tf.transformations.translation_matrix(trans), tf.transformations.quaternion_matrix(rot)) + holo2foot = np.dot(tf.transformations.translation_matrix(trans2), tf.transformations.quaternion_matrix(rot2)) + + map2foot=np.dot(map2holo,holo2foot) + map2foot_beforeAdjust=map2foot + + #dynamic footprint correction + if adjuster: + foot2holo=np.linalg.inv(holo2foot) + + #calc adjust rotation matrix + foot2map=np.linalg.inv(map2foot) + rz=np.array([foot2map[0][2],foot2map[1][2],foot2map[2][2]]) + + to_z=np.array([0,0,1.0]) + axis=np.cross(rz,to_z) + angle=math.acos(np.dot(rz,to_z)) + adjustMatrixA=tf.transformations.quaternion_matrix(tf.transformations.quaternion_about_axis(angle,axis)) + adjustMatrixA=np.linalg.inv(adjustMatrixA) + #debug + debugMat=np.dot(map2foot,adjustMatrixA) + + # + adjustMatrixB=np.dot(np.dot(holo2foot,adjustMatrixA),foot2holo) + adjustMatrixB[0][3]=0 + adjustMatrixB[1][3]=0 + adjustMatrixB[2][3]=0 + map2foot=np.dot(np.dot(map2holo,adjustMatrixB),holo2foot) + + brtrans = (map2foot[0][3], map2foot[1][3], map2foot[2][3]) + brrot = tf.transformations.quaternion_from_matrix(map2foot) + br.sendTransform(brtrans, brrot, rospy.Time.now(), "/localized_footprint", "/map") + + brtrans = (map2foot_beforeAdjust[0][3], map2foot_beforeAdjust[1][3], map2foot_beforeAdjust[2][3]) + brrot = tf.transformations.quaternion_from_matrix(map2foot_beforeAdjust) + br.sendTransform(brtrans, brrot, rospy.Time.now(), "/localized_footprint_nAdj", "/map") + + cmd = PoseWithCovarianceStamped() + cmd.pose.pose.position.x=map2foot[0][3] + cmd.pose.pose.position.y=map2foot[1][3] + cmd.pose.pose.position.z=0 + q=tf.transformations.quaternion_from_matrix(map2foot) + invq=tf.transformations.quaternion_inverse(q) + + dirq= np.zeros((4, ), dtype=np.float64) + dirq[0]=1 + q1=tf.transformations.quaternion_multiply(dirq,invq) + q2=tf.transformations.quaternion_multiply(q,q1) + + qz=q2[0] + qw=q2[1] + rad=math.sqrt(qz*qz+qw*qw) + qz=qz/rad + qw=qw/rad + + theta = math.acos(qz) + if qw < 0: + theta=-theta + + cmd.pose.pose.orientation.x = 0 + cmd.pose.pose.orientation.y = 0 + cmd.pose.pose.orientation.z = math.sin(theta/2) + cmd.pose.pose.orientation.w = math.cos(theta/2) + hololensPos.publish(cmd) + last_trans = trans + last_update = rospy.get_time() + firstloop = False + last_t = t + rate.sleep() diff --git a/linux/HoloLens_Localization/scripts/localizer.py b/linux/HoloLens_Localization/scripts/localizer.py new file mode 100644 index 0000000..30d993f --- /dev/null +++ b/linux/HoloLens_Localization/scripts/localizer.py @@ -0,0 +1,86 @@ +#!/usr/bin/env python + +# -------------------------------------------------------------------------------------------- +# Copyright (c) Microsoft Corporation. All rights reserved. +# Licensed under the MIT License. +# -------------------------------------------------------------------------------------------- + +import roslib +import rospy +import socket +import geometry_msgs.msg +import math +import tf +import struct +import numpy as np +from geometry_msgs.msg import PoseWithCovarianceStamped + +global trans +global rot + +global brtrans +global brrot + +# ----------------------------------------------------------------------------- +# +def initialposeCB(msg): + #robot odom-base (input) + global trans + global rot + + #robot map-odom (output) + global brtrans + global brrot + + #massage to translation, rotation + inittrans=(msg.pose.pose.position.x,msg.pose.pose.position.y,msg.pose.pose.position.z) + initposequot=(msg.pose.pose.orientation.x, + msg.pose.pose.orientation.y, + msg.pose.pose.orientation.z, + msg.pose.pose.orientation.w) + initrot=tf.transformations.quaternion_matrix(initposequot) + map2foot= np.dot(tf.transformations.translation_matrix(inittrans),initrot) + odom2foot = np.dot(tf.transformations.translation_matrix(trans),tf.transformations.quaternion_matrix(rot)) + + + foot2odom=np.linalg.inv(odom2foot) + + map2odom=np.dot(map2foot,foot2odom) + br = tf.TransformBroadcaster() + #map2foot=np.dot(map2holo,holo2foot) + brtrans = (map2odom[0][3], map2odom[1][3], map2odom[2][3]) + brrot = tf.transformations.quaternion_from_matrix(map2odom) + +# ----------------------------------------------------------------------------- +# +if __name__ == '__main__': + rospy.init_node('localizer') + + listener = tf.TransformListener() + + # from ros + sub = rospy.Subscriber('/initialpose', PoseWithCovarianceStamped, initialposeCB) + + # from dynamic_adjuster.py + sub2 = rospy.Subscriber('/initialpose_h', PoseWithCovarianceStamped, initialposeCB) + + br = tf.TransformBroadcaster() + brtrans=(0,0, 0) + brrot=(0,0,0,1) + + rate = rospy.Rate(10) + while not rospy.is_shutdown(): + rospy.loginfo("Getting transform for '/base_footprint'!") + try: + # obtain robot odometry to base_footprint (for pepper) + (trans, rot) = listener.lookupTransform('/odom', '/base_footprint', rospy.Time(0)) + rospy.loginfo("Got transform for '/base_footprint'!") + except (tf.LookupException, tf.ConnectivityException,tf.ExtrapolationException): + rospy.logwarn("tf error. Unable to get transform for '/base_footprint'!") + continue + + br.sendTransform(brtrans, brrot, rospy.Time.now(), "/odom", "/map") + + rate.sleep() + + rospy.loginfo("localizer.py exit...") diff --git a/linux/HoloLens_Localization/src/anchor_localizer/ICP_module.cpp b/linux/HoloLens_Localization/src/anchor_localizer/ICP_module.cpp new file mode 100644 index 0000000..e9eb649 --- /dev/null +++ b/linux/HoloLens_Localization/src/anchor_localizer/ICP_module.cpp @@ -0,0 +1,420 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "ICP_module.h" + +const char * pszAppName = "hololens_anchor_localizer"; + +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +ICP2D_Module::ICP2D_Module(ros::NodeHandle n) +{ + sub = n.subscribe("/hololens/pc",1000,&ICP2D_Module::callbackPC,this); + submap = n.subscribe("/map", 10, &ICP2D_Module::callbackMap, this); + + subinitpose = n.subscribe("/initialpose", 10, &ICP2D_Module::callbackInitPose, this); + + pub = n.advertise("/hololens/pc2d",1000); + pubpre = n.advertise("/hololens/pc2d_pre",1000); + pubimg = n.advertise("/hololens/image",1000); + pubreq = n.advertise("/hololens/ack",1000); + pubarr = n.advertise("hololens/localized",1000); + + //plane surface normal direction for cross section computation + nv << 0,1,0; + h = 0; + + t1 << 1,0,0; + t2 << 0,0,1; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void ICP2D_Module::callbackInitPose(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& initPose) +{ + // + // subscribe initial pose on Rviz + // + + // convert initial pose to 2D position and direction angle + initx = initPose->pose.pose.position.x; + inity = initPose->pose.pose.position.y; + + tf::Quaternion initq( + initPose->pose.pose.orientation.x, + initPose->pose.pose.orientation.y, + initPose->pose.pose.orientation.z, + initPose->pose.pose.orientation.w); + + tf::Matrix3x3 mat(initq); + + yaw = acos(mat[0][0]); + + if (mat[0][1] > 0) + yaw=-yaw; + + ROS_INFO("2D Pose Estimate request received. Requesting to initialize HoloLens bridge..."); + + // request initialize to bridge + std_msgs::Bool req; + + req.data = true; + + pubreq.publish(req); + + bInit = true; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void ICP2D_Module::callbackPC(const sensor_msgs::PointCloud::ConstPtr& pointcloud) +{ + ROS_INFO("HoloLens point cloud data received. Calculating optimal rotation and transform..."); + + // point cloud: SA coordinates + sensor_msgs::PointCloud pc2d,pc2d_prev; + double err; + geometry_msgs::Point32 pt2; + std::vector querypoints; + + // 3D to 2D :SA coordinates to ros coordinates + double range[4]={100,-100,100,-100};//minx,maxx,miny,maxy to determine map size + for (int i = 0; i < pointcloud->points.size(); i++) { + geometry_msgs::Point32 pt = pointcloud->points.at(i); + + distFromPlane(pt,pt2,err);//compute point2plane distance + + if (err < 0.1) { + Eigen::Vector2d qp;qp<<-pt2.z,-pt2.x; + querypoints.push_back(qp); + if (range[0] > qp(0)) + range[0] = qp(0); + if (range[1] < qp(0)) + range[1] = qp(0); + if (range[2] > qp(1)) + range[2] = qp(1); + if (range[3] < qp(1)) + range[3] = qp(1); + } + } + + //std::cout << range[0] <<"," << range[1] << "," << range[2] <<"," << range[3] <(img.width*img.height, 255); + + //initial pose for alignment + //given from Rviz(first time) or tf + if (!bInit) { + // obtain tf between map-SA(ROS) + try { + tf::StampedTransform transform; + listener.waitForTransform("/map", "/spatialAnchor_ros", pointcloud->header.stamp, ros::Duration(5.0)); + listener.lookupTransform(std::string("map"),std::string("/spatialAnchor_ros"), + pointcloud->header.stamp,transform); + initx = transform.getOrigin().getX(); + inity = transform.getOrigin().getY(); + tf::Matrix3x3 mat = transform.getBasis(); + yaw = acos(mat[0][0]); + if (mat[0][1] > 0) + yaw = -yaw; + } catch (tf::TransformException ex) { + ROS_ERROR("listener error!!"); + } + } + + bInit=false; + // 2D(x,y,yaw)-->2D R,t + tf::Quaternion initq; + Eigen::Matrix2d R; + Eigen::Vector2d T; + + R << cos(yaw),-sin(yaw),sin(yaw),cos(yaw); + T << initx,inity; + + std::cout << pszAppName << ": rotation matrix" << std::endl; + std::cout << /* std::setw(16) << */ R << std::endl; + std::cout << pszAppName << ": transform" << std::endl; + std::cout << /* std::setw(16) << */ T << std::endl; + std::cout << pszAppName << ": query point size: " << querypoints.size() << std::endl; + + //build pre-map + point cloud before alignment(for displaying) + for (int i = 0; i < querypoints.size(); i++) { + Eigen::Vector2d pt; + + pt << querypoints.at(i)(0),querypoints.at(i)(1); + + //compute correspond pixel coordinates + int plotx = img.width -((pt(0)-range[0])/pixresolution+margen); + int ploty = (pt(1)-range[2])/pixresolution+margen; + int idx = ploty * img.step + plotx; + img.data[idx] = 0; // fill pixel as black + + pt = R*pt + T; + + geometry_msgs::Point32 gp; + + gp.x = pt(0); + gp.y = pt(1); + gp.z = 0; + + pc2d_prev.points.push_back(gp); + } + + pc2d_prev.header.frame_id = "map"; + + // publish image and point cloud + pubpre.publish(pc2d_prev); + pubimg.publish(img); + + if (rtree.size() == 0) + return; // return if pre-map is not published + + { //cvt initial 2D rotation to 3D quaternion + tf::Matrix3x3 mat(R(0,0),R(0,1),0, + R(1,0),R(1,1),0, + 0,0,1); + + mat.getRotation(initq); + } + + // registration (simple 2d ICP alignment) + bool positionLost = false; + for (int itr = 0; itr < 10; itr++) { + std::vector idx; + std::vector dstpoints,querypoints_opt; + + if (querypoints.size() < 50) { + ROS_ERROR("data shortage!!"); + positionLost = true; + break; + } + + // searching nearest points + // printf("%s: searching nearest points...\n", pszAppName); + for (int i = 0; i < querypoints.size();) { + std::vector result_n; + Eigen::Vector2d qp; + + qp << querypoints[i](0),querypoints[i](1); + + //transform query point (HoloLens) + qp = R*qp + T; + + // search nearest point + rtree.query(bgi::nearest(point(qp(0),qp(1)),1),std::back_inserter(result_n)); + + // nearest point in pre-map + float x = result_n[0].first.get<0>(); + float y = result_n[0].first.get<1>(); + + Eigen::Vector2d dp; + + dp << x,y; + + if ((qp - dp).norm() > 1.0) { + i++; + continue; //outlier rejection (constant threshold: 1m) + } + + querypoints_opt.push_back(querypoints[i]); + dstpoints.push_back(dp); + i++; + } + + // printf("%s: finding optimal rotation and transform...\n", pszAppName); + + // obtain optimal R,t (solve ICP) + linearCompute(querypoints_opt,dstpoints,R,T); + + yaw = acos(R(0,0)); + if (R(0,1) > 0) + yaw = -yaw; + + // cvt 2D rotation to 3D quaternion + tf::Matrix3x3 mat(R(0,0),R(0,1),0, + R(1,0),R(1,1),0, + 0,0,1 + ); + + mat.getRotation(initq); + + initx = T(0); + inity = T(1); + + // std::cout << pszAppName << ": " << R << std::endl << initx << "," << inity << "," << yaw << std::endl; + } + + ROS_INFO("Calculating optimal rotation and transform completed: x=%.4f, y=%.4f, yaw=%.4f", (float)initx, (float)inity, (float)yaw); + + // publish optimized position and direction + geometry_msgs::Quaternion msgqt; + + tf::quaternionTFToMsg(initq, msgqt); + + geometry_msgs::PoseStamped ps; + + ps.pose.position.x = initx; + ps.pose.position.y = inity; + ps.pose.position.z = 0; + ps.pose.orientation = msgqt; + ps.header.frame_id = "map"; + + pubarr.publish(ps); + + // publish aligned 2D point cloud (for displaying) + for (int i = 0; i < querypoints.size();) { + std::vector result_n; + Eigen::Vector2d qp; + + qp << querypoints[i](0),querypoints[i](1); + qp = R*qp + T; + + geometry_msgs::Point32 gp; + + gp.x = qp(0); + gp.y = qp(1); + gp.z = 0; + + pc2d.points.push_back(gp); + i++; + } + + pc2d.header.frame_id = "map"; + + pub.publish(pc2d); +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void ICP2D_Module::callbackMap(const nav_msgs::OccupancyGrid::ConstPtr& subscribedmap) +{ + // + // get floormap and create rtree + // + + if (rtree.size() > 0) + return; // process only once + + int width = subscribedmap->info.width; + int height = subscribedmap->info.height; + double scale = subscribedmap->info.resolution; + unsigned int cnt = 0; + + // cvt pixel to point cloud + for (int i = 0; i < width; i++) { + for (int j = 0; j < height; j++) { + if (subscribedmap->data[i+j*width] > 50) { + point p = point(i*scale+subscribedmap->info.origin.position.x,j*scale+subscribedmap->info.origin.position.y); + rtree.insert(std::make_pair(p, ++cnt)); + } + } + } + + ROS_INFO("map_server node initialized. Map size is %d x %d pixels. Tree size is %u points.", width, height, cnt); +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void ICP2D_Module::distFromPlane(geometry_msgs::Point32 pt,geometry_msgs::Point32& ptret,double& dist) +{ + // + // compute point to plane distance + // + dist = pt.x*nv(0)+pt.y*nv(1)+pt.z*nv(2)-h; + ptret.x = pt.x-dist*nv(0); + ptret.y = pt.y-dist*nv(1); + ptret.z = pt.z-dist*nv(2); + dist = std::fabs(dist); +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void ICP2D_Module::start() +{ + ros::Rate loop_rate(10); + + while(ros::ok()) { + loop_rate.sleep(); + ros::spinOnce(); + } +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void ICP2D_Module::linearCompute(std::vector a,std::vector b,Eigen::Matrix2d& R,Eigen::Vector2d& T) +{ + // + // solve ICP problem + // + + // get centroid + Eigen::Vector2d ga,gb; + + ga << 0,0; + gb << 0,0; + for (int i = 0; i < a.size(); i++) { + ga += a.at(i); + gb += b.at(i); + } + + ga = ga*(1.0/a.size()); + gb = gb*(1.0/a.size()); + + // + Eigen::Vector2d vga,vgb; + + vga << ga(0),ga(1); + vgb << gb(0),gb(1); + + Eigen::MatrixXd H(2,2); + H.setZero(); + + // std::cout << pszAppName << ": " << ga.transpose() << ":" << gb.transpose() << std::endl; + + for (int i = 0; i < a.size(); i++) { + Eigen::Vector2d pa,pb; + + pa << a.at(i)(0),a.at(i)(1); + pb << b.at(i)(0),b.at(i)(1); + + Eigen::MatrixXd h_=(pa-vga)*(pb-vgb).transpose(); + + H=H+h_; + } + + Eigen::JacobiSVD svd(H, Eigen::ComputeThinU | Eigen::ComputeThinV); + Eigen::Matrix2d Hm; + Eigen::Matrix2d uvt = svd.matrixU()*svd.matrixV().transpose(); + + Hm << 1,0,0,uvt(0,0)*uvt(1,1)-uvt(0,1)*uvt(1,0); + + R = svd.matrixV()*Hm*svd.matrixU().transpose(); + +/* if(R.determinant()<0){ + + R.col(2)=-1*R.col(2); + + }*/ + + T = -R*vga+vgb; + + return; +} diff --git a/linux/HoloLens_Localization/src/anchor_localizer/main.cpp b/linux/HoloLens_Localization/src/anchor_localizer/main.cpp new file mode 100644 index 0000000..ef60ab9 --- /dev/null +++ b/linux/HoloLens_Localization/src/anchor_localizer/main.cpp @@ -0,0 +1,28 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "ros/ros.h" +#include "ICP_module.h" + +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +int main(int argc, char* argv[]) +{ + ros::init(argc,argv, "anchor_localizer"); + ros::NodeHandle n; + + ICP2D_Module icp_module(n); + + icp_module.start(); + + return 0; +} diff --git a/linux/HoloLens_Localization/src/static_calibration/calibration.cpp b/linux/HoloLens_Localization/src/static_calibration/calibration.cpp new file mode 100644 index 0000000..53a9845 --- /dev/null +++ b/linux/HoloLens_Localization/src/static_calibration/calibration.cpp @@ -0,0 +1,789 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "calibration.h" + +void printHelp(); + +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +calibrator::calibrator(std::string holoLinkedFrame, std::string odomFrame, std::string robotFootFrame, std::string fpath) +{ + // + // constructor with file path + + m_holoLinkedFrame = holoLinkedFrame; + m_odomFrame = odomFrame; + m_robotFootFrame = robotFootFrame; + m_fpath = fpath; + + // + // initialize transform + R << 1, 0, 0, 0, 1, 0, 0, 0, 1; + T << 0, 0, 0; + + if (!m_fpath.empty()) { + std::ifstream ifs(m_fpath, std::ios::binary); + if (ifs) + { + // + // file exists, read data from it + float dat[12]; + ifs.read((char *)dat, sizeof(float) * 12); + R << dat[0], dat[1], dat[2], dat[3], dat[4], dat[5], dat[6], dat[7], dat[8]; + T << dat[9], dat[10], dat[11]; + ifs.close(); + + std::cout << "Calibration file '" << m_fpath << "' loaded." << std::endl; + } + else + { + // + // file does not exist, write initial data + writeCalibrationData(); + } + } + + // set transformation + setTransform(); + + m_horizontalCalibMode = false; + boost::thread *thr = new boost::thread(boost::bind(&calibrator::publish_thread, this)); +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void calibrator::setTransform() +{ + m_tf_map_to_odom.frame_id_ = std::string(m_holoLinkedFrame); + m_tf_map_to_odom.child_frame_id_ = std::string("hololens_p"); + m_tf_map_to_odom.setOrigin(tf::Vector3(T(0), T(1), T(2))); + + tf::Matrix3x3 rot(R(0, 0), R(0, 1), R(0, 2), + R(1, 0), R(1, 1), R(1, 2), + R(2, 0), R(2, 1), R(2, 2)); + tf::Quaternion q; + rot.getRotation(q); + m_tf_map_to_odom.setRotation(q); +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void calibrator::poseStampedCB(const geometry_msgs::PoseStamped::ConstPtr &msg) +{ + m_latestPoseStamped = *msg; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void calibrator::run() +{ + m_holo_floor_sub = m_nh.subscribe < geometry_msgs::PoseStamped>("/holo/floor", 1, &calibrator::poseStampedCB, this); + + std::cout << "Calibration: ready" << std::endl; + + while (ros::ok()) + { + int c; + bool fSuccess; + + //get keyboard input + if (kbhit()) + { + std::cout << "\r \r"; + c = getch(); + } + else + { + ros::spinOnce(); + continue; + } + + fSuccess = lookupTransform(); + if (!fSuccess) + continue; + + if (c == ' ') // space key: record current position + { + recordCurrentPosition(); + } + else if (c == 'c') // calibration + { + calibrate(); + } + else if (c == 'a') // auto-calibration + { + autocalibrate(); + } + else if (c == 'q') // quit + { + break; + } + else if (c == 'w') // save calibration result + { + writeCalibrationData(); + } + else if (c == 'd') // delete recorded position + { + if (m_pep_pos.size() >= 1) + { + m_pep_pos.pop_back(); + m_hol_pos.pop_back(); + } + } + else if (c == 'z') // save to log + { + std::ofstream ofs(m_fpath + ".log"); + std::cout << "Param R" << std::endl; + std::cout << R << std::endl; + std::cout << "Param t" << std::endl; + std::cout << T << std::endl; + ofs << "Param R" << std::endl; + ofs << R << std::endl; + ofs << "Param t" << std::endl; + ofs << T << std::endl; + } + else if (c == 't') // toggle calibration mode (General hand-eye calibration <-> Calibration with limited movements (Using Horizontal movement)) + { + m_horizontalCalibMode = !m_horizontalCalibMode; + + if (m_horizontalCalibMode) + std::cout << "horizontal calibration mode: Horizontal" << std::endl; + else + std::cout << "horizontal calibration mode: Bi-directional rotation" << std::endl; + + //reset + m_pep_pos.clear(); + m_hol_pos.clear(); + m_floor2holo.clear(); + m_head2foot.clear(); + } + else if ((c == '?') || (c == 'h')) + { + printHelp(); + } + else // tele-operation + { + m_tele.operation(c); + } + } +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void calibrator::publish_thread() +{ + ros::Rate loop_rate(100); + while (ros::ok()) + { + // broadcast transform + m_tf_map_to_odom.stamp_ = ros::Time::now(); + m_tf_br.sendTransform(m_tf_map_to_odom); + + loop_rate.sleep(); + } +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +bool calibrator::lookupTransform() +{ + try + { + // + // get Odom-holoLinkedFrame, SA-HoloLens transformation + m_listener.lookupTransform(std::string(m_odomFrame), std::string(m_holoLinkedFrame), ros::Time(0), m_transform1); + m_listener.lookupTransform(std::string("spatialAnchor"), std::string("hololens"), ros::Time(0), m_transform2); + } + catch (tf::TransformException ex) + { + std::cout << "Calibration: tf listener error!! " << ex.what() << std::endl; + return false; + } + + return true; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void calibrator::recordCurrentPosition() +{ + if (m_horizontalCalibMode) + { + try + { // obtain map-hololens, Head-base + m_listener.waitForTransform("/map", "/hololens", m_latestPoseStamped.header.stamp, ros::Duration(5.0)); + m_listener.lookupTransform(std::string("map"), std::string("hololens"), m_latestPoseStamped.header.stamp, m_transform3); + m_listener.lookupTransform(std::string(m_holoLinkedFrame), std::string(m_robotFootFrame), m_latestPoseStamped.header.stamp, m_transform4); + } + catch (tf::TransformException ex) + { + std::cout << "Calibration: tf listener error!! " << ex.what() << std::endl; + return; + } + + Eigen::Vector3d floor2holoVec, head2footVec; + // obtain floor to HoloLens vector (map to HoloLens coordinate) + floor2holoVec << m_transform3.getOrigin().getX() - m_latestPoseStamped.pose.position.x, m_transform3.getOrigin().getY() - m_latestPoseStamped.pose.position.y, m_transform3.getOrigin().getZ() - m_latestPoseStamped.pose.position.z; + Matrix4d map2holo = btTrans2EigMat4d(m_transform3); + floor2holoVec = map2holo.block(0, 0, 3, 3).inverse() * floor2holoVec; + m_floor2holo.push_back(floor2holoVec); + + head2footVec << m_transform4.getOrigin().getX(), m_transform4.getOrigin().getY(), m_transform4.getOrigin().getZ(); + m_head2foot.push_back(head2footVec); + } + + // Odom-holoLinkedFrame (Robot) + m_pep_pos.push_back(m_transform1); + + // SA-HoloLens + m_hol_pos.push_back(m_transform2); + + // display position + tf::Quaternion q = m_transform1.getRotation(); + std::cout << "Calibration: count " << m_pep_pos.size() << std::endl; + std::cout << "Calibration: " << m_holoLinkedFrame << ":(" << m_transform1.getOrigin().getX() << "," << m_transform1.getOrigin().getY() << "," << m_transform1.getOrigin().getZ() << "),(" << q.getX() << "," << q.getY() << "," << q.getZ() << "," << q.getW() << ")" << std::endl; + q = m_transform2.getRotation(); + std::cout << "Calibration: HoloLens:(" << m_transform2.getOrigin().getX() << "," << m_transform2.getOrigin().getY() << "," << m_transform2.getOrigin().getZ() << "),(" << q.getX() << "," << q.getY() << "," << q.getZ() << "," << q.getW() << ")" << std::endl; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void calibrator::calibrate() +{ + if (m_pep_pos.size() < 3) + { + std::cout << "Calibration Error!! The number of recorded positions must be >=3 !!" << std::endl; + return; + } + + std::cout << "======= calibration start ========" << std::endl; + if (!m_horizontalCalibMode) + { + calibration(m_pep_pos, m_hol_pos, R, T); + } + else + { + horizontalCalibration(m_pep_pos, m_hol_pos, m_floor2holo, m_head2foot, R, T); + } + + // display calibration result + std::cout << "======= calibration done =========" << std::endl; + std::cout << "Calibration results:\n translation" << std::endl + << T << std::endl + << "rotation" << std::endl + << R << std::endl; + m_tf_map_to_odom.setOrigin(tf::Vector3(T(0), T(1), T(2))); + tf::Matrix3x3 rot(R(0, 0), R(0, 1), R(0, 2), + R(1, 0), R(1, 1), R(1, 2), + R(2, 0), R(2, 1), R(2, 2)); + tf::Quaternion q; + rot.getRotation(q); + m_tf_map_to_odom.setRotation(q); +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +bool calibrator::setHeadPositionAndRecord(float fPitch, float fYaw) +{ + bool fSuccess; + double duration = 3.0; + + m_tele.setPepperHeadPitchYaw(fPitch, fYaw); + + ros::Duration(duration).sleep(); + ros::spinOnce(); + + fSuccess = lookupTransform(); + if (!fSuccess) + return false; + + recordCurrentPosition(); + + return true; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +bool calibrator::autocalibrate() +{ + bool fSuccess; + + std::cout << "auto-calibrate: step 1 of 5 - resetting pepper head and recording position..." << std::endl; + if (!setHeadPositionAndRecord(0.0, 0.0)) + return false; + + std::cout << "auto-calibrate: step 2 of 5 - setting pepper head position A and recording position..." << std::endl; + if (!setHeadPositionAndRecord(-0.35, 0.0)) + return false; + + std::cout << "auto-calibrate: step 3 of 5 - setting pepper head position B and recording position..." << std::endl; + if (!setHeadPositionAndRecord(0.00, 0.7)) + return false; + + std::cout << "auto-calibrate: step 4 of 5 - setting pepper head position C and recording position..." << std::endl; + if (!setHeadPositionAndRecord(0.00, -0.7)) + return false; + + std::cout << "auto-calibrate: step 5 of 5 - resetting pepper head and calibrating..." << std::endl; + m_tele.setPepperHeadPitchYaw(0.0, 0.0); + + ros::spinOnce(); + + fSuccess = lookupTransform(); + if (!fSuccess) + return false; + + calibrate(); + + return true; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void calibrator::writeCalibrationData() +{ + if (m_fpath.empty()) + return; + + std::ofstream ofs(m_fpath); + float dat[12]; + + dat[0] = R(0, 0); + dat[1] = R(0, 1); + dat[2] = R(0, 2); + dat[3] = R(1, 0); + dat[4] = R(1, 1); + dat[5] = R(1, 2); + dat[6] = R(2, 0); + dat[7] = R(2, 1); + dat[8] = R(2, 2); + dat[9] = T(0); + dat[10] = T(1); + dat[11] = T(2); + + ofs.write((char *)dat, sizeof(float) * 12); + ofs.close(); + + std::cout << "Calibration file '" << m_fpath << "' saved." << std::endl; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void calibrator::calibration(std::vector pep_pos, std::vector hol_pos, Matrix3d &R, Vector3d &T) +{ + linear_calibration(pep_pos, hol_pos, R, T); + std::cout << "======== finished initial parameter computation ========" << std::endl; + nonlinear_calibration(pep_pos, hol_pos, R, T); +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void calibrator::horizontalCalibration(std::vector pep_pos, std::vector hol_pos, std::vector floor_holo, std::vector head_foot, Matrix3d &R, Vector3d &T) +{ + double bestScores[2]; + horizontal_initialization(pep_pos, hol_pos, floor_holo, head_foot, R, T, bestScores); + std::cout << "======== finished initial parameter computation ========" << std::endl; + nonlinear_horizontal_calibration(pep_pos, hol_pos, floor_holo, head_foot, R, T, bestScores); +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void calibrator::linear_calibration(std::vector pep_pos, std::vector hol_pos, Matrix3d &R, Vector3d &T) +{ + std::vector pepMat, pepdMat; + std::vector holMat, holdMat; + + // obtain motion + for (int i = 0; i < pep_pos.size(); i++) + { + Matrix4d mp = btTrans2EigMat4d(pep_pos.at(i)); + Matrix4d mh = btTrans2EigMat4d(hol_pos.at(i)); + pepMat.push_back(mp); + holMat.push_back(mh); + if (i > 0) + { + pepdMat.push_back(pepMat.at(i - 1).inverse() * pepMat.at(i)); + holdMat.push_back(holMat.at(i - 1).inverse() * holMat.at(i)); + } + } + + // Rotation calibration + // obtain axis from motion + std::vector pepAxis, holAxis; + MatrixXd KA(3, pepdMat.size()), KB(3, pepdMat.size()); + for (int i = 0; i < pepdMat.size(); i++) + { + Vector3d pepax = mat2axis(pepdMat.at(i)); + Vector3d holax = mat2axis(holdMat.at(i)); + KA.col(i) = pepax; + KB.col(i) = holax; + } + + MatrixXd KBKA = KB * KA.transpose(); + Eigen::JacobiSVD svd(KBKA, Eigen::ComputeThinU | Eigen::ComputeThinV); + Eigen::Matrix3d Hm; + Eigen::Matrix3d uvt = svd.matrixU() * svd.matrixV().transpose(); + + Hm << 1, 0, 0, + 0, 1, 0, + 0, 0, uvt.determinant(); + R = svd.matrixV() * Hm * svd.matrixU().transpose(); + + // Translation calibration + // solve least square problem for t + MatrixXd A(pepdMat.size() * 2, 3); + VectorXd B(pepdMat.size() * 2); + + for (int i = 0; i < pepdMat.size(); i++) + { + Vector3d tpep, thol; + tpep << pepdMat.at(i)(0, 3), pepdMat.at(i)(1, 3), pepdMat.at(i)(2, 3); + thol << holdMat.at(i)(0, 3), holdMat.at(i)(1, 3), holdMat.at(i)(2, 3); + Vector3d rightt = tpep - R * thol; + Matrix3d leftm = Matrix3d::Identity() - pepdMat.at(i).block(0, 0, 3, 3); + A.block(i * 2, 0, 2, 3) = leftm.block(0, 0, 2, 3); + B(i * 2) = rightt(0); + B(i * 2 + 1) = rightt(1); + } + + T = A.jacobiSvd(ComputeThinU | ComputeThinV).solve(B); + std::cout << "Rotation (Initial)" << std::endl + << R << std::endl; + std::cout << "Translation (Initial)" << std::endl + << T << std::endl; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void calibrator::nonlinear_calibration(std::vector pep_pos, std::vector hol_pos, Matrix3d &R, Vector3d &T) +{ + double opt[6]; + double optrot[3]; + double opttrans[3]; + + R2axisRot(R, opt[3], opt[4], opt[5]); + R2axisRot(R, optrot[0], optrot[1], optrot[2]); + + opt[0] = T(0); + opt[1] = T(1); + opt[2] = T(2); + + opttrans[0] = T(0); + opttrans[1] = T(1); + opttrans[2] = T(2); + + Problem problem, problem_a, problem_b; + + std::vector pepMat, pepdMat; + std::vector holMat, holdMat; + + // Obtain motion + for (int i = 0; i < pep_pos.size(); i++) + { + Matrix4d mp = btTrans2EigMat4d(pep_pos.at(i)); + Matrix4d mh = btTrans2EigMat4d(hol_pos.at(i)); + pepMat.push_back(mp); + holMat.push_back(mh); + if (i > 0) + { + pepdMat.push_back(pepMat.at(i - 1).inverse() * pepMat.at(i)); + holdMat.push_back(holMat.at(i - 1).inverse() * holMat.at(i)); + } + } + + // Construct cost function + for (int i = 0; i < pepdMat.size(); i++) + { + Matrix4d A = pepdMat.at(i); + Matrix4d B = holdMat.at(i); + double anglea, angleb; + Vector3d a_ax; + mat2axis_angle(A, a_ax, anglea); + Vector3d b_ax; + mat2axis_angle(B, b_ax, angleb); + //Function 1: Optimize rotation + CostFunction *cost_function1d = new NumericDiffCostFunction(new F1_(a_ax, b_ax)); + problem_a.AddResidualBlock(cost_function1d, NULL, optrot); + //Function 2: Optimize translation + CostFunction *cost_function2d = new NumericDiffCostFunction(new F2_(A, B, optrot)); + problem_b.AddResidualBlock(cost_function2d, NULL, opttrans); + } + + Solver::Options options; + options.minimizer_progress_to_stdout = true; + Solver::Summary summary; + + // Rotation optimization + ceres::Solve(options, &problem_a, &summary); + + // Translation optimization + ceres::Solve(options, &problem_b, &summary); + + std::cout << "finished optimization\n"; + std::cout << summary.BriefReport() << "\n"; + + R = axisRot2R(optrot[0], optrot[1], optrot[2]); + T << opttrans[0], opttrans[1], opttrans[2]; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void calibrator::horizontal_initialization(std::vector pep_pos, std::vector hol_pos, std::vector verticalVecs, std::vector normVecs, Matrix3d &R, Vector3d &T, double *bestScores) +{ + // Compute motion + std::vector RobotMat, A_Mat; + std::vector holMat, B_Mat; + + for (int i = 0; i < pep_pos.size(); i++) + { + Matrix4d mp = btTrans2EigMat4d(pep_pos.at(i)); + Matrix4d mh = btTrans2EigMat4d(hol_pos.at(i)); + RobotMat.push_back(mp); + holMat.push_back(mh); + if (i > 0) + { + A_Mat.push_back(RobotMat.at(i - 1).inverse() * RobotMat.at(i)); + B_Mat.push_back(holMat.at(i - 1).inverse() * holMat.at(i)); + } + } + + // Rotation calibration + std::vector RobotAxis, holAxis; + std::cout << "axis of rotation matrix" << std::endl; + + // Obtain rotational axis + for (int i = 0; i < A_Mat.size(); i++) + { + double anglea, angleb; + Vector3d pepax; + mat2axis_angle(A_Mat.at(i), pepax, anglea); + Vector3d holax; + mat2axis_angle(A_Mat.at(i), holax, angleb); + if (anglea < 0.1 || angleb < 0.1) + continue; // reject small rotational movement + RobotAxis.push_back(pepax); + holAxis.push_back(holax); + } + + if (RobotAxis.size() == 0) + { + std::cout << "initialization failed!! (need large rotaion)\nPlease check how to move..." << std::endl; + return; + } + + // obtain forward movement + double offset_trans = 0.1; + double offset = 0.01; + for (int i = 0; i < A_Mat.size(); i++) + { + double anglea, angleb; + Vector3d pepax; + mat2axis_angle(A_Mat.at(i), pepax, anglea); + Vector3d holax; + mat2axis_angle(B_Mat.at(i), holax, angleb); + Vector3d ta = A_Mat.at(i).block(0, 3, 3, 1); + double score = ta.norm() / (fabs(anglea) + offset); // (movement length)/(rotational angle) + if (2 < score) // 2: threshold + { + RobotAxis.push_back(ta.normalized()); + Vector3d tb = B_Mat.at(i).block(0, 3, 3, 1); + holAxis.push_back(tb.normalized()); + } + } + + // Rotation calibration (SVD) + MatrixXd KA(3, RobotAxis.size()), KB(3, RobotAxis.size()); + for (int i = 0; i < RobotAxis.size(); i++) + { + KA.col(i) = RobotAxis.at(i); + KB.col(i) = holAxis.at(i); + } + + MatrixXd KBKA = KB * KA.transpose(); + Eigen::JacobiSVD svd(KBKA, Eigen::ComputeThinU | Eigen::ComputeThinV); + Eigen::Matrix3d Hm; + Eigen::Matrix3d uvt = svd.matrixU() * svd.matrixV().transpose(); + + Hm << 1, 0, 0, + 0, 1, 0, + 0, 0, uvt.determinant(); + R = svd.matrixV() * Hm * svd.matrixU().transpose(); + + // Translation calibration + std::vector left_vectors; + std::vector right_values; + + // vertical trans component + for (int i = 0; i < verticalVecs.size(); i++) + { + Eigen::Vector3d floor2holo = verticalVecs.at(i); + Eigen::Vector3d head2foot = normVecs.at(i); + double right_value = floor2holo.norm() + floor2holo.dot(R.transpose() * head2foot); //in hololens frame + Eigen::Vector3d left_vector = (floor2holo.transpose() * R.transpose()).transpose(); + left_vectors.push_back(left_vector); + right_values.push_back(right_value); + } + + // horizontal trans component + for (int i = 0; i < A_Mat.size(); i++) + { + double anglea, angleb; + Vector3d pepax; + mat2axis_angle(A_Mat.at(i), pepax, anglea); + Vector3d holax; + mat2axis_angle(B_Mat.at(i), holax, angleb); + Vector3d ta = A_Mat.at(i).block(0, 3, 3, 1); + Vector3d tb = B_Mat.at(i).block(0, 3, 3, 1); + if (anglea < 0.1 || angleb < 0.1) + continue; + Vector3d rightt = ta - R * tb; + Matrix3d leftM = Matrix3d::Identity() - A_Mat.at(i).block(0, 0, 3, 3); + for (int j = 0; j < 3; j++) + { + right_values.push_back(rightt(j)); + left_vectors.push_back(leftM.row(j).transpose()); + } + } + + // solve t by SVD + MatrixXd A(right_values.size(), 3); + VectorXd B(right_values.size()); + + for (int i = 0; i < right_values.size(); i++) + { + A.block(i, 0, 1, 3) = left_vectors.at(i).transpose(); + B(i) = right_values.at(i); + } + + T = A.jacobiSvd(ComputeThinU | ComputeThinV).solve(B); + + std::cout << "Rotation (Initial)\n" + << R << std::endl; + std::cout << "Translation (Initial)" << std::endl + << T << std::endl; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void calibrator::nonlinear_horizontal_calibration(std::vector pep_pos, std::vector hol_pos, std::vector floor_holo, std::vector head_foot, Matrix3d &R, Vector3d &T, double *bestScores) +{ + //decompose + double opt[6]; + double optrot[3]; + double opttrans[3]; + + R2axisRot(R, opt[3], opt[4], opt[5]); + R2axisRot(R, optrot[0], optrot[1], optrot[2]); + + opt[0] = T(0); + opt[1] = T(1); + opt[2] = T(2); + + opttrans[0] = T(0); + opttrans[1] = T(1); + opttrans[2] = T(2); + + // optimize (2 patterns for comparison) + // problem: simultaneous 6 parameters optimization + // problem a, b: optimize sepalately (3 rotation, 3 translation) + Problem problem, problem_a, problem_b; + + std::vector pepMat, pepdMat; + std::vector holMat, holdMat; + double offset_trans = 0.1; + double offset_angle = 0.2; + double offset = 0.01; + + for (int i = 1; i < pep_pos.size(); i++) + { // rotation estimation by horizontal rotation + // obtain motion (mh3,mp3) + Matrix4d mp = btTrans2EigMat4d(pep_pos.at(i - 1)); + Matrix4d mh = btTrans2EigMat4d(hol_pos.at(i - 1)); + Matrix4d mp2 = btTrans2EigMat4d(pep_pos.at(i)); + Matrix4d mh2 = btTrans2EigMat4d(hol_pos.at(i)); + Matrix4d mh3, mp3; + mp3 = mp2.inverse() * mp; + mh3 = mh2.inverse() * mh; + double anglea, angleb; + Vector3d pepax; + + mat2axis_angle(mp3, pepax, anglea); + + Vector3d holax; + + mat2axis_angle(mh3, holax, angleb); + + Vector3d ta = mp3.block(0, 3, 3, 1); + Vector3d tb = mh3.block(0, 3, 3, 1); + double scorea = (sqrt(ta.norm()) - sqrt(offset_trans)) / (fabs(anglea) + offset); // translation score + double scoreb = (sqrt(fabs(anglea)) - sqrt(offset_angle)) / (ta.norm() + offset); // rotation score + + if (scoreb >= bestScores[1] * 0.95) // straight movement + { + CostFunction *cost_function1 = new NumericDiffCostFunction(new F1(pepax, holax)); + problem.AddResidualBlock(cost_function1, NULL, opt); + CostFunction *cost_function2 = new NumericDiffCostFunction(new F2(mp3, mh3)); + problem.AddResidualBlock(cost_function2, NULL, opt); + + CostFunction *cost_function1d = new NumericDiffCostFunction(new F1_(pepax, holax)); + problem_a.AddResidualBlock(cost_function1d, NULL, optrot); + CostFunction *cost_function2d = new NumericDiffCostFunction(new F2_(mp3, mh3, optrot)); + problem_b.AddResidualBlock(cost_function2d, NULL, opttrans); + } + + if (scorea >= bestScores[0] * 0.95) // rotational movement + { + Vector3d ta_n = ta.normalized(); + Vector3d tb_n = tb.normalized(); + CostFunction *cost_function1 = new NumericDiffCostFunction(new F1(ta_n, tb_n)); + problem.AddResidualBlock(cost_function1, NULL, opt); + CostFunction *cost_function1d = new NumericDiffCostFunction(new F1_(ta_n, tb_n)); + problem_a.AddResidualBlock(cost_function1d, NULL, optrot); + } + } + + for (int i = 0; i < floor_holo.size(); i++) + { // height information + Eigen::Vector3d fh = floor_holo.at(i); + Eigen::Vector3d hf = head_foot.at(i); + CostFunction *cost_function3 = new NumericDiffCostFunction(new F3(fh, hf)); + problem.AddResidualBlock(cost_function3, NULL, opt); + CostFunction *cost_function3d = new NumericDiffCostFunction(new F3_(fh, hf, optrot)); + problem_b.AddResidualBlock(cost_function3d, NULL, opttrans); + } + + Solver::Options options; + options.minimizer_progress_to_stdout = true; + Solver::Summary summary; + + ceres::Solve(options, &problem, &summary); // pattern 1 + ceres::Solve(options, &problem_a, &summary); // pattern 2 a (rotation) + ceres::Solve(options, &problem_b, &summary); // pattern 2 b (translation) + + std::cout << "finished optimization\n"; + std::cout << summary.BriefReport() << "\n"; + + R = axisRot2R(opt[3], opt[4], opt[5]); + T << opt[0], opt[1], opt[2]; + + // pattern 1 result (just for comparison) + std::cout << R << std::endl; + std::cout << T << std::endl; + + R = axisRot2R(optrot[0], optrot[1], optrot[2]); + T << opttrans[0], opttrans[1], opttrans[2]; + + // pattern 2 result (used as a calibration result) + std::cout << R << std::endl; + std::cout << T << std::endl; +} diff --git a/linux/HoloLens_Localization/src/static_calibration/cost_function.cpp b/linux/HoloLens_Localization/src/static_calibration/cost_function.cpp new file mode 100644 index 0000000..a0cc9c2 --- /dev/null +++ b/linux/HoloLens_Localization/src/static_calibration/cost_function.cpp @@ -0,0 +1,53 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "cost_function.h" + +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +Eigen::Matrix3d axisRot2R(double rx, double ry, double rz) +{ + // + // rotation conversion: Eular angle to matrix + Eigen::Matrix4d R,rotx,roty,rotz; + double sinv,cosv; + + sinv = sin(rx); + cosv = cos(rx); + rotx << 1,0,0,0,0,cosv,-sinv,0,0,sinv,cosv,0,0,0,0,1; + + sinv = sin(ry); + cosv = cos(ry); + roty << cosv,0,sinv,0,0,1,0,0,-sinv,0,cosv,0,0,0,0,1; + + sinv = sin(rz); + cosv = cos(rz); + rotz << cosv,-sinv,0,0,sinv,cosv,0,0,0,0,1,0,0,0,0,1; + + R = rotx * roty * rotz; + + Eigen::Matrix3d retMat = R.block(0,0,3,3); + + return retMat; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void R2axisRot(Eigen::Matrix3d R,double& rx,double& ry,double& rz) +{ + // + // rotation conversion: Matrix to Eular angle + ry = asin(R(0,2)); + rx = -atan2(R(1,2),R(2,2)); + rz = -atan2(R(0,1),R(0,0)); +} + diff --git a/linux/HoloLens_Localization/src/static_calibration/main.cpp b/linux/HoloLens_Localization/src/static_calibration/main.cpp new file mode 100644 index 0000000..8dc4ed7 --- /dev/null +++ b/linux/HoloLens_Localization/src/static_calibration/main.cpp @@ -0,0 +1,86 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "ros/ros.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "calibration.h" + +using namespace Eigen; + +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void printHelp() +{ + std::cout<<"---------------------------------------------------------"< "<= 5) { + fpath = std::string(argv[4]); + } + + printHelp(); + + // set up publish rate + calibrator calib(holoLinkedFrame, odomFrame, robotFootFrame, fpath); + + calib.run(); + + return 0; +} diff --git a/linux/HoloLens_Localization/src/static_calibration/teleop.cpp b/linux/HoloLens_Localization/src/static_calibration/teleop.cpp new file mode 100644 index 0000000..8570ac9 --- /dev/null +++ b/linux/HoloLens_Localization/src/static_calibration/teleop.cpp @@ -0,0 +1,221 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "teleop.h" +#include +#include + +// +// see https://github.com/ros-naoqi/nao_extras/blob/master/nao_teleop/src/teleop_nao_joy.cpp + +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +teleop::teleop() : + m_fStiffness(false), + m_maxHeadYaw(2.0943), m_maxHeadPitch(0.7853), + m_bodyPoseTimeOut(5.0), + m_bodyPoseClient("body_pose", true) +{ + ros::NodeHandle nh; + + m_movePub = nh.advertise("cmd_vel", 10); + m_headPub = nh.advertise("joint_angles", 1); + + m_stiffnessDisableClient = nh.serviceClient("body_stiffness/disable"); + m_stiffnessEnableClient = nh.serviceClient("body_stiffness/enable"); + m_wakeup = nh.serviceClient("wakeup"); + m_rest = nh.serviceClient("rest"); +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +bool teleop::callBodyPoseClient(const std::string& poseName) +{ + if (!m_bodyPoseClient.isServerConnected()) { + return false; + } + + naoqi_bridge_msgs::BodyPoseGoal goal; + + goal.pose_name = poseName; + + m_bodyPoseClient.sendGoalAndWait(goal, m_bodyPoseTimeOut); + + actionlib::SimpleClientGoalState state = m_bodyPoseClient.getState(); + if (state != actionlib::SimpleClientGoalState::SUCCEEDED) { + ROS_ERROR("Pose action \"%s\" did not succeed (%s): %s", goal.pose_name.c_str(), state.toString().c_str(), state.text_.c_str()); + return false; + } else { + ROS_INFO("Pose action \"%s\" succeeded", goal.pose_name.c_str()); + return true; + } +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void teleop::operation(int c) +{ + if (c == 'i') { // move forward + geometry_msgs::Twist msgTwist; + msgTwist.linear.x = 0.1; + msgTwist.linear.y = 0; + msgTwist.linear.z = 0; + msgTwist.angular.x = 0; + msgTwist.angular.y = 0; + msgTwist.angular.z = 0; + m_movePub.publish(msgTwist); + } else if (c == 'j') { // move left + geometry_msgs::Twist msgTwist; + msgTwist.linear.x = 0; + msgTwist.linear.y = 0.1; + msgTwist.linear.z = 0; + msgTwist.angular.x = 0; + msgTwist.angular.y = 0; + msgTwist.angular.z = 0; + m_movePub.publish(msgTwist); + } else if (c == 'l') { // move right + geometry_msgs::Twist msgTwist; + msgTwist.linear.x = 0; + msgTwist.linear.y = -0.1; + msgTwist.linear.z = 0; + msgTwist.angular.x = 0; + msgTwist.angular.y = 0; + msgTwist.angular.z = 0; + m_movePub.publish(msgTwist); + } else if (c == 'u') { // turn left + geometry_msgs::Twist msgTwist; + msgTwist.linear.x = 0; + msgTwist.linear.y = 0; + msgTwist.linear.z = 0; + msgTwist.angular.x = 0; + msgTwist.angular.y = 0; + msgTwist.angular.z = 0.2; + m_movePub.publish(msgTwist); + } else if (c == 'o') { // turn right + geometry_msgs::Twist msgTwist; + msgTwist.linear.x = 0; + msgTwist.linear.y = 0; + msgTwist.linear.z = 0; + msgTwist.angular.x = 0; + msgTwist.angular.y = 0; + msgTwist.angular.z = -0.2; + m_movePub.publish(msgTwist); + } else if (c == 'k') { // move backward + geometry_msgs::Twist msgTwist; + msgTwist.linear.x = -0.1; + msgTwist.linear.y = 0; + msgTwist.linear.z = 0; + msgTwist.angular.x = 0; + msgTwist.angular.y = 0; + msgTwist.angular.z = 0; + m_movePub.publish(msgTwist); + } else if (c == 's') { // stop + geometry_msgs::Twist msgTwist; + msgTwist.linear.x = 0; + msgTwist.linear.y = 0; + msgTwist.linear.z = 0; + msgTwist.angular.x = 0; + msgTwist.angular.y = 0; + msgTwist.angular.z = 0; + m_movePub.publish(msgTwist); + } + else if (c == 'p') + { + std_srvs::Empty e; + + m_fStiffness = !m_fStiffness; + + if (m_fStiffness) { + std::cout << "enabling stiffness\r\n" << std::endl; + m_stiffnessEnableClient.call(e); + } else { + std::cout << "disabling stiffness\r\n" << std::endl; + m_stiffnessDisableClient.call(e); + } + } + else if (c == 'e') + { + std_srvs::Empty e; + m_wakeup.call(e); + } + else if (c == 'r') + { + std_srvs::Empty e; + m_rest.call(e); + } + else if (c == '0') + { + setPepperHeadPitchYaw(0.0, 0.0); + } + else if (c == '1') + { + setPepperHeadPitchYaw(-0.35, 0.0); + } + else if (c == '2') + { + setPepperHeadPitchYaw(0.0, 0.7); + } + else if (c == '3') + { + setPepperHeadPitchYaw(0.0, -0.7); + } +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void teleop::setPepperHeadPitch(float angle) +{ + naoqi_bridge_msgs::JointAnglesWithSpeed headpose; + + headpose.joint_names.clear(); + headpose.joint_names.push_back("HeadPitch"); + headpose.joint_angles.clear(); + headpose.joint_angles.push_back(angle); + headpose.speed = 0.1; + headpose.relative = 0; // ABSOLUTE MODE + + m_headPub.publish(headpose); +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void teleop::setPepperHeadYaw(float angle) +{ + naoqi_bridge_msgs::JointAnglesWithSpeed headpose; + + headpose.joint_names.clear(); + headpose.joint_names.push_back("HeadYaw"); + headpose.joint_angles.clear(); + headpose.joint_angles.push_back(angle); + headpose.speed = 0.1; + headpose.relative = 0; // ABSOLUTE MODE + + m_headPub.publish(headpose); +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void teleop::setPepperHeadPitchYaw(float pitch, float yaw) +{ + naoqi_bridge_msgs::JointAnglesWithSpeed headpose; + + headpose.joint_names.clear(); + headpose.joint_names.push_back("HeadPitch"); + headpose.joint_names.push_back("HeadYaw"); + headpose.joint_angles.clear(); + headpose.joint_angles.push_back(pitch); + headpose.joint_angles.push_back(yaw); + headpose.speed = 0.1; + headpose.relative = 0; // ABSOLUTE MODE + + m_headPub.publish(headpose); +} diff --git a/linux/HoloROSBridge/CMakeLists.txt b/linux/HoloROSBridge/CMakeLists.txt new file mode 100644 index 0000000..4d02c94 --- /dev/null +++ b/linux/HoloROSBridge/CMakeLists.txt @@ -0,0 +1,202 @@ +cmake_minimum_required(VERSION 2.8.3) +project(hololens_ros_bridge) + +## Compile as C++11, supported in ROS Kinetic and newer +add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + roscpp + std_msgs + message_generation + tf +) + +find_package(Eigen3 REQUIRED NO_MODULE) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES hololens_ros_bridge +# CATKIN_DEPENDS other_catkin_pkg +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +include +${catkin_INCLUDE_DIRS} +${Eigen3_INCLUDE_DIRS} +) + +## Declare a C++ library +#add_library(${PROJECT_NAME} +# src/data_connection.cpp +# src/funcs.cpp +#) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +add_executable(${PROJECT_NAME}_node + src/hololens_ros_bridge_node.cpp + src/data_connection.cpp + src/funcs.cpp + ) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against + target_link_libraries(${PROJECT_NAME}_node + ${catkin_LIBRARIES} + ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# install(TARGETS ${PROJECT_NAME} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) diff --git a/linux/HoloROSBridge/include/data_connection.h b/linux/HoloROSBridge/include/data_connection.h new file mode 100644 index 0000000..93298fb --- /dev/null +++ b/linux/HoloROSBridge/include/data_connection.h @@ -0,0 +1,49 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include +#include + +// +// needs to match SurfaceMeshStreamHeader in the HoloLensSpatialMapping Windows application +#define SMSH_SIGNATURE "SMSHSIG_" + +struct SurfaceMeshStreamHeader +{ + unsigned char signature[8]; + float scale; + float center_x; + float center_y; + float center_z; + float orientation_x; + float orientation_y; + float orientation_z; + float orientation_w; + unsigned int uVertexBufferSize; + unsigned int uNumVertices; +}; + +enum EnumAskState +{ + Default_Ask_Pose, + Refresh_Anchor_And_Render_Map, + Update_Anchor +}; + +enum EnumRepliedState +{ + Recv_Pose, + Recv_Anchor_Pose, + Recv_Anchor_Pose_Map +}; + +void recvMessage(int sock,unsigned int size,char* pointer); +int reverseEndian(int n); diff --git a/linux/HoloROSBridge/include/funcs.h b/linux/HoloROSBridge/include/funcs.h new file mode 100644 index 0000000..245df31 --- /dev/null +++ b/linux/HoloROSBridge/include/funcs.h @@ -0,0 +1,26 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include + +#include +#include +#include +#include +#include +#include +#include + +typedef std::map MTF; + +tf::StampedTransform positionMat2tf(float* posdata); +tf::StampedTransform EigenMat2tf(Eigen::Matrix4d posdataMat); +Eigen::Matrix4d tf2EigenMat(tf::StampedTransform tfdata); diff --git a/linux/HoloROSBridge/package.xml b/linux/HoloROSBridge/package.xml new file mode 100644 index 0000000..4c4dc7f --- /dev/null +++ b/linux/HoloROSBridge/package.xml @@ -0,0 +1,59 @@ + + + hololens_ros_bridge + 0.0.0 + The hololens_ros_bridge package + + + + + t-ryish + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + + + + + + + + diff --git a/linux/HoloROSBridge/src/data_connection.cpp b/linux/HoloROSBridge/src/data_connection.cpp new file mode 100644 index 0000000..d3187f2 --- /dev/null +++ b/linux/HoloROSBridge/src/data_connection.cpp @@ -0,0 +1,43 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "data_connection.h" + +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void recvMessage(int sock, unsigned int size, char* pointer) +{ + int total=0; + while (total < size) { + int n = recv(sock, pointer, (size-total), 0); + total += n; + pointer += n; + } +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +int reverseEndian(int n) +{ + int ret; + char* n_buf,*ret_buf; + + n_buf = (char*)&n; + ret_buf = (char*)&ret; + + ret_buf[0] = n_buf[3]; + ret_buf[1] = n_buf[2]; + ret_buf[2] = n_buf[1]; + ret_buf[3] = n_buf[0]; + + return ret; +} diff --git a/linux/HoloROSBridge/src/funcs.cpp b/linux/HoloROSBridge/src/funcs.cpp new file mode 100644 index 0000000..fd2f519 --- /dev/null +++ b/linux/HoloROSBridge/src/funcs.cpp @@ -0,0 +1,56 @@ +#include "funcs.h" + +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +tf::StampedTransform positionMat2tf(float* posdata) +{ + tf::StampedTransform tf_ret; + + tf_ret.setOrigin(tf::Vector3(posdata[12], posdata[13], posdata[14])); + + tf::Matrix3x3 rot(posdata[0],posdata[4],posdata[8], + posdata[1],posdata[5],posdata[9], + posdata[2],posdata[6],posdata[10]); + tf::Quaternion q; + rot.getRotation(q); + tf_ret.setRotation(q); + tf_ret.stamp_=ros::Time::now(); + + return tf_ret; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +tf::StampedTransform EigenMat2tf(Eigen::Matrix4d posdataMat) +{ + double* posdata = posdataMat.data(); + tf::StampedTransform tf_ret; + + tf_ret.setOrigin(tf::Vector3(posdata[12], posdata[13], posdata[14])); + + tf::Matrix3x3 rot(posdata[0],posdata[4],posdata[8], + posdata[1],posdata[5],posdata[9], + posdata[2],posdata[6],posdata[10]); + tf::Quaternion q; + rot.getRotation(q); + tf_ret.setRotation(q); + tf_ret.stamp_=ros::Time::now(); + + return tf_ret; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +Eigen::Matrix4d tf2EigenMat(tf::StampedTransform tfdata) +{ + tf::Vector3 origin = tfdata.getOrigin(); + tf::Matrix3x3 rot = tfdata.getBasis(); + Eigen::Matrix4d ret; + ret << rot[0][0],rot[0][1],rot[0][2],origin[0], + rot[1][0],rot[1][1],rot[1][2],origin[1], + rot[2][0],rot[2][1],rot[2][2],origin[2], + 0,0,0,1; + + return ret; +} diff --git a/linux/HoloROSBridge/src/hololens_ros_bridge_node.cpp b/linux/HoloROSBridge/src/hololens_ros_bridge_node.cpp new file mode 100644 index 0000000..cb1f031 --- /dev/null +++ b/linux/HoloROSBridge/src/hololens_ros_bridge_node.cpp @@ -0,0 +1,421 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "ros/ros.h" +#include "std_msgs/String.h" +#include "std_msgs/Bool.h" +#include "sensor_msgs/PointCloud.h" +#include "data_connection.h" +#include "funcs.h" + +#include +#include +#include +#include + +const char * pszAppName = "hololens_ros_bridge"; +bool sendMsg = false; +bool recvTF = false; +float keptHeight; +tf::StampedTransform alignedTF; +tf::StampedTransform tf_hololens2ros; + +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void callbackTest(const std_msgs::Bool::ConstPtr &subscr_ping) +{ + ROS_INFO("Request to initialize HoloLens bridge received."); + sendMsg = true; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +void callback_aligned(const geometry_msgs::PoseStamped::ConstPtr &ps) +{ + // + // callback for receiving alignment result + + ROS_INFO("Request to align localized spatial anchor received."); + + // convert PoseStamped to tf + alignedTF.setOrigin(tf::Vector3(ps->pose.position.x, ps->pose.position.y, keptHeight)); + + tf::Quaternion initq( + ps->pose.orientation.x, + ps->pose.orientation.y, + ps->pose.orientation.z, + ps->pose.orientation.w); + + alignedTF.setRotation(initq); + + tf::Transform tf_map2sa = alignedTF; + + alignedTF.setData(tf_map2sa); + alignedTF.stamp_=ros::Time::now(); + alignedTF.frame_id_ = std::string("map"); + alignedTF.child_frame_id_ = std::string("spatialAnchor_ros"); + + recvTF = true; +} +/*****************************************************************************/ +/* */ +/*****************************************************************************/ +int main(int argc, char **argv) +{ + if (argc < 3) + { + ROS_ERROR("missing parameters: ("/hololens/pc", 1000); + + // floor surface normal + ros::Publisher pub2 = nh.advertise("/hololens/floor_normal", 1000); + + // port, ip_address of HoloLens (port should be 1234) + const int port = std::stoi(argv[2]); + const char * ip_address = argv[1]; + + ROS_INFO("Socket trying to connect to %s:%i...", ip_address, port); + + int sock = socket(PF_INET, SOCK_STREAM, 0); + + // connection + struct sockaddr_in addr; + + addr.sin_family = AF_INET; + addr.sin_port = htons(port); + addr.sin_addr.s_addr = inet_addr(ip_address); + + if (connect(sock, (struct sockaddr *)&addr, sizeof(addr)) != 0) + { + ROS_FATAL("Socket connection error."); + return -1; + } + + ROS_INFO("Socket successfully connected."); + + EnumAskState askState; + EnumRepliedState repState; + char recvBuf[2048]; + float cameraPosition[20]; + float holoLensHeight; + Eigen::Vector3d toFloor=Eigen::Vector3d::Zero(); + + // Spatial Anchor (SA) in ROS - SA in HoloLens (Rotation alignment) + Eigen::Matrix4d hololens2ros; + + hololens2ros << 0, 0, -1, 0, + -1, 0, 0, 0, + 0, 1, 0, 0, + 0, 0, 0, 1; + + // transformation chain: map - SA (ROS) - SA (HoloLens) - HoloLens camera + tf::StampedTransform tf_anchor2camera; + tf::StampedTransform tf_map2anchor; + + tf_hololens2ros = EigenMat2tf(hololens2ros); + tf_hololens2ros.frame_id_ = std::string("spatialAnchor_ros"); + tf_hololens2ros.child_frame_id_ = std::string("spatialAnchor"); + + tf_map2anchor = EigenMat2tf(Eigen::Matrix4d::Identity()); + tf_map2anchor.frame_id_ = std::string("map"); + tf_map2anchor.child_frame_id_ = std::string("spatialAnchor_ros"); + + // tf broadcaster + tf::TransformBroadcaster tf_br_; + + // string id - tf lookup table + MTF transLookUp; + + // string id of current anchor + std::string CurrentAnchor; + bool transBool = false; + sensor_msgs::PointCloud pointcloud; + + while (ros::ok()) + { + askState = Default_Ask_Pose; + if (sendMsg) + { // if receiving localization initialization from anchor localizer + askState = Refresh_Anchor_And_Render_Map; + transLookUp.clear(); + ROS_INFO("Refreshing point cloud data and anchors..."); + sendMsg = false; + } + + if (recvTF) + { // if receiving alignment result from anchor localizer + // update tf of map-SA (ROS) + transLookUp.at(CurrentAnchor) = alignedTF; + tf_map2anchor = alignedTF; + recvTF=false; + } + + // send message to HoloLens + int nRevAskState = reverseEndian(askState); + int nWrite = write(sock, &nRevAskState, sizeof(EnumAskState)); + if (nWrite <= 0) + { + ROS_FATAL("Socket write failed (%d bytes).", nWrite); + break; + } + + // receive message from HoloLens + int nRead = read(sock, (char *)&repState, sizeof(EnumRepliedState)); + if (nRead <= 0) + { + ROS_FATAL("Socket read failed (%d bytes).", nRead); + break; + } + + // received message + repState = EnumRepliedState(reverseEndian(repState)); + + switch (repState) + { + case Recv_Anchor_Pose_Map: + { // receive point cloud + // receive transformation of (old SA-new SA) in HoloLens + recvMessage(sock, sizeof(float) * 16, (char *)cameraPosition); + + Eigen::Matrix4d anc2anc; + anc2anc << cameraPosition[0], cameraPosition[4], cameraPosition[8], cameraPosition[12], + cameraPosition[1], cameraPosition[5], cameraPosition[9], cameraPosition[13], + cameraPosition[2], cameraPosition[6], cameraPosition[10], cameraPosition[14], + cameraPosition[3], cameraPosition[7], cameraPosition[11], cameraPosition[15]; + + // obtain new SA position (temporal) + Eigen::Matrix4d map2anc = tf2EigenMat(tf_map2anchor); + std::cout << pszAppName << ": old anchor to new anchor " << std::endl; + std::cout << /* std::setw(16) << */ anc2anc << std::endl; + + // tf:[map-new SA (ROS)] = (map - old SA) * (Ros-HoloLens) * (old SA-new SA) * (HoloLens - ROS) + map2anc = map2anc * tf2EigenMat(tf_hololens2ros) * anc2anc * tf2EigenMat(tf_hololens2ros).inverse(); + std::cout << pszAppName << ": map to new anchor " << std::endl; + std::cout << /* std::setw(16) << */ map2anc << std::endl; + + // update tf:[map-SA (ROS)] + tf_map2anchor = EigenMat2tf(map2anc); + tf_map2anchor.frame_id_ = std::string("map"); + tf_map2anchor.child_frame_id_ = std::string("spatialAnchor_ros"); + + // receive point cloud + char buffer[4], bufferswap[4]; + + // size of point cloud buffer + recvMessage(sock, 4, buffer); + + bufferswap[0] = buffer[3]; + bufferswap[1] = buffer[2]; + bufferswap[2] = buffer[1]; + bufferswap[3] = buffer[0]; + + unsigned int uTotalBufferSize = ((unsigned int *)bufferswap)[0]; + char * vertexCollectionDataBuffer = (char *)malloc(sizeof(char) * uTotalBufferSize); + + recvMessage(sock, uTotalBufferSize, vertexCollectionDataBuffer); + + char * ptr = vertexCollectionDataBuffer; + unsigned int currentBufferPosition = 0; + + pointcloud.points.clear(); + + // read buffer + while (true) + { + // SurfaceMeshStreamHeader contains center, orientation, and vertex position length of point cloud + SurfaceMeshStreamHeader * hdr = (SurfaceMeshStreamHeader *)ptr; + + if (memcmp(hdr->signature, (void *)SMSH_SIGNATURE, sizeof(hdr->signature)) != 0) { + ROS_ERROR("vertex collection buffer misalignement at offset %u.", currentBufferPosition); + break; + } + + Eigen::Vector3d center; + + center << hdr->center_x, hdr->center_y, hdr->center_z; + + Eigen::Quaterniond orientation = Eigen::Quaterniond(hdr->orientation_w, hdr->orientation_x, hdr->orientation_y, hdr->orientation_z); + + unsigned int uNumVertices = hdr->uNumVertices; + + // move to vertex buffer + ptr += sizeof(SurfaceMeshStreamHeader); + + short * vertexBuffer = (short *)ptr; + + // read point cloud + for (int i = 0; i < uNumVertices; i++) + { + Eigen::Vector3d p; + + // point position + p << vertexBuffer[i * 4] * 0.0025f, vertexBuffer[i * 4 + 1] * 0.0025f, vertexBuffer[i * 4 + 2] * 0.0025f; + + // point transformation + p = orientation * p + center; + + // store in point cloud array + geometry_msgs::Point32 pt; + + pt.x = p(0); + pt.y = p(1); + pt.z = p(2); + + pointcloud.points.push_back(pt); + } + + //move to next header + ptr += hdr->uVertexBufferSize; + currentBufferPosition += sizeof(SurfaceMeshStreamHeader) + hdr->uVertexBufferSize; + if (currentBufferPosition >= uTotalBufferSize) + break; + } + + // + // done with buffer, delete it + // free(vertexCollectionDataBuffer); + + // ack for point cloud publish + transBool = true; + // continue to next process in (case Recv_Anchor_Pose:) + } + // fall through... + + case Recv_Anchor_Pose: + { // receive anchor id + char buffer[4], bufferswap[4]; + + // anchor string id length + recvMessage(sock, 4, buffer); + bufferswap[0] = buffer[3]; + bufferswap[1] = buffer[2]; + bufferswap[2] = buffer[1]; + bufferswap[3] = buffer[0]; + + unsigned int bufferLength = ((unsigned int *)bufferswap)[0]; + char *strBuf = (char *)malloc(sizeof(char) * bufferLength + 1); + + // Anchor string id + recvMessage(sock, sizeof(char) * bufferLength, strBuf); + strBuf[sizeof(char) * bufferLength] = 0; + std::string str(strBuf); + std::cout << pszAppName << ": anchor string is '" << str << "'" << std::endl; + MTF::iterator it = transLookUp.find(str); + if (it != transLookUp.end()) + {//obtain existing tf from look up table + tf_map2anchor = transLookUp.at(str); + } + else + {//create new tf + CurrentAnchor = str; + transLookUp.insert(MTF::value_type(str, tf_map2anchor)); + } + free(strBuf); + //continue to next process in (case Recv_Pose:) + } + // TODO: FALL THROUGH? + + case Recv_Pose: + { // receive camera position as 4x4 float matrix + floor information + // receive 4x4 matrix and update tf + recvMessage(sock, sizeof(float) * 20, (char *)cameraPosition); + Eigen::Matrix4d anc2cam; + anc2cam << cameraPosition[0], cameraPosition[4], cameraPosition[8], cameraPosition[12], + cameraPosition[1], cameraPosition[5], cameraPosition[9], cameraPosition[13], + cameraPosition[2], cameraPosition[6], cameraPosition[10], cameraPosition[14], + cameraPosition[3], cameraPosition[7], cameraPosition[11], cameraPosition[15]; + + tf_anchor2camera = EigenMat2tf(anc2cam); + tf_anchor2camera.frame_id_ = std::string("spatialAnchor"); + tf_anchor2camera.child_frame_id_ = std::string("hololens"); + tf_anchor2camera.stamp_ = ros::Time::now(); + // broadcast + tf_br_.sendTransform(tf_anchor2camera); + + // obtain HoloLens height and floor position + holoLensHeight = cameraPosition[19]; + toFloor< + + holo_nav_dash + 1.0.0 + HoloLens Navigation Dashboard. + + David Baumert + + BSD + + https://dev.azure.com/msresearch/Robotics/_git/hololens_navigation2 + + David Baumert + + catkin + geometry_msgs + rospy + diff --git a/linux/holo_nav_dash/requirements.txt b/linux/holo_nav_dash/requirements.txt new file mode 100644 index 0000000..1e4d396 --- /dev/null +++ b/linux/holo_nav_dash/requirements.txt @@ -0,0 +1,3 @@ +flask==1.1.2 +gevents==21.1.2 +gevent-websocket==0.10.1 diff --git a/linux/holo_nav_dash/settings.py b/linux/holo_nav_dash/settings.py new file mode 100644 index 0000000..c50988b --- /dev/null +++ b/linux/holo_nav_dash/settings.py @@ -0,0 +1,34 @@ +# -------------------------------------------------------------------------------------------- +# Copyright (c) Microsoft Corporation. All rights reserved. +# Licensed under the MIT License. +# -------------------------------------------------------------------------------------------- + +import os,sys + +# ----------------------------------------------------------------------------- +# +def initialize(): + global appVersion # application version + global fVerbose # verbose console output + global application # application object + global cwd # current working directory + global numHttpServers + global threadIOLoop + + if (os.name == 'nt'): + os.system('color') # needed on windows platforms to support terminal colors + + appVersion = 'v1.00.0102' + fVerbose = False + application = None + + cwd = os.getcwd() + + # If we're in the "src" directory, use the parent directory as the base path + # for files to make specifying paths a little easier for the user + if (cwd[-4:] == '\\src') or (cwd[-4:] == '/src'): + cwd = cwd[0:-4] + + numHttpServers = 0 + threadIOLoop = None + diff --git a/linux/holo_nav_dash/static/images/Logo_RobotHandshake.png b/linux/holo_nav_dash/static/images/Logo_RobotHandshake.png new file mode 100644 index 0000000000000000000000000000000000000000..c407ecff163f1823c33fcecae485f54c32950e35 GIT binary patch literal 59580 zcmeFY^;eZq*9A&<98$Wwq`SKt>6UIdlpt|Hx?4gT2_>YvTOD(7uy z4R!Kxr_pzEvxDR1<`EI)77*p;qu~)0<>3_-5E}V4&;kdy$DkrFqaR>#)QxFIXqbC# z=}jOHd8Mr_uN@-`A=D`qjywA#Jo~oaUjWC&{kCxErSV42o(pvG``YYF4I7K-w>h6{ z+V}8F8+paNP)5|`mH6r4X(JcI;?NM%P}#YmDhc5s z$&}5n%?E0{|L9TW+_Snozv`=Ds2Dnn`fX#jk`({L8Fo~0^6rez;7EVe`#gs>CKSPv zsL}LMTD0wjq7`X~JQ)p*w8h@>f&o9_g$?Xcma7;(wRmvk4XWaxVjENLu>xc$R=PQy z291D*qo+O96iVM(TON1(2^)`$PK+r*Ie|P=-XA<|^FL3+>WszG3l@(aNz8rAEh-`! zz_#{=CdL-#j3~39;exlcCLfC6_G}+zdS*QTj{DOVo^(q${g~7nmR^JW(lu16{eaEW zYaH-Qei44s2yw`ej12hh1H>kUd6i>7uD?!|oJMfXTT&6^S?VFM#}ox$J%uE{P!$a- z${Lgu%8L;xQI{hdT>s}Cm@*J0xUVR%%BWvHW|w#QT&AA}AOrMaj!9eWZFs%g-@EoT zb@Xfauwd@hv5|D(v5n2Xn##K^qoq*N2+J1kM#b0#Q?RZD9nHauYD-j#K!(Df zwgOSf1J&@3XO@(5X^+Zu2fR%C$immzwfVnJkA9h*{GSnWZM}{T_O~$iNn{`fPm4#1 z5i_afNQ`t`ranRAI+x&L$)w&tUid9?t>~+VECrRffxWL_ti8U#DYHeA(MJKVLyE>F zHM({m=8jAF$S3Wi?}vIM*;w9PlX(m^y6;Am@wBStfK?LclcU*KcI3sV$z^LqBWmav z?uE8W&diDBBxUx^uT54mRMvjf^nag(t41VV z1yL2YsL%N!&+_m+u7~RkGGkMVu7rASqV;kodeqyaIYrUoSoW3b8ZLUbR^9r&p=+MT zM!&)g3SOz02~!qTgvcX51whd3+7Qu~&116?xy)1_X5LPTIGo6{GYT>RaY@)A$a>6}^ZCz{@MpH#iwWRJX^ z-V~3xBRV?xz*t;yeVn#n91v1N;5gaIU)VB&`LP=5?#)!JdI43>OvNGLZ}X2oTVu{y zy1eGd3Q;j|kaUPZwj1IK?u@+KLR+)%XOEoc*hbJB(@KWx(4&A*1S9LFP}b98rjT{! z5!3|T@3kdYZk=6>N;&_7Q+Hc?bALFh>U`euN_3x#wP;fsav25=)K%+@u9hd--E_!> z;kxhSa=(ff{^xAU@YmOL^c2kx@03P1i`e5nl9iB$9+E zMrr=S|HAu%)S;v?ixAS;ZmR3Z_FPyzT0>3EtWMuE>M~>D$4|#=wU3wxC_#hwSXrkA ztFv>nMlbxgbYH`F1(N2nEew}!(UW=Blq}#&j&7W@`^Wl_L9#s>)Az08T zSmwNR;GgEff(Ul`7~Alt9g>?@p%YlXs|g=d=FqRV>>}Nq((nGNcbRn8&DEhqA=bs% zPSFe9oSf^1_VuML8~B;x9vtuA|57~uR-;5XUWZ2~OCaHMw9Q(Y?p1*7h4%EO*lky2 zUJUg+zos;9<6aglzw3Q{@k(|Qm6jqeo!*Ko(6+iv_x;14dqG9!==YsVldOfy9Zi8? zhOY>#_ZHf#@Dh>=kD);b#hI`#eX zH`FvA^|3GURhD}V7WYAPT*$QsksiXA4_@)v8Ww7(sFr@;(x<~Kv-wl_oZ`wB`GSL z%dd2r@L{h1J@ha9lTH?~_YalgCZ}`SRfLYw0aeBo`xb0EvDGVf%WPws;Gw!U^q@?R zEjx)*87@inR!#(6^o3Y|Bq8B^eIwLv1i3*JF2tdCJ{}nhMtkz<_!rA1Iiq{h#JlXt zRIF>It{W!gctULZu}*p1P(mHVrvs&%+Etc~7B7I8?-@doqhkO zupgUDT>;$@Pn*H7`2L00$bKS}Mq2%J!NK0G95EKuLQ1ypjQBLXF*^%>QrOrr>V*%) zQC>8NI3Q_SS2V}m@GVcKki%C9G5OHg$`0?lZ=c&P$0w@FogkbQ$mfgRnI&&g zJV77@b#y@RXsbMyyY5jyL%c*bZDsFx|MTpzl;1uaWh3qJI!I!17;)64u~CIOgFE}{ zkNQFeP5#Z9LWHgBZX7k;G*zq#kT{2bbTJH1@h@`h7&``6)xW+s#KEmmSZ~-}!>qUv zEL|eBki3q(%@-bnD=95t<^EdjYfGutwS+9>Dw7bT*@!otKa6i>A`(147J2`YFNY1J z%xYi{jec_p<*XWSW(-J3f`~#cH7?qDSv$4ApmRmlrG&!6Evc_H2D?|M)Wa zJc#$69nIz`=RB*}SxKgoWBuNx0&}^kIbeI=A9GQS%_B|r>W$|*-X#^T{nv%;HMZir zk5(~DGY)AjQ7*0|gr9ThZR0*68{kFa>66EpIC0Xsqpahzps`>D{K~3}9jNEMnkW26 zI#f<8RA{qV6%gLpknY||GP*kYt4Yast+A!+6G)2@wDX0p95E?Z)3TCAv@TjRH`pp{ z?Oj)Jp2>U$Xob}A*l}En`@Yp@Jj$vYRp^V0@cX}{r9)zzbywYLyl^`tdhP)AV8&8eV;R>mo#=1NCNA%P?S)zURu->iX93M7Z2|FGX zJ-i!@z497e8J%k&x(UG1NVMeBUR!UB^WV*)u0Rx&MWkC|?2SHTjadWuY`I`1nW)mL z7$slDVb5u7dty$1^|gjflex^>j|6!^sPhd(VPi)4oh#E~DM_fXoot+7)&^|yvCfhY+ z_JNQRf*R{_o8KxR2irHI3p7lk;8;;W#p=roeMnUom4=Y-Jg&IZ&1xVuPiDeGmfeWk zdia2}&WNDg>wXU2?X`@*2lKzW?wYC5K_TZGhFh1|NaUp6udjCO`D)a=R@d-EUCrt# zOVuHUD6h$5etX^L>I}gp-w+9TC-TK(#hfz|b$i`0D39I{V%- z#;4vp4yDdQ9IUWi%RietP?`eO0>9mHUud5+NQ^{vQc*M&PhWvTQatcBspI}cDk3HU zuh+Y*V}~tLOXQb1jX(SNaGx51Scw(P1*C5~bQi{91CYM$h)$xU-U`}>_rM(fe%$u( zcqd^Qs9$O01ORX>y~BZmH0T;sG%SX38LPZpj3&bDvwu&rt}3Bsf@c|}(Hd>pN zyNRJozq6qD(1C*Xrn2bfJjzBJ_nyj2o%&=)gdbpB4w&s|EOf;140?V0J54SJBYv3- zL>xBUq|P~Cw6Qe&8$9l8Vr-uw?;TCW(PnCM8j02_tIQBi*1XMJvR)Jp3Cc!m27wHi zj^`5~Gd{(kG@|45dXP52kTFAjdeY6Kh;F7XO7K)|ak|L0HFUb$o%igw`;X%n1ej%n zmE06~lG2&};Z2rwOA+n9Z?o3>i})rwVBkz(4+GK;V``pL!reNG8eYWG&PG_jkB;|) z`F2%Ca4rF8d@&vH1_v@E2u>ygMO}7Fy<-Zd1ZUh%(gTaZI-@}ku+O=K`EGGydjxR| zu#?ijWHFZ+8*J-dbPvnrh>L28 zIh$2^&mMJHtKf$cRZC1KX!k{!6O_wLv)a}JV%=$D+(4+YD7mEm)Wwi1X;-mKy+KE6 zNV=+B{0#Hw)%5t_QdQFVWBY{iW~fPH`twS)t3&g_>gTt$gFB>?0m{x?)WxyIrdjom zBy=&tZD}x;=wXbX?(1eYv{8CAi+V=ByfrU{Y`?q_KF2rX)LqkW*pU~d%t5r^VYFxL z>ex~PDfA0l%O*{R{=>!B-iihaMlJuk*3iFF06+-Bf#l)65UME@i55y!j$*^eNtsCf z?%O$NbPvlF>n)c%+QsJam)N-k!t{uYp_3GVJ=kyDP)#y%{xetaFxZ9V#giIp4hy2s zpX#3dI&YkOj6IYEf`<_He1ZW)4mzd+gk3mfzb{WjE9A-~B-yJ()JB=Y29)#8OSEy&j-J(pc=eoDD*TInciM*zoy3n5j)Taff!LQd`XEA? z5ocW-<651^wl39v4BCrDr3gjG5*Y`MB=hosc6SShBjI=NO4pt*AR;Tr8neE0SN##= zc#`)0eDL}GHQfvav5&=&G29(uzTjNbj8Bs;W#WTj zHJr{)Mu@>&Bgqvmjb@i-2GrOx@=tL(l;ViV%6wVK{*9N)OEJk(wEkglK8~S{E7shu z6v+_J!s5@_pVK!`ngnI<5AQBAm4+42_YyMpGEd{SVWpi*D}+=?I!NH8ykiWH4}RC1 zJz{zp03b`rJV&JNSs-QoW*fbh7=ExYtL?E>O6uhYky}I8mYjBsUZT3n{=)Ubaba9>wf6938x-%&xKLW z{*j_R-71OQbqGGisc8xsT~cD3jtYlpM0EF>$!QoB|ImKFBx{T})NH4RO0D$`3BCqd zpN$~LTy)E^tbM;&oPI+-zMznRdm^1Nv(^5_=a4v@Tc(G7pLP4A+=}Rv^f@j2KH^j= zDH|45xPY~T3U(TK`7)Gx0LG6BtXipG=gxMY753g!-vvcLmf%4!urNyPK)*pvV~W#N z$c+doYBki9Y+sBYdsJ&aA)O#p*tZwlhYWX})80*Y`$frMALFTl^Kq7iEd&2tc&rO_ z^RAAr;mlNI2ptxqg(kacZfXOQ=UdwWvs=F58Gr>-gK5Mk{hzC1iS#KA*o1) z^__>mj?E}KXcw$JvIp^n@BXy~twC9k#HIZsJAK0dGJ=Vq1kOCfTzKElg@ayNsA+Mg!AyLun=0@$ zcC^9`>lD4DlcA(jFWdOkyh$13g)QPD^3i zfbSwrxA}ijK>fy|ZiK_Dn*sh=oCa}5fxw_I-7=_IH@~NGSr6%CA@tx%w`^?>nx+3S z2;7J@8_Ihrg5pIC`f8tvt0&ZJ%MRy*CK^#5oQ0;SE62Lo&8WmV#YJH1h8KsQ8TY>) z(OTL$Y_kYaN1E9!CtC&;&4&Exxy6lH?Dh*D4>6PU@oWYLWf z-}$4cQj8l{oU#~3pOSS`GK{qh>Zsvkt|Drda%`Zh&SzUt8(KgB+we&{n*|$HY;MkS zY{Lo}YH`kT_r4@@<#iTJ3KXXAu#>UeJ2c&>OBijK&RMzjbHP=dPZBJ$W%{NWbeZBQ z#q-~mp`anpsDlkict>=zS;U4#JF_4VXLPfTX0a8_&kCGZc(sJ*W+Aq_> z042}CG$$t=c4X8(CErL%k7C}Ai`g~#0ZV783b|3*I{KqYv7OZuR>0(?-P*jn zsa>y}c$-xXQWL35pKUqzkR*7OWw=ShegZ%RdQ)FG93 zsM^)5)lg_UFI?Z)w`g`Pe(Xb!n~{G%BIOd_;tbMqRlxTs$bYNkwn7A6g}_h%NrbdQ zN|Q*TD6QN}LnuJIi`gVL`d;{KX9-7^yXUq_M^Cimby!5o(n zqy+J*?|4QB=NNyusm8s%bT1DV#o;Oncd%-yHvdI~Qk&!;!fLFXqnt z^LuQQh4T=S7V@2gSQWhfhW!`l?;2LkQT*^;qEs@td*_uLWTpsNZ! z=^JjS`Ka#MjJCm%i1Qhqj^+udV9OP!n1(E?V+L&T6U?aBICRI5Nus-u)T1rYAtB5f1pag(Sk!ZZ)x>sj?d*=Y}hIjq`ME4r`TRH440#>v-tX zNb`AuKNT8LNM5SG79npm?o;M}6K(jQX20br2hekth6TBR_`4)GMZh^8Uq@>h+>;9K)jk?Q zIdi5R_CXm^b$`k{AIMyuP0!@vKA=!bY>^M+y(>psv^X zq6B7B1BVHKgdWn<(cM{MP~t2{g#Wz6)caic=HFoY=UCNd2SWo=UBq>UU<=S}t^&xi zKM0@B$+$@*YlmuyFho0sx!n;`v|26m4QZ)q=<>Ou@T!U@E9Bn4-yt*RWXm5fpd5ewkAju1#3YJw9-Byez5JV(*uK%7k!TC- zKPWonrC0yJ<4wTr9H&|&4!Ke*N(Q)~3G?L1=AzQ0pViUx@}7VcO-#3R^VYzr1vctI zPccnbYblh~pDBf1P0vsU@14$cb#buqoka5I#aPm*`GZ$Ri471SdVrWZ|NPkmW?3ub%UIjpNFNt7(37Y1!5b-cDSJ9;m(x{TQTN}5b(4?83=LHiyWUJ2GD|E+R zz^qR-_}QX?qj9q|HscWv(Crh#PhmikE*lC z73N~H{mQgS%o_Ej{EIX9R9l~66X%+S|hdlP^qOoroK*< z#dQg%_vo_ips1T9`Sm7LHR8QHwgB>6ht+*4+go+h1&ShE!Ozo>Sfa0MRjXd&=0nJ7 z_}z1gqNTd;C5)PCI${^isQF{kU+s<@yNvb0oChz%_Roi-%Rd$;e3M_)_>li|DO9tg zQ^Z}KEjW0FqU*f=0zv8bD1(A=zRt8a?tQrXB(l26i!)T-5_t6n2UraQFXvZ$bBP_I zMi`>JqJ4iSoo~OJelCH<_0Z1<-Vzz?{!hhYVG-bqtlqL5o?*~>kziz1wUz#?-e8`P zOLI_g>$5&9l*vH7Z;F_X_?gi!lKY2fElbm1%K@w~lPM9^{z}cpuuAZ--=>hT&rt>W z=(X>B<`djJbB1d%dOx#h4i~uaeO7riDu+GSome{rbaT#_$(XQu@U6pp9~cFgNiLpu z(Z|3?6viQXz#%DpHN}~~(LfS9q0Stg8CS>SOxtTy4Awc-qY&1>H7{Sqhfnvb_k5=I zz#bpgZY~-4al%D}oA_>r5gftFI zxKhvz>+1YROFCH;f8mb%@e5moYFBADK=5xPW}vznwf~xfrseZy+1GzsP_&FVmmnTw zHU=84x|$g^rFdqN!RJuR`-gpuHxb#H=G9?*ps=r&3^nYnJuz0>MrtmeXg1G4=-?kE zVb`a6g*LV?%piJvxU!`a}CC7^0cc&L=7VWucigLMTp7E)s zxf&6rTEC-&0v`iO8A?l<(vu*Y9X{J&ZSEYAcA8p7Bld$x+?TaWc8oVJ`b~(Fq5$~^ z_+L|#%ykCVuo_lSU9HB5yne(W+CTnOD4c=kqY3l=KU{d|8N*^eBmkDq8!WNttsj{u z#AD)zxn%Vt3FL8MJ%+07p$CnwQ?eZXLl;3Hl?n4hB!xYgL~HIj05GB`S0 zl_Tfq9MQ&3ercAzUAC%m+t2WeSm-DQ);9r96>7b|#GI~qfPsf^+d(S%?%$@{3=gal zSD(DLKe6B?<1k(98-{S%pL?HFG<3D8S_Y@0FQ^7Do4ouzW+V=Vrt&htZqHZkfu`GdRfEllcHr%e%8t?qie1BoBA{$;WPp<-9QVnA!XHhY7OtJn8zb;Sqh zQ;aH!UF=Fd9BVZ(qsZ&Ai0!$6AN?BTqTP|vWKF=#k{NGcf3{2oy=qSAZC`CkErTD= z_YfBvE2t=|#yCOK{beBh_C>!!Br?H^Fd5$%44t$R{yyc1DnW1bm!a3jNq$n4ByhM{ zlt|U@d&)7^-_bR1g|k}w=?$v@Tvr!n5$f*JE%8%n%`g=DbFq^$H!-$1wYRuj%*dj0I)pwzU5(N=ohJZQ z_bbto>--T<{tZ|Jd~NrLL62tZ8_y4RgtRwh#-^>7@V3;q;yP6BzjC+FC2@O{4JViQ zlNA-GxB|RWo>|c5Pb1;06L4oU_8YLK6BCI08V{HxdY~?G zP>`SME2&<;Yxj;!`Z(BNrh#UIR*n5^bB;}yRV{z)x^4DwuZ3X7_3nz@>Q3oCZVczD zq~_F~BtnWoaLr(*EZokws8UYFMe!+}_waREUwE&}+BVu&QBe<<|es4<@n*<-g9SJB2mp8j7vuIbee zX0b~b4RI_ZGE_^i)n$~z}%x=W?i z96ls)xZ;xUMj2d%ELkzTq9T>}8TsdVU5h%R0af41f#C$5jHUIyo({b>>8G%e(hg!r!e$0tMztl4K_3x1q`Af=GI)$<!TKjva)=rx-8JP>Bc(^jhFCGS|1sFL(wn9+YnmM zgX-m7)?}9Q0DI)0H38PG>LQiKe_b17AevJCtaI3q+2{h^_unl~d6s>^ra?ubF}K8h zp=Tn>lRRz~7R6BuWnCi%Zm3B295=qGJ)N!x42shn_17l>$Qoqoo_aPfn3Rk~PpW06 zxUhjX`(b-6?j<7Wn;f976m;J%U1WwDGH@xy08s8zqTBEamAC#WEr`0bH`4F7paJAp z%@LVCzb5}(0i(t8ZGHAlmM|Bf6}~)3*;fIg)Z|?XvbORC@fy&bVPGp87Yt79nG#e!*0no7- zs-EWfoor6uZI)lm=+O~HcZx$C5I|b@d@UABM1<Z6d5U(4P*>w!uE{ImzYb*|H`3SK6ki(o*lr|=I^F& z400F`xr1{c{lE0A09TdjNt~|tp}aAxvq@Fat6u%M;X>+r38I?t3mALf@f;j|0a>s8 zs~cI-mgoN?3Fc-yb4^6aq&^4zRn!xCcry_ekuQ12Nl5WTPHgc)&FGJ@vlcYWv~=QD zk^vLOAR=NS{EzZueD2A5g)RJ%Q^IPe$=1(3X)c_txfx(iZ0Eavb5MaHYCqz+hAPPs z{4$fH0Iir5KVNd!jYBGK86NB@l2H%2*nW#}=~C*u@|a8LV%o$RF#!yV<&XL0{w0|x z_h?3aI}qz!-4gnZer5cQC!?~|^&x&aHI&LHhd45xPMNel#|^wcYk|75V&ri0_+5YT zLac#8gc|Snkn&kV*u~x6(?p23U)p zs7r9~vABaQlQXqR2Yir(&Zd{CUcfV8Bz56YQ*e~d^7*NGesr&1_BqC;t?EY{AzH_x zM5Cz+`j|T@6=sFc+Fn75-z9F%SqVSG$jn9Eq>a<;A@b&@`{DjEGOEZqvlp-os)%x& z3aUDP`DH1^rsek}_J^lc;zc8VjXLzQWj^y%w%KDi4#ySww-1dOEA5O$I^b39E?SsK zUG1|%#iit2NHz14b~_SI)kGaAn+`E83zP_gmWi5^DFz4F#~XiZdSdf>zH}VvuoA=n z5_qdW+Mo%Q}kM-TDvSo@$1+Ueoe^QtE8z7N;cFkB2phr1@@G|k&Vyu-O;cvuzV1alT35q$h-QgLGEdT7Aa*nu1U98!L#8WR2Av{0pO*869Xgep`Ec zGG;Cb@r|_Cl+>$}%bD)1N{{YT{w#hU8OX5AMpO;LT(M`xJy(SV?e{T(vQ%jimbSD}@EIZoH^kZ`K4uec z#{t_4PsY!x=9LP!JxY6^Pa_%8heHf|@7?id33P1WU}#taBChSP(iP($Xq1A*U#mHP zA$ugM%6#n8wcx2&auQZT)P;~z|8i@PyyWlOWuAV3cD_F7Q^lvy8~7zD=|%uZB5&}0 zZe*X7f3pHAnVTUO^YuFxT=i_b;`H`YmG2wMRG(yl``1O#L$>e%t%4uauaNg>;Qq_= zF)S0AkyUivF7dM?$_^VCUilXmRNwGXewT8GS|I}!S%z>foCPo*z2@F%E*>;-JBt63 zg(WDLVp@QKF;;isUrk6M`8mz5{bj+=q%2_g`y>q~W&EnQUD$%wY)lV052-`=#TR`v z94c%`;3{G)Sz^hko~OAEAc`V}Q1wEsR%hQEm!Xh6$$_xfz6e#;5|~UM0z`fi&{oZ^ zf5p&63_1AMUzM6`Vv}WT`wX@5uMRMa&kRPZc_P%;TaOL+8s%NDlg=}yS;2c=N|F>1UHY$K;hNK zVElmEd^ls%B{CFKCIit>H$OwnWV^NU!6@7S|Jy0wO{$AB9g2Qc0y9`&gl5eg`?ycy07t(S)r zR?3KC^)xcVNFcLWuGT-f=`}-Modhztg$H<^9mC&5zu-ikR13! zv#^%RRi!MxTK8WjTqztA@MZ5aJ0EcAUadU$I+hbDWa*%W7e{F8(8}S}8xWkqW_3K| z>MFb&@NeE_CyU$KZFdpb%H7LJsmea!;%^q3LA{K=UcO*wo$Zh1jy>6PM;zyM`EGOb zS8LYEmvgDNX3|0BeLhvs>5@ua@*jWMO!PV0J~1?gXOyONOaTXcjV&Wd!7ukMP&29W$@DT_Krw8?@RJhZg)pRwdinV3uB&Q`C>*8vt z15Lhy%u40wb#G`?!+WrqOa4;$J7vBaWCE$FKASu3j}nQ?2S&BWsKr+OevZX4MEDU~ zz@`HaeItRRgrcwPRw{R^{RuzH{I*^Ck_pzMCp1A9HU$g`ZNh#6fYdk^%K`E<*(2>e zG0q9Fw9+{YL1u_^Y5Sv+h5jfTBQ1Q+`=$l1Lk?;@3(km}FmgBL&|4j0y{~w=luM2b zRk@6*64v_Wb1o%6ET!zLv8-^HmH+jJZ;Rj*{`BB$3I=4yNuk-b-M$5JRfE+4283Vp zxj-0@-s7|${)Q2GRl$e3k8uhS)X*Z`x6kg7&c_5uS8>;l?X3`^X(&MCwB3Xyr*_+5 zNXH#kCoI131C>{{WGbTd){IFoX!Gp%;!@LxszY`)WTu%J46<4EbCZpqt;s;y-jTl* zD6n%PIeKQ#gEaT{ls*LWLMGdj1+?C7xe@7i5*qh9z(1bw?IT<%v1?C_^eV8nA$^UC zC=JPug4}m#t$WtGBKz;+uf^ujb(_?THIXyTTU}T=bEV;;;|l9`7*?wdeqD)XQsPYH z{yRpuUI4809d?Lx5!-uNj01>oHT6pIom&6X04t$UnjniEgQ`~Ljd-dw#hpnd<{ng5gybhWri9V_0e znQ%^zqd#prsxhn$tbhoF>6GALDkrWa@3*A$1YkWAPQD0=A(Z#u&T2$PFAL}r2L0m^ zXmO;izm7jwyFTB?vYG=*gkuyExvw}6tnNj~uLC?h+@en{I-(h$(_17G( z97y*AwtfYQUndCq#A!n+Y)ayBn-f56hojDid-thC(`%t-g$coVMBqferRsq+5rV{w zU*s_eA1=}W#0SuNp6~aBCPn(^qccb*AFjT=tq_HH;&ZBE_odm=ce-x8|GRqmHXR6v zKy4lHR5@b9s|nS3FX8t$9x#V=f79u7BmABC{rCKKyFWjl0^ZfIHDGT_Z77MD-`o)) z#Gx;BvECkg3sutrZIW~=M1B|~Nd7+6@JnBtDr{kBr~!V4CHLNc*G{><)1)QOh3!rY zGiLb)R_7Nd#l*wU&D5{u8cSP;r3D4fjy@IX(36KcSCTje$XUih{#UV94x1bac35v~ z6!0R+g0-`_AHA$b{Yl4PNRL_uWv$vurIs_yrl6BReW^Ev3N@ve^<$$Nc&+69e35@@`GV+X$1e2*fAObqohWO(P>6Qz^KBScbBrs;$ko#;sIunG<75 z*SJ{#wCks2@gWnqvQW%FvHaq}>y1$t zQTU|B0H0=&)Lwpxs8`awaZ4|OL2#Pogv8KCv0flS0peG$6&C?FQuV{(`x-fvg^1gP zhIhnmH{?^~MS(IeCDs`hT@`h%g4tfLSA>$!$7gLp<`i;bSebM4szXY)I8V-o>ejZ3 zohE5w$0`}B*U2Q>oBAQG`CTgUNS_%Ubg4pe_sw;`&dI zzK;$30tDHghFV~DjLh!Sso%m_I{fn~D)r3|MpM@>!H6-Y$}t(v0thrExTBwm1<*Xo6da%dDPuz@bk8uh=r-svx#lOv(j&!x zGMMj7MZHpfj?G0KAaWH;`YVdSJ%Pra z>;PI5TUXTHmr*nmFz^mzEWfawX&O>43T2{I;YU1%>SCr5-v#@LJ-Zek=*KF=Q~qrixi)Dj|rOiRF1rWl{r7Wx<6n2ZC4@N{hSy$5lF zb8u!7*rM$$t+IL&8w}e)1NO;^@C9y@-}tcZLyRXWOYTy?7d!$UnR}l-FWL+=T$NzJ z%BN#&GSR3%5a)fbH&hz35TgDP^)4-1p|)EwnE6N-4DU?x#?fxKGc&#}n6Snvz`r0_ zvxD_8KAex+6juQx;Ii+?@9jZ?Aj<$uw2Pe&=F#VmB9gMehY;5RG3lG=yfW-yjO+C; zQqE_Eje!oZ!)Yu{aQrHX2EN!Y=@@CAYaCqRfmL3j4q;2n_Z_p(@`Sf%X42XUUaTKBxY(5;&1?NF4D`$iulV1@Fb zBOIOQjyKK_P3Z3*=_sF9D5*d5bf(jmlW1r2J8|~|=7O>x7xA1PQ4O!rzoj(T4=FjB zt#OE85G7eW^#vI4k}?)l>nj}yqQ_b%-S6U}(n#^*OXMnk8B!e{3v8%Teb(Kp_o88n zb9tOy{HA_=1(b-1P*1C)vFH-m_KxCIq+!C1N>lRE3~T9b1!GUluZa{i4J;OMYOM{` zHO6AwbwD8ChAGW8h=2sYYfc2!4Etil>-Du)-JDt=IL&zY@A#5w-U|7ibVlgA44h~9 zPo0z%t`X6Eioz%6<+t^Q?=nAecDU-^B1pzd=t&Wd(uaMZz*b{QqBv`5qTzL?q$xDC zFwjd$n4kD?rU^zMqm=E&_g{BQY{8#$cT6I2n{!JYAMbznqFZydgZ6ERo&LwvobApm2+ zuEr)BoJ%#sHR@NfoOSa>SbUa&YGk8y@(Tk7hlGlTU>PA$npLM_gc7XC&K@X!iptIx zYgN*mS$UF4M>hH_fd{=MM-2gAhQ%4RHrh?8kXVN;s;}lbe$tT)#6`Nf_yr(}KdUQ( z`H#Men|xD=Fo{Jm@nuA2^Kd{$p&`Ezv}ViqGO2gT1$rj12>ivx0UOf&Gp01H8Hm8c48)^gV=Jx5FUGFk$@ z0lUTrAvA=~QIr7003BnPnJK+ub|B9`Y0mlu!l*oY6}-`Bi7nH)h*WsKd* zO{_MmzIwyW)IAZ{@$+Icq(!Hjn~loY(hSx_@1o6}`_L7D#|KBB-1(;;*IIo{p3t)^ z{53ye{`j$#emO&x`hjJ)i6t~ILTP99Wwq8!Y4Pi!+pIrePG**uXAaCSmqAZ}$>Q?k zS7>&LK7Yo{$H%aqagKm&91=(`31moB+pRJa<=2;UnW`bv%{{ExUts75|4Uk2xt0Hx zTzH%}p0qbBn?S(OA@pY!byVyLu%PNi+CI+}d*W}ST}lk61BOql!0Aazz6Py-iT*)T z5ns}iX++kjp#*z(mY+k;|GlPo{Q_DWemxVpjUKnVTxJt-Dnv&SAG4q=qm7lOoy?j`Jtkdv+B_ML!^nE4RUNUh^! zUNrre~4>^BS9N?i* zvhfejFO~V7Ql(x|dierbXHCi|@2r?j93e)HJ~+PX;G_swQv8Bfyx-^psDol*#>Sf zp!d-xW+^!_Q08aw`DLit-{K7FPxaiQoPIy#{$uqs)YV5<-y{7y{(L{m2eHKYGt>64 zSFSJd6disw@3tY71+Si^@bc0m!tExo-f`)UdFgGzWW~rwJf}|vA-y1ignYDwv^w5! z_bE9YiMMMqY$zoU-xCr8Z{(#+zb6kU@`}c5$RT5}UjI$lS@Ilkt77SsS4VbpXVkng zIRDGh5UnBB2t}@cFT@Y&Aah+Scp@1+5TzWu;BIo=X)E3n6fuoz!z-o{~{6*x6mc#$)_*X{YWDK+PUFfY%q;&mmi{% zwg4xcd~UD;8LF`Q9>q3p=T`@tZT2xFB$_jkrxSm2C)hY5BIL8CC>2keR;6$#+J-%F zS9da6yvKZeIX{rx5!7L&=uX(j!{~avGtW)4z)N#(G~s!Mbw+l3ia6>|ED;rYR1nwP)XX#{SVs{j%E`qzf(vEUi56~lj7fTtb7*C#(H zZOjrAOLLFsYpQD$FG0mAkgV5#<2%>|YcDD{v%)Y|Ozp%+LUDTX|Di_VS*5F+R>T?x zZW|zryMfj)xCwrlJIC*Ntoa)P%Xk0=!*U3!HmXPG*Vz9zm;)z#b8Azo_(Z^tT@3l? z=lyN{q_t(w<>bV){QT%|`w6K%Ic>~ukisOF33M~K<~GH{7U25N1`Efvh)}X%;4}Ou zIh!kQV2lBym5MGb6(8Q6#W}g~bKBFkGv{Q|;Hq#v4MhORrGUdLZs7jc8u*O^s%Em1 z6d|IzhFWkCQea_5%XF864EMKTU(QY)VGaur()Q&?(4w*mUNCw6OZZk+%U}(W!!|CH zJNlL?Z|q!XV}{6!y~NGPPcx_Q3}B5Ko*B1>AYmQoY-h*?gZ=#yl}7^jWMzcgep^yj({qkEu%Q z9awbI;xjuL2rXDNXt3L#+Ad+9x1TTtX)=EK$ouiXR2dU(VYQ%@mv<(fwWdzkA`AN# zgH7LOLPC`L=V&r*c)V7D0a?W;VJ-!pB}`7C^MmmP%pZAo#r22BYc(P>+a>a5Pq%tA z*NQNE4H5|_GpaqjU1f2pb(V_9Uuyb~oA;+IN?@sjD+pHXmg z2ey|t;rmndT6#}MRC0nrDhIxf13h*;+GTSxD=3(_da+mzUx!)ug(PXhHn)(M(bat= z<5^-^)UoE;x0+B1%fJ3v2DFO6o4Hwnuodq$8bbwc5#k5)@#(!5VOzn}7$kY)8;GW4 zq95Fn@i8++tl<)O2y&?ot`>9fMb@TVoNR4N{UdlqD`FxUqglBSHSp#)qL46%M&|nt>ORS>Mz)${JuAC zn4yO5PC>enlFgH`QEBDihQh{FPLRk5n7^ zN>8fG>y1SJqKH&aWZbNQ`+=NoqvB-nbMU90AOUsp@mcpP=N0`&dgO9BG5NxdR33zh z4M9*#_)s^vHv)>BStTKX&wH zN$RANHGFl};F8}^e%4^9g&!C`xAG;y0wOEpz<}^pB=_a3Nk_9#eIC)yo2T)m(zA^@ zb$8Ey2YhbpepF;UUKwLNE}%Fk3cQ!d3wYs%aKe8YfS7A;2jvUsg>-+!+0l>Z|MQ=I z+FC^Qbflb{&c&Wolm~_^wk4|@Qo#-TEIV^mZH>ozDW@bVM!r=yh0YdGML`f92wDd8N>bJw z(I)$UsnLeE%_q6Kvrc!Q$o}u+3KgQxx_eo6N-p+ljn##!8juY8tth?Ib^_w5%M}7>pdp5f8ya`wHeQfBbZ&3`i%2-UJ z`)K3#Px%}@9S3BSE#iSS<2fxnvr&ny(iF)K99HfG+*m{HxrnrHLC5Y>?c} zO;A&2T9J-ZwCJ;1EiX=I8Ua{jXa7F~lTy_bKp>ECzOqCyb&tH2wBDD4Zv0)POoTDAYvKp9l6_QtAq<(KF znZYtqJD)y8*`vQx-sEVw;PTnGNuEolm96lZYkEsYp9lLsMbhz`YYJPhc>L742#N5~ z1TnnaeltQsQjY)MVLl^SF$P}hwwXtB>u$mxAG-hy=vv*uKOUwR%SD6s4^MsSKu^G! z&w-sVWHPw&7HxRdR52Nb)&U$Xd&KUU*M(8o*Y~ z{*%}OmnfPmBwgn~<9)4+4Sh&=Z1*I1H+ZQ1vVJG0OEA$FN5AUxx>z)S%5_omBEoln>NIcq;s&2jl zf`YHD3W&p*3vY8-_@+n1o~8v`S`J_}Gvb4r3~2lcjtt{*7j%jW0`a7vyN? zh-OQQh$Jpbm<5RDnHFX8gY2yzvjh!a=|+t>WfUmACsokDT_b z)X@yo(Vlu{J4~usXEgC({T_VJe`JrQ#iYaYI5hNcVwy^!?=B}y;^6}p_{7+~CFCM& zu(D?yqliJd|6gwGp*;o3bH4n2Wot#yzM!6F$ESj#!iv%EQI(*0kS+aJO*J@qfJ-f? z{=h(gi9_@A=dY2v7gI|=(x_60Sk&=kU za>i@%vl?*38jaivZAq2}!ZW!f`7!5SW;g+pFDOIx)E6(6_EO?Erg(aMj%sq>iMv*A z>5~ZyJJ>qKP4rCEM$aIu$bn<+C?%fL;`;JnX{?K~^iwDyr=PG?`Z}myB@4u!-gYq% zYfDq1#Lm02fQElq{dof~*^Y(KZ867)O1V!p8vrnkjEy~B@P5l2lY0O_K${q9N02+U z)dy7lWi?Dm_Ymb1aBqB1OOEH1&j((T-PsJ^6)AEW(_&a?-qmOeNNg8Iy!qOhEjNSk z8T$;Pi|qJ)RZ_NP4Idu2*oU1hAL)%sgxZ=nG#kB%umQP7(m{KJzjP9;kDg;p$`U{2 zKYMFUvG)@QJzf{+_%$CM6G#n#r25);*s0BR%O9^LImF>$K}HSDpuOFT4&W&AH17h& zSwZew7QjKHri3@Te?xgGt@?~UdEcTTQ7(!C-h@pIS9w4GeZ5pzmf54**2C+j$yxVr z=^b1XSN_tEqhgxgoJ(k%y?I|VN=Qp+FCB7SSQJqt*VRfT7m+|Z`0DDa=iyL8zN2O7 zQv89;4TP=2UVGqtv={&#+s6P?s08pz3^RQpc6$f!yd5=5n+*QMLz4W(rTn+|shtQO zxY9X-OY0Vb8@;9z7G4{*@!j8rDkM1z;pJrHk;zVyYjL^27lzbQIqFW}7Dd%@D}TjF zke0-Mj^7^j6J)mE&n!OsX3Dc1E*TjIlG@_OcXVky%HYTXIV0QGSLz5#krx{6@J2(M z!~K82ukrpJ&Ppo}2|{?fEjp1+kW5dl)He$sU>wZCRoW`vt(1V7tOwB4Sg2(_(}RDX ziLisXOVHI1N0^xZMKamu)*hiE%cB_fE;E{eGZezpzh!_$z6RyX3 zXS%l`9=-$Cy~v(@po0id2XbuTLO%R~SsigW*CH9TtcxumIUh3v%1|S);{p%qMKy@)(|~prh*>cr99V_~v!c1$o}06^SO9owg~_(CgqkTkWJXAcoja zK0wHHKaxr_RH3@PsYxs2{C-YhAl}KQ|E#Hy@s+@?1fAlz&!>u>G{KMS6!&tCoc~f7 zi(b9Ynpi9!<{bY#lZs6(HsW){6Xc>cy3c-wm>XSk9x;|1e?>^+)T+&F9SK}fO)YO1 zT4n)t;1U~$Y*nav^ZZ9zOWYB|V%x`55l+=_m@ez@d%~M=Ko`+W#INSoJsLMfUNDiy|`$06Wj$r7;d|$!d(55d{szrH!1i;c^I_xDWEOY= zzIl%n7M3nNb%yn8v;o2`sQ)@|C zYxbQZWW~C%-lWsA`W@3R+Th?Z?wdHRL8zPovPm01YpcJs{X@{5@1Ku;&BI~f znN9lM6a$}1X8@`+;~lb2p@0Jw=zq$Xay?Z5DzlcR(;PxZeBn$D%IM#yls|h)brKu? zNkvD|hA|*qZLdXHIy5Tx1mpmUfGL;pmw+*0o3JRZEKt zlXxQ(+F$5FjK%ZG9Rzr#OEytBDiL1SJ z#)qQtnWrMz&V74GaIWXuF>qcpdrYF|{(XYmtc`YvHswI0qjY3td`a?2$vl4dK$bxr zcY3cU6B3Hu|L_yyPG*2p@)>|`l23=#Py36`KH4MjCYileW$FJngj@Vl`Zym~F4;ty zai(!8Lvr=yTs5AODeP}Y^|U&6_TSCTz#7-|f*J&3EsvY`4F@3&)$k*y5!wzh{wG>J zRci}y=wVE@@&;enwkaVS#S4P2H&bXOE57n zQ2Y6~)F-j^E4`f1YE*TfFdg(3qrodVw_It@jx5MWonypBTS#@zW9CH!K~|v4#d9^z zSVVAD>n^<9;)FT;{%ihDnC2(B0F~5)(nC;fNI9XQgaF$aY$l3=hE{}Qsw|B0_PH5w zrr%tqms8%h2>{{xC`(pur&AiK6Q5e_N9D>J<~!#=<|!+bT>rOS4M~!>%af= z%Qy-$&7h4q^H{4}vn@V@Qk{d248MIXst6L!8Mx6!E1IZM*2A1L5kB)iLZdi%Z9JbX z%H-hh4V55&{KlZ0Wa0#byE>R9E&MD%r8E8PeJ)_R0MS7HcUDo~7l=Il(iS@?hJav`mUgzC#H^9q_kY0i+e6@8NvKE`~B8$%OTyX6k z#Qh;KgDH-+KIa?Wu^E(5RcRdEc6EB?;i(zM?^2juM#*xTpGAsMS5^;?V#bb}<++KwM$7#>ZSSJmS$(r_C(xUd_7ab$~Q4e_t;F=8_Rlv1f1BeO2 zGcsC*V5fX(kAPm_u|=|01oVp^u(1h=vCo3=sf1gBMH;+Irb8}D>)+>`+ihKn$=7n& zt?P*8bOH&s3qi>~)w=#rT*^&C2A!Vz3)At9>n=dBwUVV_D-)q3dX83apTP@!ge0@K zg;n*L2m81qlL2A@Px*O)u@SxSueWF8H&6aCibk?PE)D$_{(A!snA5Zc zwP$~997yorhK2-$c*jhG zGFsw)6jixeli2xF+JE`0@iAmHYRC*$w_W&EUsQcZ#%QG35NE9KLqt7IOX7`sh=u z6^hkCU3^`u0^QO_WAvX_kci!@3!u;C)Yke$dm>f51^VGNIDLt-LM~i;jLrM{aM4+g zHJV$(^i!n4D(YkIbJy|H2Es;+6@fYzM^ex`3upkom<_se(h8k*Wo(4gygzu=(YZoP zBkmF!dK%1m?*A@<<87E0R6x?I;N8U^wE6Lqbb_-e;s5ANxyH=NRHsivdyo`3kxFsZ z@u*KzsYV|GZ&<+Y#1u!!Ar~V|SSDEcr@{PrVPF~Gg%%s2cL7|JX+W2$=+%knjU~}S zQ|tJx2R~5wGro(o1PBy*MqW6HZR#E>Io(q7J$RxHa=F|z z&_6}~D4tADTif1DrTV5LH%LB7+B|=F{6t{obUXd!W7mMgH*(pQLEu2KI7C>8jM1K& zl-AbWg@HuGqM&Ni1Kh}a1cz%r{yU;jK8sugc!8J~1>@|l*HTS7t#H7dj7)|#9#6bd zB&r0)SW)#`2M@)k)Y)(-SxAwv#|9dB_|2Znmc59yi~8gMr1i|g#qm#k2;fF$lk&g` zP=QOeI$9|g`=j*=#cf!@+C2aN*b~5H+rhn0nre&vQVqQ)QKzMTG6u>Bb_Di!OcQlg zUWsCenJ|15OvAhOkMuMM2?*5}Tn0|H%=dgvEB%8q$*n7tCW3Yp{RC=`X|?l8#|Fem z+B?;`>h-x;K!sg=-7pc1Zr%p6|3|b`ET$wJjGMLcya|~l%}3juo-18&=`jvpMY$i_ zpr?!&&GX1L5qtuANFzV*fJ^#+biNFvF!fELL$GHcTxyRW7)Vo5>rm<7-|FVb;ab-R8+D$p#^6VZ5zf6lriSfznBq4o)`$1-T|%D<2}s>bBWq_4Pt!huzY zk1vIv9zj=ffbG_=u$21r;bfoo&|6#aDL&P08sjC!xhJd%6?_fYOQ#;|L#&dV+!E#kmkL73!SRv0pVW!{)nWB8NN4(8%4hj z{*ZtuYZ?w-I^;(L@zE6uN#<#4w+$f+s_JpYQk?@s`D;8okwYrr7fD;4fzB1l%6AYN zmIhh=E(zn|BW-Qk4RQIpxq4u?GxE0+4_kbX3p)|>$-Nv#+CY9w>B-y%x4QAYjGX9u zgwJkjQ@Uwq+<5%?wy|6hKU?CwIA7&Dn_BTt-iIP7UWTLGgx8|6TEnHkS)lL)bo6LC zT@+MUa{1^XFkL?p{=D31rsmns#A^1nTbjH+8aeWF0w7h6f1j0C{RqrC5pT(DLy_PL z?^XLPFzx|B9ORyvZ0TwGRuJq)xdFeD)Fng zm98ti!B@wgCn4w+ zbrI96Fl9+9|GtBLpiKfIdGNiJLCY%dsKz7~dcf*!n++OD z1yoc$W8knr%qV{Z9mVAT{BaRndhbD?JfwfO=(pf6+}Jsk4t)wgpI{jVk)rzS{Eiv$#kJg*F{3FeTJV4C;< z1SHPulrq72-_2(fhDDZ#tpcr%V^G1Re<~0dS4W2l5`e;iSNW+~Pk>?L&$Q67OQlxn zDBC?;VGIlZKQxd-!!?zqkfxJ$yBm7h!zy#j zING6(-Qc1%sIM0JYkf_>R$if|P=DlHwXW0AEW{tQrddbKcimo5KnamzzH7jbEJ*XWR5mYj>&wJCC|pCDY!k#WtAR0YFVG0L)?!PZ^`s_B6)$ zE+|RwtA`Hs%|uQ5fMIr)rHq%)j)Z83T3;)P^9JatQdC=1`5S`p@=3PO8GfPpv)&l% z7R3M3m9LfWzlN(I!Gw-%%D;Ui0c&cjc<=tRi7`J1hh!hoMmeYeQ3~%%?lFdK3<0OAjH3 z*l25|%r5=dloaNn2}aeGjwm7BP$&u*ATujr^Xk(;TN%{D-1S*A=x)Kikr0BFQ!g z{G!-aTYVFQMI-4$?^%S&+NkARVS60{)BO3hu#O@5R)t1Hbl8XY!)^ zDU4|EdXPJMMzeU~11TOxO@A1D2>?HBzPaG*vqHTIFJ`Q6OgJ&K|L|s^tO!{0uirx1 zl6f68r0k2v-%_GPf_$-sz{hV3zmk9gq2FsP4bTU>EzQ}$MR5=;>ACDN??!L3Ol%qU z&M5Y^>{mS`$0+s$XCX7(2RrMkFj8`Rd2cC}Cjv}FyvRC^CB+d>{q~IWFsu_-ZMZ`u zv|g3R8axG8G^>!(=9afz-eF9?yW?meP0nv6jX@jmcQdAzIB$fxi$x3Q7oooh?4#&I z+k8ExSG`oE=5{%u-uqM;Y4d(D;MX$OLpY9F)W4ZYY+REY@$nrR$+_x-^NVBjMPRc$ zgYrJE_N z(ooeXP$o#Uw$@E>9RT_S;+0*R(yw6&46nFi1R9@;Rj751Xx+sdD5H)O#iFN1GNeaH zd=HI>BG#XoN)y5mvH+wrHRJ~#cw&G&2#DAe(bP?@HlCR2#EUZ zIjnSV+!CRr&1snPWepg~W1;RzMF7J+zKmUrq~e&7Uad^5blE7}8`Zlleb(e;SU}RRQB9F4T{;B9&NC9lOCu}o~ z_WpeH7XXPW^kYce{Ezx?3tzDT;=me`W~z#86gUa$UU(a&Aan(PC+8nwFQ)}rv`;fZW2wcHPAHI3$aVK2-9N&63wWd>m?zWv)cW2p@mAKU6L5j&(4LeS$w;1+yjh-^{R7|P+>`8=6syta@vTEjyCWwV`a z#P8d)Cq%9vGbTWv7~}#Ybz!WCp>ohJ0Q7-hKdxqhl0fgZvyyyDOpt{V<{FaJ?R}4xwB(5s@T10PDYv`N!&QOw zyDY6UEkx4rA;hO5Ahfyo%J9K6K0ovZly-S}?BY^$w)*6F7)^#BH8U(g-wQgd*dK88 zxvR{`?~T+tC?q{6XeIIqa^J^?L*AkOoL$X12dD7R7B#n)K+oP3F;&j;{Vg6f3vv!= zVG4U#QBvW-HB8_Qft)0(nC|a27s!v$I;7|fR;p1MhbPidfSxP%S zwQ5n~v!Wbl^8C+YAG$uLJh~p^W)MO#)&{>9D*&e+nfm4IqR<8k=IeFG1jAV;w}s0<&%xMI8KYA7?l;xd?~=&W8w@Cft>VW#MY} zP-6ceHBSIR*Bcc1%bnd@bK9`O)8ng$%jw?bzh;sc59(&|{kap+}cap%JKkhK$xmr#Ak%BWoeFXGG(1B=H;8L)w)>hNu zv8(r(-n}@ubvLVExWc)Y*@$q5R>{{kgji2YJz*>u)kSm3V9de1nR{GNsjL8!{nK?; zuG6;!9y|6hGZ4g4HRO>cFTJYq^sFwZ8=={NFItXki)^Sq4SH9O>xAPNL zNd#@ru7Zor)ht?ygM7T)sMue~qD|O~dYF|t6L=ty1!@U<0%zF{uJ3;k{J?i797_D% zg>1-=gPCx8BJYpu9L}Bzis;UNF5?4tfxbBw=AQsZi9br`7SOqxG__rFlRM8IhugS( z0(%5d%xFGcy(~ro)byW3GOkG(niGToZ>kJMJu;2d7OY7{-IqAfzoSUA_PkRSk?{sAqj|lazTDGEl{Q@JnXFTLQ*<%uk`b6eww$ zK>!Yy;emLISlML5cxnq^#B@Ij&IF;)&WzH4D3A6vl!NP_L>PKx;U9`l3z_ zCDnaUBbo9^{N9CLq7(iM=B$A<{sV!Jv?M0;DE6MP9ei}+u6KAay zLFapy_QZI?74!qtRE)>DTZ9RLMuLs2^B+=OO|ty6gz!za1^S_sH82Oi(7fS|Zt`4{ zODISg{5KS3_WUg_>883+k;jX}>D|o$sebQLaOnl6zFpZ1i?RI$klMyO?t3ajI6C{z zm+wXy-y>P#X20E1`_2~4yo|rSldnq~A?X@rb?1M=-zVbVj^uL(0p!&t7_Wq5jJH5h^Vi z+#l);XwjCjvB9rldb~!1Lnv3kr%+odq>RYF09GrlU>#T!I5HsYF+b_+Ch`Mv)|*7u zWTM63SdGR{?sPzF;(K8`;dWqYX8_A!gv~CAD8o_dLJef#gJ|Hk6lfF~esA6b<5%Wp z9{Bq4F>Hrz55Eh=-s1ge`~pDG0GkX%U+6ptQ66~v06*Yp-qD+`t@R?e1URw?xXPKe z-~GAT?SCX?K+*X?bU(uzv-Usamg4S@51)Q1v;VB{GriRAibXWgY< zQ?+=)7ru0s)qL*FJ-q-)d=?h`MN57pgD=6nUsx9F@(h5(Q|K!0) z6x-eaG&PU*4X>MBlTt_o!;a)%jMwg0ybSMqCsSq*TTd5$Dm<1ROtdJEPsa54YJD`t(-7MW*EDtjBb5(@jsxN#->{lFvf| z0$ow&WL;;ORNqbk*mSX(uWh;FqP3py+&l~VfCgx{t_NUnTE~QETBWV!W zpi5fJyIDBqIgl=+nkjETj%#p4;dzJZrWctbIQxr!n zoo>i;RxB(f=-cO5Yr;Qr)E>zB?S8HzboP`nBs;zPTJ;5Q=+CK_OlKc(j|@ZYL9b&B z%&7xPG6)L96F#sJsAq%MasuX7BCceBkWI8MT37xDs{OVWSS>6Oq71VzP9{*m? zKj}F`uIV?9dn+sT0U&>EPJi$U)_^%UNE#~8s88nV?->EF;&Tvi3WjuADfJUBlO@;K zFVBSpF0^$D+(s8ceIDRfa?iD98)@%H{1)gP&lVvnAj$WTCnlgVhkGwNQn%R6E_6lmN?P_RH)8Qd^VA1QTGpumn1u@SsCCyFA7`@Ji(sBXLvq#M_|s7 zjoSmfd!)LaEXjzAgu3fwG|o6CVHKTvb1INE8yJ~0A~*;_@;S^8kv5ZY4h2#6HhLq= zy&`9)IOyw-=DNWMj!D`hKEML5O>UyvQ@H#4_3r)kQ)Ti{b;o?cOV|WxhVv|u_d<+z zF?b7P4%~#3K}#PnWP|1MTU1w4Or(=C_7g3e)HeZSNdsldDag$88s_cK>t|oo zRo}pcn{Cj~72kV&4pDx%dIuHpOECpwbIz+{n1yy5Oj2nWcT!)Jiwtdxv96YnY>%X&H`*LO5 z@dTNj;(D7hBPiQXlWe}bnTdl2lLmZOgk_Gtt;Mj(vE>X`1h9!oZS1<2te7{*=F%e~ zR{HK)ti7DzAmCGJtw6e850=E+;BEPM%b5}M^l$$YgVOTG&`PtY{>BhCik7%7I!&>? z!8~0=mskyEt{i1Soz(5_>R_T*l%QecE7@q4>GTU`6JYt9iJ42;Ijnbq@Yq@pk3BDU zdGpWq&E?lo&vg8N;8R6zo1H@b*jp02Xzr4}FT6X!Gy-C#_$u2UYUCXL@q9*hBcrC2 z>Uy)e78vEJ>6C$_svg%9VFX~PyhpZ_$YEj&t%J)US9!V$_rZHBqR9)p`#0Y>+Jna2 zsWnRUN-6A?P zQS$;TT*3mLfzX3mn(-%Gt`H$V>f@l(CA!+Yi{|Yw43MB=(JmB8g)Epp^5(8|IiMLN z#ht5oW7KTzuQ)%1Hkbtq+3n_&;7c8Uz*G;33r=x9TT2JSGWxdDodwwozk+s4-p#h4 zp2HOHTzCJt=n+T*Y|n+gNBtzYrocq}|4PXkKvD8YnTB1RT&xpGJ11e(9e+>CN;5e?% zy?Wmy3)l}PeTTE%xVI-wPfB<1ikQG}hrpzJBV1wUbFxVzrj&!n(O^tt9-vs{W z$;<-dI%$;Q1t!>^h?dmk!MGcep=i`~4O89U0#q*Mv(DX<)wD0r!Aou7%=8MRn!ya{@u0e#$0DP-V8QKI7G=5TFQ zs@pBTMyxSHx9~V&PeA`jgvSMLvS7x<%unJ8lYnttZl@VMYY;05pbN9DM6Zz>M z$vSOFg*1&d6ZN&r`fI(9>t0Y_|8XaDH7Q^CIdj@*5dM~QA~W>*^L(A>wVr{9D-%(%Zv8cZgyEb@PTq*0fh+Uf`fX6uOw)(3Qq0r%*N_iC!O>=>w+ZwO zVEkbUzvl-LSa3^(UFN^LL9#5aFGZ?U|G#wY(*03xvfV0Xm=5Mhg3!n~9C1#niRpKZ zSbBS4bRbgvDj;fjpLzN5l68OUx+$tya_mSpYU@C8S!j5UtOO?u z)_^9wIH%lbknvVK!WkeEMu2#lRA(agAJ6`Mfs^0$W>3pD99a{Aa?=K8jQ8bDJ1{+f z=M4-oB2~tJ5obn7OoW?I@aG2B8*)dI{r)?SYv&28SU%5(I)1S5anE3?fTKGPz)m!!pS_$S&M7uZC3POxu)1s-;w!EQxs<)^$m-<08YkM7BI8BX zXSPP%Q{oti;~dKN$RnwA0$;sI;RCEJ0xKlj7;S$TlYmUlKu0pu4P3Y2-W)Pm9l+C2 z6uBHS8X9@!i-U3lEk!aF2h0Z+0j$Zz^1tHb80z+%3VML#V+~;3j z=9tkhS~0d!Gw90N(^5qbvs}Y8`xvcBjGr^<QrMc)f8;Cs1lQx~CkTS5RWxl6T#`-uSekAH$Q0^9hv8#T zlVk>&)VTV}%PPz0Kbs@dq?Fm9x@4FGomu*FE~k&9?V)$Tv*TCKyoTu}0C*?3Ck-E> zyj>X=TKd!Zl7@g!wcdgR%uu7mi$wZ~!SysgOL0o|X%fYVL8;R<3cs=da;p zkT`w1>|@)g!X}x;?_F!~BV-N{ES?2F!@^-p zM3ImI69JN+N=6U`+9;z(NR~h3g#8Q@|0yHwL$@-0oXencL@WbR1?*aMANo;t!-i~u zu_OQa7Cg*BWIw(5owPy`W4n@1=AU|hJVq0M)ZtkFI`J*jC$5PDxPS+CttkoT5}o}iQkZ5x) z(vk>l39=nJ0OSCI|3!g+(lku}8<)`l{h<(a`TdK$!k4G*$e<%0kk%W{o2?{7(gJbW z-gI_%tl~XK!pU({*?7gU=CQiXHIx<0S;$wa#paVQI5B_XB@ct5bZqF)~@RA5o zzs1XAnKIZ*plHCMQQFy+7x(_F}F6r1)U3rh|ZAAKYCM(z4 z{144IYD<0=^<2~G6l%MQg6?S)24-U+@ey~GrJ=6h`TQi9#UH>a57+zwv&Cn9Mc+K3 zyR3C)*Z$SUiiAW}KRB484&TS*D3x-hCwK+V@Z_K8g`dP#n|VhKNZ#(`eRd(XZ5yzR zik?BA9`xHQ5OQLwa`crr{9 zcVTz+wtn$1{suTM5%nF?1}~6;YD%;tuvt}}(%{6*F?-4)3l9kS5V}BP1SzB<)S3EU z=x27`9n_!96LZY>hI+}UfsJlD&*A}|HcW$yN5|%n?D;Vjm@JckJ^LaSMu@?@o8<~6!9Oj{j>i`TLp;J%Dl!O2 zfCYBsiN~{|yQcP!MEzd}U=`Rj63Il?k*&tMMtlreGo_?y6b)!-C_GFvc)|k!c5`Vb z*o?T>?~+bMaPdB-g=9SBpnZ@sG`eWDiE#8MRdL<9UytMOF_yoUw385r8%oq3B@oe;9VTs4+fy)Glte z8{DL8Jvk6^DB8=|l?d;bryxt`NoFTss8}))j{5pL8Rl69AR@8%hlRk{D_UI3 z+w+0vLo-#QzQ+1fSIXnew}I(@SBWLsPBs1+?-1chym2W!m{hzmApZ@I0mFLUZ4Tj! zG$5msqSXI1^8{mudPxM4Fh65^eBiR-d{d>Q_sYhivbjM0TLDP7&Ylu)8+ZWHp_P!7 z1-vtuj~&K|C<954Lr0m^UDEU~ua@%O!^~(DqPgOZVMXP6J_e@4F~I%+vd?WR5@v-u zXy2yKGJ@0%0A0Del~2+a`_%e=h`<8Dug3w(t@^(trNcF>N|3B!;IYP0xIoajtSEAA z@^jrnv?+mqFZ1nGKkGyorFXYR*41z%dQ@3}j-@QIq;2FQom7?%K&c8)Bj;3RozfU+ zX-5fAnpP-Gsag!B(<2yCts*2YP@@3i%Bd@yM*t|Wun=T)60Y-_0iC%eP{bh0bAI}K z;g}S`@$dV=K(x$j8zp}H_^y3h&@v86>rgv}X~MlMWq=b#%G4jAqFcid@%2fxeI>-| z8;|gRIaq5;CtT zS-n@YMq~76c_|2{X}6}z@Mz2c)AduY`4VtP9BIyJQD-6JtkL)9k4Wv4Mb6OgxL0DL zjzT;Hk&hsO3W`u{X8ta?c97c+JW63z&}=zdypg#Ci!l{%-(!jCe$EEiu^AqwSdOZRl{7mW$~ui!U%xNXEbRxkKKYmG7?q)3lQlny2tmO zb6y90&?{WdZ+V$3a^JWHBHUbuKXtsZTYidHzI(G4@wR9v1nqGiJlpSLPz$Ym;4KjG z_|dqB5EUCXu^v`q?Y(Q6^)4hHd*wgHf`hcRjtjfVa3mcQ>4c${y{*m#>m>jZd|H@O zmLX!K%X)5SBvOsvj~XLZ=b<2lvB zSFZrkQoz2an8;Puvm`?^Bl*3~ave3u<^XdQLNC*}5sr)S!*%T@&L?f@N;v;wD&=de zd=*&+yl+9a(Kg`V;&r)o_p~b`1m6L+!KIW)m9s@G^N(VWw$JU@BDu3O#40>03*^ti zRBclF#Rd*~iKK5P;6J4Tnsv_54i|tX!A2Xx4;7Io>|L*I6~qt~lMiGnLqS{`!v$zB zFTO(mO3MR+S#j{Tl2%hJ<&I z+5xju|1AJZxJ|~lSAy7RC{!X$I^JiTj}V8DLZRoLIJZSDcokrX0*FJ)gEG9h+SEJx zDULCjtx-FjJ<<S|^HtmU0PCTx?{iefZfstLct2y^1TmWVSDHoKSb={~auQ77WHF(ot_5z1 z3=7o@JVdP9ve(~N!AAY87|ewN5jz3hP^g^7`a940@38NNpoRY@9XAVGXxhq99y3%A#7^|+PxyP^C7e|>C@ty!4q;JsHM|Pn}3e54bbIgEU=lGT1ZMOFfTMN zo|@e87Mz#2+u&z>?u*NM?ldA(Opk}JjXG2enbrT_MA4#=7*&Xh02-k&HAp8Bu&QWR zrWN04YH^BQqH|rkp{q~=4&Ik%zPQg2_4ZRQ4FfBhie>d?{g4{2yr*o@sY$l?w|6Cl z@oZ}WIR-^<0~ojJ-uq-Xvx6P`SuB&NR`cxR`es?l?3)Fspb5V~52(!}OS2GV_|CsF zj7DO@x||FK@9FS#{wM%#KWcJ$;T|{It~mb)K%4cYj!+lWrO9W@8czz^Pmh{OTzoHX z&Q-o;lkNK|k#qyQ_X!7p=UCsMuP_l%@Nmfx5|R^<5)-+!?FajK6?rBEzC^H<=Pvc{ zlB}vil7SHSh2iL&an?Wjz2(Ia>5=YM8x)LuR?Szr()j6ZPDF`r)3DEv0uM^(dH?%9 zm^IhMDueD3g$N={wVJ;Kh%yM%7sN0zkW@(*i&=O&-&07~bw$aso9teru9aW3sIv?I zdKUBBQl@hbO9^}upy6s@nhAqgN`y@Y3YSXa;;lyWFviN;6|G3j+<5ty6UCj-m#oPv zJNvxrtH%$w8k6kXWN!MJP6I%h?;rxnV9DRG|b26 z=lH)Saa|8XDGz{vY0?J7mB82g*R?Ec(dglJHop*FEkDDY8)LN?1RGAzcDaG?TL{Uu z&fBzvSxplo>Zm<1_dEiJlDQ>{{GCn-*!z?x>DGFXV^vlBNZZWDAi&?fhRAq@`3urA>lPqD7VpYe=T(zdQ zAbO1XtG~MaHM5LLu)ZNrt8(Un^+5&6RF6Tyh~VDYC;ci=QH0x1F_C1{yUZ|b4m^Uo zkc-pSAP(hoj$^*rY*}I!I)RmjRP6>0M${1?7z3l->o^k*Sr0fg*npIpWmKv+496F& zG>+ik2SjV z093DOUN8?)AaeQ#hC4M_bZDhZUwPaSVLLIa>`+P@`!=@@qCY3|-nTm1_n$o@=;{QZ zBUeP3@5n9wW@y%^BANa_Je>tYmCqNg4;&ilE-C5m2I+3;Mnt4Lq#L9K0qO3N4(XJZ zkVZ;CI;86k|KGj$3&1(=nRjN--fKO}cZ9k7mz#o%_-p1fkr-*n-)HHyAf}8)-UlFv z0Cwk3%o<($LE~yt2MBivg=phwpab$}*}<@obL6SYyjKX04drVlFxw#!SOR|r-U;?{ri@muVNfA+KPvI2pkT0 zr~I^854c{vY*tnx72p!|EDK817tNN?pnxTRgK;i45Q;Z|T*%KGgRG?rmJav~g#r7M z?BRyhj9u|0jDETONia?yy8cnfD&~n-s(J)@G`w=xnriNMtpHT#{%{r~bO=xQCMXDr zPk5Fxn?k?!^dVg}T4WCsN!qtva8DaGLOa~Rb+ZlxBJwWR%rAuoL}p_1dVnlcs@wy1 zt`Yus-Fd|mUIu;oy#>k|jVyB6fTL>3{j~7z4kWhy40N@{!axRvArtv>WTDSfmhgN$WQIr3g20OiO3Y zKun7yI`=Xg49AXJ3``sk|17s>b(rXb=#0Nd2x66Y?thE~K5Nx3pBxbH8crdTjLAYAf_Wz3?rg-sP#50kZSTPQW_CU%Du)^IGVDr2IyPzE3L6Rk+ zJBVm+HZFQfllznm;mHPx%#+kq=|J@4n43q0SULyeH20V0@1{_3%aTcVUH_Xj|qy(WvUZAl+^Nwp*6D`L*RD?j^baolUc}1rznRrceQieYt??I@_0w24rJ;|L&?O<2yxfK zARWWAGgI-3a09RBMu}p@+)OfeZ&TRxUUcj?>k(tXP52EVtNJ_{iSWS@n#f5b2Hqid z_J^;mZs{}tJ{Bz9w)>iJfg_hQ$QTjjI(nYL?llC>uCa^2u-%2qzXkLX5JACkyAAk4 z2fyD@Uh~`E^#2rhOe&OTU4C&jT9cyYQUW57lFhP zGZ^WbOQC$3s>WYH!S+TM?Cp-e=Ee0eFa<0~hJw4jCyb%T=o!S1#jjEZDx9L$B^n+Z zp(co!d>evUSe{%c+St@XIHX;ZKcrlAbqt8UA-o|m=P#TIFo^Wz7z52FaFGmB6(7V- z*g^Tcv%2=-uhl)bf4ZDLXVe-y(`Q|CiS^kVtLQTWg4yGNwQiLUP$VB1lbij{)ZtSk zWmoX7Up#WHZuRO!_7_rez3d^SNLgp9ko$=1Q<~COrR}G6v}j`ph{XnsFfNhXYOeCc zW_(SC4Z!dLa) z1x%6ve;0vF_Y<;~7uX-A%!;}3AUfmYiQ6PJdn1XxZ`ZbatQ>s|da)-( zP9`9Y0flupb&$9l2Cfi$%uM<%q7-lvjZzy}>t;w|FrVZ~9nsbeuowfmGpA-GTdc^I=!&0;Zr$NG8N-5D z(XNlW`m2YuDwA%%y*?bY(CR0a$f8Q?6$(PfA^{@x7cwq}GOx#hU8^|FVRr*n@|GCS z$5YrA(3AK99GiX0x03+wNX-!{qLuJY*`G%QJdZVLJ^YXB(jyK=_l=hspnw2_h5IR0 zpfetISjBS|?M)00%YnjlVF$Q#L?h3Zb=)TFtp$ZlL}gAP;5SnM*x&x%;Xl{&4W8^t z1r&^o2Fy;56bGY%w`N@>6Os4tbR1H?T#-&rhNE~ed}fE&Sp-31hXe=~?Q3gM@#gC; zZD6?)vNKZf5Tdg0!rT?`dG1LWN_2|^sk;0r3|p_n6itgi2)LUmJ!4MAW8kFWq!O_H z3mTBqLZ!wQgsf(SFa1xstiGKP_~3i;vLm0gym>B6vgR3-c~bYhAJ0G;uG8nuaY={q zi`RtUMkR)jcyFhYh}#Nt_W&d_cWB^8z2*yT4+!V~McX_qlcKEP^v``VSNJ-}RJ-2y zweIVNpBV4I5O1vG`s9(>rYfLGzIYd|>=s7(am-BHg3$aGzdN8?9`ijj2=K{xyMQ;l zXRrV&3lSW0lt6!;Q*qr0ZL|++a7m}1P^&94{V()Zy#vL4hSyi>tis) zYF=1iuJEh{a3U%Eag|Lvb*xWGtXeU0%lQ3foNT)P3(PD+x?u>WwO0J8~L!M=p7m*TQ5mk`7zMxOgysuOhDT zOvUt(&!3-SS-uS*!i&tH8$cbhQXA!Cq>n^`Bi63hCx(&GbN;~UB#O6M-cGC`cui(T z7%uNV8R0dHTVyQKQxjqq40Kg%>u&%LWQgcu?Omj`3N4T48cz34(8ST4PVUITix)4? z0mx7gvundTiVSl1&F5^9@8u6ekXg4TePZ_zzgCUZar_$guJ$;ie%8@RR3n1YT0Y36FdrU{u=;l@rtK3S*tw2 z%GV`rQ)nm1^?(C3E1D7a3-@?Va}Y+S$4bW0RXB^_^YGj$4VwY8afJtsd_b)1`@;r6 zo$UEjo&Na-sa)Ou+?ZNEKR7i_d+1*J5aZ!ag!e6ykHwp^ze*?YgS)yaaEju9eUll$ z!sm_LU8tpz_`VF`Mc~~8h=-B64n;P~eywA2)pwMo;#rd*$t2rGeqExvn)`2qa2%s-+n01_uSLYT z3u;d_rgXdgZh>|J;CL+zU)2UK-AZDiK6z=}vTbCAafO-@G45Ep6spmGYpkN6WY&A- ziL~|wrsOGYNyn2si~)>rn}mq5WhO!iI5UX5H&ws9C#w8cnRUv@hP0;mV78jvL(&3h z0@o%#5JY=i#8&Xh^7bGNe$8Gk00+=u^lF^|1vV}J2 zxB%%IMBhAI?t}w}U&JkkxB6+9&o-DQnQopw<322ajtTV1i)lLOHL8QIk}7x^3LWr0 zS3q_B z%vta(;f~H6M9ct4n$}tJ)IpLP2{V4vcV4y#%gZs0IbB(xG6(lbiNQ~F_HRBbLyy;e zS%FbOY5-Ui%`~;c-vS-oYN+KfPbPj9>$P8CYEIi|H{X?)`K@IFQ;Z27p2-l<)m&zd zFD=E1R?1}(Hm}%$RI|4xiD}Zy^_&`Fl6pFDyV3hg^6at?JFXZ#0V9+dBY{+Be_3-g+zf zLDB$?j0x`h^0Qd!Qy&4a6oK8fsWeC2R-u_zu=6a{tTBQTgu%q1e2PQ<%2=O_2$agR zO{)R>-6OpQ20E{=E)lDiXmE7sqE*6d8ct+bSG>tFxv|m^%hNh0em0%GC5QP>0%#uHP4#zeC42RIxi?yH<6YXwmC(B^nSc$pEfvt~P}4 zRA!kAEeXHZx&REZ5L#>s#@l0M;WYt>0GiM|7bWHJZ+Rc9+NBE}siXAmc5kHTtIHow z;yBWz2NC%YI;W7|R+{iRJO5E@Hf6?f<=sQsD&mUS2(LednfI=}5HY3ih?%qLgH?FgZHrrL0Lo>M- zE3oZpO5SEvWn?We4Q&v|!vP#-ai|to?63}&XS)kx-Y1cGn#P{&Ta=z8{|F*9Av!9u zI_dGjC-xq)TGLltRQNIE2`6svV%6p?!JN2YGCPQs!+;W@iu{_zwyOco1>qWqjMwv0 z2SM~kl>L^Ukylc+pf#Eg(YKJFKVqG$6Gzv6E)SU`%EfMT^>O7=un;saKFQ{3J{;n1 z|A}ah2W#G`L&KTUI-VGKV>ez)qd!)yIQ%k0#i33h?j5gBHFqbHo`}fJA8Y07(tj2E zRTl9f@UCq#dYa1dp)0}Pc2A}`619}54;fPaWVGTHU+KC`{;-q9UXx zbp$OY1ld{p8z1xC?;}Fy6EIe++bNSY$L{9y!c;$@s~j91mN~SqA8m`e98g`KAzZ`# zM7-#xYc{TU4A(%eVsyAHU=J2( zUE3v1b=2ByXu=PE=U~d|^)sB?s_sG(K1Sq@xDy;Wrh9L&dU{by+siKiB1FvSzFiFo zNyxE9^kNdfS=;EJ1UwJ>hK^yE;Z!i%o1mb8pq7?&E8@;l-7~|u^Y>lA0hmn5!z~#^ zreY0|o-N)@hH-of@+Kui%4yTwA$1~gWNW+@UlXJNOXVE{L^)%p|aFMMC>5p#Hp zzBnZuGi1|vyKyCx^H@x_dtdDqalx7>il!K0OIeS4k@!u03xcpLL4ufdk zIMpR7L|6;|tFN95$cV7^SNJYpK!hGp02vFiuL1QwQl>|pKWq;TB^Vm@UDBW<&ifgq z-{@vIyJT(z8dUP73Ax_8|BL9m!O=ch3Ind;BmM+d4ZUZKCUBVcG7s5uU*W*M(*ZN| zb?qX#V$b-+6VO+29&qKu@>M&BA!C#q(k$2xA9?>nux`r=hiw2!)*8~+*&A*hr7@{r#ka#s<=C!%bxDKc}#ZgJWRL2M_|Cu3&KoPN$S|`XOvE7 z=`l%9ra1RnKlN^`LcC3_!`JLUOienv(ls#cair}splBW!-*l~TqHz-d;%TRx{=C>J}YZ=zP@P!BvE{9bA>26;TugyGVh8?i< z03IoW=k(kQzl>o6Gsj zf9^)pU%=<<8VW=%fcBAo?5BWR4wCxr0X9Nxx{PA9fEp;J-@z1&U?c1`Es$+vA=8VG zPOkK6wM#Q5F^#7x8_p}TrheN9v6ftpVSq~|N-gC-(l5%*{*4*M$J0#NW0!zlfk5kX z^65aZ7xT2O?#=Ev6mvR(fWXn&W8NTjC! zf^GzTuSqhijQ6Y)6Vya3h2fpb?X5enA{EfBk3xTOeK>&;33O|A!n#*Usb9_t5aNPt z1UF*sU)HVW038U@#p(!)*z)SEw#(A@Cvv~S>(7{Z`fGyWYy@OTYJTN}mZHEyO4$ID zg1`G>nns-nI8J&LO@Bqgg1jwQIXn|xAa$WVaLe3PFCGqX(<_Cs+8^U~K|zbaZF+F5 zNcxluElmKuQedQG{&?c#i7i-zer<^F3$gSiq%wN~uE{@1hfpU3Rr_0v!Z5{d=j=dK zW@(CD{*O{rE1VFiFtFcJq;Yg>aezjRUTyx|&s+@vE}_;lVE$Ety`xTIs&AUcs$~rU zNLsg`;{rWR0=!p^RFFZ&V%yGWYD*NQnIsM59R0o&zj?q(k~MUcN)r;L%IhASPO+zy zGqHkS!G4zLanLpqs8Pxg2pE=-XDz_$R9vicf?@mq_K_iJ+pxmlxPO2~Fta7c{H7TP z#UvRB0BuBNulU(i@_5(U(wwaG`&%j)z|084qfU4Z5Cw7FzviX_=uEKNtN~@WCONEo8oyfCi? zDf$dXee4%$w)f|3N}GJ4j7h0u95ROZ)5j@qz)n=Lfq^UU7=xUJ!pE)T*nq>!2tVMh zCXtmVxzn@mOJd67v16A&$)jQZ(ghuCmi<*EACX=>5TPhMXE`@Iq6ado@#1|=VFT7m z;vevJ9`AEEkzHh4Lz{(9{(Mfmwv_Ww-2sp&cI8@QYhaau?|%a58+x7t#GxR>$Jh6y z!}t>rESC>>r!MqMOe$pjjSkQXOW+HzklKk%iguM6O~yvKL|p>s&OC&{9l-YV{KK+l zlR0hQbrkbSTt6?)Lu*?|2 zJMr5x(n?u@W^S!(9M!&4>RK6!QB|6tq9Q}0r@3jV|?Qt;gQt~oCzSsBS^461PN^H zzzX%lu`dlM8dYNa@#|D(MlKEuwpwaYnN+Yu_TsH2SCe!~I`eSY)vSBn#Yu!4QCA?I z4KRaa^^5uOi|lu%QckyJQwg(Z9TX^fD}*xIe867nXgx$t`e`!-eaq^~07ql^nJfc3 z$hPU;Qbs_;R%CyXJ)Ns@Jwc%oOBu_^O{Qv>GsFJw4v1Q(>HkHR#+LH}#5$Pa6hjNK z)JYr-{O?kpBoPrnsskJy4h|LIi92>`6s#aGcPGVoJ9sGM&EK zIOfPQa6HaMx|G8oCX!h8BiNcNquG76jjcSdsql z>LnGs`PS921&M40O0dz^a-=81rW)02AcL{Ck9k37lO+g&slgIk;8jzaPXZw} z&9V$rN3SGs(9Yp1#E(X~Gq*bYRn~WZQvL*w#MWQGP`zz2J_U-*_X`M$T{0ai^cu{< zU+D6Wo7Vk({lPT083e5zt_qmI&mO?j=JDEku(ME6(O&DKoKf_3fI9MJ+kHP^TO%~5wH&Jy^73x ztiJZjq(RXyo_P>C^p<42zf23bJVzTv1H->o8ln&R=@gk$xe^+!tbsLzm&o-YerwuXnxL(qF`=b`$S*)6rqMS$pDauPNwn}Pi6 zuQ0?^!>}wjZU4TDlTbl=T@Ly^bzE+x^ywL&|1aKM7iKpaummIogLnA+^(;SrTj((e z<`;BS-cCA9akAlr#kB^sJ|#!#(a9xol(^OTQj32j))}NA2xJdZAOi#-oE;PFijIFm zRb#5XKQ9`A3Fa@=5scKj10+%ae< z0)u_KnehNvAoM(#Tp;N*KB`ZGrdK$9!U-Pv6})ARdcxvbAxOxOSSpm}M-k1Ed>E6i zGhl{5{7YtDiPo)=?Q6k``4&L;A(>_zrW;^HVShnKSWZUa`@D1kavp%)o=b@1=Q&b# zb{me(2MT;b>@k`Qn&&%1>!89%Avr_2b*0cKA2}%&YbY(6_jo&{q%{bW*xt|x9z0;F z$m@3A?d?kdzQEb8Eme0bIz!0Gj=~pnINC7XEYjz+MHVQyVLGiwJ`-huEl8)JPX9l~ zhXQd^YAjYC6{V`v^l&p)XP)H#dL}8~=+5O5j8+L6J3FXj%aV-;UYm5GtfzaBfT?%S zRx~KOQn2iQa50);ey3mnuI`X-9cbcnHv z%8Aj%PYv9dKmHe#Vz~U9{}}1NuSa41V?qu;dW8s_I@@YlGhjOW2}pjD1R8$MPXDM) z&8u)hQlVKc6?f59Vhr>a6t{B0Q zx5)nrvN~dOyfkUB(U@9CvZjy3sW;QHK%p6luo}?lnCNIu_V{OM3gmCE?ML{iJH$tn z$7J**TKhK|7HWpO?B;ho9o>hSmB9A_Na!F(gofw6^6wg|n))6#Ec(CQSE{+tzAs=C zmYM}w+6}S>QM;2L0mGK+w6&mt1Q1smwxe7U9 zsSiWZ;iyicfG;1PzvAHAh6B=7l6Jp<>{*Um#BazTMub_fP{ZO-_pc9yjs|C^mrmGB z1aelZVa|Ad6p+WsHoYjZFEiCEkc%;qY$DADuqIbULbcXVK4&1$twYs_aM3KC?(lbB z0Zy076k?yC{d;64HEW7S^HEwFO^ahI`KsZDx!uX+7paQ@Ukg9h2d)jnq zde+*KTig}w0YHhJ#{FuFd=8*~ReIB(*#*DaQ?f!L#-HswY2|cGc-IJk{51%t)A#a( zp%#TT=uL-x`2BpKItd^I{5V?l1!Dl-{BIhftijS3QaR>Y7H!oVM1VdH55S% zFPAcEYmiqy)}|-bw6**Btwk-hV+ro+c7+0(Fp19s3?)Y;{%Nvv{1EX&e}; z9~ASNayr#m5sPSOa*3 z;BeRk*&(k&)fg+dSn^MhSc;GYctJ$U`PL5zHn3@-SN6WNmIR8;c-Lx#1me2i5~Y;EVD*EP1Ivk^bMWUoN2z?nHq%L-59Xw!9DJ84#tjw%sL17i1*t@t+Ux7KV5!) zTUYABd(?Zp1h#+ftInBsIYijs!Nn0Af`n+F_+Oz23cR)sSc5E35|EUkr7H9g7=wWr zc-@p3>#$QR5Yt_5dLH;>@80TT&c7`-l!56I-d*&&w*nHsRJUT#SRE&Sq9>z>#mHV` z%vbrw06>@X(cs|D&(BE&wj}1#A(kOCrUn>~OHdB{7~=N!S){%HXn>*gD^x!_1LQ26 zJhl@m)oSum22a3~n;gFc@dF_8@O(+8KuRpk?Q2FbNFTaVt%$Pbj^9ws7~0p zuFfa$0%;RJDYd@tk=7`_uLZ1(Li;$NU%?)SELh zM2}wa#Dw96%%)bqN4=&ha%TZlbRpeOA7cY*|LeX{^6e|0E_6Wirh2pR!U8`GQ9$sE zAV@wHa%0f~6cFILS!WIDVD0(cm=NLfECE19$SL06IGlUFo4rZkMmbIwzIxPX9lshMYZ zb2!x2Yq{jB3za4~Q(7BaHSzR5ai?R_0UC=nX=E4Vr<&isIZy;k=>K|S4bu0h-gIbl zz48Pmj=K?BDF!g}=R{roCb|z7V1rOa`kfFnMUsIoJe@CrjoME-9G1R_*FrG{v?!Qk zjieDH&>-jELEWrII0niJw6_FG@PIYW-b&pYY*#GsPcS(4_^q~kszMBa(OV=hXuSfj zKG^Cud%g!xP0e-B-V$$tkm32-A2#a>`ETKz#9bE(E^OYjkPTY`pyrmhlowJ?^kM+= zKk%XrT|WkU0ZyqZVuaLMO?J!25Vp7Qi5CDM6?)$V0Dg`^V9Z-oltMsCMb(Q7`k1`9 z47dnQk3-pg$awTzQfxwtZHv(b2!sV>bdOqA8*Q)L@$j?V)t(-3A3ZjA1K4XgM}0vfx>v819@8vdK>12c;qwARqzmxHdM34LK!V z>4>|tsU|uGnM}OE85WG53R4PGr_0CZAt+PeQsb!OtwTaacw%&T6I;criGfIZ2sjW8 z7w|0GzX*U~8MRC$1YQ)A+ZA_(236IA?P#_AQy8|OB`r6FvsaJ4V7#K6CcKpiWhqRu zc}pm@L-VdFk`n1v zhIj96{KOVw@)QfhXrxl1f%9KfR9|^H>wp*fAmDEDz3dx6Bw|`N<5Y2Y0~CN&KA?`r zqy>$|P}zs~K(a(!8~yq1pF3UvNfI$S6$1ydlG%EZ*nDqzELMwQhZensUSRszTt}xC zKcKDkEto=(&{Nm(-uTY0*bFeBO%DPOs$KgMzn^E2?L^{>tFVh$G)!G`{|9nQG296t zhIzXe2vyg0J9`Ghok=nPEe4o8cdC3ek`cxXYGyr>Y)R;(&5GRST5h**)nqh6Gkox~ zm*c*nGq3~kF+ycy1yIX1)NJ6oW%qQA)`d};1IVq(K!LPH5)_B6pvDs*kU83ehJgTu zP(Bspg>4Yo-B~U~PA05%`85c~7g&8{Wd1e4;Pr*S{?AjF#>W$7Zzonrw%35S%LC{ar0psMsZL4EzrjlEf?SC@eD37be zn4}=!h{;tlT*%Mw564(M7Ipa7iFeqtpS^pD2W5cis~rq1zQXhhd4Y*v5^*f-vcaX# zL)e8Po#QH)?27QZA?n&)&*N0ug<{K$Q!%{0{}I zGgg_~QHU}VtiFhp@!X~Bdwa1yp3eKHAE;BnG@VRRHXT$AKyg0I?{x5k;Y>sQH3mRp z$O;el$>vIt^r3?ivg->t{E+fAfTP3}uaWAHWkS*OW&1zQtyC!`NpFXysd$XWwW;64 zl+&E8JX6g=+j%3>m!dV8Z=bQ-HDsntFFmsVSY1sALUL;bC%26R&cHnDH15S*`u9Du zh|F~y!#JZomnMBgAE7nD!Hy0jbDRn$SX%MtsI&vox={4gz~fH!KlD=A6!5DPzTHFK zp#AqZ@F%;|44^TbtHl;5{6rmn8x#sN8_pCV3{0JBK$Xmhd^4ocs)g z$nd;of&Iu=Y@6M$O3Wkt2>t>GjQB&B(I4PviK0t_zt(srF{%m%%_rYZv>azs4@**2 zSVQem*aMUGjSvgNF24IaXX;&XlFstTi&_2){P6y-CJv791<+@#eV;t_eaFeP>2-Z^8GOpbMH7iW?m6pk13?-Kyon@l$k+!#&&Pmm_-BMsdA*=2gV#MxNj_T zO)g)m>j+@#Kqt5LMWSWt6?{Cg>6BxmnFy6NG$5Us^u44!-4up2#wffvQrc}sfeK&n zLk}o%A-{}HBZM(U78g-LfnFPqHjHj1eSkb9+dPo8x0aUN{4zfP%c2YT;8f5XC)H6w zb88^rT<_8SGzW!$5lkz1qWyr0dkY|V1Ti5NpVUyB03sXQU*v}+;BH`5@rZCSXiYAA z1Pm>6*ctuk1NkT}W;Hi|rP8iYSa1GkI@D+{C^|_P0r$6WuQ-BUumk3VYyCD<5LZUY zuIt_zB(@W+s(1;+MCcJt1gQ_p%PYSe!i{QjOTf1WQ5S!R5NhDqS7u%yqmyEj=0;vR z=3i29o07_rdRj_)NP9^-?XSp8;?F7rQPBs8;1pR9IJ|Ld`kSfn!KAR)E$aDYpmJU4 z`$0)8$XLSLHKfNpV2Yna{0Vxs3m_1>FAM{E(LKx_Y~xO=yY!0(s&j)MyA~!GmWt&_ zvsogZ%X!0SaczNN+GYi1a|z5o6!#$o-)f56Q6Io8ctp*OKa*(GP(5%<3m#w_xr0m-ni z)X4^1!NlK;T^ugYj=8ppSI{QnB-ZBie1Rlz!1&RJ zs1GA=nn(lS>emJ>3z48XQgDs@Q|UnuOBxSE7ofmWe_xUf-24@vSMc|nYXZP?*^mSG za}_|ma`hyC+YqSnHiy3S2UPDhA_8HR>vJQ9dGX!PG1DaHo@*TnwHN0f#$Z+9kGY<1 zIi#IY=3zLvT@E(Dfy*H(X%|qoW@Nw8E+(^uyEJ^}|m%NcNd>YRE&mMBRB;lD>08iHGx(2+M zt`v}Y=Yat#)3+ThPG>a?Yig`If!Vn8LH(TMZx( z7G~7k;|(RDopZi|zwcdQb)c`ZqSu!43h0R-7G>b1XJw>+`M#bvPoww`Tkzfz9%z8n z{PYYjLu{`$hXh8c8QZ*s6QAiPW6{(4z!Icf_Pk6|-Fr#X&@q{6bia&P6+)GSGB~5u zab+0jnEm00Wn_xEv%m#oJ66WmnCSp3MGdfifp&OZQZ{(#goL!jsXqXyO^4?%)MV7Hf1RhM65rAf0dF=LVX1Wg2mZ?~6t^Sgf!TZ@>e z__-au-UcxR@zY&o<20Bhp>!iDp!EZU=go&lcOamw1AjI-`7}U%II>@N4Lq;OF?O{s zuOFR$6|LJ7hB}hIaSkrWrnjhw;#uBM)(_zJ0v}B={^_o7COe}oSy^^8fZ^6{YCl-S zXO~btD500?HNKCIcSoC!W7eW~^$z%%&5VWoq+nmH<0_HY)if5?8oO4um$v5u;w&J6 zKiZ>zmfosfYl`a=MHc%@_>KB~HR;XnK{;R&RPAR~&FvhCVBDhaNOQelAjumi%%w zCERBGkO@n)O7Qz4XrD3AqdorJIDV`e3po_OXB`Z^fdWj_MrrsX z*+@Kf#Pp`cj(41O|%Ae3xy zn!p0($)FBo9OJ*qL^>lAa3(~Chpbhvg%~@`tR5E0E9mmQdktRGJ9dYWFJT&j?l3@) z-I;asaU<1>!sjn5oOnix`2J&(1RoJ(BuR9~E}Fa^%0B&YaPJy1dz_ z8V^Z5r9 z=2MIPURR+acj>~5;6wPu8$qms{S?RCae3jhw6J(Xa8Yjhxax6eF;d(@G_9F9-A~^$ z7{~ek;rG+^{kXog8rorT|I=9NZ z+e1APRp66^8dcv5WgiM55!EqAZAIB$^2hp{zPaqM>Z^`Ffxe_uC*;D-K8tC^PfmDk zBZ2${Om-0^>Vi9Nu~IVqAqh{{hcT;){x;~R-(EdVeT|YmEQ}(}(Odb!LEF?~O za(^t2V^)V|Y#bloT`wO!`F=E*yKtDPmWcXW;-pBzE%*3?NaVtQ^ug#?gzW4wOyAd& zJ6>#@&&FwYwCdFQmvhPFV*WMk-s{ooE=w?@g(lR1Q=gkdN`)IJ24 zU>VKsU>udR==9pf#XLCa9M2|?%kW@;7l3J*HfESDvrY@GCef2gtn4?Q`v*qGqdp|F z4LPk(Vwc^>frN}r7km8fA%tY(q~RYTJnq0l!@K9H{M&n z47d)#ls_FmufAh@i<3=LzSAyW{&}U!wdqKpeJpT)@`%qh-v0ozLDSPb@1r{x@5Oqq zm|>2{_2$2s$UY=UED^h1MQTU#enMVh?n4q1B6QX=;zdGcmiPU=I1k3_t;n7Cm7R6m zvxob_%O{V8OB3dOY}r}gKNUI{+}z!v^Z7W||9!o6Rk))0Js~xooArdb_sZ>Z%mumW zWB*8Ww@5GIh`-v$o{N9obAL?G%p7ZZYjsH)loU(y9 zzqwIruRxpbe?Mi=(Bqfn<^8o@d0cc>{KPGTMslvIso=+Mv73pO>hafRTHlX}Et*HU zFBS{c;-J}gff+JSDYux@CiqG4cLuMx^U^<#d0mwAlttARZXe|ps$?g;})Zf$Y^zoPU?$M{*kOvo;~b<(m9cjIZwl#epwS^R4X9yafcr02cu{>dr7{APZue-3k+u5e>pNcZNc z0*0YQe^L0byX8!MB%b?15yHOPR?lIxthw>D30u9+?(c6ReGyhv?q=N)cMbRP!|G)q zI#xsh_6AB*mna5L7lJJD)l2(pinEoRo@Mzcf-MmoeqZ8*Sjol0rY%)eG$yqllJ~E? zAnX!_F(35Kv(j5cPrzLH{a8_5O8KlK`RM{qqkyQCi`9>VF=6>{@?d|+nqFdFKx16} z4SwIfnn{oIw!;5X{d?Bv9y19Bh0g=m`@y0~ zV5<3QDCMroz-c8CiKzdE2LAvdCZtmlA@)*CN`J;I2#Hj3YAZ~W(k|m4%O3HOwY zYY5Bs26t__;hy!XiGlqOH#(x;I&CErn^XHqq#M?u7&0pN`KE7@7ztvqBQH1J_XPiz zj!!bYaYcB|Ol>D6K5y?Fi_{{!)|#kFa#bb(8;LBhDtvo>6Zg2>KEW!zxXWMQ_A*(F zMQp%4vMX=sDpHDb7x66g`eFCa7Is&r9El3ojB@O*wUt=Iu~LiY$P8)V!M|m^>A3-o z(Cmv(YjN{HWeU?|zZq*-D z%BzGJ#@Qm*S2}#{ezSPae@yL{KxSAB7Ml&5h)$-3q4O} zCNf?fysESIYN|#@{*^M1e;*SKPj(wj38EyW7BRoQo##G0e&2AQENlmpA-m`(7qYVD zIPm4@7dTM$YDwOF|Dsr&?A3DI_xr-=8dL1;y9G&-ibBz-xy8i6%Y} zJ$-q^=z=LgqYF8t_5WsdUZ8$s9k$8*{pgjDh=;s5QMdZh<*r>khT*-DbJGV?*Wx5Y z7MslEn;>GC`G9&ep^>&9X1V)(9~t)(@vQ?zo z;T~C_^i^QsUgFXRQbYWq*H|_kJpzM^2TqdD3pevaWtp&n*{mDgM&-Y8d$sVDNHP!O z<=e|D3ga&{VI5~vhmyJ$I30r*34Gw&zI;W2 z`UBQ0;c6_l(TluTV^*#~k=a6s5~bbz26*2LWamPzh4a&e8NrMM1Zszu2>*1jUF-vU z!BOiG92Dy&zg!_}22V^H^CugP&d5@4E*^z*0op$JcoG|j*G+6!dTuK}f|lQBjp`Ly z_TeW8R~^lEl+N6Zz5^%74MbHd04af&xu`hZ=VF;Jl33+=q3-=GBeUqn#4rh z2pjx|UNmyBo&1ZG^%s5mnO*l|;4W>>ilC`{E>}c9_n|jxj|Z|MM}p6<+sX8A&;V?% z^EU5sd;!lGHZ|*ly*{5KHm=o+Lh6|!3PWYHO}@l_w7Q| zzZ&ee5(CqTI!-I{8GB`)!MAw9H2Lz5IuJS;S8w)mWy^ljwV`U`TI|kYRjp3%F9Q*H z=T5trR*jZfuN-&9*C5dpcB#0H>4rXv#vHzt#HMjI$3ZIRF3BuIzF{jl@#B?~RX!!g z;k2-WNpXL)E+9RWcBxKcu-d4M)u-wiEw#*?#P4h!+ZE*0+zsJV7-~r zy!~19x*pq@cjA=1L1?8N8WY>wflq&J7SKMyT+CR%e@t90-$N#S&0l~9-KF)21m)II z=dIMvIY_s|qIzFLg1hcUIyL^N)Q--?pn0^uX8+L?Qh?SjHG@g+?3ySGYL&Ci9k=Br zqET>ksS39yeWBYee2VzQ{z@4kc1D5+_WI>in6X*g55*nZKfGvdphCY>e_-WVc38VW zOMp$mPdY{DW`8K$hV__+LMiNaCHPuMLJl=ht%uh7LcJzLzt$;@1*pIGr_C?%fuch- zJeF8h)mVO}W~s1hdxfr%Fot;3|2qGvK z&B!d~D5wnd@|q0(Z&}hh6O_iy_|*C28ATj`1n(X|EV#LNX7E+OH7ghXdu%;NPI7G6 zq~cZGfJi?Ny*m!&X67bIbff3H7ZZ6Sc=(FLNrl8=ABUG#XZHy9TXpbH1gB&iby^LW zz^07FbH-`O%tEgTJ;363TV7o$v-H(Sl>N@{%{6Ff*1l!i(qpzu+ZZcZi@4$;9`pJ; zl^q;qhkR5Cmib>%A(52oarAj#XT|ARL7rV|iGe8T^o4Smw$$d^hGK05^i!OOw*@iY zp+>C}gjqBlf;c<}+Il)p{$^HI;Fz44&{ypyK6ppvc+EQ0mHR}u^=b<7Y={7)Y^&14-rzk<1(xWu7a3jICtcbW(4Vw=+6rk zQ%grmHd^47C3fAU=Oo2LA`MQQEg4kK7B0-|L?JuDoEq?W-Xoh4XgDb4rDA^e*3G=| z<~FKaI`1d3p0v9RktUT6o0eKj_36@G!(_Eji6YI2md>EGqu&^D-L+BE#=gSA*kx=Y5q9 zbWPYLF#q|npqEkD$Mb?^50AwuHN(ERfj3`2azi2YwWX_D91rjoR7t=!Q{w-$cjf<3 zukZVfEagm@93wL-OO_U78AG&)2HA3iLMl2K8e0lUQ4%qhkSw8$>{~`NvL-F4WM}MS zNR}8RX*u6}oX_X;SA2gR&+9$Ub3gZe-Pd*9Uhg@(_rPIS2^{Y%rY|#yOIX+7$EX#5 zHQRg;d?98qy8r6&V-SlU!^&HM=?ud6nJN2Lmo(R zH#c!wOq4e`yOz&!U_;Y=t>d_)%VN?W4tc+OAt7_&V|Xdts>$mwq1*$Y+Qxp^mbNl@SH?L%;2 z&+R$Ch0EXlAn98Wz5^C?BLk8}BVw%kL!k=+!o#Y+@nlxobfu;3p+pPoYvOQbY-}zC zL4!yc&#XO82<(caOD%W%>-p^5QKRzFQ~7$TK2Fey zBG^gHO4Bvy%1RrQ7^*Xm|NgEr0KH)>*f>SaJ9?i@wq>a1W@T%==mk6G$4)cHwS?mI zJX%_SEG$d6<(?MIQ0FxLwIHBzPR`#x{fyRbt&n@*1qf7{sC{lm>-C{Mp>pd40JY^`F0j z=OqdKtYZ)Nio7o4C9g>+Ri2>8FIW1+;|8VVJHw-~5XYCGn8go7pXrerPQKTlM&j`L z8Mh?bGANEEL{ZN*##@x7co0edTFUkLCJeBnb2rFU0EX+BD^>KO*>}sE)!r_*4}>I* z5b3*4D&(*)^2wHPAj7a?E8*#?lo@#ByMTaN-9oipW)%5VWjJ&DR%epzMZ))`iXK2O z#7tZb7*>mDiaM_=GJlx)N=?k@eNiaKhZ%#OQ!#| zG(0CJDurel{QKOLN~ei%3m|dBe>!w=&x8B;Sd2;oHk2$WIue~nkzF`>TVTJIoMy*s zV6#7tUQcn1`?hbcceBud&(_4*Q)w$tvB)Xbqwd9`H;JIR~6iuV(3u%NzW`;Z*%+PEs8L*JBG9Xm(@hUma4Hdih++m3} zI2xz;;@;>NcDu#Yo0NF}oJjVqApR4RaM7LttF4z-v1vd6OTC55E# zO3;Rtqoy9+Tn8b`9uO@zK2&jAdeOnfE7YWHUVFpyc)}CPkOCd3t^mYhzAfO zQdM$1qCwgBY_w<-EZW_>UYgR+gkasa&h;yGM?{pG`xolgDFvZbq?a^f9*{({*YkMcg=>%8wBgV}y7- z6YEYKvNn#oxKqsD5Uon5Qq+sBA&o=p>%me+*zdRccy%7uz?S8r=}-HYCIar;E$)othrT6_CI-FV+~k!tjknhTsb8UhUvSMDVq zApzz@UAvH1p*RGueoZV&^5gDQlI%yb9Ww6T!FkRfXg1b8)_HpLT!m8VE8&QPp##%a zzTIxjUi(w*5c76Z+|KTKYT6(wwWKG-gL75QH3f?_-S0YDMR5l5ntH`Go=*s#=uFZ( zJ&Z&xA&MWtOv$^BKjLH8rL;NX?TS@NC$Af~yJUFt?2!KJ=r1SXr#Fq1#;=q0 zLU-3Fwp1IuQs@B%P=BLXz*SO`>oWm@5VMJ|7xqE)EsUF!Q0L-v!;Wm+79}Yp-$Ihj z(yC{FZr;mR3Rh0-i@I{_xY-U4>!M~SlA*43x+mS@*Wk_K>|S?vk7eoyAG+dU%A`cb{ z1cSK^%=(fe0cEw;I+aGY<+l@tb!Cq=!rwYoDmM+{Ov2)32 z9V6VZKg1arSG0`>HTOad_&o)9WN;$wIJ_bKo?)2c4vIPz6$=DruBhLyLV>tWbr|C&g) zvna;O>TP*o3+uM88x=hg6fCH3Fx?c~kuuZKP5qqG=1rwSm#s;;x$b9ib)y?S;b{If zm*6YiDL@Dv1APVIdM=JtONndm>;I}fDefE3ry5m>itW2}H4P|phjytb9_f?Qw%-x| z@LI#oUm3|aO3$oPu2QxcFc)regV??piS@I$X82rW8sL!-Ga|+#_J*8)EOGT*&IEl! zOy4nPM4*i812>MHYOs=$BO)o|`+BvP?Gm$mdzvsA0m34w&wv?0=HhTCi(g8f%C=iL zm*XQBDvOENbn1it#{~f!kBId0{qv{cJ6`f`v3dQA`SX@o;gyU=y>#P9Yw)wYtc&X= zXHHfe3Y1Xi%AuOQAyZN8rn^Ra61EtuIS6c)Avf)UdJYIP!oBxk7hfczj5~My$kr@6 zLh&YKP@8su1kiayfSvBy%{1*oMwLVBmJEkAYf@g0$dytmspWsJIFn^pKC<{5ZW&y4 z3qDiLI8*)Es=i(SLSlYqtJ4++&I70F0(1gG2h1Z9i#U*tQg!7#mKWFRG^-lNsPmD{b(YRvW*qmgBQ+><%G^Xc}7GoOW%I>kmvl zqh&=y0;m!VP-v~im8oEZjsYoKEg?x|A~OOtX;(A(Y2V(|G9wfsVoy{_eh)06t1^_9 zYg6LAjk&}l2*Lahnc!ZAMqmyWks=(?Z@+lxGq;VH~4)2_DIce zQrIqL?2Kobn8ja%ts^7!3YUcTJhU4}#vNIBLN%>QaGunb*e%epQZlP>J1tIg(BoUP z5|GNStXLrlxeCG-iye<#kOeAe{HvT*TeV9YYKP`nSLPbMx;z+&#a|8u(8}Br$_-;d ztHVU|uVNmly0Cy}YQOPwV_&E7kMGjPh%nAb&FeV@iP`c%29F$ZkWjqDp565I9ltr8 z<3mbM0rY?9SgfD-xW+3F!m=72Y{{X2abIg0kS){^v8JN@Nzd)RnST|??#6;&Wm(LF z+>O9OmA^wX4uc7)E1FifuyR)4FHX~e4VEXMS;@$hWyPV+r;`T>34#fTcjn%mE$@7a z!yC|-sVF*^5OewqS-GiSAH5Pr8bwI@7h+(-;(VhkTrBTw<7q0&76^|k%)pYLr*;=@ zfpW>RJ)3r|M(t|VaN6*>-5tbb7`g2!AV3E(vS{XNZjRM^1YwBHIkwY5R&%8b9zj$? zY3RS#CA3}6f7^)UL0uE>QXEM(^?$0_UUhE5ID4@hK|*HYH6KsHfU)KICj695`dKx+ zM+O!_BKWD4DK`j22B+~Ogvx5$CL{vv5Jg7E&~xt9HhzS8(A_1IE(AF;D@E2S&ZgJ0 zRt2(eKT04@ls@3HP$XhE6=fJ1SN`vMK(pO{@FPvi9pRU_oc>{-6K%i7K{IhN}upBnM zB>28EV8Z3y2|frw6zzO9Os2kd-!J?xEkQ<6R8&xymI-=>a4Y>l4Dz&18_`47pz0!^%0stwvr>vVca;pNWd1-OAHVjH6|-5RhRW@ zU2Cj=dKD0Px^!~^clVC_n5Ixo4GBiL9*=oXJWV|jsyKumuUSOUXzuHbgT@Vg2GIqx zy>>YCwyYh?_(FjzF!@wt zUMYY`na62f{4_tW!}J^Vekn*;`(e-sQiC3Fd}ARN30c)+A_%hLl&pv#W#S|VZC@0P z2SH|!t$!{>u=D?4{-4M^)R_B+=hx7k1Rb_v3B(IA NK4xxEa`fEI{{v#STB`s6 literal 0 HcmV?d00001 diff --git a/linux/holo_nav_dash/static/js/app.js b/linux/holo_nav_dash/static/js/app.js new file mode 100644 index 0000000..c6d712b --- /dev/null +++ b/linux/holo_nav_dash/static/js/app.js @@ -0,0 +1,194 @@ +//-------------------------------------------------------------------------------------------- +// Copyright(c) Microsoft Corporation. All rights reserved. +// Licensed under the MIT License. +// -------------------------------------------------------------------------------------------- + +var _clrControlEnabled = "#000000"; +var _clrControlDisabled = "#a0a0a0"; + +var _state_unknown = "unknown"; +var _state_not_started = "not started"; +var _state_running = "running"; +var _state_starting = "starting"; + +var _nodeMatrix = +[ + { context: "pepper_robot", lblID: "lblPepperRobot", btnID: "btnStartPepper", btnIcon: "toggleBtnPepper" }, + { context: "hololens_ros_bridge", lblID: "lblHololensROSBridge", btnID: "btnStartBridge", btnIcon: "toggleBtnBridge" }, + { context: "anchor_localizer", lblID: "lblAnchorLocalizer", btnID: "btnStartAnchor", btnIcon: "toggleBtnAnchor" }, + { context: "static_calibration", lblID: "lblStaticCalibration", btnID: "btnStartCalibration", btnIcon: "toggleBtnCalibration" }, + { context: "dynamic_adjuster", lblID: "lblDynamicAdjuster", btnID: "btnStartAdjuster", btnIcon: "toggleBtnAdjuster" }, + { context: "localizer", lblID: "lblLocalizer", btnID: "btnStartLocalizer", btnIcon: "toggleBtnLocalizer" } +]; + +var _lblHololensSequence = null; +var _btnHoloLensCalibration = null; + +//-------------------------------------------------------------------------------------------- +function onBodyLoad() +{ + // + // no scrollbars + document.body.style.overflow = 'hidden'; + + setupMiscellaneous(); + + // + // last... + setupWebSocket(); +} +//-------------------------------------------------------------------------------------------- +function setupMiscellaneous() +{ + var objBtn; + + for (var i = 0; i < _nodeMatrix.length; i++) { + // + // add additional keys + _nodeMatrix[i]['state'] = _state_unknown; + + objBtn = document.getElementById(_nodeMatrix[i]['btnID']); + if (objBtn) { + // + // disable and hide play/stop buttons. + if (false) { + // + // set up click event + var idx = i; + + objBtn.addEventListener("click", StartStopNode.bind(this, idx), false); + } else { + objBtn.style.display = "none"; + } + } + } + + _btnHoloLensCalibration = document.getElementById("btnHoloLensCalibration"); + if (_btnHoloLensCalibration) { + _btnHoloLensCalibration.disabled = true; + + _btnHoloLensCalibration.addEventListener("click", function () { + var msg = JSON.stringify({ msgType: "calibrateHoloLens" }); + + sendMessage(msg); + }); + } + + objBtn = document.getElementById("btnExitApp"); + if (objBtn) { + objBtn.addEventListener("click", function () { + var msg = JSON.stringify({ msgType: "quitApplication" }); + + sendMessage(msg); + }); + } + + _lblHololensSequence = document.getElementById("lblHololensSequence"); +} +//-------------------------------------------------------------------------------------------- +function EnableDisableUIControl(id, enable, changeColor = false) +{ + var obj = document.getElementById(id); + + if (!obj) + return; + + if (obj.checked != undefined) + obj.checked = enable ? true : false; + + if (obj.disabled != undefined) + obj.disabled = enable ? false : true; + + if (changeColor) + obj.style.color = enable ? _clrControlEnabled : _clrControlDisabled; +} +//-------------------------------------------------------------------------------------------- +function StartStopNode(idx, event) +{ + if ((idx < 0) || (idx >= _nodeMatrix.length)) { + console.warn("StartStopNode(): idx out of range."); + return; + } + + var info = _nodeMatrix[idx]; + var context = info['context']; + var state = info['state']; + var objLbl = document.getElementById(info['lblID']); + + if ((state == _state_unknown) || (state == _state_not_started)) { + var msg = JSON.stringify({ msgType: "startNode", startNode: context }); + + sendMessage(msg); + + EnableDisableUIControl(info['btnID'], false); + + _nodeMatrix[idx]['state'] = _state_starting; + + if (objLbl) + objLbl.innerText = _state_starting; + } +} +//-------------------------------------------------------------------------------------------- +function setROSNodesStatus(status) +{ + var enableCalibrationBtn = true; + + // console.log(status); + + for (var i = 0; i < _nodeMatrix.length; i++) { + var info = _nodeMatrix[i]; + var context = info['context']; + var state = info['state']; + var isRunning = status[context]; + var obj; + var update = false; + + // + // all modules need to be running for calibration + if (!isRunning) + enableCalibrationBtn = false; + + if ((state != _state_running) && (isRunning)) { + _nodeMatrix[i]['state'] = state = _state_running; + update = true; + } else if (((state == _state_running) || (state == _state_unknown)) && (!isRunning)) { + _nodeMatrix[i]['state'] = state = _state_not_started; + update = true; + } + + if (update) { + // + // update + obj = document.getElementById(info['lblID']); + if (obj) { + console.log("changing label to '" + state + "'"); + obj.innerText = state; + } else { + console.log("no label object."); + } + + if (state != _state_starting) { + var btnID = info['btnID']; + var btnIcon = info['btnIcon']; + + EnableDisableUIControl(btnID, true); + + obj = document.getElementById(btnIcon); + if (obj) { + obj.className = isRunning ? "fa fa-stop" : "fa fa-play"; + } + } + } + } + + if (_lblHololensSequence != null) { + if (status.hololens_sequence) + _lblHololensSequence.innerText = status.hololens_sequence; + else + _lblHololensSequence.innerText = "-"; + } + + if (_btnHoloLensCalibration != null) { + _btnHoloLensCalibration.disabled = false; // enableCalibrationBtn ? false : true; + } +} diff --git a/linux/holo_nav_dash/static/js/websocket.js b/linux/holo_nav_dash/static/js/websocket.js new file mode 100644 index 0000000..b47db4c --- /dev/null +++ b/linux/holo_nav_dash/static/js/websocket.js @@ -0,0 +1,164 @@ +//-------------------------------------------------------------------------------------------- +// Copyright(c) Microsoft Corporation. All rights reserved. +// Licensed under the MIT License. +// -------------------------------------------------------------------------------------------- + + +var _socket = null; +var _wsWrapper = null; + +//-------------------------------------------------------------------------------------------- +function setupWebSocket() +{ + _wsWrapper = new WebSocketWrapper(); + if (_wsWrapper == null) { + reportStatus("Failed to create webSocket wrapper object."); + return; + } + + _wsWrapper.initialize();; +} +//-------------------------------------------------------------------------------------------- +function sendMessage(msg) +{ + if (_wsWrapper == null) + return; + + _wsWrapper.sendMessage(msg); +} +//-------------------------------------------------------------------------------------------- + +var messages = null; + +//-------------------------------------------------------------------------------------------- +function reportStatus(msg) +{ + if (messages == null) + messages = document.getElementById('lblStatus'); + + var shouldScroll = messages.scrollTop + messages.clientHeight === messages.scrollHeight; + + var lbl = document.createElement('div'); + + lbl.innerHTML = msg; + //lbl.style.padding = "4px"; + //lbl.style.color = "#000"; + lbl.style.fontSize = "75%"; + + messages.appendChild(lbl); + + if (!shouldScroll) { + // scroll To Bottom + messages.scrollTop = messages.scrollHeight; + } +} +//-------------------------------------------------------------------------------------------- +WebSocketWrapper = function () +{ + this.webSocket = null; + this.connected = false; +} + +WebSocketWrapper.prototype.constructor = WebSocketWrapper; + +//-------------------------------------------------------------------------------------------- +WebSocketWrapper.prototype.initialize = function () +{ + var host = "ws://" + location.hostname + ":" + location.port + "/ws"; + + try + { + reportStatus('Connecting to "' + host + '"...'); + + this.webSocket = new WebSocket(host); + + this.webSocket.onopen = this.onWebSocketOpen.bind(this); + this.webSocket.onclose = this.onWebSocketClose.bind(this); + this.webSocket.onmessage = this.onWebSocketMessage.bind(this); + this.webSocket.onerror = this.onWebSocketError.bind(this); + } + catch (exception) + { + reportStatus('WebSocket: exception'); + if (window.console) + console.log(exception); + } +} +//-------------------------------------------------------------------------------------------- +WebSocketWrapper.prototype.onWebSocketOpen = function (event) +{ + this.connected = true; + reportStatus('WebSocket: connection opened.'); +} +//-------------------------------------------------------------------------------------------- +WebSocketWrapper.prototype.onWebSocketClose = function (event) +{ + var reason = ""; + + // + // only error code 1006 is dispatched: https://www.w3.org/TR/websockets/#concept-websocket-close-fail + // + if (event.code == 1000) + reason = "Normal closure, meaning that the purpose for which the connection was established has been fulfilled."; + else if (event.code == 1001) + reason = "An endpoint is \"going away\", such as a server going down or a browser having navigated away from a page."; + else if (event.code == 1002) + reason = "An endpoint is terminating the connection due to a protocol error"; + else if (event.code == 1003) + reason = "An endpoint is terminating the connection because it has received a type of data it cannot accept (e.g., an endpoint that understands only text data MAY send this if it receives a binary message)."; + else if (event.code == 1004) + reason = "Reserved. The specific meaning might be defined in the future."; + else if (event.code == 1005) + reason = "No status code was actually present."; + else if (event.code == 1006) { + if (this.connected) + reason = "The connection was closed abnormally."; + else + reason = "The connection could not be established."; + } else if (event.code == 1007) + reason = "An endpoint is terminating the connection because it has received data within a message that was not consistent with the type of the message (e.g., non-UTF-8 [http://tools.ietf.org/html/rfc3629] data within a text message)."; + else if (event.code == 1008) + reason = "An endpoint is terminating the connection because it has received a message that \"violates its policy\". This reason is given either if there is no other sutible reason, or if there is a need to hide specific details about the policy."; + else if (event.code == 1009) + reason = "An endpoint is terminating the connection because it has received a message that is too big for it to process."; + else if (event.code == 1010) // Note that this status code is not used by the server, because it can fail the WebSocket handshake instead. + reason = "An endpoint (client) is terminating the connection because it has expected the server to negotiate one or more extension, but the server didn't return them in the response message of the WebSocket handshake.
Specifically, the extensions that are needed are: " + event.reason; + else if (event.code == 1011) + reason = "A server is terminating the connection because it encountered an unexpected condition that prevented it from fulfilling the request."; + else if (event.code == 1015) + reason = "The connection was closed due to a failure to perform a TLS handshake (e.g., the server certificate can't be verified)."; + else + reason = "Unknown reason"; + + reportStatus('WebSocket: ' + reason); + + this.connected = false; +} +//-------------------------------------------------------------------------------------------- +WebSocketWrapper.prototype.onWebSocketMessage = function (event) +{ + // reportStatus('WebSocket: message received: ' + event.data); + + if (typeof event === "undefined" || typeof event.data !== "string") + return; + + var data = JSON.parse(event.data); + + // console.log("socket msg: '" + data.msgType + "'"); + if (data.msgType == 'initialization') { + } else if (data.msgType == 'status') { + setROSNodesStatus(data.status); + } +} +//-------------------------------------------------------------------------------------------- +WebSocketWrapper.prototype.onWebSocketError = function (event) +{ + //reportStatus('WebSocket Error: ' + event.data + ''); + //console.log(event); +} +//-------------------------------------------------------------------------------------------- +WebSocketWrapper.prototype.sendMessage = function (msg) +{ + if (this.connected) + this.webSocket.send(msg); +} diff --git a/linux/holo_nav_dash/static/main.css b/linux/holo_nav_dash/static/main.css new file mode 100644 index 0000000..8569494 --- /dev/null +++ b/linux/holo_nav_dash/static/main.css @@ -0,0 +1,98 @@ + +@import url(https://fonts.googleapis.com/css?family=Lato:700italic,400,400italic,700); +@import url(https://fonts.googleapis.com/css?family=Open+Sans:400,800); +@import url(https://fonts.googleapis.com/css?family=Droid+Sans+Mono); + +html { + -webkit-font-smoothing: antialiased; +} + +/* + +*/ +input.customBtn { + font-size: .825em; + font-weight: 700; + padding: .35em 1em; + background-color: #eaeef1; + background-image: linear-gradient(rgba(0,0,0,0), rgba(0,0,0,.1)); + border: #c0c0c0; + border-style: solid; + border-width: 1px; + border-radius: 3px; + outline: none; + color: rgba(0,0,0,.5); + text-decoration: none; + text-shadow: 0 1px 1px rgba(255,255,255,.7); +} + +input.customBtn:hover, input.customBtn.hover { + background-color: #fff; +} + +input.customBtn:active, input.customBtn.active { + background-color: #d0d3d6; + background-image: linear-gradient(rgba(0,0,0,.1), rgba(0,0,0,0)); + box-shadow: inset 0 0 2px rgba(0,0,0,.2), inset 0 2px 5px rgba(0,0,0,.2), 0 1px rgba(255,255,255,.2); +} + +/* + +*/ +.butt { + font-size: .825em; + text-decoration: none; + font-weight: 700; + padding: .35em 1em; + background-color: #eaeef1; + background-image: linear-gradient(rgba(0,0,0,0), rgba(0,0,0,.1)); + border-radius: 3px; + color: rgba(0,0,0,.6); + text-shadow: 0 1px 1px rgba(255,255,255,.7); + box-shadow: 0 0 0 1px rgba(0,0,0,.2), 0 1px 2px rgba(0,0,0,.2), inset 0 1px 2px rgba(255,255,255,.7); +} + +.butt:hover, .butt.hover { + background-color: #fff; +} + +.butt:active, .butt.active { + background-color: #d0d3d6; + background-image: linear-gradient(rgba(0,0,0,.1), rgba(0,0,0,0)); + box-shadow: inset 0 0 2px rgba(0,0,0,.2), inset 0 2px 5px rgba(0,0,0,.2), 0 1px rgba(255,255,255,.2); +} + +:root { + --background:#f9f9f9; + --foreground:#2c3e50; + + --foreground-light:#34495e; + + --size:50px; + --ratio:1.2; + + --transition-time:0.3s; +} + +body { + background: var(--background); + font-family: Droid Sans Mono; + font-size: 10pt; + text-align: center; +} + +h1 { + text-transform: uppercase; + color: var(--foreground-light); + letter-spacing: 2px; + font-size: 2em; + margin-bottom: 0; +} + +.headline { + display: block; + color: var(--foreground); + font-size: 1.5em; + margin-bottom: 1.5em; +} + diff --git a/linux/holo_nav_dash/templates/favicon.ico b/linux/holo_nav_dash/templates/favicon.ico new file mode 100644 index 0000000000000000000000000000000000000000..87f75e8d427934b011fde410bb4369e5f0f30608 GIT binary patch literal 129882 zcmbSSg;Q10)(24#1nKVXlI~8WyOHiL>Fy5cmXPigl#-V2?(Xhy^WOUlK4us=!`yog z`>ws#uQmh(Bm^|X>lY*h5yYW01cV9r-PiZO*HrHzArxI8AOr>fcP$J7;qDCy!Nm06 z>tb>Uh`c}Gl|=u$MuLEl-iCxg0zY5h&+IJ(#Q8NOM3}s+1Oglm9C&L4DM?Yq*T24g zzkj{8wnH(vr*o~8sF1ST{86T>8`{iN$jV&FvImsZ`@mSylO=t_NM?PzlQweuLrz)k zc+N1?9mjCP-nRASYDhy|?LURCf$k#jua*mrE}rar@{H9abE2=kMgv%Rcz9UG`5aHE zf0Opt&~0>wC43Dt$dUUKhDr$)G6BJ9|0&WQ2ZB;Im{}HTwY#6`uQ@~pC-z@X1YcCj zF03L*yLBV14OR%*40yu~=s)1qk^iq3S%6#i>kAeR&xUuDb&+T>rAJYr(@aVuSQJ2) z51_|F-;-rtLdrrh!NhDqacIE|eHImkkxi#rK#Kt5lHPj~imrZ#P;KJHxx2W+T1;73;ktrj$r(DHJ^M385vhKbU5b)^m#`4!` zx8s=E-}IyqmK}*UG2S=fB_3l9yR#Sk?)hh!&ZH69<{L8bg{mzVMa0C&TO4Vn zlzft*GogO%8nXXTiXgEj)mLv(?bfN8hZ}{63-4$M1)&{DQ*iJPVLqW~i2Lwc%jW!B zhw~+qdizZj1(P!?#aHyrV%MqDnOFgm4RLLcXlZro{KflT`NH&2=B;o8+c3)FT%RD*Wk)4NIQ>ZOXyz-mJOmzr8`ZObk3ML2KRmQE#H zK8lX+qa3?~v7eeoA0FTuPrnUBq;SK}D)?cZRL03`y_h%>mEAfsz4ejq0lZ8Lu|FkB3 zeoOicp*WJA;{n&cw$U}B>7z=cyvT85p7(^x?G@8ewzClFI-B)7S3&_c=!gD%XoPy4 z6AXjJ4T0XEU6(loG|p#SWgl3v7nos*H7A(#Ubj#m!o}XJLq|=;wZ1n@Q{ma<^?mrG z!G7#0b;zqI^v^TmaC!j)YMj{QSJ;Tw4JqGD4l1e4`xfR8b*0{-@+xyCQ&~MJnaR9paI0hW2z*Ax8KBP zv3yOu+Lnm5;G;Z~uZUaW*txVf0@QaNnxK)^P$fdu&}f2iuv1I64W##D6y~%e=L`t< zsLF=dm%Lt98&c&~3(pQ4^)}>t%^~hl9ck-+2u@MT-@#%@ zkTXn*m>L_EH|$$AZ5V>2LyEdlLkhKdpP|IF_(#kaqedrA)r5aVA=w)()W5~HzI@ro z_(%R{&Y%og&dTsz%D&JZR2tD~8Zn+Tew>WK(o!8Ej;qL%>L|LCx0MtEabstnfFDKO z%?RHCbg^5do~;@bzZKKJZOMdppF_-qB;N3Ls;4?p!sbr2W{SjWIS0mk(r6tUo5S6+%KA0{#lg2$^>=r(GdL zUg91w>E$*QWX!m}q}GUQ@-H`{u!bFF;eMR47QTaSQAW*E$TbYw#_OONrNhw zvcTAd4r|sYMF-0=D@HOJv@uApxMF%H)qtNLBkTFv|DhyM9%ya!v)nto|4@MJFOzIf zu*+5tk@L!|4*G4|oN404SNeBlcySi}V~o<6a<`)ZpPAaMQ^zi?dX}5k%E}0F^aMmk z*t{*#1r8J2<-aqssM8jY;lR}cv5x3*%bZG-IO)al=P5GyPN}XO9`6D96dcik>gJxW z1J$ysX9+fM1?r=I$haJ~o{qZLf*o5JqivuhMMYYBFiQbvSsQwZFC*RWa$c$gX*c2a z$!im3aWV^SYOBiPkq?X^^_A9#TMke6U9R*{|B&er0o}*wTFIXuGN5xT0>9Nd+KX@*+pLW<}6fYY$92(tm(J$qqj{Vb8Wgy+5-YUzh)TPW|3(m_|%g`SWn zwJF(2l7>~~lz9DJ&w>vfU2eoasc9{o{_6Je&kTL&R#+o5zo$*noZmA+u3PJ^!j!hf zOLGxDnZYBfwYMtuwfUptxLqJynj6M$7;$AP(5U}CvW-9vQ|}|X z^_Kh?JKa$;$`t+e+62~%C|Z0c#kl;myl>=TnJh09fGeTXUzn%(q( z_b1Kwv@ObQvpZ2|AoM{TgWPDr^L@v*XC>_uVbUh)r%KDV_-O-C^fvO1{+Cg*Aq>=z z2%k6lmdB%gtvPeFbCe>S)w(Nym#zdkmQKl{sIAc)Grs;(aY?e43-T$r&+| z*JnMLbM$0MXIaVb8QrxbRIBH?kkI+(-!!<;Bid?WdAzf!R;1x`?SeqGxTDOeOiYc1 z`)SGo!s)MSgOQh@;_Md^&+ZfP0{MkKv^4rc-Op_NdH{w=mb6ix4hTuXx;*Xje>qI!EsG zT=sKaXWVP))=UbcnyM!DT+*w9CdYL^firQNJ51w zOhWYu65o=R-6D3u@HAfXQQY*b$hyoKHf5`u(q}rbjy@ZCXo;ZS+F&FXEu@=mc5N%|IeVw+W z*rYFHqFheBJtOyul5JR?jQ*nw9VaOA8QJl(2rW46Qa@2C{a z_DAD0ESogyC9b6SwI>A-6hT&zM10{eWFzs>^PhbYygn+j*fmC-^hT&(31?ki#U(xs zfBw92pdMrs5#bA_>J-7s8^5G|eN5SKj$QF>R^Zu9B;K`c`7^Y55>Ww9Y>F^HF(9}$Hc zM@$LcuE4irX3;?Jf3{#3{+lE$R-9bS+FIN046hL^qK=2f0vjf|GWOc2v0f^AqyVJ4 zP+G=hUr2;Q$B3BQmSQ9&9sCskLtpn0jv@RvhFTO%0m8f2b&NFOQzBv12c0TMu>^qp zwcIPNtMu4mt1lj146xJ`M96v^MVyjq@On`C<^k)bIky6N-80DB-z#DaZBS@_v8Dep zCcD*x^HcNNF^Z#E#8md0whUMyqMiF0vH8%DB3pW`Jw-r=<4Epk$S9J3s2QgwUf8sj z80@QWhhfHTRSxo zX6;W0`wnRzqc3at*s~d>!mrnJ*RbokaD$5=N0SBbw?^wKU1LglK9Y|_FwStkS0A&1 zFT7k2>1&XZ=35QyPj{v_q-J&Iw+utf8YKyTs0Hz(4qR z$tr4Mg?l50_vvYASH>EGiX1&xm-LADy4LU?oo||AO@K2saFbz7OGi8n7Q2q1s^`I)hf7Ka>IsDqBqj96}Uxb$Qu(Mt?4q0 z5y_Y?A#d$M2V0?BoPyFE`uXotXmZ4hhF(e0bclT}OCQyWsZKKH%+B2ACdaOY+3u>* zrSk^^>CJabIFA6BdZynoq;5SNWj#sgNUVA}n z%XgpwZAtcDgW3{q6R+XjbNTyLW?$iPkwj}Y<(_-td>T^t&eXgU;miAM3D7hVepYI< zUE>sd*JJejE?*gE+OBQLqU9*CQ}l}wkAjSvj6CA6c7Kndt=-?}5&tzqh&05mH7?=9 zb21y)*rwcvPueYp@^{FImG5-g4b7{vaxT%LMH}CqN#b-{<@6rGs~9-uj2waV-=sj0-HLWO7$gLvHj)`xwe zo<=RwB%rjNFn3zYb$gSa$0xdtsZbd4M6GSd#E?L0ID_j_Xf5lP`4G{Ln-f znz;wAC_%Je7QJj#yfHH6KhSu++xMxnUYWv_9B{FQloG|qD?TIosqfyti#aQ6tc09h z^h?mjSejCd8HMy|U4!kJAn#vZ(oCuu8|#_#--ScI_GT>v0cAKgL^{uCrW3Q)8GtW6 zldhp*!o3fjrq>J4HV49PSonXLmj4T;?dpQjw?M*q#D{&EYEHhT(H1SS`$LoaR{0rP z`PYZwa~lFdl!?dV;B%u|ub{l)HD#nH*Mn7#lq;*jrwl>|{ykQo6_ulo@j%=Z^tQ5@ z0b`bdn`(wFFAS`ZRs4jb$k@ZJquSIt`NeLp$NPGlqF57VtMUV}!kp9g z6FS2xyXuzW+5ZKjZ?3B8iygWqtM&VPo_>>t={ zJ$3wWob=gtjN?@0Uh9zY@uTBIvt=R!9bQ|oSbn8wf&7{Ewue>!Jw%k^ph$!+(I{!2 z7d6q`mlxW!@Y&dVoK$oetF&mB?uDsr;|-gyirsHa%Y6{B30y1fIoJa__$3GS~2?7^^CgWJn!5)!Wa0tcc~KyCv7#V4Sg8n11`11S8M=<36snV_@Vc^ zqHKB4VEQZow~phjf!ldIq|{-X!J%uMm@$}gmpdoAn86!#eLBDZpX4*VM>^5 zXE1V_0=c>DSVE2=xQowpKgItnuYrc7;zMx{TW8|JM{9=-DWn!rXE4)b!**QPXQKGo zwU+tFnMYwLp%~4gFy>ci#Cm1dU{9r5MTLUeVBuvWr+VEKcfG4ZYpvU5($G~!fO>d?cXEbHv!!;Tqzx3aD#c1q@t?D{yeP^+4Df8# z{8#lKb-o3%*n`QJp#t9y;FGHcVfDtWc%(`1Gg7_c;IG+1b=K_?-7tC1YGXG#Nagkh z0bI+GBhH<0VW{@c-O0zC%D)hdD2CwzL&aU z_aVvm{H=1DpKmB1PliSX2C310=!aA!ewYS?+6fF;<$hH11i|dk@JAZ>buqcA@bMJEBWU*M=G=5`YK}O~H%BESr ztmT`S^uGz@XEV$!_whEa%gkCscvSaUl@lus%p~~8!y+a?&msV9fui(WzY!-WLli5z zG!?sT=xe1AQfy0dEUU=Pja#oV&b&o`sWfr7$J?*E zV;@(P7BoBV^DE;u8zK^X2##?Wzf&ysMaE%fD;>7wmIs?QEZHi(eM=(DOuqjH=xrAw z*OV?t?fCZYP)HJy2w9!!Q zySgHDJ12UQ_rHJQ=X=ECN(w1Ixf*qM+-uTGh~{eA6l5>vWm77d3JZp{TGEk)44%+}u}Vx{%Oj@E?yNOq2qVSd z^oR?LC|UB89qODY`#yn@`@Jk3#cni~l{-X8!g^(0TVN{=Z76F%p1bWiWicVHl{ z?~cg*l#fH>ju?y&l*=z^ew+C-326j5lN1-Y$qQy)9fZci8pJZ2p zVkLZY()@A7fayRGqlc?J*hCZI+v_s`A{u%)AaclXixc#Nh{2ARkkGxsizr+pE;&K~ zAm{GQz7O|gBf9yM266OwmBUV)w_U&THL~1r4gD#IrQpD3`c?OYjN>#_mU{ZxM4Zvt zO}l&`3E)F{^>ne?_Kp_5qH`u-0ST2(N^%+|HQj&qoo? z4*^*!#3y*SqdRdJ^}W4sts-f-=U43sH5~>E&|Sm|XD21K;BwaXsYiEXk$l@mdbG9v_9 z5F?25U5u-4=){pos_5sc!Y8}O7$i6Hz(o>I=%+naW%mVK2$6y=9Y-2O4RqJW9b0`c zj;)68;5EJjXb-u}@Vu!~1eV0uD+aVi+Js{RgKkf%n&Wzn|coW9@I_v|Uts#VwMqy#W&>qZg;KdMxdd@1MFntjv zj(0SZvS2@`!_Rd{+m~7NPEU(}ugis)IOZ8OxQE1z<~slR%b-o00HKM2K$9@->Pne4 zlW4$|)m{j-?t53^{b~H40(Bh=ZI$D{?3RJ~%ADO5PP|9JRjyZwS?K{W5K;WgqJZumfGvmD^j2^Khy6A0gIMJ00$JUY3=%wpI z0s8Mbf3QKDCTo|+kp5F4qGzxFlfaHof7z}vJHch@STfT%W0rp!t3O|U3SM(8g%=<8 zR@)-&8XZ{cA^ z?Vk+olyQJRkaa)TUU+-KVKN)X+_I5*LQgml-NA%7M-G(%=5k?~Iy(GoIwq zE+ee^BkyL$keZ->nbglb3>vt|KhP_C?Q@1ByD)aQt)ALJ*JdR*yku?Ery8i8m{CYD zte0ML#2RCRWjpU)u&OzE#f`AY7o*r(*lU;qt7-S3VQscO$!YmyaafRpR_rhSle}`D z%J%p!qTcc}B}ZzJ`$EnvQPW6cdzjCMxZJ97_^cx9k!XTv$TMU1(`BZwv(^#JZwfSV zexVTxP86Vh>wUcm-AunP&ttKDVqbfINNvq!w|=r-OZJW^;$L?r7qb^5@Nb;lIRWvR zN+8_4%O=bN)nG0HN%|;_MabSekF*(bD5uVQPtz{#^C7|tIL(WeEs$+~rSnixik4T4 zFBv!F9x*-f|)3v=i)0&CuJk9Bw1Qb&6IZWHjOpBgSWQu2I%9cd&s zo;m&Va(N>??3z$QzST?ulxJs)RYm4G5|ElUJDF!L*S)x1=i!Gvzg?nFAA5~6SQT;X znT=1){d|i#8M^meoyIy{@XKt%?(M4onA&=UeaXAbuv`Hsv)egutyOfdhg4}qB5Mj(ECj#$6QI|(sQQ9LhS$v z?7Ug8M_js^pp#kwlm6L**_3N&cO~4Y790xkA;Qx={!qN&j1tnvfv5%8lPR%@Up$oA86HUE>( zKfM?Y_F9up#wOM?cDREYDr>47DLo0zIf9DpbEf7g>Mv26yj0LW5xK8?$Jn)lL)G{z zaPYaRlRx=PZn;@_^_6k{(eii>?>8{=yu|}W2Vqh09e}c$0mRe0xSg?7D=!w!q*7-A zN>dXvTnNMRr`7Sd5t|u)!l)E@9)6aA$9faGxo@>=ku?J;pUaA0q&%q?1H%;#Cvwnq zkGgsUYD@JKoYlbI7>dhN{|i*H`UJxD-vWHT{Z=`^8oQ09CJP?sZ5=rw{WNfMwl$_^ zB`VYf#6^~~21n za^AemXw`)5QIS?tByh47WvN~s?ugSh@1>AGG*y;|Y;H}87U~NCs9)3h6xKAj4`g#wWE}AM7Vg;#W z?V-FzyVg63K7KUkH=ivBA2Fw+WxMnvHj&q<<06pTtcDA#st+Uj`=P$b`~kjVJbB(z zufyG~$B23vDQN6bJcRU&LKKk&$CJ#0` zQ+qaC9yE-|0tCciL_h=Yf_1{R|4yABf9v$KKGPxsY ziG&R}WIXD4vH?qJR5??b*TSQ|gRR~AQBwu;VWUD{m!svqN@L<#CE;;>;d@t6VG;_W zIG|ksfl|Wc4zkru&{ct!4T#F*n1A(ns65G@Iz~bE=a#OH0|NcTe@7WQC{NB+{#(Ee z-WmFn+L(RQGt5^coSQIqS_sDDmy<$SZxCnjJ=?;pk0R3 zlAO!{DqbCkX(99-_-j9}h-X>iQJov8$3XYOh-|?FstVAm{z(fjB8%7h(Q6RqDKys* z9iM;ACFi^}g_t@Jb+_)_s~v}mZ%2l*C^n=DC>aqoOqlS5HX+ls$_Q5*HC|+Ws`leo z!o_i7^Nc%3k@)PQ*~70hX+szGI~r`VT*Zvc{A+b*9L6KJw+TI=fuf4DbO4o}D=oW+ zA2{-OWdp^w=?`r8Te9^HoKVf5xx=$x%)9Kz2VIor<@G7WOJWljnGYDdVdMyQ7iM?h zy`c1Mf<=^a*#=!&+28#2cJs!9^i8{pwJ+FZne`(rGd_Ud>hSOnM(pwMl^93=+%$uX$kakE2Dj%qtlkSR6*)?clj);aO z8$*1PF$8?NSg#N&&wbyrkAi9O6rI^#Uz|Tvk63$*(qI$p;r24_JPq#iRRZERm|q#I zQN2=fvy*%E^;Hultp3p(AoZOdn1SbO9X?76`|8O3G8_Gm3Z?2;jW|I00sIv_C9~n? zxNI^W0Q%qidbp3j#15>XhDl#0ct{L>kZqAZ~do|0` zqWlPBh2JbVyjFtP0)=L|y5B4IOMNHIxCC^L*ov=kZa0uUtM{D%6&i}vmHxH?3y>@@ zhbjM%MlQWusRC*-(CXsJP=pI>Y3>*vmpmxxwc^pxrgpgS9^s^fg!`Nruw6-Y8JLM2#W@>w*P6Ngx;#dQ>&ik%;Qp6liL>C=6oi;isI-ZW zzvb>PIQ@Bco_incaOPa&B8dOK!v08_-|>&*r{Vx;Jw4y(rk;qhKMfx(b?4rcn+s=^ zB~t?ppuEjTtkh|%a4!aB6WdQQcU|(#a8UPMVwH4XTkEUQIprIo#Cv(|Y*RMLp9QVABhz~8xmUS0 z%_%@x*{pg2xsHTS$N{u#g zW4K*f0WOZ+Uz)S2rVrsS^pT+pSjhaBSqQqdLb!7kuuPJ_I;0WDDszrli_|FJ#|dpfVgf$kP03e~_!g79;siMlJa?ky7iLMX z2U^R?sq^^?0bqF>@6F=cDYWLZGyqaKyghW&UVkhpIFWyMNUrIj|ca7rc$Wmbc$QSfOFyE<~79$)%vVo`K!Q4NOBBFYbAW$ST z_bUXQwfvxz;k2+i35YU;X~erFbomYp9MVS>*=8LAL9>#&L4IrcX-jkSfOg* zu=&nq0qEiYGn+hpa~c%|<}{HmgZHKi{#ro5O9M{GWzEtT!f$ahoaatL3Q59V%am^s zo=aKS!l6@pvv+$tP9Ww;K3(s(hoJfdL=FZ`uY~=ET@mrow{ciR62%>>{VZbg5_a+p zRAUMqh5tf56pnLV!s+Jq&l)jy$0oCM=Nz}@ThOQrepSb+xjg%gDCs)Q{-_n0Rci{` z@p&$H9F+fKfa)b2Jsw>nEbM{CTA^;eCxF8MoV86#UoE+ zJ1|vojaEo#_VBj)Y3n*ui_Q=Dp4yK|v;uG1R_(`}IWKS&>P`1F*ypj$har~Cp#>Gg zkxUVpQV~2|ZoiEWT%Y!gC8r4NJJcQRHEW>5oQ>Y29OIKRv_9Q1u~{$!!kijR5odWAU&}8s(PgoTZ@-0Wh>B<-ghVtl18{egO#_4zS_(0S zZZWSC?4Q83G?|Nx90G|n@%yMAl633)^Q%{xE8N@vXpp$==Ws~^1W8CvzEO(mR%ei5 zg^8%g-dXOtwW{g1lsJqmUaaMw9JDP-Yz5LsnTC@COi$9t`%3u%F4Vu$X54hY9uWj0 zGVY(Xg^QtxPHEn^Y9&(LBsSo2vJN+#BNN@ahx#=3hA>u)Y&2&Rbepjg5!-`I5|vFK zW$QW-5t<8y=+J9Gas50IN0nl!X9n9=t7ysFrepElPTNV(*K8hg<$RagI5;1^{7*F^9u!f#uH$7607n0O}-U^u}dOhTMmllY`f# z%(3M2VGHN5Eh@r06z(-Z;&>X6W|^r{jepr3lZf8Nk&j6&P>3szvu@cPTK z3-Wig_oPIPAHKQ31ldgoEs|x;SLC;TD-j>V`E`kY_#JK8k@%Zqr5FiaO{(iPpRx7t ztqq*M`0APSJLI)RB}q7j$lu?gDBBzV4i?2Ug_g=$j?S$pb0nXC^H5hj-aa8EHo|Ef zd1MjT^z5A3v$Tfu2N~oWMz_E7>RX;BcJ~nT4x-b#62dkI1s#Y)VU*P#@sgGJH$kVM zII?#MCX>D-TA8bzCH1t&$5)8hV<4;2J(k+x6jmZ@gl&KSw_;Ehc({O%=p6)|_X5HR zdhmASrST^eqonXi&X0S>9;xWH@UXBER$sM_cZR~+hBUiYEO=p5@^w4S*sFjpnDw*= z2{dY8*rLVzH~l#)Bk-w=k`v6I{6u??0>VF14zpH3kne6-9Jyn^&}p^!V@}F|gAqUo zeE^@c@7Skq*lN9QbGje$%PK;zV7^t0g*+{BL%QJb4ej!;AVpepl|nh;6Z-{ zXLq#=_OaQ^TacH^ZQ_sFBTc^4m|jVxvZdR6g+NN*W+~p?#RsORpwz!F5Dpr%TK&Cn zTvV6q`!1isRO~#{*DR?47{)eqIOlE)qEqx(jN~+3@o`{*r+$6IOKSs#{?p_GB=Lh*NXn zm$gxWBSP~~BU|bp8_xuBb-6EsFE>bZmc0KcL$c}{_yZEC`&>U!JMf!o22a(i*6?4k zDM~l+crJlyonFWnp6$T|Blpv5vkCq2GskE5_L1klk`KkP ziC?0%`#{$@b=u=4v#P+X&;{mtZFR1ozX{Dm)*;f%RpEj(V~ow?*45;<4RcMk&3L-c(~5v zfIlimMFO(E$4JX?_%uH^P=p|97*A8)3(bJIa%Lmv2{c7SoK7$MtMxzquVq>;K5;0r zJ!LTd_)wYKl4vx2{+4-1$$Q|T^L|o|Mj1#XLpAms3sP~;f5Td=bQhmJc*NF#FI_0E zBdOXWt9FcRz^Uw(Xz-HChu;$UWtH&_=nFuB@jqn2m26h z%LH5NzsZ5`Lx{89Rsr=FF(7NnV}cEIy>1mRoAwx05thnhcRZj`-kvre@;@VxU)_DY zQIV7`6sI>COQCH=V=A{T-41|yA!*zX9d=Qxhl!#8<|z0`ZaN4aoCsRso~9SwC0@Ah z#UTt?yn|1{vpE`N!F`qLfX~Qm7_DDGC424;mQM25LgEl|K+2e8yuZf|@6-l{F1O(a zkjxm2HpIne?*}^MIxt0059b6Fk{>WnmveWTf)C+m z--qi+gR8g1g5ydnF=7pNO=h@+c#mpDB!qG8|FP4mA;SPgUCVQ*ZBRLZ50L8p%tKHe z_60)wyBp63iOR24EN+&Nf}3Z(ya;!QvjSqqANsfzNEXr{RkFj6;L5Qc=aG-ZbC)=q zy2A@Z5U0mYW61E_&Q65>(DXG=P-N@*4T;&@8DT?>_S5_g8Kz(-`YDmEuAJOe6!IdW z;6+fhLoX=_pmDdelJ~+9o0A+ja3*!TVossgn+3e7{so1@@v?3M_yfP%ca%#B+$T5qHl*_MF> z^}#gqlbJHZYq}BB+k0001985Az{LgwA?xSTe^`sq5K^2&Ls9alFfB=;hGP+ohEb>g zvPIXREd)k`18zLux1cQc-ZXcAZ-Otd+k`Y)($7C4%(J4^@Lk{hK7v1HjnY^w{>fshV^{}?|%>R0DobjvW5jWSdgJb!lsD=-hR2w{>6m! zZpyq&;67ZX2+>Rpvn68o&kx;`p#(Jc2z%lQU_mZ;%YmGy+^g~c1dyJNymAPu;V1ao zo-g?o-)|5f6M*|8Kc*ZC$nk`@wvp>1*i(V-Q9p`B0^-99QB&x}(E|Fa_d`1@A&f|O zKZ|iywu^qb8>!yGC6e~LDksUWv}Z&Ufa1R(x|EI68ztm}dNVE9ry94u5dHScsOl>7 z`m>`=+SsV-a7!X4$iv`Dh%1&)Isgki1-13pV3md(vqofJ%}~d6)jZJ0VXwo5->{pu z#{`N3Py=}SKVYBD^Il>8EjRhPn8qJb@HyT;Y2zfXiUBuCxMv*T31CsyxX5lt`g0ar%V)jGO(^ zqO@QY7V5^2iQ+ zr&5ZiG^!P5FYjo`Pnt2*&gIP<$yB+FUq05uv7JITJp5g$x z_u@FtlxSH>Oavir3Q#;F>8In<2)k;dnBwT zc!PD7z8yHaXmI2Y(Y77>_|5*|WHeP1z*SGr+uz#pcBrq3T5n4HGsh1N>FDs{&>;~u=7dH|>u#r?!><|m z^E(XVLtk1W-zLd%RLDZvGj;`Li-L*76V%|NwpUl9A&PNMh%)edt}#<*-$pINJ0pR3 zm;oIAJM3He^I^efW^YwZQhK{b_pi(Z!4amMk4cYryR=6D5MTim4%|DE{S;yKdL&>d zM$4GAtz6aO_1M-Le?Gv=KibRFUX2*rweS1_GZW@4>=)Zv0!q_%(g>Vfp3%;y0lPkK zHSBMQ%AGg}@$0OKRj1|kCw{)~t}&ou#lUxi(jOC9eiDA{+#b>v9r^vk_Nz49m%+e( z7!ZU?NrOy?5gey@-`c2yvCvU~Wl40By#7%2pnplrbO#anA|z?-P);mRDHU$fjBRX&SJ)I zWR#bLYcPa-SUP1xu%&r@OgKJkS+vJ}MG5a#fg{-}L&DLULLu6$2 z2*>x|Y^R#Jt$NJF3e;aPUqCvuPKt3EXw*Gd-}?Fht@a8^r?%v@@$#B$N^kx;e^S1q zxvbuIys?v-!e%Pf-4n0_%d}qji=Q z%DJ|2rSR~KL6z&lF?Gj@0oI+GLem6#%Nxn&KdJ{vfev>4{|NVztBS{I_xMd&Ep6M+sAN}O zi{y8ll-HkBV}82|R%}^eyFtaaDF1lO5=Didh>0No(>&gUJFfcPygY$Q`|Ef+16d2b z@Vnwe=i+-wQJ9v1ai}~3bf~#p?Pf7Eyv=3PmrJ##F!FwL2h*ObX3$48cy`A3KoIxe zR008>9c<}9Aqn8jLYDSJWxJo5Qk-9V2n0B%F%+fKp|)pBJct3#B{YtB`ltAIUt?%L zaait2YHZkpkXD8aqTj#RSU0PFE#PqKv*O;~j^ZNE)}C?c(+G9!ZBoh=5p+Ko=2El^j^f`e0h|IS zWm2%c`hB<3aEIM3v}nQcY!h&fO7IqfpX-qhJUsLtk%KP4>eQ3ZN!*pv>y@YV$Nk8v znQYiJRbJE_F{ZZ8fdola+`qYbG7ch*fEW-11t98YrPf3cW908(08&POl!{UR1Wo+* zu`hz1@15KyuJbp*%k`C+G^}DdwTBz&Z-D-@NH=|!>w0(?5#j`>3 zvm15Zk~{LTmWrFkLj|vqQX|~vEcO)J%sSz0vW~t^4943OHSr_bs`&t84+R`| zFCTw(yuaR@*)nMzPGtlAatkD3;eU1@27HAcO(V{l#7}Upi(|5v7@2U8b7it11+2ET z!9a&NUFEq1bW_a1QU_vA z)F0k+DgM$)d9B(YI~7!+0Ss+2W*Mv6VosZLV%~jCjF<-mNx-04cs{hRr$@SS%j|Q3 zy~t!cNy8x3R4w=1=kyl?#3=epcturvAZc*qa#-relCnjFJ4g6Z0%P}7dvzsDdbEYX zc{31UVu%z-j<3UsUd5CPJ|l|k>jB;rP{Zw#-!#asoS6FnSY`O!(x#T_WfCF9yHz^TS2jCx zHctnPzZPxpjBXImPFd{-@{M4f&w7sXA8T-|L+3i=kk`cmqBKdazCq2G2_*!avGbc9k|^^bhu_GD zhey%S-ayLZqDpvFgz?nG&B3v<8GKz%s1FR^)_M3d83U&|bAow74NAL9#;J*Hzd7*e zlj}?7^eDKtWw1lkYsHUc*H87B>>@!4z9P@JwZ7QcyJJ$vEcGFB#QCO-f#ZwrnjILS zZAjw(uDF4bRNI1#!u`&-iNa1KO$yCjvKwflTp6`oZvXCCV}y3J_e*ll*J>-CrjaqY zOVmC=X_a}Mw~i5Y9-K40sMFT_@#`s^@cd!eus#~Q9Fk@d8&tkz_!5*)iCBATIqSDeb5kTpOc69$#NQ z>wJFQ9SLt6TTWKqY#KZ}t=qQckE9AEr+eAGaM;-$$VqTWZ&BHG1XojF$!+V@l1EMD z#)Qp-XSX5r!LmgW%QnfLNx816qFgAnYE)Uv$1R;*oZ_B5EzVO}a&Xb?mha3~dI_a$ z&0RJuN=amKu=YN(m&hYbo30=#COb5(AggdkzL13W5DHbdf7?}ZV-I6;AACu-ZjaDe zKkD9vC0Dhz^M~5^XdCZ8~7<7D|==A*8*-aG6SdHzS{XQ!>3zlRUgo(C4y(d)i5>!tPC>Zz5ATy*5tA&Pm^b&G z_bt0Sq9^RjChr-?BupOrZ!{n1P(u)m?&uL1jdzg=JV&qLzAX}`c^O{Rf)FNC$ z6jJ>1x>WE6-Itm+@oJUuq7&P;K8QaqcvwHQk-gYR#d~+c`KODL?l!-DQlw8=+f=GOV6GTT_@e{G>{dx& zEEIOPYuC?_(s{s{P?$Q0Kwc)ktd-Ty`^f?WDw0dXDhy(BwvEcdU=px%z;E63uNPyOPru4y*2PYdn_tQ*qnRPQzLhke?k+J3^l}Uv4y6tx-SNGQJ*}aA$l;XR0O)ob?0R+v= z+vXcuk*VTD8fWv$URoNU}kVkSSykWqAs+<#@&lC80mD@D8~Xp5a6P7uqs+^R7XbGDqL4B>~{qX+P-rf*Op z*Xr#7werlVCYMqPbV+xar9c*AUXDSu)f>t6sa~rl=I_a}o3#3b2VtdaK|MHI(QfnQ z{lr{%8j1uI^W?H8TYXZ4j4e$C2#y7?WwED)(Vo{@mmXa{;=awTbN916#S3p)myMEC zGMGjL$OR)BDTL*cxn?0JVrid!$?6WV4M)nZ5pq=1a&WU4mDeqNUP;s7sul{iXRa;k zW?1G}bX$6J@YCI%Dg9G+9vqd(*OyjPUT^Jav4Ba3mc4xmICbdDAx>&ZPkEWtg}OPK zYEwoJJ&~9C!ie#f%>sf=U?RD)fmIzP@7z{zMR1Z0|8!#dsZHtNyzaD!sCLVHj?*&B zX6FZyu+;EKANS+|vxz3Oh4~7x+<_<`)5Dwi&L|f^aFXwBi8(heWE|Ni5a&fMcDmgm z$eQ$LhbjlQ3h%i>X^gGFZo`Vqu_W`}m1mpXbQTbZ;34Kx`1^Qi#_Qqh?(+n;Tg0jP zD~aAIFL|JMBLA4e_|y{*ug4+bt#td1zy(huVh1gbxZ%FD;!((a-+&q7LpICsP2}Co zLw$Z%GvP$~k^ARYkPox;#GZgu-=>A$CpY`tJ$iHQ?iO zpt5O;7A+`Ap7>TY00c&llJ_TA-(>p@%4Lx+4^~^_#w(op+LH_T=H=3$7LFUZM&MxoM1ga?DfuW2WCDC zY57sIWt$e49R@LdjE_BUH1Q&NYM@r%dhlr4VyDUZqRKlLTI95#$)0sYi-_zNf`>?q zb<7y^=vCu$@pfUa=Me-=GcW0Jw%H)nVTxKF5#et6jry!L-hK4a9feu9hYHdxFqQ21 zJZ*Hpb$u+{w(}0W7$zTj|D?tf(N^YBXUh02Wgc3-ywYK1>o#O(wtqWmKNaPosxbt4 zs|D)VUMgztAOAdn$ZH4N%e@VV0 z{|p&ZIl}?bJNlI`3(gqwZc}@aZcV1G3V)TJ*LIldphTk8-~DiFs9@8s!mEM^MMxhm zvswCu2&n`fMYZ=!sD_5ujGXY1>w2UNc-L3DB^B~nKmTIoM1!aE=WJbEl0CvK#a?s$ z=FoMy=RS7rBVRCZ=%CfaxL&kIMb8dWDl1gm z((tr+-&}ZZLREyaevil=xK6yYt~qQ~()D}*gVM=c*1xVi%-@`d$?(`>#z(>O6{S#ab!bWI+Zt7Ma_$%+ZH(;qHYZtUu07f zxV5|8qRkWtIxDpPcFN&H?nq^#x=DeiQxn=>o+eF#i^xQ@{5FO}Q1OX=A>#vw1So`S zpS#>*Jdxdw-j)YNUx_9-8R0}QRLdKtCfRg3mAMhvHF5mB%HBkC)PFp7ak**py%A~_ z6O;z!D9w^{alf%*==Ig&1B>?TE|Uw{Hg_-O8OBFe8Y>8$Gxpp^5YMQp=+(U|C>eK0 z^y5d~#GDTi4lG+~uF_?iD~;B!hHtzCcu}U;@`8V=)i%)_leIwL{PfF@6f}2 z&1REruxM~76|GrENekr0rlj;3r8qk3sfph@m-v)7?hkyGQBX~*?b-m(H3dcS?rSL} zZbyBt#Cj-p=&yBo@VvoSQv+dg;-%OAF$TyzeQ+ zc)bZzP5A0KArYa?76FRUvhTN88m;L!nCfH^4}aA@@c|-MZBB}IQGf4g zc5-}|^LJ0XQ_2f@V&SVAQBoek_MmZZIO=n4quA7g5zS8?Ki+-7$SYHq2N)kLHP)W_ zFSS?2O$iBB#=ebTglG`r?~o?yt=1SD2&!-m_Rt)mUoV<`;^a6Si)3 z-oLetvdzcxV?JZ$=dFm&bCwg8&vTU%y|`?1Nx*X^DW}I2TJz+quJ^fnd({jQatHMN*F6rt z`QVCAj{u#ly<@D}gwG}-PP+5ipeQO{B%5>e*{IMw&?3w2B%uT|H}$ z@zq&&rk82MSWYL;|dxpr`c3qECrRqWt39B!gH_bKdwc5w~2XuX2E2}Bz<-;I7H#6>RjJiy7TdkR=Rv3B` z3r*uvYTAMiui7a07U-?FfB0DeVx5nZweOOY)nhtQ_>>2a?Iv`utg(fE$}#KcR$7i- zX;wW>FrXRVXN^-Axzm0(BYos`&u1?Ym%g^J#l*br5BLvz4^nZ{ZetwJ-{^*MgY&Y+?G z8&8g)vJIY=FMCtxpC92y={5PGWr+kdJA`)~*>w#G$?z_Ub4;Ax9Gv;7Qi^(hkj+48 z6P=@!2Gv`oQ&F#zl>JdSxBt?T$UM94U5|}vF??ZJ|4=pKboZ&R!}OPF#%A$7QxYi% z_F&9c-w(>YM|HkP_NzPCA9-rxaWl(&e6FEii2kl~ulb)QKJM>-Hs751{?83f3_73MPsPg)3EE$m=~pC~qi|E#a`iYK zBHs|?5M*&YNAvcKk|W7PNnaU}qJJoAom0!5=W<4;sGT3w(ksgAt;|auYq1GQWjk7s z#--c3uGvr4F*+x-Z+O``os|#T?ihcx*~(Ma>Bbj#ZF4Oz2A&X3r!moXT10nb6GvRc;QFalnsVz9mW`Xi`%Pgc>PhK`1<5lIyvLj z?w^SyKE7_N@i9-kq_+3iGR8K2{J5wSvhz*VJT{7)3p;Vm=~@$kh+N0VVns*uT3(*E z$#GnI`e|KtLWts3mzJt4W7H`W3oV%-PE38BbFPqNtJA}W#X~oG0UbF<=FQOyQ<44ctMe@n<2gEZ zo!~b2;@Z(YZ@%?Xd7dDCl5F6!V(UZ%dX;qL*=i*_x9{b}M^|2JA23F!X`db=W5+(1 z)-1D%e&f}(t)o`CrHt*!%VozaGA|MqG+HQU$ed%urKe<|$2Ys5OB;E7;msmB9^v!* zl9|I>!!>>F4FfMIOv@Twcx=oi0WGsWJ$VQLql8SV=o9ty9p&|sWq-uB-1UC3*m$~2 z;)Ku=TQaV5N>u!1&8n+Qsb_#VM`h?zf~tS$RWE*_M`BLHw<$O*Rq1=a!1CDRQ^bq3 zTk6_>fNb2V=sjx|#I+siII=iEx5xNUukZ9euwa@jZ)$wAaan6aKZwuin;9H;%A!=HSay$Z zRpc!#D{@hQhr5q+%06iNG9dcm)2mVm;>5nAf_h0uWI9nQ5okx0CGcXCtDl;pe6AR| z=my?u&&ctlVAGa<@Q=<7`-j&{k%cC zac&ovjh~p-eeV%}${^0CN7dx@lFAAQcq1_2xkK^O({V!Hk`@GiQ}V@CRYw78LhzOZ-_eEsL zEz`gFF?N4P!tAK1m{Dj*oK2b7bNzL4R5jvUAB(s z;5M2AL$0o(+@JlelEYgMZsEM=g;0-V$-R4b^_N|k*Z0zJ>kFCdH%1RV-K5I$bzJ|e z8dmFjkEl8;!!M~~DSKp)4Y`GAW^AC1v@Fa7H(VIi#a`0L7_ZEF@H*em4tf{!H~N(V|aV1 z-u9W$TgGwZ^7&=sv;wMnQk<$;*~tU^n+>{s=pm>-T+q8$KWh{t9^K5Ut=4W|=g~Zr zqEM2a=$_L_k7nEQc@>@g)+!8*Efhw9x0ouWQc4JEtt?KK)Y;yADr+dQp0}MCBd=lN z-j7n8QtwRU)t4`8(*3OeVcyBbZ?=_4l&`m*W_x0gpb)`J?-QE_QR0`$(_w+N& zGa0qEnK9$^;ga3E7v@gQ=d6*qXmlrrFOkyS@^Tr;1O3mF14@4Vb3?Z=ntwHQ~0O;HkJ z9a7r|((I=?v2C>`1;6y`zOdZX*lv4IG21q0GW+IrHQ#kny^ENgyi+21#pEcp)yz3T zwh|@Xj2^G)W%n^wG$X4dt+@F0rQ5Tp)bi;JvlODJzM3R(@xGLh?aFIY2VWBln607x z!JHC#)}}AiZ9B~{eg7u+w2gk665A{Xm=(z+o}Vbw=8@Wy^NRP+OrXk~DB{^^!Y&8L`sO7|0bQ+A#_+uQjFrK(=rI+$>+@v{y;NV)bg=^d4K2w(V2^>LLk)efJL z<2~|S$>LC!HSG(Lf}z{e>jM)|6}99^NDE7 zfj!@>R#6R1^Yv|_W2}*u?Vg<0C3cfsrnk#@5N;pmbm%bDCn139$nYnqSa6~l*8679 zUNz?J_<2XgB+nU;mc zf!AA|I&X8MafHjs{IXk;i!@eh%#l7$r3jA`@woNNmDw+ZB#D!};V47#O$rxpSfV(3 zm*c6EqP;GLy`E0AajL|V5+N~nf{kL(ApS0uieV2XN!!huKuhNGiy>0o&%W@A(Po~x zQvtTaa*Ln0Ax4YZ>~Y!ZNBr}xhQ-GhYY`Vee(gY8%0Fv<_9Z0qV72g30jWI|JFR^G zxXEPUgEOyO(J9xrYAf|3C{aA&ZX*i(zx$|QU~liYOjTjpI_1K}M4g{_b@D^u57{xT z0|+L+VmHu;AYV!~r%LWC+Z;W@Z#A2u1y+T-aN7Zq)8_c`)08OC8mm5v;TINPb)Ar;L!jbj-?qkxgHp(*>)?^QuD>Q{_!*TZ zyfZdw=41suNR;u%1$!A8-tbsB@X||}hykHpr-rE%&85=Pyu{8$xy;8Y3n)l+s$<@R z!79C5D=qD%m=iDD=n%!}g(nHT%%4c}!Bn@|bY;dmM|Vq$_RKJs?pA)crG*@Kj_lr9chjbz{AP!`F-?}q zJTx1XM-@zmi`!GlG;f!Pi7Q<0y$O$=+NV9Zuy^~(1{nzj?p~mJdSTbiF7vlM=uzz^ zNk}iatY5T{lD`T4nKjl(?fv+S%#Gtj30_%CeY(Y|k_t*FeKamd&KuRyUio4tlAuPX zY^VAt#N<_bCGS&I(PnIn$%IoSuFXg^m@Rv|e}*Vg8YqTqcfm0_@I&v!_TI_C%SCp1 znn>xq+(wyyBP)(k)vnC3Cd)})5l}+YqGe9I@Ugu#R}`uzO9#KYqp)oC@eOj}*3sJA z7{+4ReV<(M?S>s6ZtzYqTA)Xd_~K1Mf)P=g3n*Kc-ah0N<-Sr~;uQ6KQNm<*%8y@jV}}rBfDg7Xo!#0x*kPK( zQ)inUP;lM;LRKDseXY@RQv*YRio)H%nG7KSyFv#zU3tm(#7V)M_n{E z^0b-KsEkyq)nGlqt0#YIY`XCCnZA+)2-)!oIKEQ}&4Qvh8`LvJZKfdAa2W zmhR8IF72-D?Q7bsY;j2&-!bq0apLk;_= zELY7{G9S=$;Y@{_+R24EQ_r`L6)C@MB&H&NT#!6fyCs7LU-f&|U!JO-ny+@VY`XnM z_udmMsInAo3s87P^w{ZKK`J&x3HwHV>lBR>R=hj5GFT-*TF08$<+R#Th}Lmc&Cx+R zVfKv+*Pfc$UXXcd{ZygCbw|kUhuYa~jND82pKzYFxPN8Y2O&|jJ!>BHg{G^jyqOZw zk)*02*>0*^1m03f%V@v0NpCZKqWR-Ckb6j#22NhOBgd=%QpM2Uu%l$bQnDL%28UgJ zK+sExMM<|`#>|S(#Rhn)3)e{<0P3>P~9(~iNU&sS3 zt2TvgN7HnFOZ8K$Ytj(fJ-el~*W+@=jK~wjy@}ZoLB(-iQenji| zhFzP^^M~5BR=qS!bk&FisuE5`PP(OQOl+k@6?=Vr4xFbXQ;PJHLv@VEQZuGaQ&B^$ zHX_^gbQ-3SAK7!o=%Po45*cGcHg8O}_ScHk)zffryhAJ$IV*Ku3jAxWHVw9FO7u;y z@|^zd_)qiC8L!^6)oSM%wqilo>{_&+;}W=uxijtM5Xrt~8TKu_6$j8ZC91`haXpHx zsM5~R1h#!4_T5DY!ko+hwzx z@nNkCRVvwsr>aRdTDAU}c>7r4z2y_~-}Z=5QP^bDn*Y(|=3~$J-k6hgG|u4ukYb7r z5d>PLvv8@frlr;C(Wo8i;v{Y(R!SLfE5wuH&j-BT>2sk#Dp<*>bYa?c5r+Yro^3Er zpPVv!@z`sxjSn)X`q-&=eCserrr(;J!lA7v?myXR(DheI_u>rfrI$B*_Ru_ok_s*Q z2@l>fx@Tn6Ez5+>8+SZ3GktlKic8!}izyDto*`;@w?pQGL$^jB)tzEsU(R=7!12Zx zhFok{nL&kQ6q{-<;C&!s$Ith6;g%$Ey>6rV?5?|>L4w@;$Hx+8yWfqSSnemW<#t?* zuP;^hRMyW_C7KD(G5NJ-EoZ-@y5cdDhJH-4ij8f(zvV`W#`DYVHc6%*Ytg=i?8O%! zvU*7SHy`WKZpWA=H~Ah+(1|n&lok*XY(3@Ttz*P&4Y@U8Xl8MqRpo_j1QbM zi`t$&bduc16BI?GL8d|kBYHj5)73Cl@6+R@-SFkZ1dc3KyxNKBc|#^ZP^pz7pK1GH zV!bByikp!Zb1-3Vn&7$pis~ZiZNMHzna3*6CX&U9x#ugj8jC+~Ru=lmnHj|s_26J0@3LfniCz=nt z35O>8D$`Kn?ufyZ(n_wgv#Kp${}UrccJf&Y#V^=9D{_i$=CjvULRL$A%#qn5tMly4 z_`dI3o|~zt*lh`4-^)tP$YDIN^u)Hcu{}-;$BU(3zLynqU7HdUdf)H(VS5{;u#(5p zEp5haEEg{7*(Rpnu4~Q5ou7We7IYXpr4ZvIF27sUf!Rg=D}7MUt3V*hLlgwIVR2`SEQ!p z?K|V3_OZFr7)le0dT_|CXhE4tqj5ZKwuC(io9aB05@W2dNQPhd7@j!&^l&vl9W$y~ z9kn#yi%)QemuLBb>1KNyNiCjI!rOo7!psS;oDW|2a_MY0QX=ieqznmOWuE9G!=Kzu z3kv7EL^QKlu@o62r)C}*$g?9LTWNfW(d7OQHs3(OvxlqlyK8-9oAhMEHsHI%g5sqi#0!{9g8yXkj=_I z60=26Xu5d+f+hYbpJDL27{)$3^dj`8SlX2K2 z+3W1kM=@fRjh{}Vh#|S3Gt3==7@aY%it~dnFe|N>2OgI5_G&SHbfl@I ze-~MYLlVTJp;9H{fgTB#54}A~wj?_HR*f_5b4>+sPJ5tk8mB5ergJl0tAgEz1Dkh{hqe#C3#MnRc5^#NV`@kCG->PKQTk}=~f;J z$v?SU9uyv3LOYmjwf*R6o<7EacIKkgzc;tW+nPonwWd7dgUdsw*d~vf*`dR_lm~~r z2WYOaOWrd3Y_s{znw2RXX#JG4NlAR{hvjp6OurdU{$z}D#irSl$Gz&=YPV|88b={N z;YEYT#*X?}OogKb(q(rxP88`gFuT(RuVcOZhG&?M7MN3|GIV;TXTPV)JgpH3D{EUC zHmlJE1Fe+MSX{@RZCr8snQ?FXq=OeFRTLU2-R!bi z>fJl%D&r3}eR}S-EpSWpIVWQgBdbU0`5vAJoAT-_#7$8qxRokR-PIKmQ5#6X-<{rN z2U*rQQ%^sdeM(Dc8&s+&Q;lr=JzM134lVwLA4;i5a7Du&S<5EU%wd~WByh+$_Q^6tCkvG(M% z*v7ltPRSIqU+ys~?OdC^M1dtn2!VlAP@o_2Dy2kxW%Z^CmQnU;kJE3?O{4r8?4m>Y z5jH6nHm!Sv8n$EZzwWxQ*@Q@s{zF=t`FHGYd^%}T&-CqU_EHHM<5JH=`yLfC0qe(Y zdg59>GQ5z8Tg2zs;%$4d#q3@*heBdpln=kVv`dobSpP;Hnyez=Mqws@VN}s1qbnk_ z*T_aK@gyeQ1vkfN<;N?py)C=e_CzmHT|1dz={0MEr)HR{SG2GY&2Bz_lxKxN6NNmx z_vsZIR&a<4K}?1GW5W6_CB8i5jxlKE7-g<;U}0~~gM_gkjM|%Z)led4Ptuc-8zZ{Q zlT=&NyC_FqtVrjInfj2j);(jrrxa+ltL${OSJ)Nb{+rTYFA2WnX)lmICRZactNUJ$ znPcq=)oCzOVI~6d3S+j8Pvpa-d;xFWP%)vam>GQ?#x~6uI?1em>qUW+cq#mP zVArhGo@#d;n|3`UVV089L;ct+%^iCN(Dof?T-vT<-j+xw+~FO4OYHXH!+}G2)gf8< zD>|O=TGlg=Sc3EgLXjHpRXa}TuGr}oD#7YCd7j(&?WPu6?uCay^ zhVl0H8BOxCD<_Fv%o#b;F_el3C$w&{rLnM4^DRw0pEgM`pz7WkP@ZyYpuRPNmNBJa<~oEI7-RVqJi zz2d=F$J*>BD%1Uf+$!dx%Y|pkkBvR4Hpr++?>KTos<(6tH&c_oo1UvYAEan_ylY~K zEt!=%nwz91w%+K}ZMSY-0)=(96i1VDOQz-RG2wZa+TNLxqa1wxW|i>4s!7wu{TJ$; z=YKk8E0y6##k`CSMTaH));h~s=pE2_KPh8Cr~d2ApEMm<(Inu2o!)S%yK6Jd&o!bX z=;Db2`SZ&r`Dz}P2%Ih;TzN#TQRVi9&5T0y?SkIj?6$*RYxL;y1!`+)Q$bB5N!sOy zig>*1Rk5I~t8}9gBE0%t(mc)O8v{{{v#`uwskPg+WP8>T$>bcJJ(o9&Z4a?*J(ySB zX_uvkT2F&rOLZx5+;%M?#h+7d;UbUcfljCDSL8`c8 zMUi2PK-s%|!VAi*rf%aQlx%>z*hd$~4wPu_OOb(o(neJsXkSs6)@8v&f!WG;uU+qR<}kxFZg*lKc8OUVH#RP4>a^ZLk~3cKtm5S^gu%oH1t42 z4>a^ZLk~3cKtm5S^gu%oH1t424}4<}Bo(AH<&_oR_^F1||AZd66YIgucHGV!eszhd ztg8AG9;x9OzM%)KLhdlL9Mw5LHgBB2;gb!g{s}z*xv%SahBN+<19xMe{|S%P@C@J3 z10TzZ88x?~oH;P()(+-H>g#X#bi=8CLJ#B==QD~AjW}~)!JS=9Xm;G6@L2!&Gr)o> z{7p^iWby-+I_q-gz%mzI27W<9t9uVT$z_<0(G2shwCIeIn z?4tL-+AaQ4_k;ERG>>7#0vV>455vS2|5CU2T{q+PHiUs40KY)>=@AC@K|}lhJrGjJ zFtbA#rqMHo>EgvOZ|MI&r8&jD;NSw713Kg%lvS4hDUbHU&yiEcFsd;O)6|1ucxdd~ zdNRzbf*-!@FLwdkP#2C2z#ITRRP`Unhbl?f+mlJu#k+dkG4=!e7{)9Amm9izxgp?z zrmrslH3u*s{;Ms4RNyR<^%!&fG@-S>J(gh#ep6e&uHy)~uj6U?*BpRe_%F3edf0Pm z)iRzP`w_1g#`hOo^YG!XMn0~09KR6w5ZQsy19NU^FrIIN{}WRnrG#o1y!qdnhrZX2 zXP9D4ieIojNqWVx*=$4a)%)GS4}?F6Ik4c4CIdh5Pj2^e7^W+io)>=kd+7N~5w4s$ za4UwCR6RG~L4P_vR6=W8gYv_?zf?*yyKT-(;l8e}9_nU(YjueB7)! z&iaQOSVMSmcJZHs55<#>H-T^*R?l}PpZ-=B!vN#?omxdzC9~h}0yFRSPUcm5M7`fS z^greo<^b%1kLABVKJ<{VTZ}h5_ERVX2L1oLworXWaH^2FihF+w&-gaVc6|k+>SBJUG#oREC+lMj6Z&k_+KVD z`FnL*Dc$Y{((S-+G4{Z4ACTSmC$+qi56pVk{T$mpvxou}_1J(90T*QF!0&_)y(c(( z7P+ykydO_`Kk@fhW3`U%yTWWn{{CJ@}KDzvIQY_iq_lXB}q8v*S#0dHn{cKa>?Qo1dC;=D?iW8nhn>0j0la zgG~ot9_t<$?lIE+zn9kf{*GmRH+?Uwdgpup9Ut2DOX5S2@BMwN#~v}e`+u0OuglE9 z+MG*k^oaiz!inow=q2W-ap6OH4ERL9N=v16KagT|SoeL1rxEnwSGlu){yrWg_;Pf$ zb;#X%|MHNmSi*;Padd&)y*(5w`1f@IY`u{Lg<J~m9oM*>*>g$6%f`cvF?G|hnw;%+oF*gRFtnc&-;Iq)cv z1Y6m{SW^g_JGg3(7(M`AOFBN zyb|%~FMWWyu+`0siOD0Q`zJKSW%EeZgNJt|quQ?np4XRbzQF&mzW-8JBmYOw>nw-! z`?EOzDFqpf_KVYh$pXwb*d9gY-=>HwNR}tjM;s|8W0=S=E5jLPQc$&B2kfo|r7rQ& zc(cCUP~vI8zx&fUI$s*!y1a*RPy8y zinShFKt?3RB~1RB14{^-ycqtFaZP;5sJ#wjIzCNgTDfI0(*lc_)2Zcz&HrxErF!fv zu1jIf%%`}%Us@Q~tM&Ki>&zHV%ozC};1U{mTXW_?WNuRZeaWXQl~j~6;HrVAz{-N! zj>tz^dC!0&pLTkj;LOdFK{uJ7rK{@wLF@5?EAHuY`U)7!>r4`m_1Ivit$k?BEF#W; zOS~6xJC1V32C@F5gcsJgE?{pR^uH_FY0v|*PP>_>N&XZwvf$){!S;Z^0AKM~fCDGy zvw|=_;C#p*KM{0;3CxK4F8(oWHN=wG6&x5hY^FwdO=B3ullVfbL7BTMN`ohjwM>={DeU~qd zIdl$mHrAaUje!H{2XKxbksxPaGAj z`yP~w069>zvGH6yGw_u9;&_463!e`<09;?_e&hioAN<@KCk8qf-^u-h_pCYZ9b_;! zfcL|X_@{JpBkrUY~_o3FotFr3_C z0!Qkh!9Rmsu?)V&S;yRCU6;QxXAY1q*hF~3KNa^Wqp`jg`Q$I%i2K}19N3=~bEt=I z{_7H0^AicnWXB!+B*d>UC%)G1k-x_JO;`ia<3HNq2f!D^wW4#A|F+h@HvX88X{3*U zCH|~DgfBf`>W9p~c!{`I=px9i`sTiU=^pC(9>(_|t@)Ou-`TP6O}IAdihN6RBw5FD z@`307Xx$E7&$AqV3-^HBuh})^J$U7aA0F_t|C>LC{+>_v0$V#qkFImn-{D&xrC!bj zVh9<8`()=UYFzpMgq)b~y~(QOUIDOtwgEc^cEo)S)*E8XH;7}R^k_flRLn`N!TRQ&vG-Bi5qJXT zDJvhP$ydbxc>UjMh+QDhkdJH4cc2*NMWW2rLEL}#w((i+ybQ#4zb7{bV+(%|I3Vmw z?s3K6wdMc9@2Yv;M)DzGgTa45gD-(|fZt%gY$yM5pU-*bIAKQ@Dc0l?=gILiaQ(L* zvN*b@zUtEYr$;htUH>;n;om|&{L{Xo6S--uKhMhh`EROYmYh!d!C!0+C_5I$zINYi z1EZDz)(K*O>~*-0@VRO>U=ZBruzw?lgtdnTjD~%^E=TBX*zuTy&}n;#OJ+eB1aM#E z8lYAsa6;&N@X)_D*CBf#m$+jN;3nYnKf8f@ol z>n>T~|3Qai?bhb&)rRl6QND4_F$D(<93aH~(J&Wlo>O1{W4^N3;y{1lO~}JN)Yt6uLH5-(l8*TTnTrPbSaS?uA7U)`dfWWX z-^O>zP>m4SSC~79AzUWA6yLj-)+GK0PW-us^DuXj!wd`p{3OWs_a%jdJ?C-m1-S;% zdC4UE<2i9q@Q6H9gE`nQ{8neOBW}ldaON*~1;|ZA`~r3jFm1>*%s;%I@*#uS!-;cO z<5{qKFjs!We}b$BKMlMUcI;ceU>GA3LH~5F8Tyc$e|L%cqb?0Gf5=qyG5%)fP+gAj z|I43H@%G;iV0B8CK=@rtl?=nU?- zB4iQb3*XW(w#G!2XhUPojyv={_-V04-*Tn;J@+H6A@n!;9_#pKv|F9N0Jb?~B5d=z zj63%^(7A{sLXMz;Ps05^`#1P3$Ps`o_r3mVT^AG))4DMd=c>! z_>$-+*xsAzI^6mI_C0hwbUyG$aQqNMf{%xOhra+D0{za8du>OI5BeYR&7Xl0Ko(+N z!uG>>LpDKI!RCN3%Ic+H`hIS^7rO3Vyf@ub?KX4(K?&U`M#GLf@VoOAlC2AN`?WEs z&-bB|!Sk%113NhJd-nP{#4&(9TJxS^58?R{|AAk~Hee|17;@+S1M`L5fIdYIAZ!o~ z$~!(tF(J$+taJE*Y&|jd8a0o2AJ>JhukQxV5axg#@y}qxU>+!uO@MjFwo*C=oG17} z?7hKWtr=^7L2)^jrwV@#@ta?{UKGZF#X-cKjxs8d<(wP|)VG7Z0^NnWcOG2vM({!~ zZ!izA#$gXapTn*|{TIv&oC8}Q`W12lIv)*rMr{A#byk*QePe8IM!R!tF|0%OJnkc8 z3%F>o)!EOoWAr0O#56em#(e{h4G9ht108|> zfe&||*$=%?efphkd@`!=$I7B|;>fgcAPhubb^`(K9S40I6Y*!SW#wP|y#cgzXQaf`rf9Q%cRe#klK3)c3* z+y)o2KH{zHcl^vF{1eo##n`qcxpjteDQfC_e19pOHzTf{5=7`~r3x%XeU}Cr>i`Ea@3; zE+qWV@5OQ;zYtHwJcW+n=G)^Ly~!`c>+JVK7Ggf*yGa z+fXa(OAT-PQ7luAFpp*)f7dCUys9{QB)_bLF{ky!t{t}Tz!AateoF(-2{;e@ckY}r z@KVvBzcJr{Eh5+Cd-GQy$26axDX{(EK7w>fn}tX8ciG0WxG1`MKP24ScTVj|^cTkSpL30^eoFA4k~YEU)ylH}sh| z(BI&}!&V139k&XeIBW&*(17zmSH1fJ=J=UQb6$pgf*u0r8vIiDFTjv7@1QGSC&0g9 zp9lEDx8Uqw`tJIE5Bn8hT#y(0rIt_QI{cHK03V@d3ne>2Ev8yFaE~)=M&x0Fs~AIg z7iE0qGjNT6w6S%tkynVgGjut|&4m8{5gr=!34CD8Cl<#+f*Yp!+h z7?#jHsckO|r#H`4j+zBS!Ru5YC^eCjR3 zSWpVdCQ2vc<|W{~qa-Kr8NGz+Tx;&Nj=zC(!T^252YHmohg zY`zEogN{ay9I#5rfA|g={cDb8&Hpi0_^J6i*1iMXM34!Ht5Q7Isp8SucB>H6q3GuktrIYPGO*J?4sHe_)_ z=vm+`b-@e2cE4Ds$Yliv3I71GtJ)fJ*f8dZd4QvU_!ldefMLL{1nz(wDQ=!LaLQk~ zy(Rt6+IHUgKX#{>OYjj@$nUSoal{;et%(=|_k3V=O)GlOF!9T^n!sH#=h%kT+#z6o z;E4d!1D_0d%=b3f@rVH-rUxv#CUyrI#Bvs(H+B&g2u=*k4`Js5d&C?)Me(aI$&~NC z*ZTY%>ff?s@I87R_kvgge2K|H|9@;T*3d1rjXCB+3sQ~j_u~jIEQ*l zeust_Abc_O{cFPVzNKNGq}}m<=ew|Di7{tw3idS|A#31k+|H`rKM(mYm^s!z1mF98|K{h|_zwDB zp5!ma0_zgE{Z;b!fbS!&!^#Qn@&3}^me5gP3_dybw!(S`pB;7p=EC>ZGe)7 z&YEX!Kekpa^Z>>mcEZo(tJkF;>gycTUxWMy=M(;WZ88AdR@BlrCd?4$)kU_~<^J&9 zsBeS$HIr<_x-{qk*x=9usDXpI06z|Ul>?`PKfs-z_O)xmzJokL?JDH5BTlsZ6Q>dD z9{6D}#r)Aw+X&+iSp&@HPim-}j9S_l3+Vj?gx^6w!(Xgxtmj+%<0avZtnIix_S-%U zdkr`oWHET9;N-A%rh(al3s4tM7P#pcQ~Y4>y|2Ji=XRveIPRKR=(*7gJ6NLOg9TV1; zz~`{HE#kZJ@85Cw?x=;u;=u3&QGe}EYwZ45s7LTK8u%sHi@`9ly1p4|9954!VF8bV zC^oa>Z}F5Lxd*I!;QomFLQjB~UXxRRHO_Lnq0fQwBBsmw`IrYae}Fq&A*}FEYryl^ zdL+nKudjyd0zW`K_s`jxl4SSo^8DX=WxpGk40mjmef?XGzzQMXVHZGVvw11(HLyoE zH+Bz9;Xdhj;7N!Vv*XXfe<`Q!SE?VxK0|#RxyK(lOh3|KN1UTrA~>JG_}MjH^9Vlb zX|gY11A;>beiqgq6}|JaKY_8;4T zy&%sE`Wk!<;IYuT@aciW*No4wpR4N;c^cK&!FEn853(HV8@3|2d+rq5XR$vvZ@I45 z{u9nqB^ixzfgT9?N?ZW)0{dleuE86uZJhBM@FDO4z%!ghek40bfd58t;lsdGP%{p) z7qK?T1L$SQZ}@tM>Hlbht%q?xMDbh1YBA=>O~iMzHIHBq{0NTtqxbl4d_J1Gmc`-_ zvyJ@QxK!i#z;)plBJc5YW6i#fF$Na^`3AT)cSEij_GQDlbLo0)1HOhaht9_Otj^Qd z=3xBr%Mpv`u06+ouC7Ox9|*gUwFeQ$!+d}afK3Q_fdAne{MQ<6KX&|D(wbdPZq62h zK9CQ<`swWZHILwnPavHRF3}yr1i>>T)$rK{J~^%dKLD{G^gXb5*lCde!1tg7Fc#q4 zVCRggpDa6kL17DzzbyMbImcX`9Ew1-FSvU zts}&bzNMwp{9t`R)WSr=cpz5;xEru|j1%e!K>j1<_ciWV^;Q1=Z{W6&^_XMaIq8^N z_+e{Q;giTo!)r#q=l}nO{v)rzPe(2f_T8!}>oI1tNr&Ifu04OWu3ZGonUyI~T>1f6 zE7m*gf7Ffz=LZ~nVDi9X!NIHxuE*X7YOzP?{j>A*!MLX%hf~I{@)ORzLs9^TR%{Au&6SFanG_ zenejtQ?21@oUM9Y+SVx-7;AqYtzmrTOBg?5Iq>D!F^4R{c(XN2*w@)3>i?mR&9Bbk z{E=~}>t~S*iZMbi$d5Gm_v)lKI(~{R;+oL=OG&n1e_r4|+&O^I^H}d+<5$49Kwb{k zEk1+TY;AS{@I(0b++z&>H)IF61jseRoVZFgVBb;>X+x{-0q{CFYn0aOw>HF!9qIGn zeX?>M*8;u(or1bq7(cdw&yBoK_(+d z|8=n?>+<}6(m9CNB2OIScarS2&o$U{sA&v&&hEj^jyrp-jZ*|20C~XrfH$*;+kn}jc0kR1FLunikH8FY9^$~@9z(VuUkq^sa0lm*>5uclA!Qrt{c+dZ z0v?Q9ps(>eVFO_Q6P%B^z;ZfKyOg_OuAn9n8}|d=fIOgv_P-v041lc0*g%h?9vJXl zY7M{^{Myf)mkG?;N2Y)2ZP@eR z4Ak`3!QEunGppmVw!tw$4G7eQKnxImCcC#OI0n!GI3Ji{L;HLW$WvSp>vTN%hOqre zMEqk7@*MF2wjK}03whk!xtn3x37kAZa7Qo~;2XexgdNDv3t&C?o14qa*2zcx@`hG> z55Qi7oe$pr_vR1Re&ug_74^Q@np+r0*!gUXkG&G|1wWJ#07VUa4&XqD1E8h|IA_rN zkOQnK0PoShmL9!-H2RfrZ8s-*kOw=2`LHB@~qT9(H#U4B0p7wYW!HD1a|NA_$u>{l& z2CfV_fcl+S|A+;kp$09BKck*>L;G?MJj$)M|5*GEIsraEa>&31ZH905Ssc<*zm5 zBV(+gQ@}L@{s`<5^+-@J!X>AgtDZx1u#^H3zo}hu}{|L+Re-g4(AMWrY`&EVVp6B;04vp6M(M> z-Y>hxYaUVG9hgE*9O-lS*6{lG_W*nZ^Z#O*u9LA z^KxTyi~nxNv)^7(Rl(tp01L*L0_VlP^`C3Nd=Vc&egX1IVEZ8_;79WeKlgnNuYbM= z_9y)>rT|$0o&k4^VZ^ISX8MC_92b0W;B=>6-{j=zpxzqx^F%C&UCWU1*c+;${XRVa zF0l^ja?}(bNka!r33+JPTMf1(>hxlr!dGL*x#kgEP|OEleGTo;>;Z5A5c5UdMXQjz z92o$P4{(0AKF6Q=sM*mU&@d;qR0!cYwe*Qx%Vp(k2t*He>?93 zc@xO3Lj4PH-RoLI;YXgG{Vce!sC^2q)xXh@*M&SX@V!xYhRr4Uk$cH3%H`A*tIIXO z{l>l@*yD-2E@)jo`=jUFq%lYS3ieaR9-Q^rP}ANq+PzMfgiWxGa$!(+{h#2~VQr)K z7xKwXh!0#JV_x$?v8J$3H0prWrJ?o*>I8rzUPbxEKdYrsPR!TszX? zi@A-u+U!1tU;DOqh1r}MnLjHR3iY3mLyX%0*aP&RXvpzHtxz`C|7+ig`oGot#ZdB5 zJ+>#5_k=t~)J;e2w12W8F9x--P$Q=<4f6%|5%yoNkA|F4@cgm=_rKLp>ksukGHIWg zy0nK0zMMWl?qKN;?D^Q@0!JRpC0s9D{ejIm04wD@%E9|R0K9FHXkh(#w zW7NtwCf$}mxo`hO124X=4SABNr4CL#e4x7MJM4*wd|A}pbxrhT{Ib$G`L<#K70f=e z*-^(6`^NuUZT_9=z2NKe{TNf!05I{jd)PzC3KkWPQwU$hKKf^9S{wQk0;yHkgz!$>b zkP~?QOZ$k{_8s1z_MAg4ktoVB|C#L>$yeBssKLQD)HZ`(AM_~~nti>tBkJqI_raK> z4j#r1c~-E0u;;xQ)!jsm{BJc^K9(0#&YmNuHWT(;LEWADY##|H*ha7g^8c|zK zAA9Aw(Y_lv2kRO44Z9d~0oVe@)t=^%%^PRNGWZrpryQZZRG>d#U*LLpX50hz;)E=* zqgq?2yA0g}8T_S&x-pYTonf5=F90t3tqnRG&w;woHTU*|oWgzLhkH!fzfnhcFZB)f z62NPy9|Ri^`i`wFRG0gKE>wGZlp|BIw;Adim&)YW3rL;CJErup!qx+{dvUaBW-@eS&(tXwc`#2gV*$Hwhp6R^7w7NG-q6$I6~J zn87cSIQ5E9g8=&!pf&|`CH8;Ay2UdiK7=)ad%8jE7=42GKaw6xp*f4#3F=Bfrr|y4 zdhA=2{T0~;`2vgy&kbJ`I-!`bH+&y-57vo%Xc1?&jK9}`vH0r^^_p@pz~p0 zV2#z*@Z6}k1$lvffu7nz^;uBAx4v)(?(ZEJf=#S4e%oFs%R<~oEnmxeaP|u~dy`esLjjz3qJxo!L4Es)CPYTo)!u|xZ zIYGS|$!7rjlB~iri#RQQ62_+4J1VuI> zSg0gOfv}WCS`whLl$0t<7m5YC*v)~qlE$B7VXVWp7BWb_?x>wHaEnE?6~<|K4U&THy=lxO1P1>(UnE)iEpXh z;#U5~(toYXZLhPc_*v}~y5Fl#=t1jU?KXNK)#{-m`6A8&P>*kI0RnU03j9D#Ep>Ka z2+i`Tuw`>0)#^%hy42?47xB}q1@E_;r*hNQ#+ehv_L~Fzt8v>Jag}wU-Cq7LzV;s#k57-NR zFw{byjp=ICrA+N*gr`wMLySTNit4YiHOvzK%W+ zQ&=;6K)P=@Z&?p=`U-Z|5$vZUXK_+ z>@y+a4D*KHlwzWaOSb(jdhXL<`?RG$@mYD=>$fzpeR|=Pg`09e*LM?UP8rK{|(q?ieW6Sa;9<-p|_~I=!y__$SZo3Y)*7;R~j9;-@qH-Vd7%=iuiX zOKobVtMw7vM(0@@umn2ZIlp3vW_qH(whZ>~{JtNAF5ef+&6?&L-QUy5+wcujo9Rb& z>C_};2lz}KF&~T-JvTahJAU4zH8Y!HVX!ji5qI>i$@LvOXuUU!4F=n`R=y|BVavZ5 z_TcMb&r*A}o&CSFJK7m`@qap}AQx?H=t<{i{5tAsJFi{*3+v&>R|($-24~LG34CJX ze$k7!4oR$6^$b<-Ih$0SYP#U~u=BTV51bpD`|bBF=5pR`x2L(WX`x zU02L|@Ppt2){1e5%lp3=a;SJFEb?D_<8I; zpSP~QY5u`s{6{@TXYk=Ki1V}`HmFu}+5h)g;^N|2ZO8rdK=!?P^Fzm7o97b~&Q8~9 ztDM^J=8q3uzcR1W3Mb_si-(USaXvW=Y%qBS?cm3X>C_~B?u`X`%x@jQbL85@xN<~l z4x1~m#3M=gxW+a~)!3)MHT%g9$SFE^C!M!8bIanqZ;ZLT0jvwg*UWEhc8{U>n;2j2 z;ka1aFfYEJ_-8{5(2)K%Iz_;x#H>eRU$fI#MTM=vUsz9a0ZCbG0rH zo<4IV|CFzT>3x#Vlz=x}7J1k*9yiqeE|1a^SXw&-CmBwX@Y8l&v+f%58}MHkXgQ}} z_nrRUk4xtGFC4gzAJpG9TKT*4FvZ-Lb~f@@t$Zha#{5tRp-%8R@N$L%qu0+jbT#nh zd3)=gp#S&rPVg1$1h?q=MHBk4*SgOQl?4<+X~u(DHTZ(>zzwWUR{HDgXX#KrHeP@TPVPJ#$a+n{lJ- zME(+wuNkkW?z?j7c!&Mv7VEy>%KLJxaHW00EvggzJL6#8ROKnFzK8qpv%q;09$596 zcD;u)a_@?%P4npXq~XRo%Xv*9_XdZB$NedC^rK^K{wnmjy+Lv{IOXk<{_5t)bKMm@ z_xo4;ttrOm{L$aUy2kx^aO2YK`-|6QSFYKX&Dr^OGz z+!YVe7~rPZqcSJ(NMn~U*_yBBZ{sG)S+RXZu4c3EH2WLAjeIKXnAij5`b&BuSx_Tz za{DFZ%yEt7P4Pz_2wmHZUzsjv&$@goo()dvURt+tjc9stMc+?AA(($v&GHA zZ6R`&p5J)L<*^0$J92$EtFV20De*z@J*Gwe5BE!bCFj}U^7;@k@3#=@M3Ll5|!Z-L9@ch7Bn*a+>gH^rU= zeu{mPFn-t4rn1;CfFC3`{@4I~3~?78QOXs%u01*S>0c9Lk1L2PiA(ORUfd~rB=o;$ zarS4kc*l6!YoedzUvTl+LG4O*P_A3v4==Wy<0`ka>i5-QTYoxtM!uiIz9KeXEM^Vb zXO0U%pU4s5xyprUqxa-aejaDhjtg#-ylCCtX?ko@@G0>r>@(+g;Tk`>b!(n;!_6J6 z{BdhzF9iR}nm7OC{_uO`D|f_xps77Ov$Gb>$;Pjmov-WrVm_q)W4mW>?Z|nY^a4GF z=Y;24j)C@upM~#FH`}9YZ=5qe4}}M4PwaaUgA(zDwS%W_Eb;oBGx^=%H}DI5_N5(N z`Ft>c${bE@@?6%1vGHtbBo)OPHook)J%YH5e~9@iZW@f>TH==BSmE06)76wXW^tCC z6?s?nLy``=GCqU1#uu^|1^>_<)3UJ1_=)sWnVaIXa+UU>*~>{M*yE<%gAx6q-Ua?3 zJNJut=37H0mATX~f|HgV%*L*a1mcG>uX}l3XQXVW%m+G5-|}sXd}=v1a|{oaos>@% zZ`awQbg#OfMolbTb>_6TEeV~BBZC`r?4teI7hc|!UDA25Zyz$;%Uq)8r z`1$r+m|tv6662z6#X4Fz_;foRWNwtjyumr2vf<^t&)K>DeERY=n*EL^d2aNt=e3sE z0dwB7mc@HGR}1!jq%-v4t6>B5FWbOhDE2EGaBKLsICOICY;-%H-!rk_y9>Tv`MK>K z#T%t#zqDXiHaYqd$D!E9w2xs$*gJLtK49MqJ8x{*Vn5mVx;i7}`?m7CXE-*Vzqk%? zHLPD;N4nKIu#R!qwgs_+&od_09$Q_7If?k4q8va_? zF+5528jMX*7KVB`XWhYk{OyaoV*dDC*O%iPw#(n>d2t*Lz5OCXDdxEOtu1ANg{b+Y z*3&ujpUT%MeJ`G%zv*~3mCm;Ha7RHuYv;1m45`H>dU^v=1#^=R4aVZZvoJMT3n~ z+SO#3m^G|+7tZnNuYZt@UOYY5?=QvvNO6rlW66(T6YQIW`5sC9I{xT}eT{um<~po& zdc;!V-r>+O?HZ4f>l__D5cHrCIgCAkr}gD{{V-mAJgv`-@U&W4eem?dDJh54u4mv= z*@HR|fz7vCue8~9;Sw-kcDPQ&GF5qfIf22R8zBb{>l7b0xpm(o$vc+w@?xq~GokN; zE&NBk$v>*{{p!BXhQmh7d388}9AgzmR&_0Pg|6K^IF1n?2zFS;2Ic(41^sdE)VqPL z9g4tr;7nz|(KDzQ$DbFk5FD8&Vl{&1&XV@G0ic3C> z+x01(Qxtt5ew8nh1LM#CBl6u^(96D$B{(Ov$eNp7?;YMPkB%aZ|^%+dB6@j6vg$Wx~12x&rbrE}=x$1-L z&JFAGI(Ej}`bapgygmJ`%_(PXe5@PuLyXyq$Pcrb1naz>kh-~l54~aUrx)Bg?Ul|i+~gmzzq}tT1_lOGl51BFIN8xLT~VVi`h(C< z_(jF>U`MSbZN_&SXng8E#=XpAgS9)q=+tGwDc!ZLFMn-r!4b_hHR9CE!;=u(%Uust z+@JlnZsn+99Qp&!4BNT8`(Qrr$41{4*B>0#TytL>rLrv_$aCm#^|s|W-Jjlwp~;2b z=A+U}@=6J(fc5HgxqJD{-k2YUBKFs&d%6yt;NCZ^S)cP9%s&{YId2T;9OpRDecn4% zfg7utHX-ag4E*?x29|tPynprjo!O}QkN4ROV=oVF?#s^()E-tnD=f@@Yk5L>oizVp z_Vl^eLmOYo*B^VJj<@-)?fRe{0`q~Ts|h3*P~-x`c;)Nw-ug~<+DlV&{lj-+&-sk) z67hqz&>3riUNkrH9Y(KzKgXIU_r8~1xBTU7N$>i+@8N!M@SzfTygHk+yVvDDfi-~Z zF(L!+fq(}NtH3D&mdLS+KAhrHLx)qSBi+ir8*4pb-g=deO?9Wl#m#cb>iwFdu2Gb= zZ+FEtL#c#_EsFkp`kXp>&abKxb~JI3#Xx*^d=xn>d@8zNNBFo^f&)d|lYJCd<4vvI z-IY!4TAR)3e!Z64#`f?Z(we5<=vXgyh_2PI+EmOJ@g<%J9}3Tq;F8Vm>B^>ecjoyq zK0F^=45mJnYw%gsG+DN1PySss%8R02u)N8n9T69A-jhANZf^cP@xqhgi^`R=gRb*N zT(d0rg7zo85dD1Cn&9?q-6;BfGB%X#f`AHZU6 zkNfjA`M3D&k8IwMOtm@VD8Ew{(5#DL}N_4oUs HDyjbi=wYdB literal 0 HcmV?d00001 diff --git a/linux/holo_nav_dash/templates/index.html b/linux/holo_nav_dash/templates/index.html new file mode 100644 index 0000000..e2fad9c --- /dev/null +++ b/linux/holo_nav_dash/templates/index.html @@ -0,0 +1,116 @@ + + + + Hololens Navigation Dashboard + + + + + + + + + + + + + + + + + + +
+
+
Microsoft Applied Robotics Research Library

+
Hololens Navigation Dashboard
+
+
+
+
+ + + +
+ Required ROS Nodes +
+ + + + + + + + +
Pepper ROS Stack
unknown
HoloLens ROS Bridge
unknown
Sequence
-
Anchor Localizer
unknown
Static Calibration
unknown
Dynamic Adjuster
unknown
Localizer
unknown
+
+
+ + + + + + + +
+ Application +
+ + + + +
+
+
+ + + +
+ Status +
+
+
+ + diff --git a/linux/holo_nav_dash/webSocket.py b/linux/holo_nav_dash/webSocket.py new file mode 100644 index 0000000..9f40f4e --- /dev/null +++ b/linux/holo_nav_dash/webSocket.py @@ -0,0 +1,221 @@ +# -------------------------------------------------------------------------------------------- +# Copyright (c) Microsoft Corporation. All rights reserved. +# Licensed under the MIT License. +# -------------------------------------------------------------------------------------------- + +import sys +import os +import time +import numpy as np +import enum +import copy +import json +import gevent +from gevent.queue import Queue, Empty +from gevent.event import AsyncResult +from flask import Flask, render_template +from geventwebsocket import WebSocketServer, WebSocketApplication, Resource, WebSocketError +from collections import OrderedDict + +# ----------------------------------------------------------------------------- +# +class webSocket(WebSocketApplication): + msgType = "msgType" + eMsgType = enum.Enum(msgType, "addClient removeClient status") + + EMsgKey = enum.Enum("EMsgKey", "msgType client") + + application = None + initialized = False + queue = Queue() + clients = set() + + # ----------------------------------------------------------------------------- + # + def on_open(self): + if (self.initialized is not True): + if (self.application is not None): + self.application.setCallbackSendMessage(self.sendMessage) + self.application.setCallbackQueueMessage(self.queueMessage) + else: + print("websocket: application object expected.") + + gevent.spawn(self.handle_queue_messages) + self.initialized = True + + self.addClient(self) + self.sendInitialization(self.ws) + + # ----------------------------------------------------------------------------- + # + def on_close(self, reason): + self.removeClient(self) + + # ----------------------------------------------------------------------------- + # + def on_message(self, msg): + if msg is None: + return + + msg = json.loads(msg) + + # print ("on_message(): ", msg) + + if msg[self.msgType] == "calibrateHoloLens": + self.CalibrateHoloLens() + elif msg[self.msgType] == "startNode": + self.StartNode(msg['startNode']) + elif msg[self.msgType] == "quitApplication": + self.quitApplication() + else: + print("invalid message, msg = '%s'" + str(msg)) + + # ----------------------------------------------------------------------------- + # + def handle_queue_messages(self): + msg = None + while True: + msg = self.queue.get() + + #if msg is not None: + # print("msg: '" + str(msg[self.msgType]) + "'") + #else: + # print("msg: none") + + if msg is None: + pass + elif msg[self.msgType] is self.eMsgType.addClient: + self.clients.add(msg[self.EMsgKey.client]) + elif msg[self.msgType] is self.eMsgType.removeClient: + self.clients.discard(msg[self.EMsgKey.client]) + elif (msg[self.msgType] == "status"): + j = json.dumps(msg) + self.sendMessage(j) + elif (msg[self.msgType] == "pose"): + j = json.dumps(msg) + self.sendMessage(j) + elif (msg[self.msgType] == "exit_handle_queue_messages"): + break + else: + print("handle_queue_messages(): invalid message, msgType = %s", msg[self.msgType]) + + gevent.sleep(0.02) + + # ----------------------------------------------------------------------------- + # + @classmethod + def close(self): + if (self.queue is not None): + msg = { self.msgType: "exit_handle_queue_messages" } + self.queue.put(msg) + + # ----------------------------------------------------------------------------- + # + @classmethod + def setApplication(self, application): + self.application = application + + # ----------------------------------------------------------------------------- + # + @classmethod + def addClient(self, client): + msg = { + self.msgType: self.eMsgType.addClient, + self.EMsgKey.client: client} + + self.queue.put(msg) + + # ----------------------------------------------------------------------------- + # + @classmethod + def removeClient(self, client): + msg = { + self.msgType: self.eMsgType.removeClient, + self.EMsgKey.client: client} + + self.queue.put(msg) + + # ----------------------------------------------------------------------------- + # + @classmethod + def sendInitialization(self, ws): + if (self.application is None): + print("sendInitialization(): application object expected, client: " + str(id(ws))) + return + + status = { + self.msgType: "initialization" + } + + #status["gestureInfo"] = self.application.getGestureInfo() + #status["status"] = self.application.getStatus() + #status["pose"] = self.application.getPose() + + # + # serialize + j = json.dumps(status) + + try: + ws.send(j) + except: + print("sendInitialization() exception, client: " + str(id(ws))) + + # ----------------------------------------------------------------------------- + # + @classmethod + def queueMessage(self, msg): + self.queue.put(msg) + + # ----------------------------------------------------------------------------- + # + def handleException(self, e, msg): + if (e.message): + print(msg + " " + e.message) + elif ((e.errno) and (e.errno == 2)): + print(msg + " '" + e.filename + "' - " + e.strerror) + else: + print(msg + " " + e.strerror) + + # ----------------------------------------------------------------------------- + # + @classmethod + def sendMessage(self, msg): + j = json.dumps(msg) + ws = None + try: + for client in self.clients: + ws = client.ws + ws.send(j) + except Exception as e: + self.handleException(e, "application.sendMessage() exception, client: " + str(id(ws))) + + # ----------------------------------------------------------------------------- + # + @classmethod + def CalibrateHoloLens(self): + try: + if (self.application is not None): + self.application.CalibrateHoloLens() + except Exception as e: + self.handleException(e, "application.CalibrateHoloLens() exception, client: " + str(id(ws))) + + # ----------------------------------------------------------------------------- + # + @classmethod + def StartNode(self, name): + try: + if (self.application is not None): + self.application.StartNode(name) + except Exception as e: + self.handleException(e, "application.StartNode() exception, client: " + str(id(ws))) + + # ----------------------------------------------------------------------------- + # + @classmethod + def quitApplication(self): + try: + if (self.application is not None): + self.application.quitApplication() + except Exception as e: + self.handleException(e, "application.quitApplication() exception, client: " + str(id(ws))) + diff --git a/linux/navigation_launcher/CMakeLists.txt b/linux/navigation_launcher/CMakeLists.txt new file mode 100644 index 0000000..4403126 --- /dev/null +++ b/linux/navigation_launcher/CMakeLists.txt @@ -0,0 +1,195 @@ +cmake_minimum_required(VERSION 2.8.3) +project(navigation_launcher) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a run_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a run_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES navigation_launcher +# CATKIN_DEPENDS other_catkin_pkg +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include +# ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/navigation_launcher.cpp +# ) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/navigation_launcher_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +# target_link_libraries(${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_navigation_launcher.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/linux/navigation_launcher/config/costmap_common.yaml b/linux/navigation_launcher/config/costmap_common.yaml new file mode 100644 index 0000000..cee5502 --- /dev/null +++ b/linux/navigation_launcher/config/costmap_common.yaml @@ -0,0 +1,24 @@ +footprint: [[-0.25, -0.05], [-0.25, 0.05], [0.12, 0.25], [0.20, 0.20], [0.20, -0.20], [0.12,-0.25]] +footprint_padding: 0.01 + +robot_base_frame: base_footprint +update_frequency: 4.0 +publish_frequency: 3.0 +transform_tolerance: 0.5 + +resolution: 0.05 + +obstacle_range: 5.5 +raytrace_range: 6.0 + +#layer definitions +static: + map_topic: /map + subscribe_to_updates: true + +#obstacles_laser: +# observation_sources: laser +# laser: {data_type: LaserScan, clearing: true, marking: true, topic: scan, inf_is_valid: true} + +inflation: + inflation_radius: 1.0 diff --git a/linux/navigation_launcher/launch/hololensstack.launch b/linux/navigation_launcher/launch/hololensstack.launch new file mode 100644 index 0000000..f4a2c8d --- /dev/null +++ b/linux/navigation_launcher/launch/hololensstack.launch @@ -0,0 +1,13 @@ + + + + + + + + + + + + + \ No newline at end of file diff --git a/linux/navigation_launcher/launch/holonavstack.launch b/linux/navigation_launcher/launch/holonavstack.launch new file mode 100644 index 0000000..86e2b95 --- /dev/null +++ b/linux/navigation_launcher/launch/holonavstack.launch @@ -0,0 +1,42 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/linux/navigation_launcher/launch/navstack.launch b/linux/navigation_launcher/launch/navstack.launch new file mode 100644 index 0000000..c43ff88 --- /dev/null +++ b/linux/navigation_launcher/launch/navstack.launch @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/linux/navigation_launcher/package.xml b/linux/navigation_launcher/package.xml new file mode 100644 index 0000000..6dfb2d0 --- /dev/null +++ b/linux/navigation_launcher/package.xml @@ -0,0 +1,50 @@ + + + navigation_launcher + 0.0.0 + The navigation_launcher package + + + + + cvlros + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + + + + + + + + diff --git a/linux/navigation_launcher/params/map.yaml b/linux/navigation_launcher/params/map.yaml new file mode 100644 index 0000000..0280009 --- /dev/null +++ b/linux/navigation_launcher/params/map.yaml @@ -0,0 +1,6 @@ +image: left0000.jpg +resolution: 0.01 +origin: [0.0, 0.0, 0.0] +occupied_thresh: 0.65 +free_thresh: 0.196 +negate: 0 \ No newline at end of file diff --git a/linux/navigation_launcher/params/test.png b/linux/navigation_launcher/params/test.png new file mode 100644 index 0000000000000000000000000000000000000000..67852f5580bc90fdf531406121044a86b6ab47af GIT binary patch literal 1409 zcmeAS@N?(olHy`uVBq!ia0y~yU}|7sV4T3g1Qgjg(X9wbaTa()7Bet#3xhBt!>ll=5YgsBuiW)N}Tg^b5rw57@Uhz6H8K46v{J8G8EiBeFMT9 z`NSC*SblrDIEGZ*dVAGSkb!~Yh{1vV&yTY*Pxp9n$uEfEz}krn3_KDbWRL(t2O1cG zh=G|6gdh?lSq>5?*u!OH$UzbWdYXXveWb{#GN5D#WY0q-;F)Cv$_>_1;zu^4rwp5H U%BeNKfn_Cwr>mdKI;Vst00gk}>Hq)$ literal 0 HcmV?d00001 diff --git a/rviz/pepper.rviz b/rviz/pepper.rviz new file mode 100644 index 0000000..f991228 --- /dev/null +++ b/rviz/pepper.rviz @@ -0,0 +1,267 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1/Status1 + - /DepthCloud1/Status1 + - /DepthCloud1/Auto Size1 + - /DepthCloud1/Occlusion Compensation1 + - /TF1/Frames1 + Splitter Ratio: 0.37704917788505554 + Tree Height: 424 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 2 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: 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: z + Class: rviz/DepthCloud + Color: 255; 255; 255 + Color Image Topic: /pepper_robot/camera/front/image_raw + Color Transformer: RGB8 + Color Transport Hint: raw + Decay Time: 0 + Depth Map Topic: /pepper_robot/camera/depth/image_raw + Depth Map Transport Hint: raw + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 7.51200008392334 + Min Color: 0; 0; 0 + Min Intensity: 1.5169999599456787 + Name: DepthCloud + Occlusion Compensation: + Occlusion Time-Out: 30 + Value: false + Position Transformer: XYZ + Queue Size: 5 + Selectable: true + Size (Pixels): 3 + Style: Squares + Topic Filter: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /pepper_robot/camera/front/image_raw + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Class: rviz/TF + Enabled: false + Frame Timeout: 15 + Frames: + All Enabled: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + {} + Update Interval: 0 + Value: false + - Alpha: 0.5 + Buffer Length: 1 + Class: rviz/Range + Color: 255; 255; 255 + Enabled: true + Name: Sonar_Front + Queue Size: 100 + Topic: /pepper_robot/sonar/front + Unreliable: false + Value: true + - Alpha: 0.5 + Buffer Length: 1 + Class: rviz/Range + Color: 255; 255; 255 + Enabled: true + Name: Sonar_Back + Queue Size: 100 + Topic: /pepper_robot/sonar/back + Unreliable: false + 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/LaserScan + Color: 255; 0; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.05000000074505806 + Style: Flat Squares + Topic: /pepper_robot/laser + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Unreliable: false + Use Timestamp: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: base_footprint + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 40.26953125 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 7.949053764343262 + Y: 6.601431846618652 + Z: 3.630021333694458 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 1.5697963237762451 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.130409002304077 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1016 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000400000000000002a10000035afc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000233000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650100000276000001210000001600fffffffb0000000a0049006d00610067006501000002b2000001130000000000000000000000010000010000000385fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000385000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005a00000003efc0100000002fb0000000800540069006d00650100000000000005a0000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000002f90000035a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1440 + X: 85 + Y: 41 diff --git a/rviz/pepper_nav.rviz b/rviz/pepper_nav.rviz new file mode 100644 index 0000000..536d87e --- /dev/null +++ b/rviz/pepper_nav.rviz @@ -0,0 +1,661 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + - /DepthCloud1/Status1 + - /DepthCloud1/Auto Size1 + - /DepthCloud1/Occlusion Compensation1 + - /TF1/Frames1 + - /Map1 + Splitter Ratio: 0.37704917788505554 + Tree Height: 719 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 2 + SyncSource: LaserScan +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + BumperB_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + BumperFL_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + BumperFR_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + CameraBottom_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + CameraBottom_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + CameraDepth_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + CameraDepth_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + CameraTop_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + CameraTop_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + ChestButton_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Head: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + HeadTouchFront_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + HeadTouchMiddle_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + HeadTouchRear_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Hip: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + ImuBaseAccelerometer_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + ImuBaseGyrometer_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + ImuTorsoAccelerometer_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + ImuTorsoGyrometer_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + LBicep: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LElbow: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LFinger11_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LFinger12_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LFinger13_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LFinger21_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LFinger22_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LFinger23_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LFinger31_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LFinger32_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LFinger33_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LFinger41_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LFinger42_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LFinger43_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LForeArm: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LHandTouchBack_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + LShoulder: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LSpeaker_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + LThumb1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LThumb2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link Tree Style: Links in Alphabetic Order + Neck: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Pelvis: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RBicep: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RElbow: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RFinger11_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RFinger12_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RFinger13_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RFinger21_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RFinger22_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RFinger23_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RFinger31_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RFinger32_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RFinger33_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RFinger41_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RFinger42_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RFinger43_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RForeArm: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RHandTouchBack_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + RShoulder: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RSpeaker_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + RThumb1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RThumb2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + ShovelLaser_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + SonarBack_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + SonarFront_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + SurroundingFrontLaser_device_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + SurroundingFrontLaser_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + SurroundingLeftLaser_device_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + SurroundingLeftLaser_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + SurroundingRightLaser_device_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + SurroundingRightLaser_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Tablet_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Tibia: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + VerticalLeftLaser_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + VerticalRightLaser_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + WheelB_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + WheelFL_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + WheelFR_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + l_gripper: + Alpha: 1 + Show Axes: false + Show Trail: false + l_wrist: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper: + Alpha: 1 + Show Axes: false + Show Trail: false + r_wrist: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: 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: z + Class: rviz/DepthCloud + Color: 255; 255; 255 + Color Image Topic: /pepper_robot/camera/front/image_raw + Color Transformer: RGB8 + Color Transport Hint: raw + Decay Time: 0 + Depth Map Topic: /pepper_robot/camera/depth/image_raw + Depth Map Transport Hint: raw + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 7.51200008392334 + Min Color: 0; 0; 0 + Min Intensity: 1.5169999599456787 + Name: DepthCloud + Occlusion Compensation: + Occlusion Time-Out: 30 + Value: false + Position Transformer: XYZ + Queue Size: 5 + Selectable: true + Size (Pixels): 3 + Style: Squares + Topic Filter: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Image + Enabled: false + Image Topic: /pepper_robot/camera/front/image_raw + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: false + - Class: rviz/TF + Enabled: false + Frame Timeout: 15 + Frames: + All Enabled: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + {} + Update Interval: 0 + Value: false + - Alpha: 0.5 + Buffer Length: 1 + Class: rviz/Range + Color: 255; 255; 255 + Enabled: true + Name: Sonar_Front + Queue Size: 100 + Topic: /pepper_robot/sonar/front + Unreliable: false + Value: true + - Alpha: 0.5 + Buffer Length: 1 + Class: rviz/Range + Color: 255; 255; 255 + Enabled: true + Name: Sonar_Back + Queue Size: 100 + Topic: /pepper_robot/sonar/back + Unreliable: false + 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/LaserScan + Color: 255; 0; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.05000000074505806 + Style: Flat Squares + Topic: /pepper_robot/laser + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /move_base/global_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 9.423486709594727 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 4.725549221038818 + Y: 3.7505757808685303 + Z: 3.6268298625946045 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 1.5697963237762451 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.130409002304077 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1016 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000400000000000001910000035afc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000035a000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000276000001210000001600fffffffb0000000a0049006d00610067006501000002b2000001130000000000000000000000010000010000000385fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000385000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005e70000003efc0100000002fb0000000800540069006d00650100000000000005e7000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000004500000035a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1511 + X: 67 + Y: 64 diff --git a/windows/MSRHoloLensSpatialMapping.sln b/windows/MSRHoloLensSpatialMapping.sln new file mode 100644 index 0000000..f941570 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping.sln @@ -0,0 +1,51 @@ + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Visual Studio 15 +VisualStudioVersion = 15.0.26228.4 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "MSRHoloLensSpatialMapping", "MSRHoloLensSpatialMapping\MSRHoloLensSpatialMapping.vcxproj", "{B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}" +EndProject +Global + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|ARM = Debug|ARM + Debug|ARM64 = Debug|ARM64 + Debug|x64 = Debug|x64 + Debug|x86 = Debug|x86 + Release|ARM = Release|ARM + Release|ARM64 = Release|ARM64 + Release|x64 = Release|x64 + Release|x86 = Release|x86 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Debug|ARM.ActiveCfg = Debug|ARM + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Debug|ARM.Build.0 = Debug|ARM + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Debug|ARM.Deploy.0 = Debug|ARM + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Debug|ARM64.ActiveCfg = Debug|ARM64 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Debug|ARM64.Build.0 = Debug|ARM64 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Debug|ARM64.Deploy.0 = Debug|ARM64 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Debug|x64.ActiveCfg = Debug|x64 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Debug|x64.Build.0 = Debug|x64 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Debug|x64.Deploy.0 = Debug|x64 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Debug|x86.ActiveCfg = Debug|Win32 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Debug|x86.Build.0 = Debug|Win32 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Debug|x86.Deploy.0 = Debug|Win32 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Release|ARM.ActiveCfg = Release|ARM + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Release|ARM.Build.0 = Release|ARM + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Release|ARM.Deploy.0 = Release|ARM + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Release|ARM64.ActiveCfg = Release|ARM64 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Release|ARM64.Build.0 = Release|ARM64 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Release|ARM64.Deploy.0 = Release|ARM64 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Release|x64.ActiveCfg = Release|x64 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Release|x64.Build.0 = Release|x64 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Release|x64.Deploy.0 = Release|x64 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Release|x86.ActiveCfg = Release|Win32 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Release|x86.Build.0 = Release|Win32 + {B65D7EF6-4502-4FF4-9C74-942A42E2DB5E}.Release|x86.Deploy.0 = Release|Win32 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection + GlobalSection(ExtensibilityGlobals) = postSolution + SolutionGuid = {0FE83196-7E59-41FD-A4EA-E38014624DBA} + EndGlobalSection +EndGlobal diff --git a/windows/MSRHoloLensSpatialMapping/AppView.cpp b/windows/MSRHoloLensSpatialMapping/AppView.cpp new file mode 100644 index 0000000..d39f3c5 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/AppView.cpp @@ -0,0 +1,231 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "pch.h" +#include "AppView.h" + +#include + +using namespace HoloLensNavigation; + +using namespace concurrency; +using namespace Windows::ApplicationModel; +using namespace Windows::ApplicationModel::Activation; +using namespace Windows::ApplicationModel::Core; +using namespace Windows::Foundation; +using namespace Windows::Graphics::Holographic; +using namespace Windows::UI::Core; + +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +[Platform::MTAThread] +int main(Platform::Array^) +{ + // + // The main function is only used to initialize our IFrameworkView class. + + AppViewSource^ appViewSource = ref new ::AppViewSource(); + + CoreApplication::Run(appViewSource); + + return 0; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +IFrameworkView^ AppViewSource::CreateView() +{ + return ref new AppView(); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +AppView::AppView() +{ +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void AppView::Initialize(CoreApplicationView^ applicationView) +{ + // + // The first method called when the IFrameworkView is being created. + + applicationView->Activated += ref new TypedEventHandler(this, &AppView::OnViewActivated); + + // Register event handlers for app lifecycle. + CoreApplication::Suspending += ref new EventHandler(this, &AppView::OnSuspending); + CoreApplication::Resuming += ref new EventHandler(this, &AppView::OnResuming); + + // + // At this point we have access to the device and we can create device-dependent + // resources. + m_deviceResources = std::make_shared(); + + m_main = std::make_unique(m_deviceResources); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void AppView::SetWindow(CoreWindow^ window) +{ + // + // Called when the CoreWindow object is created (or re-created). + + // Register for keypress notifications. + window->KeyDown += ref new TypedEventHandler(this, &AppView::OnKeyPressed); + + // Register for notification that the app window is being closed. + window->Closed += ref new TypedEventHandler(this, &AppView::OnWindowClosed); + + // Register for notifications that the app window is losing focus. + window->VisibilityChanged += ref new TypedEventHandler(this, &AppView::OnVisibilityChanged); + + // Create a holographic space for the core window for the current view. + // Presenting holographic frames that are created by this holographic space will put + // the app into exclusive mode. + m_holographicSpace = HolographicSpace::CreateForCoreWindow(window); + + // The DeviceResources class uses the preferred DXGI adapter ID from the holographic + // space (when available) to create a Direct3D device. The HolographicSpace + // uses this ID3D11Device to create and manage device-based resources such as + // swap chains. + m_deviceResources->SetHolographicSpace(m_holographicSpace); + + // The main class uses the holographic space for updates and rendering. + m_main->SetHolographicSpace(m_holographicSpace); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void AppView::Load(Platform::String^ entryPoint) +{ + // + // The Load method can be used to initialize scene resources or to load a + // previously saved app state. +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void AppView::Run() +{ + // + // This method is called after the window becomes active. It oversees the + // update, draw, and present loop, and it also oversees window message processing. + + while (!m_windowClosed) + { + if (m_windowVisible && (m_holographicSpace != nullptr)) + { + CoreWindow::GetForCurrentThread()->Dispatcher->ProcessEvents(CoreProcessEventsOption::ProcessAllIfPresent); + + m_main->StateReceiver(); + + HolographicFrame^ holographicFrame = m_main->Update(); + + if (m_main->Render(holographicFrame)) + { + // The holographic frame has an API that presents the swap chain for each + // holographic camera. + m_deviceResources->Present(holographicFrame); + } + + m_main->StateSender(); + } + else + { + CoreWindow::GetForCurrentThread()->Dispatcher->ProcessEvents(CoreProcessEventsOption::ProcessOneAndAllPending); + } + } +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void AppView::Uninitialize() +{ + // + // Terminate events do not cause Uninitialize to be called. It will be called if your IFrameworkView + // class is torn down while the app is in the foreground. + // This method is not often used, but IFrameworkView requires it and it will be called for + // holographic apps. +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void AppView::OnViewActivated(CoreApplicationView^ sender, IActivatedEventArgs^ args) +{ + // + // Called when the app view is activated. Activates the app's CoreWindow. + + // Run() won't start until the CoreWindow is activated. + sender->CoreWindow->Activate(); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void AppView::OnSuspending(Platform::Object^ sender, SuspendingEventArgs^ args) +{ + // + // Save app state asynchronously after requesting a deferral. Holding a deferral + // indicates that the application is busy performing suspending operations. Be + // aware that a deferral may not be held indefinitely. After about five seconds, + // the app will be forced to exit. + SuspendingDeferral^ deferral = args->SuspendingOperation->GetDeferral(); + + create_task([this, deferral]() + { + m_deviceResources->Trim(); + + if (m_main != nullptr) + { + m_main->SaveAppState(); + } + + deferral->Complete(); + }); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void AppView::OnResuming(Platform::Object^ sender, Platform::Object^ args) +{ + // + // Restore any data or state that was unloaded on suspend. By default, data + // and state are persisted when resuming from suspend. Note that this event + // does not occur if the app was previously terminated. + + if (m_main != nullptr) + { + m_main->LoadAppState(); + } +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void AppView::OnVisibilityChanged(CoreWindow^ sender, VisibilityChangedEventArgs^ args) +{ + m_windowVisible = args->Visible; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void AppView::OnWindowClosed(CoreWindow^ sender, CoreWindowEventArgs^ args) +{ + m_windowClosed = true; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void AppView::OnKeyPressed(CoreWindow^ sender, KeyEventArgs^ args) +{ + // This code does not use keyboard input. +} diff --git a/windows/MSRHoloLensSpatialMapping/AppView.h b/windows/MSRHoloLensSpatialMapping/AppView.h new file mode 100644 index 0000000..499dd21 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/AppView.h @@ -0,0 +1,66 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#pragma once + +#include "Common\DeviceResources.h" +#include "MSRHololensSpatialMappingMain.h" + +namespace HoloLensNavigation +{ + // IFrameworkView class. Connects the app with the Windows shell and handles application lifecycle events. + ref class AppView sealed : public Windows::ApplicationModel::Core::IFrameworkView + { + public: + AppView(); + + // IFrameworkView Methods. + virtual void Initialize(Windows::ApplicationModel::Core::CoreApplicationView^ applicationView); + virtual void SetWindow(Windows::UI::Core::CoreWindow^ window); + virtual void Load(Platform::String^ entryPoint); + virtual void Run(); + virtual void Uninitialize(); + + protected: + // Application lifecycle event handlers. + void OnViewActivated(Windows::ApplicationModel::Core::CoreApplicationView^ sender, Windows::ApplicationModel::Activation::IActivatedEventArgs^ args); + void OnSuspending(Platform::Object^ sender, Windows::ApplicationModel::SuspendingEventArgs^ args); + void OnResuming(Platform::Object^ sender, Platform::Object^ args); + + // Window event handlers. + void OnVisibilityChanged(Windows::UI::Core::CoreWindow^ sender, Windows::UI::Core::VisibilityChangedEventArgs^ args); + void OnWindowClosed(Windows::UI::Core::CoreWindow^ sender, Windows::UI::Core::CoreWindowEventArgs^ args); + + // CoreWindow input event handlers. + void OnKeyPressed(Windows::UI::Core::CoreWindow^ sender, Windows::UI::Core::KeyEventArgs^ args); + + // DisplayInformation event handlers. + void OnDisplayContentsInvalidated(Windows::Graphics::Display::DisplayInformation^ sender, Platform::Object^ args); + + private: + std::unique_ptr m_main; + + std::shared_ptr m_deviceResources; + bool m_windowClosed = false; + bool m_windowVisible = true; + + // The holographic space the app will use for rendering. + Windows::Graphics::Holographic::HolographicSpace^ m_holographicSpace = nullptr; + }; + + // The entry point for the app. + ref class AppViewSource sealed : Windows::ApplicationModel::Core::IFrameworkViewSource + { + public: + virtual Windows::ApplicationModel::Core::IFrameworkView^ CreateView(); + }; + +} // namespace HoloLensNavigation diff --git a/windows/MSRHoloLensSpatialMapping/Assets/LockScreenLogo.scale-200.png b/windows/MSRHoloLensSpatialMapping/Assets/LockScreenLogo.scale-200.png new file mode 100644 index 0000000000000000000000000000000000000000..0ce8b8ce5e117f723d2282695ec0dde68209edd0 GIT binary patch literal 6366 zcma)B1z3~a+aE{>h$4*$OhQ6p1!JROG)xHz$+3V@8*CsblA^RIC><&#ts*UglqldU z2q+RNq5{%g@(t^K|JV0^v1`ws^PF@4?)&`iI@`7AGiZHw)?=&y0D#@l0A)_QgZ8h3 zOtepH`pv7f8w=UMmI45j$0D$Q_(b9%$V`_rLlDy8tOpR z03=O;7oLg%26%aTQ;-2_qCfN^Y2*EA1ySG+5vqrpsMfwgppEGnpbp6w4^)x|$zeet zB_JFj4_1P~6``^~2nYgJ06`SMigI8uQW1g#LxI0uqBLv1I0DifrT5Dg?MY44jY=gW z6%@{&KQDhCDo^rtRRALph7pAQZ z1*4R-!5|0}0#X8@eq#;2DO8L%7XRBek!D*FhrvNHE?7Aj4o6EV3=Agcf>VOZVG$r4 zmH>q+VH62J@JJnBJcdg0wIq=|e`o5M-<|;K=+H6~3gKq60C%zy`f5SAUF~P`YCEk!Vw99|0xQAS%RTRC=96x{|`}G+2Al#%>OBj z!y*YJUoQ+TgNR-jSG)q*+f@|!CqPIYk|)WRW|+1+=s)KTb#%`7k_bdk+5*K~UmIws ztD^))C@IN7#Z9Ig&A*2oM1ZmV*=Ea5UoSWUdxqM5dS@=AP{-zKNIRF2sGrGk9+rO<&q6 z@^QY>7XUcAY>3jbbQ_zs4J5xlTfb{L!jz+a)7*!ghpC4GZLxd#mN zxbgE3uE&duCni>&fVIHQmK1NYrZ zNfvduQ}ONLv85A3PXwC9WrG;+_s+J(O;|y9J)}#&PbRtya7xbXWHr=Gk_?7Zu@q%T zt|dd$if}YPR!Vn5r|VcnAtKb?f>Y6<@4E=SvWRwRXOhi?<w;@X~OCY>-uCY^qnG?SMejt(41U0sTaC|HtpX;uSwa+uP2qE$4{g=rrC<9 zG|jL<1zw&iDzET0SUpX@pwGzJP@7`2eZ|KF3W=Z6lZ1|zFsFTvG$-&2w#&DLquHi9 z<@sE!kL;xpbG)1%9if8y#nQ%!*!nX zT>g^i4h;29884T&=FYzKDpQ?P_DzhR=cSl5zNSbnp#Na@n@LNT&zo(}7oQ0FK;p4e zcLLRfti8z#NxgM*77q|#E9H|Zd)SLzDW-(KmI@_(}^Y*-P`Z_ZBNJXJGu z+^v72g^$ov_0q|;SpSsmL^4b1C9(Tf9`~=ZfV4x|M)ky+G`j zb#giLL!&;(Y^=A*_K1X4n1;3blG?F#P|3xYOofoxDUq!!Q;zCs4l78?i?rUL=l)ml znm%jNSzQkGwTEJ#2-(%m#J4JjwT|S)A{UTm?;H&9WdfFiN>#@WhMwxW)cer<7mZ;-xG&YHKosu zFE$ttwqH&mu@0BKL7Xaoj>)%}8?mYgpKO56tlc==SUzu|iFv-yg}mEDD&xrMVT&4Q zy1-coy8h@=%*$INCHc7naeS%4$uqOVH4fTM+v%%_eQh#zZ%dm# z(x(zL-MQD{-dV;FUkzDZU^CeSZfL}TSCg_zKj`ocHoDN4gviamlh3)|tDA9PFfSf! z;}*H(ITyh*o0fZBq}^&R@9vhfs?f>0Pd$6Qkb173AfVag=US&(^jEg9iR0ZB1Db#@ z{^NzY+tvvY$cmv*nch-C^WlXsgRGM!*Si;Pag_wuv&OXY7Z%KEq)Yf=EJjZ4w2H}8 zZ;6+viNGC7nL3T7w5GHd&n9q7*Vyq|t=V$KbsvGrET)uMp`OiF2lB|;Id~f0tuE1n ztXOfZM{W-Q0rX52j-l^AzgB*GbIPg9rOYGR)++V^F`F5fdrd(2uZ|;J1$+B&i8w(jl)vS6te*y$2b+j&1rr=(vtX#csjYyI72899Wu|sst$t)>0{wU#s<6ea zvctlwz*YNlnVUoy5F1LvWC|XdWf>&0o$DEGT@h2LR9I8bb7#G)Y$}EL(hDW2KyT6+ zpl=Mv=IR}!G?8DcX}9q8jpoNzsYjkVayw1T_*}o1qU4Q7$0Zy{Ecfb{m|g<`s#`Zz z;!ZIIrx z5V9!1)Tpr!!N5N4!-;-@U6Iavg^hZBoyXs5;mR(c8dkK?510?1JRe~+Xha{YVY>L- zN!V=ELGxD0qlK%_=@dCModTZFN6Jesst2%6Q?3*B+aVJh`P~~G%7d^2Rkl|gZCdIy z!UY`Ts*+V(&|Q2}wl#9n8Q3nv>cG)n&k_-g4O-$BwQrUCF5eB7S0B9EqKQW*?cf{F zt!A$ky@AvhO)4Aq+*5MgG_DAoR5*35%=Zn$bHi8AXwDNNk$byU!NpoQ*kXzw>H>wWI6m%o|63A#N09TznA#i2Hng*7rQ)L4@A`N1Gp;-JIwiF=SBrOD7?O0nHo z__>YCxsKb(<=lnT!pAZqF=ot%=tDchbF5Pi6h^Bsar1cCF;91YnSc2HX+pQ^Xbdq& z7MqUwV%vZ5eyQIY@8E)`vL>#C3bbieEc9e z3U>y_zO|r%)2=+xvLS#aft|x1{0_~>#vGoer>M8YktQMiwRyz_&dB0w5d!2*x7WQ3 z4MpYOA}e|=Z6t;btj1Vn90haC_;l}`3!!HmW0xNN%9!=i|5^6gRIE{YItiTxXwrCl zsVp*GVTOU6IMDSbFvP@dLdVD}LOrQlgD?M0UE^Ja9Qn2U{zqty`u?W)x$JiCH-`mC zX&M}%_fE~upEEn`sRFNcsX!kJ=dal#Ji?365c#>Bk{(n;N8i03|A-PS-8Xkw*^pF zQvGh{SD*MAv1(BKa5n~SFv4o}np!d*hcy*JJM*?tmbn=^7SGg7i9%&dQ1eqqfF+0s z@gB*@!Yak9tnczaopTm?SpQeyp!t*UW`iqBSoSjTr@IHE*21h*@Gl7};?SnZmC1ZT z(dsH50=OX?^|pr^?RFR)3dN_vWik0`R+j2M6IMJ^lZF6w&)iEhVm*#V) zYdBJ!va^~{eH#94@TRPL)wg_xiR+ARRhQ5Rk%yr!8L|LrABM!L;RP>!YJ-s4a!Te~ zySjei*qks%g~dd9pTkn;xLAQ^8@Ad3o1Y`(>z0!iG?Y%5d$LPC=xq)nw}^$@XPRE| z^fi^rw`%AUV%y0R@~#L`j6AEpa)5Bna*!Zq)X;u`4A?Y?&OZ|#v(~Td@~+ubAgM`* z>w95SVQ9jTq(yCCis*AMuUYiz&7&PuKKp{DH4BFHO0UAgV7BskP1!S=`0^IpmlNXY zTKVqD-8JL^L${0cj@xwaae!2Yv3Z^3^3H7@)e#AgMrriy0l*x!P#~7nDr$Fsxxlsp zG;4g}km)#RnO;!KUiK6-eWKRq4NC@<@whD4_h0(WLqE1(%QhCe@sZjV8YN^4`DC)%4Kk-p6NaJ=jNg-I>Oi2g`|Z2P){<*klZ-t{J{;ZQk1A$BaeS0`|DGmIJ=}f za(2#t9B5hxIH%b0Ew}6JI%ki1@2o04+qjmx^B_`h?g;Qm3tMOXn8bPE7w#tf(({RD z0`*V&Ba$p#^Tl<65eZKYySH7v^|oUvl2UecMZ(!EI(=@Z6FTi8b&F+ zA)$9Ho4E5=I2}7n8o#b70J=FzI~(nEIjrw0w^x%Qm;rzk1u>kdasgWb>gFk@%1TNu zQ$bOyYG@#0vKw>e`Y0$br7~lJjzEuFJ^}!Yu5+C%&;984;TddFt4|>3DsS)O57xM> zNn20BG{?sgCIt92(cai~#`^kgZ|GS8|HP562DV6RqyG9_)hUyBu1ha2Hus5ymIchb zf?bsy3*$yQh-`OGR0f5lDWY4mxrJ=`kAJef*c9h%GLNm896OBo`_xR;04I%g~P6~eh4V;{PukPkwjeQ@Kc6an`Qlq`~K?T zqQ+T~;{JC|ybHi|csq4USdQR@djtzxmA=PN@d3 z($sh@EKa5`-Yo4vE%3aS+B+04By)%tkf7Ws-idJS&6nC-E89L1*(IaDbz7j*D?3Kl zXs!%+hS*ULl+nf+0e4yigKl}EWrN1%Qq?0w?`tZHSJ7*RAg2pu8_&wIC zzR7F41%j8lk(KYeOO7hZh580vPM0o@CZ-3J_?+0%BJg`?OPL&%kJ@xW0Mw^gYTms- z70&A9)tLdumKHw(gV{B!i5f+mrdLIn#~s> zvsRA-#QG*>!@mr`NMu0dEwMc14Bdecn&u4UXpSB}Xw-j|GAZyu(k_c()M;!TFX-n0#Wc%v)jGPVqqZpRRZf$_ z3_SH66-LUnrB@h?1~ypEea`?~;9xG#I$H5HP!;rD0-Xvqfx=_VF!=!!Ep$QAqfZVW z8A$`FD8$N<;j&%>l*W0_0_5hIsm9Yzjd@0*|&d(6fiMKL4Wf!3O|E_dmfR+A2Z4iamkM%|B}TxmAl)QE}LI(Jb65UlOy zQJ)t!eO%ITLLEj$S{Du3FMSTl!Nfhd_2{@x(L1@g@Xq-Gvs8ieUc!T-B_n$*fK#Zs z<@MvJQ5E|Ooey7hU3h_%jT_FoU3nYErN zVm~=_p?x8C`tjIF6Z;k(l|4qla=S;y6~m7M?Ca6!i;FK>zbo>G>I?%vocwlhMcwLt z>HF)Ltm$4IdzseGRS)NU{3_$a)0BKnAYb$SwF hv8NI`PIqus!)`kw``pLT(fxlQ40X|{a&71E{{rgdFSGyv literal 0 HcmV?d00001 diff --git a/windows/MSRHoloLensSpatialMapping/Assets/Logo_RobotHandshake_transparent.png b/windows/MSRHoloLensSpatialMapping/Assets/Logo_RobotHandshake_transparent.png new file mode 100644 index 0000000000000000000000000000000000000000..1e1f316c0bb4271f57d3ddba20b17499771e9d18 GIT binary patch literal 42610 zcmbTe1z40_*FS0?pp>F?N(h2O*U(CXgusBbbPhE`mwi5NFxIb zA>Birdw8DrIq!SU_y4}{9Iguoxc9yG+Iz43t+fr)P*WhfLw)DkwQEF5in5y5uH8Ta z-vju#z+aqp(@%hp+s=x5uxrI{s&c1>K$)7jMA-V)AeW@&BfD8aPV*viCcYazj;E2zq&>MUbvW2@-xYN_R|rfu$R zZw|I#l9FT;_Y?&PKrP{>jGj;jN0_Lm1k)8=QQ&9npShVBuZFj?XMn}7}D_B3_o=H=qSF6nBZh50|@ zoZVaSdJ$bUH+rtRfy$*pM#b8>Svx0G`S*ks18##vOx)zTF1??+mgi&{CkLQR3C+CojOExDZ?t(h4A*+5Yl zCkH22U`l{5{(t|wl8lUotCN+j1MmQ*sql&MPP&0^$|25CnmF1Oz}}usI)y&s;>rN|4_|(8|L6 zU)0oHZ2?s@b@+FxSgtGpiu^ogU|?=j5U+)ZIf$QE01Ofl6cGSf@R z1^!BgL=|me!0CGZtwLIsE`R^zV9R(VHln8HSapzKGRMk+r3KU9f42QE_Tzsw^WX1# z*jNHY{~P)EYj&8E72Lzr)$*w|uy_BX{Bi%En1`9V|M#r_?~d{>p8lQn|F^vU|Ka=Z zJu$a2b+onw3@bMib|u_c6ZF@KaQ{CK>+0FRnX7*d2W%kr$A643@XJ5u+tLvr?FtxY zKj{X>YuB=Plw_Z3droeg6Mcj%C8G(@7O}*K`-^v{`lCg_+1x%u@UG3SeGyZPr}*>t zF?nqCv7XN-BwXHqTTLn#V}=I>gW8^o6}q2Ezo4-fpC|i+d(@`UCEXLv_ZH`g+_T$E z12@S1d6a!^x!m&RHuvkt8ZSf#!42~MMF3(FD z@n>&cIh~o`0EfUABjCP(ukZXF{$5Qm7FALQM-FZLGGE-p8bpQOmM_F0k9LqH?BSSP}}_p zmrec?UfGjOn)h>_kc4Jf5+1VOe_ntX^wN0^c~FfJdwj@MM8}-lKCP2CDwz{5a6WX! z;G$k4Yb)s@RI57(v_(yF+l@ybl;#Yq)qivuhp}X%yR4gp80A#E9O2$fvd+Szdy7kx0ULxixa@CWBg4o z7Ut>pwC~9EkZGjE*jz1&FG8PvL~W49))6!md(1Vu5~P#bs9a@sDB^S-dqj#f5KoVO z+Mm$^>WMZ=%^VA=QAQ^}Sns2US-f9O5$%bD{xvM3HKSGJ+t73a>G|@C0EqfUlR;SL zNfn2{J&&tp9?ReKKDmb;raT>-XcNY>K8+tb&3)p%xOX%QoF;=XY&w8lHt+{JZKqRlVrBJ#eHaYNx&qM#TiAi!oW_;Tv-8%+SeV^_sR2BqZo zKr6B3VI`@9-&TBww{*m-c+qw+F;i<+aD#(dwZiMOg&xA6L`7NrVhUMq2D9m4x8BFaCJ$t^KkNP9??Noh>0K8Z(nZ)Ghj6BD(!uV2VldZ(Tsj4NEaD9W&YOy-on zN%{>1wcqbsfUdANlQ^&*kc{#pgS0;O=Qa~7{+;a0c1JXYDW_;->r-{Xl{5gz<; zv7gGGlr>Y{pNl+uwtXp9e*TB4DI{C*!kdMZJ5d_Jk$QkGBwLTk7jD^YRR2-sPY(rQ zH&~j8=nphil)N#hs5SL1dS_wbihosAw*e85H1#!+2CLJ0Opo7azDCv$>NM$vx;3`|Lx&R*HL=|Gf1`xaYp)iI#YAaWHDv!o#vGo zfpS_v?!7{)@+9wYbV@2_Z3^=z=$qA~*ctOV$yG`kcwk zA<`tp3!z;5M zosrMVyr^af?cUUlaF=8!nXJM5@$veOwTfdElT8ojNJ~7$B!jO+H%>skxQduGVy^|x z5j`6fHnZb-@<7bmzbvK8Wgd|lyhBq~N=&X?%DMy=BQBCpGO}b2YSCmJVJ_x?MotOX zps?b`c=S2HJzZeD<0N4TMga3Q{@D8KcRAST3+wnoXXm)~ErSvUs$%1!SO+b?F=~5~ z^YOjsd0wX1arAo)j~#AcDMUbT@95gsn)t^Sv`K5(P2mT}e~eydE7+fW0VWrI?f9Q{X3e9>A0p*0w5?~r1_rRJC zqbZgzZ6RMweCFr0mnL`YU9i@{kt0Bu$f*9wDss3z@w@xis=Vr<=f_Q3t=8)~>lk5V zBkS&*?e8m1+HN}h`e*H0rh#o~*j`{!A{pk_sCQ;?+KV{*B@N+88J6*d;{m5%I%P?Y zYmKZRud#VUOa+`AS)a$UePadW--0ukhY)Xzx&k zY&Ag)3Dy*A9K4Wdtcj3%p0Bq-DCaP2vkdqLaJ=>2+JV+^tV$iL|yrfQ5pkAl5}RgS+>fmqq|PUFQB|@aCfQO+XRmWj>OTpbL6@y`5mQ zi5V<%(8o*h*5+!FO>EJITbF}+ZEe;qU&JX}cMx`s5i6upXs>E_IVja55LGFw=nz}_ zv6qd_5G0@Wn%6SpwRno^`+t%vE4X@5#UeQx(|5o*Eo&lo-4Y+ax`3rV;K+i{N@W&FL_kZ(WGLu`1@ZmsM%{sTF4N+p z{2qeKJ2AMZB(^w1jB%;PPn>IMPaP)coebunLHgVVL$C}o#0_{6ZRro!Kqktd5SwWZl2B|1~j~MzZac6p%JWlav|l zEjPv#CdrnOPmV--8tRdyO>=cs+$Y1`RC@&?Pl;2MQqs%BV zqVoQlD&Y;LzC)Xr+P&5zb}-ELBTc&9eG(*b>6~+nuFGtl$APt9Q;iI=tiJB;h|d0; z(Pi-)uYsFb7sa!s0Fe30U2RE$$|tuv*yNB{pbLp?QmpnYY%QBaws>sr5*}3epnst* zMe6o^GWR+9JR%JnJFL&rIQmNbYc3k2GIdS1RJZtnz%KeJ3-8hc^p0IwDf#Dk(*$>V zoW__%QabX!a>GmC#hJE&fikbCOs%pn$nj6AqZ9TAdK5R55J9GOP(aimz17 z9ZSsqDA*t9djL`Sa?qgkh0Kq=ek>@4@Qyq64s7!7%EGTwY9k>NTZ+C^OcjyFWwX&J z81r)9t#9hi!8yxV_>YLnTh3TL?t(9! ze)Uv1UJl1z?+fyCm?=gW7In{<`Y6sWpi?>~#9VOnDQ@#JprnsIq`JT)z}zefw)mw< z>59+P44hrRHN842*dp=Ah|PTSP%$DkvEcZR78FmSC;G)EZM}Qo)^WXvU;C$h=?u<3nYW+VAuMX^ zAxIP+u)GI!Ga)r4qD7*`4#trTUmpYE-T7mpJf(hL{N;lv{~iCi9au~TdSns&L%#jM zoRceRk6&+`2zaxjV64*C7^)NTW}!{Q{Td{mZo1WLmQ;P{kAQ!FjvMnZh=%BpcIF~R zBw<%jtnL^a6D%;^t|=5%sRBD*E6{NKqHa5;F$QCbf-C&EpGog*>}xoj`h`~lJF7K9;J}d^I}5@S_N^E_8Vsn7 zp8O?&bkP$2?t_b+?Zp&}%~+v<>coc{iRK3F^HeA#KFWcsPcvAeUH-O2WeKvTq6LmE3pynfe|c8gg#*_WJs zLK9n>SgZViyqKE6tFecF(!e%NEN{n%*zYPtZe`|>^~rt6RAC>yk3{`mETIX3puX}d+ z@s>>t1_;vN0%HGqpC`e(+`Q{5IW6LTuEt_#K0%a^j#Z$5k|bcds4MP z297*reE3c8z2W;d$pRMJiO+1%mr_>wMcWtHfM|%4R=gPx1H>k@Qr|g_9E{)}00~GC z+&Hcmf}lG_(Z*pg%~giUqj@=S^ma2`xtysfhiUuacKOlZxUtF+EC&1*! z?A;Z@cQCR8l_`4e+a5o=`@b*(v;4sJy%x(zk&M;IVw1)Eu+43Yh(N;( z+bC>1ke!9$`iE8~NpIJj41|s;PDG$IE=B$OVpw6+BVP%#t76)TEJ^L$IrzGhO*I-3 zA0~#^X*FK#=CpB%aw_(2-wKh2$P5FrYAK<$ta57>TQ$v6NB^fx`nj)kAoH0 zfo+9T;l#iE06-F7%F0?fbT_cs=P>T2-3>Yss~q8!&tk$WZZMDRID#6f!EC4zQ&882RO z9rwa_dX-G^l%t$f;PA4oHfWIKG(OAjR!kmo$3(n&)Fo=Zf6H&Eh-Vh;x)EE2LNiGq zlkZu_9ZVUS?cFfh;JQ6&XfuJ8Ag0<4h+b)D-;(O5uA(Rdregq6FjkKkZ(>4Z>`RII5mL$mmz=@jbAl{u6yA#0bWhT4|TahjSu3K{Y z5U0d4xIzgx>s>VSH?80c1+Hz52uT$BNl{@}RQl~IUZ(j2XsmQrg!ctk6&>i+rW>QrDzBQ*sqzHI7K~R%P3qoNQc^t}i5geGu-#eHYhP{1Fi1yp|mQ6TUxN->bC# zPGcVS3b{;ztAc0kLuL&)C!vwht>?R8PMeQjWA>aYFFdtN8?MJR2^9w!KuQv)ih4~Kd+<5&4yMQcK>W?yM8*=)$SrB6sV2oM` zCpao|>Nq&cD`8pfn_F{-5O4b=ajv6_ojnC<99Z11WWT(+d8pLaCJSls(Sm*<0a-(D6C$%HMCnfRw%;(v64v#=)3AT)dJl1M*79I4G5^hqr|F6J>w}cV?zKHUuedo zn+tP(roRINoQxE+dYN8xemk7=Ri}G$MCTVHAk@DYj6h{2tk|jORqXU~(xsF96+gGC z11G{xV8^N0FgXcvn7aIRe(~yv^(O1j#L_U6T(iuiY?<3teS6OzCa^rn)r+7%X%e;_ z1NqA(FP%s*#Ml&ExiICjJUt4rgPK?^q~Gt5#Rb|75{m6cEM|g9>wBZVySQFnSd!cH zgQ5D60xI&;H6k=|<(D`&Wa2z*FkVcd)QB#k{eyh>>k zO!&YCB!7kwb(1-{Ca90=@jmnm)q zKwJ5tjTBio`|#KK-i8RF4p$E=hLYn?%%t%^X{J?R z0~w8&)f(iTI>F%_Ws^ZK8?P}YH4O5XtifeI3%*$?nvwCKbML3Ek~}0vW@^lH0YMl- z2VtkThz#74^x2}2Ach1MYvdD z;tC?bP_x9?^+y?WJ+#Fb#H>WVDk2j4j2H9Ktj#xkZ+`Q1nf#nzngZ8^;jFp!xmL#T zyL>H6ah>WD)5_{8(aU2xtp9|dHx+9tGgOMl-iBS5k)3=bq^8OF*zs*|zEFcf^t>Sb zFZXZanL}ya$MwIy1(EpJTCeCKD;LnTATiril<&56;~aA9?iGuvN@FVE^{rt>gOi2L z3hwnay(k7Lk6JdD(k`S@OZdgCR7v{p-$)#ZXteagrl`Lfg+ysyz1(TnYs{M9s~=k= ze^I#|Rq*D`2rgl7WgE}birFLivuSJ+la92jblgk&-7NKGBgEbhVhMEy3w%DLMk2%5 zMS(Y!qoATeh!Hu@Sv#=l*DtjY>t5Mtfd#aK@XAulOFKn_QMIH7`Fgo8IpHJXavn=t#$|QC;u-B0Jns zqN`s=jT7Tja?!%+B4pGRn>T5AvYHM%@xwaJrlOSiS5p-`hrdSJ=}92Zjt&lv;9s5B zsh)m8jR(Kl&m_}IgRG8shI?^2G3>x3iiC6>k1s554sJ0|2pTRKK?7_P%|RN29FCUH z*vPCwg*%2%83r^MZK(m9^%ZAQ&6-&fgQ=jUk*hoK{<=MJDS=Py55gw~;RhL2?wSC} zN3t~{bOXzz-Rph2&YFn<6YzW2Tw^s z34G%oM%~Er$9Dl^@oqd(x>sIY`($I| zwJ9_#Olj+j_Xv#{NL$XS`HzKoB1=)I-keJF!UwW>-UakCUj2p2$tTHAzSUE~cop3~ zbE|E6Sm1vdqU3@bxfx5cINj80oGR3K#-t#BHhn&*@?*# zv%|Ay2R7(=Pr%)s+QAZaqYA!!wUjQJIr)RdAAc6k)Cg1XMJxwYdsaJ7bCSQHg^y@$-rPqhdIM0)Ch1|(M6cSuO zNIW@t(6hlDLj%d5z^Mdawbv=*>@`xi^yzm~;o^=}jTYv{n7 z7B;(zq=Yjlu|Q1JlhNgVnK-?T(L*|^f(Rj_rsS&oj}PQL6gDRsR;ceOy-t3kAGI&I zmOAU|{Ee+0wtem^56FUs4!meqzSyldMEa7KzWXV-w?dn>Q^nMFF9y`+G} zm`v-;Ryv?L0*ux(&`!cNg*=f#q;@$S+~=_ZcX+KeuLM0Nx3CoJl;)7IbTo8RG0^QPT@2}JH1xU-aLwyb7^L{>Me zkt@$0eW(*VCroFH>s-+SgrxSk+BVV-c7f=d{Ide~ca$Cs#g=KZM!i<+(Jl6J`a^0N z0)RBgb*Z&<4fo*UMqK}WDLXVGwC>IDmm#3Y}8(Xx|cTa*q9cyav_rO-3YIdN!NsSo0e|{W0H{qYCax6+CVI z&MV#vi>!-#D32Hb7XF~z)t1>HmK`91_tdXr2AWDu>$TBsjObhM)-g0r9A~p~6RI3t zhUE4xpOy-RN}+mIkcL1|#rNKW75x&GL z*n#O8F8(f>q|Fsgov^Fa$f#0xA&%0$TQbeT(QjT6p&K}c`g8{X4`g0^E_qk89=H+R zevQiFtgFbdbB1o(r7-TezW9!5BBD=k>#|geo4XwhpqulHbFFkMXz{(F?K04L+g1Q) z=#VcpHJoJW0{#zJM~hBC~H1n0+7dJlJwM+fAz? zHOTUi*n^lq1h(#StvK)5n+4a<4jn!zELdBr>rc@vz|wy-cd+{%Y>5!6&AB-Hu*BOm@cB?+ zo#8;FXuN)EPH#mqK4CYfk=VOgbyIxBo|@uSq@_2bFD>kt7BHd@kt4f-C}{T7MO#5p zQ7$+#pLAv8bhFptEDg7EZNZTDK||TE3qr_;-j`5Ex9g^^wC&?EJ1~f?PKvx|jHUlH zeI)C^D4YV)eL!hceJLv|S}q;BmGsz`7|{P{U1L2-VN>dFo?rHATPd1O_VK_Oto6>5 zVjc+=ddaP&iyismQ{joWBvm+wSzJw1=b=B(p5>hF1spdbL{zd8P=6}vWGK`Sl&9V; z2*WAEwCdnPY?89u-;si5jFG+EZ)%&ThC~jq@(s&hu>Vn!&HOd(+)kB(Q#+B`oMP_v^FG2+Vs-W|By>E}M;yE*BH3eF{XB ze=r|uA}sJfOH~_l?8fPoX>a^ToxUlLufU3&l;kZ%8~G0*c4C6m&^P;|2e4 zr>Nm}hxV(Y$_v|nJ?-E?2q|>->3A0kHFgTM_aAhIafQHl?z4JF9!txFyKs>|TWv{& z;R1pyu2iAVQRP;eoSumvRMI-Hl4VZ{((^IBFvBI}4>Bg08sB+)GN+6xA9cF)cu-_x zT-i3RU_P>GL-_gyw7*!~!17&fqss47ucAv)we_yjqbuHN4-$vRj;mDCG#RHrUmRS?a$T!p)U|v>#`7K*pr=XKuTk z8k`JXApE;=$=&_ffyjQGizFKg2-JR_{(5>%xM)af*U zUf7bUe%>nFO5Z;i{bKtbE%6l$)G}ns1`rNJi%VK51`$~$yVqOI@N}iulhi!DfmcdMVi+>;3Sd< z1Psv;8Z3P0k8uO+-TsYgu?Gq%1|*d9b#_!YL+A&0HUh;xl!og#AB-0bUc%z* zn)~#=-|y!Px#vj7iAf~gw28 zKDuTSGyY`Y_jsDtn#Hf2}Y_l5eULY-U5iU;MjeXao))COTcT8R*V zPj2*60J`>B=rn01^K1y#*3#>AdloD$*r2<6rsi62h>cWlw$*Wx-gd7JlP)rQUR{4w zhOFc8XrFI|a;q_IWp*IaseR9h!~Z#=e9ti*%TQ2*h- zo7Xt9M{A3>vh`?yK=|ivGZqFM?bPOcCvAP`+vl-azavmzz1)3qea67=(wsg6d zz4u2^d8RU$yuM#x*Z?}*k(EbwH%Z;Tgy$!2i%KDl&^eNzZ*fV?3^hC2dN4LepY+{V zE=qNkD3-mNOmQ2m5L@fqLDlen7&j(A*Txnzh(NswJt~#t%`_N4Ve8oC-Ri z6F@i(teVTSa!`YQ#Ob`@z z>b?{=_1W3i?ZD7a!jL-!AK$@HE;R;=*Ee}*eibOg*h?rVeOu=Q9<2QGpc?zL(mJV= z;nDnah8vi6`k`$l1x;n29{_Vt3#C7k(j|KdVaZGrQXUoay$~gCxS17^%ygjI-6&G2 zJjtV%c(3Hq9MCKmAaHM`Ydnz*5wC*DvT*`LnWh6~<+8T!v@Y+(h*S{};$X!3qDmm6 zUO?TV^#w&8NyBrqYn9iZe)~Ph@q2vM@sxkx!$HSu>dEu4%8b-;IzYs0{XV1AWYuHQ z%G>*O@y3C&=vF6DWA6x;Uik;#-m-G0$mSUwob&>{8z?X4iJ8bnw}LlpR?1C9l^EkwJV)WoOd%Bp~tgH^NE@zz{cW zh`9-f6*Ei9QynYLEU%uhlfpdFc8e`0xYSi$E;0vXz3r52SMtid4eQmMw;4 zd^o%9POLF=%Tf`IHB|38+J&bc*(<(5ojsYtA-?ZbicXlaQa1Tv z50qtP${h1+*X-3Ag>@xH5KUu~s?n=f$z$sXRsS{q$YDv;o%26+&HITU8eZJ5I-k+t zp~xMg`+UO1fv8dV$s%MeEdVvU+@n)hyOS1dN3DJq&yIuogCAc&q91z`B2-8mNk9*UAJ< z+(YY>u%EX0s(d-u&3Kw;(Bx=aXE*r{Puab?W3a_##q%7wBw$^OP3fXv6{Jgq!-)v_P`u7Z=PPvL%Xcx1EnuE{@? z0(s>AJ12Y4qWi>R`|wvX7d?B&s)UH ztFI-6{*r0>@d@J)x98Bno}a;D-pJ(77{B?rX$|&alutOboB9LYhjv4uMX002Dj7**d&@_u_*FH;lT}WD7{qSxoH*WShR01HTofsW ziGpKItIa57fA~pH;j41=WBV+AE%J8#ans4^PGDHq#UgR%CndD_+ECM36DH+Ebs_U)tiTzm2< zn-h=va)!xg!shT*U*ts*N;`dm0}CZPp;o(!K*W~fR(4ySK$B~1t;aDL`ljwoOqV^l zYO5^*;9Mp+#{GTidSmX564f_!I1TM+jl+Sv=-L3!11RsJz`aM!{c9hh9``@>r01SL zxCJCDkE;cL>>&DSTlIaqRnGmYJQmf{QbS4`?(74I?5s7gDR8a1TdL>CxDGF%6Lx%8 zvWJ}JsPw|Y5Ui?P+f$h*Y1JrSy;j_cvkVNh^48e^Sg_$7O5-dQg($U!ruN$Jxltw8ub%Bl=F~bi}&v zlQg2w#d{w0#MSl-wjr|biUPri<6Q-KMS~L0It7R5Y_$bICTFM#x>nRy?ndE_c%+-8 zDzFM}9{<}Oxb!oZ7a zg_e7hwGQmiAQZZ#`J1|qt5CkzdOWI4@9pVo~b+h@@2&1RV&bS|))VJBC@WsLzSJL4P*TId~2Tx0vTeV)$bEDnd z-zk^rxR{R2im@`w#U%p~Ma?dxI;zPUO~pGs43DUY43JSBU$S(eef% z_r(e#bSx+en^8XksByS|Ug~Uj&7Vj-@B2K27@|-b=FxlRl0vIc6y{Ak!!aFwVh5A+ zc=&wMvB7sPyf1nMXzR4*p60QJwv)#MUi9rHUOB1gw|PWM&tPZXZNlSrHe@iutGR#y)@1RnbkNpEI2l@_L#ho7^os|RV3Ya8Uy2Q2|0<8X7axRZ zpHvy?I%v8@4n0<778Ss6Rv<$~k{Nc7F6X`QIuN6gk8%V09F01?fWAo;C_{H!=7xWO zXN(AE)BFkn^1wdl^SR7i?NfFPK|4VZX97*h1Cn#2elftfi+31ByE@D~i8P7ygu(Rz zN$7r`O{Bn(oJua3sLeNq5kTXNMv?Mz=ja&ehQ^^A+M}c9>eD* zm3;Ig5nrK0W^gfD(SLusW8sh*MLBg1{Hr--TGb&zs>JZFUA}UjJ)x_sg)Mr~eSqHS=uzt2{ zThX*6=93=p5drk_;n@EcM&1OVTo4zz(^Gr)c5;-j!3u56SS zAi29aKNV#tJ(_H{$6~9)q+BK>g}IB~KEc8E@(dkQk!&9CwGh_Yu&hl09Z(NX7w#(< zYP&5SKP@_p^z%Ent?{5e8%)+tFBHl=^tL}yF3t<3X{Ae6D`HU8RV(|WmI zfLB{P5lm;ABw@GG-QD1bwp zWj%Q7IrQv+Y9V_g(Fe^%QghL6(nz{$lqw}VT2DE;%osJgtTW%J)um|bX#Bx>n0f#U!(54_cj2BM89DczHFQiL&&m`uYCIb6w%*VBBWaZ zV0rQphR-v{fu8s_z)BY??;$ULZv}1F=RfL+^@a3Y)l7)=+^MS^&Q5?BmV2nP&^-H5 z7cr0|-s^FUH1MBBugO&?OA5+{axZ z5rv}Gw4f)2Y?|5*oOz@z;u5+CJ2kd*pYJ%x7>^>d6N%x8#I7F zUqv7V1IKtMyYIzj-FkA{C#!Yud@g4#&3Rx0IK$Go=@3#_tK*UskaBbz`33wi7%b{D z;`kHCbp!4z$g-l6Qf>MIN^UD*A|aeE1~i-ksaNW^(|dr5dmq$48bHvlk&AcVU)Tk% zL@4!tJC_n&$A?(^P`6LZJ8&vdM1JOY9L6bAU7xP8Mp*`2QSjPtz3OhF*dQk0AEPK; zb0-bd@uk~R0aTB06itnxcVK+OGE$L^$_QoyhqzNNlj>?Ge46~D_Q~8q?dNE@3j4s# ztE)v@>VLfw#<4$kbnYgo6o|T0W7DR5wzqA;R#vqQRA?ACwxb4!Z9nX6d z;miPOMjd(va9AQCI=j4|w`g09qLUDSKo`iP zvU4ssQDA#^zGWCa{v}r{Hz3MsgwT2$AW0cfSEDI;1h-jF^QZ5oOBt-cSBp6VqGehc zetqp*TZFf^hTR5F;g!-J_A{SJT4xvvCjYqd@D`15bEE-{1`|Rtunms38V_;@ycZ~Z zxaZUD$Fl{%QA>(6xJIs%^`sk!Khx9I?*`gHAWjo|)Y297zL*T6LXz7VkC1~>PKju> zATro-$@b_n`&ASCizVPO9icCJx+2c6eR z6f^1XIFW4f{f|#~XaMgqE#EHFSVeg5RViLZZFKn7JprxLT&|tE5vNLe2R=nW4Dmc@ z5Vi)dAB+bGuSk`ytfwF;{G`IF>3yctZ2aaZkv^}H&#;pzzVcxn*jN457?gxLHOmw( zd(xUy+^rhy4T`1ZD5>zDdS}>}fzHxHd=@IueY@e_HuymBB@`X~rHdA5NIg2BT(|?L z^_qpjPeV_{0oSoB2NEhCzo9w@rvh?F=EHiAd4$;A${){0l$-Rc9INtybhD^Wd5$qu z%rlA0!XYX>gs8DNgYmqlGpB~usoru%234e=(JKs(mZ zZvxPK{S?4*#T5BcZ4cb+;wVo|g5MJe_zla+dQe7NPlbOvxbZ#kGSbN1vnmhr3#J;#806P*PtIm6ViH( zc&&$QZ8aqCmlV@hQ@Kc8VBLk{9&~r?S%rw|UsP))$Uy{6FsV1&=%g-CFN2}lsbaaN z{W{6L4PVP`BUS>%yNxFtPhXx2BMsW?Z+z#^3&wFlrX?KImF=YUmN8_{3b_?e#^$sM zU_Qm5(}->fIgYEqb7L$IO8nIptyfOA44+p|aA(ubYEtyP+=03HgvCW$FlU#D-`B)m8iXjb)TR5YP0w0Ew7?!4(L8K= zO2$qz-{HNuyM*8QEl8I5v@G4ZhwY4B%KFu47KmyP7>t48sKDjbAl~1e5YW-8@ zTIQK30E+~eRt`M>y;XC#c2+un7_zroNNAw$+{*A0neLKT-6TG6Z+-IprsYFYn*_mj8%z z^vJO6`2_(0yJ69|j)qvr&j={jgG$Yf;VyE+QPVEm>#D~EPG>{uCr{cqF z*Y*eY<_dwkoVOG7abAAg2&F8l<9xjTNcXvaE3feMsYaz8n`o$2dr{Q>n z+-amGgOQILjF#$UG@l!IEn^vu)t=D^I;QV9IS_5jn8Lm{TZjZyUMs<(22fOrJdvME%<9 znt$F=KYuesS#@yz=ZR#XcPA?2NX+Wb_dVFwBg$;?nR{Wmr%{h?NC0U+|JwP`WvcCI z2%@ih*1MjgpY8Gj3hJ^+C7a>Oe&{%QfBFY(`nlD30@}OG|COF#Yved>wDp&QM8xl! zOC5v#Ds8zE#@L$s%)>>Ot$`O!58d&(ZiX~xxf6GZ0TEMa&mK&;uDV%&i1q~2`USw5 zI77pvx4;b&?=FTBmNL&q3N;Jcg!-+y|J7_h!y=*ffJq4(Js1X3dT7o}kB>Vwv#M*J z?}Cza-|COP5Tg8~`+;lkwQ1}-(P{_aCb8<%kXvGR_Pd&k0xC1!^K|B6XnVFY0kDK! z6?H6DmKlrINkH4ENEh{(#j3&ws;@c(!kRI)HbS)QU(#jONXHyLw zVczcN0e)~iJ7c&gg)ZqmV*&n44GHy0W5p#fD9nAb!PN7DszNi)VR z<_;<|8NaGS@A8dQ@5?m3#8_f-&N9w)eUbS0W`pWRynQ>7_tX_+>43P~Zq!RW4rty$ z=s!a;<`{(OOufepM!3!vb&LI|FL&$N$?+rK$6kvGlXe2vnd(b0d#3>Ci;9*5CKI^y zM=*<-Y8|W*&MijQ?byt-&VI?4T^H0G)hDx^dMGpjG2PKF-Pl)E; zHZ9F6J>kO!8lDm9&yn^S$aDQE^)vJGvaMMr|3@FSH?>_N@q5W0-6*M^IkH+yi}6jR*bUpsS?z)u1zO<801YOM zU7k6KAAmfUe22e{=j4?e{Ht>F0D#AST5p7SIab|S5o%>oZZ9Uk4`Gg3hQE+j&+^^ufpkV2{q4MF>5-6|5pdcZnRl^m#WmjIJF|?xE;uLRZ6N!5e6J|C znxxX%3g|d?t-k@qU|qmS9lK>lRGAmotOf|_&6Ruz#`d`eBiCn-z;jnE;`tL*==zx< z+Bn1>pa4>x_JEiAs73Roa$|4WB;0(M@|o|li9=7`bEnfxd%kqJm{~!4BP%?@QM>pj zdY^RMfUA&X`_*GO`t`^Ikp?Wjmi@-abolZo<144I zv*uIUopDZZGqCjkqUkF9qIkcqih?vEol=4zCDN&YbeD9glz_0*k|GV#A+fNe;L_b7 zCA~{69g<5(vvj<(-_P&;19o=inP={E@44rk`w!qo(MeU02iy?iD6)H<3oNcRBIR|x zIy|%y^ewP_hY7?oAUZzHp!WzN) z2X_v`DTS5IJs`A9KJRpTuu!)BxTj1=!6z$YPUvMFX+p*QJ^>N6nTn@jRr;CYIc9dX zFFq*c1{|pfR&k6eHz@l2)})Lq>jv-7>wOgOCA?BHz*Gu>YIny#DJGnHD$RnRE)$v} z73Pe>mTv#a-$yNLUo5&%dh5^SvWU_2;ja7t{fqEuhyE8B^HKsovrE~1CK=)yAej8k zgtR@rFH6t6gi7)cEuPBz+6Z^a?N^=jRLNJvAjO0LT$FGB0l?!%8!J(pb+JOdf2hlj z$~L5h+uM}&M>+TO`GbjID_9uOaQ}bd-P$-p=Z>>?SYp`H%H8W7HbLR!WnQ(Ih1ba< zLezQu3$3izE3aR7+qwF*Y+RXbpYC=Lz9adUB`ML0bPMSJkNQF8Hnr!}Mzc|O`Z@o%_xDcx9QQd`sfoVpRym{Gfs<-QPsy?1ExANYX6tXYHQZR6 z=X>f(^oB{B?2CRP(^mnD=?(I-gI`P-_X~eY8?4#qDaDj+T{;mGzMJL0?Ub`63z^)k zbegaGG2)&mpcrcD?v)_IRmWpz9|dpxv*Xm65PgUG>hIzHVzBG57{1)oY1ncKYy-(z z0vj%3ut{({Tas9OZOBWFTV;w>fC?AoGoj+-{W+QYMmqpnZ+}At0UuN7LpKX*y`p2dk6XMhXWJFxE03fJH zg5mZ~yjY<`*aUY<6vd;fh1dkOzVfu(8CoHYbxh++mAX(+hY&7jfs9_eJ~!!eQU_9V z%H04nK!T3H@X*Mw+*j&D^Q;7hvAcRZ)JI}b;8NI?zdgTY<+zM3?t)=vYXA37Go_Bk z@$p|k|K@Y-?I>^v>Y+WehqlmT2VxWL{9|~wO^w6PDq!(S|Hbr;SE-w8n1eiuhe=Ia zH|!Kx#Z0iINX#IniGQt*t(R9Dv#I+V+MK<#_%-gzhHObC?tyu{(c}7AqE5G(Dns2y z2me0v4Q(7HpLAdJ^qBLGX=eWtQ8J>_<24AgatV3Ulg`G`+HUJ==BUoX>6|m;n*5Q1 zlFCLYn5}2|!n?k^Ii|8mxB;{_`-s$`Ul;|PS|5{b2&rBFT@zE;rzuWi6V%@+Uvz`b zms;6ko)s%vtPp(@tj5Twg*Yd5sqdWuc35QTyM@x{n&_1sMan?C#3bLK2x?&&0d zj`+^1BngMv|Kzs)__kM=82M>kq}P^R)HI8|(3wCnd@iCI)&V2%A={{9rk9$!?N~VD z|4Q5k;^BhSX{^XdW=D}(N9wpskjy%qJq@rx%0%6r&Sku@0m?%#r2mjbU z`!Z1N%If*gzZx4S%N>Cp#r1k0^##Q~S~|@wR$?qxT;LCmAcdBK#?;n=p8Mtk1?uPO zKREticX|Dy>768hdtmZ1f$x{Z+~YXx-(HM1^|KI7(O1>X1JS>Pfch)Xer!`ta zmrr)T4fk8>71{R2n>JL3C*f!873u|)>!g#VTE2@e*0TWZ;$S` zcRuOgp8WkIGM@WiQG!9~TbMWfnTujmMirQ=jw`jJ49)b8!c_w{>|K(TFS@xT!8`47 zepN_8{o)gk&Dgx}eIMapbU>*^?r2+`Ok^Z{#BWhF?9*EI&N-7b81yU)bXJ>u8cK{G{1{Kh@&qEsGeNyx^jNM4+@NHw+B&}Su15LJ#Prq z#MWS(F}a}v?>OH*r<(Q%LjUQI$YHRB`>jz|{oxu!{eejpuLrIEK-}-bGT<&|FU{v2 z<3;0)2E2Vj;6&5HN5yc7{CggY_%erhY00B_0@=y=%?kX96hF=`47tH7`HumrPy+Hm zZdSqgcA(2x#Cr1HZ#q6SB1v+FyibpC6j4WtuPqPng>;of5^~d$H1t0eNJOGEj z)S~67{_!k=vX}R+C`=MK_HAr%qjnwAG|qEmBis&`p4 z`?y1<&m>t0g#47D*rgxb%OrAf=4`-QhrSz+`$*q~sX?b^4_NyJjP%zu^Kr=9dwsBg zKkL_--xhda`Vu24D!nhO_rvtMO63T@OinhC0GpzD)}&wOuBjhPZ?>j4*K`sKgAaTD zGEu2!oiZSe;2h&&HNpyRQ2>g0QozjU+0Tc_herMMbiG!D|1o^)<($F)@*@1VFa#X; z$7Df)AIpV`3)r0zwF~c*dl0{%hId6Pba{Vy#V%3xAcv*+KYRkf+XyC0y=|tDJ?XkTJ}NMzL2=!^ zd@(2;WBL<`n__jg%l{DOjlZ9Z?d{`Ze!;#Fg*~7qQ2koRqP($P-kZO=Z7-wuK+oBf zL#?)vc2@CM9U-do`oQLuuxgrI_Ae>Sw_GzT+PYbFs3SS9?4#*X<1ckHei3gQ7G-ey z`8K;!M)3<3-Uq%B9Q0{K8Rc^&Y`sAf$Gr*E{<+_m?S`$lo6U&Z9?I(JvZu$Qi7kN= zvKw*Tr>>bGSy*lVm;L#5WG{=BkIfyK8I&Nm#a2Obv|j3{*)+g~j4d7BrTHu<5LffA zMQzCi@*%VV`KjMLo`*{Oa>`C08? z9h+(DwpD>~lzJ4@P{}8bPyGtJlonX!XH=&|_iU5@}idy?06Vb}9zTaI-T{~ao zm$}(P%#Fs3kQf$Q7c1x6qSMn(l6y^DbxMWKmd%fB<+F0Kk=pBWT|zdnI3g|4p76ysnBJt~>y(HO zN;PU5)H8Kj4k3Eti7cd%)jDCOYdr1ibT<8?lG@# zZXySl-)=ztoQnfmDm=sN$rA^G?e3r!jo=<(~RQpL8>%w!Kwyjgl-ja{u@wHiItG;1brvY7B~v(=w` zp{W8TEoAsaOu7KpOBs3NA_`WT;;|*MH)X?&1E#Mt8H&R&-#dK`BDLlDnd6m?lFQVT zY{G(@XGhcQJoh_7bwU^Y+(S?%55pYmPcIxW_FCh2TfMpujiYs%PKJ9g$CMdI4_8|F z6gG0Q$7&6)enzCyHO0O&!N)w$F->_6tU`Ua)D%(_%- zeYyK}TuZ8MZ*3F(y3uP_etib{Na_gKH4K^|hFVUKt6Sw9sMNV}Aqr;2h`S{gE>wya z=7Ui&Y9T88P|KtL+%LalS@=|!O{~TC7am3(2qWJ*@OcREDYTcsB`LJ9;afZY=`Hdf zX(N3Cz-sSVW=%7Mziy@hkOVfAfsehX(7)J2fKKtl1#@8^v3wH_?q$jyPn=JocWs@2 zg?vZOQGl|-^kxZYMA9|SV#q)1E$@CU-XAc z@n1D-jf`VHME`DU`Ft_SCAn;%v!|K70ln*5dIT_IV)PvMCiCzYnQi`9Tm7jP!8 zW!~uE)orp~Avb~EDgo8Ik;-t;?QUi>?7tJrI|+3lXgqm7s~POP^?W2@z3>ks{@eRM z7k;KX(q?qx|1AKhO&9aU>_n~gw~M#7UZZXuKr@!;eYjhJ!I7#i{Skpw*nR8MjBi-+ zi~QC_O%xE&p=sqBc&eng>V(eiYGGA|6o_$rwot<-17noTxno*clz)8b+2(XJe1cLY zQ(L5EJIvUX_D)()P@xY@T`C><;1$+hQs!MdF%m%z02N%lR@53RvYD?#)~`?d!t?7d3}fI8!USu zb@HOiVU4kCI5?vz0wiZE4UnaILa}!mC-qUrUi<+s%EgZec+#lwUKYjOYFv=p)s7^& z{MJ;l`4>CY&-~xs3wZLBnxNz~RH0sDdx<$VK-m&d7v zUY-4#^>58`@(9|rWE2rD5drq;S0PsuyASth0dV+nJHiUUhSmK>Bg?L4jLWH77jypk zCQMZdkIff}314P#`@~0IL06UCzK6F4-jqv&C{Xu-r_l^>oG}v2f>1nkj?JW|j+0;! zk#ck5^IsK2237-f_`V8V4FW0##&oSskj~ALsNI|Mfgqt7<>{6&+A)NiemQ6eS`9zFaXh}Moes+<{QK-AQW)FD8!!Y? zvYpF5tvkQZ6V}ixJWGpjD`*Z;6>t1ZlaA^P1rn4ZksG%4L#G zmziUNP@K)dx6m<@C`c$#@~DFmIg&I511-N`q=`$kC}cw#7t)mvRGLN&P8F|Y3P$L^ zjl7(6mxv<$L4~557O-&)#QeGH*ADMpWX_teAi(^jTv#*Yrj1XD>v@h#XEeNUu7Ix# z_(zrMg&dCnae*TA?k*S+?bcVFDKU2{E{vA+iMR3F>%JJmMeu4v;%pSZ%Lz7SPiix< zI+9xah}BrqxM_W=w;ch!>TWiTMD=UV^F}<`@>CL};Pxq{uLW@1?`s#=6JI|-P~~Q) z4+wyOxB0UjDf3Dn<0t@~at_hp|0U&MJHpYnw~T-oE!|8m-44G1JE3ba#!iHO?LpFW zH*cUSf^jIfS)uJlgxQ+t#=Gu7mR=Ree6U2&Q{7C}=Wszg^R;l}DFA zb!g2nC{Wz_b3eY;zQ!!Cg^0>N1PnoywxNA7TR*k!Wob-!e<6T7IW!lGc3d%Be^t8r zBWX;T36pY2_B@7$t@yw3`+6u`Byp9;lSQ5p*dZd_`^iGHynOh#1tjY9KT6dl3*zt3 zZ94M-UAw)H&{Gh!y}7OLx? z(kphRX>v8pH@Nf$z63!2e&hE)40~C0!k+J7OY`5Y>fPLm$CZhhiZiKWjo!$S4?vRQuJCUK%|=@UjY&s`DR^(YHP? z=D?UwGR?GKoB67-LSc(G>zzd@b)@_5;!R^)yN=vNMQ4=yR0KoP&s%e0A_`9NcL0eu zjQM2L`@?cMK!f$pQiCB*#0q7PuY4@8hW6B!dxmxs*8Z%J-IT+I(Y9i%QZ{q=xeq>Z<2JYtlzQeNf#?x6G9`QxiSb<{gvW3iPw2e0XushyY; z?L}S`Q_z%~A;9l757)iA4N|+S<{W+gfE!HIQ*7OnW`@$8^A_W2u+xi(u`tGM<03LC6Olq$~B;(`k0KdMs*2_H>5$9hxR zU}KHRuZKDjcB zrI##f+k6@Q4ALxd>he;d{iHTxdo4G>k$GgmudM#T&})*-NFyaLwK0WK?aBR%%Q0F?=>6wh zQ#)J@T>L1Gy*jmHfTTEEk2_RJk=VjBlPbX~nzgkJD!wmUnht*}IIHkV;mH2DTOJ;9 z-sNFOh=~Q^nG4Y$tbleDDrKmL;SLR^#V!GA?i(G)K6A&)Fpl59Jn>!X0uiT_h0uur&_ROBoxQK`pZG%>;KFf!Nb7&n8V{6G}0tv)K5Z{li^;~C70Xm zfm=kqJ-z_!4A@a>>-=Voh@oj%)~<0K0rn@lE~*M-&criBJCm0DFLMwVOt zA8`K3&vVU2SF0I2152mhxz4ZMVDJ2pk=H?xc665~xREzog1}AOU*chzuX}`o$2yF=BIbt+7@US#-b4w3>k{Tn<{|WIeR;Unnx5aL1QOfN0uz z;{2{7wbk|`dSq`X_cMhF0RVX_-fFLYG(%Ya=-J4#inZYjRqU+CZ$YpCs!3vlR9vcc!0-uC6aYT;grM3hfR0A$+m}_G=K@cQrHqv#jp-lzvc-A4>y$zc{ zL%&Bl0|PX9t9HBxIs`|Tjz`M#Q?FxMXv+49CV0kv(I};dnv0(Mh`p1S--g=CAY;|+o|ql|9G@Yi>ui8sg!pUF zNXGV#*UP}kv8e0%(r1W5C^728hYRHrx#%PePU99FtdnesXx$=5cm1(@%I~F`>~Uxv zS887kuY6rR43|!1$f6=5D7fx|;D41k!&?{bUEnEfTW*osr=&#GQ;2qL+uXnGK$H`$ zqt$aAWCKGbHzKcEd)BRBK61G#Q)31|G ziLm>9pz?@nzK>SiN4NG@vZ6dR>M48kaV>j0&B6skn~8;-!viq*9%c#nxk6|*k66im zQa7Ca@w-Mx39QoD96Xh$s-LApmC4ebfKLhmfu6} zxVi6c^gaF)mkf2pg_%a_>`T!*Ug`57@n8Ws8Xx!5f}<;R z+Us^f-z%}36zgYb+sWEQMa0hog#0C@YcFIwIv6vlcYMJ+z5B(tHyvsM-vD^-gT>tK zGc6?_OrcsmU{TD*)=Kdyr!Mjx=evY$aPezG82nb#N8|gMHvj?0RE81d1p}OoXIie@NwLB(D>9-TaJpFpuo12r1MSdN$U@qLgr=dKV?t|U!%)VTVSg@KfUoZqjA zuz%L%cSrE4q_Cc~oJA%MkZz?R)_QjTpl;_17?voJ=Zy!)d)5#@=0+K4#N5-+rC4=n zF*i}U?Mhl3mQSukS>6lI-S)NZAcf;p&!thkz^50kLIbz@Iw-K!NIPLo&@#w8r+D}c zMe#5VkvsU!Ozx$`f1nr&P#MXu0?;5m{zx#v8 zD6NQ#p&<+eL!Akv8B=d#b&v-&*uS40BR7=Ok)K)(T3R$1p8FHUp5r-Qm|o0@SX==B@?Ol3m?o5TBei|LG!s_@vzcj^ zf%1$mxZHtsVt(on+smftl#%Mw=+Wcmmv7f_Mns!KMlH+9U=o;>I!{Q5L1n^mGLL=h zD4;R4=dUy!0b7>(b072fw_P^@;QN@R|0s{;RV&ZA`a;Dm9YVlM23OjV72n8jH28I> z7ZI&b*@`Bk@a5xMRZ(s_<>wMeSBq|y4m*)D=rJ#kfU}$SHJQD93i``aYY+OCPi&3N zfasqz1+bw<0JvhN8F-qtRbsA9jTn(EW!_~`5dO0}H%5fLVWFfnb*xCKe8PX0m4lix zncq^6y)6OEWBM$re}DqE{{F)l>Zud-+I(CBYzIb++wQso8gBtWp4g=>Zi7L^I+wF_ z@UtmBz7Teu^KyR&u!I1~h4nJE+T9G<)41cn-ml&~Thg2I&cA-=yivbo>E!S)z_vHq z7x#*=6_d$QQQ-(2ge~s@ZJIiX)6wgwV*p0Lb|%P*eO<^t+Quaf2Hs460%_j$LQQD% zZ*_ztyW1K6JU^UP6B=xwFj0r(G16hWQGWq1 zyCIv}3qWT52tY{E4*i=fD*@q_GhRUD0$t?fHL&yi%V+_E7GFK{06^(_>9p$8kYHQ; z^n-7cWOY!WsIm4K+CgoHd@5+RY1**%>FMhe%*wFCx!Cj4aY{=d2 z`T_c?p}}r*pmIZc$|kkf-pL;M2|>A8>Qlou!a1<%NkB^2C$KWF1flh{?&|57jYeTB zgcg1>NGF#+o5lKZPLiMMs+&B05Oh8XboorL0oLHYn#<8`=KKFBu#08i^XMEnG6mj<=P`!oOVh ziH;Bv&hv=bmA+OyxVv4unTh*UI>*p{NW<7$)b*}4X3Q7xk1OsXzT`EkgO>>Pyb{}A z0nh{N6-Bp%7vO~>w`-L$_MpJak4ACZM=vb(ceH4NO#a4R+KlH9fV`G3HRPiPK)v{g zmj)R+;n3=<&w$nn7eDY_?tL&1-ZIW&i^vMy`l!u*TZz$@UWVLm(Ao#s*h?Z4_ptI? zBo$U**S7rP-K79yB)_d^NXR@Ha1gZ z)6d>!Omp3~EX55aLe1&%iaDlbJICSZi%+~G1QZXBOgvmB!{GVE@Iz;R?&-rF@gVlw z(YpiIF+s~kz&a)N^t)|ArN6_7a(dzk-&ELL32Y9RhhULbA$Qd&rr13AgEwDA8bG)vonfD<)YJHW%Ix_iZ-}8~DyK$$q z$=bmN$EV#b;9x@G6i1^4RhpW-HM=yLRBdA!W4K;)D!@*EU0ou^4wDjAam(kOo#QrI zaII~jI+UVHJq8|+O^NcsOTHIUKS$%l5E({|D*Yg|TdXX!W82~u@W~HT; zYgh;Htykt#0G^w^Pa-r^aykWoQ}o+6rkn7`jSA`W+8fi;bGiu>bdHyzGZvQ>Sql}k z#aamd{i<@fikd}RSipZIxsiXO=cPzZ64)2LCb0AI-$dl%Ygd^#rc7MLK#vm)%U0B@ znoDaxaw!6GowQ=jAr~gNOVBB3WWdU3i%Ne2(ly1Vj+`+>H`*oKL`glG&4ulM;H&6K zNMObVp+$b>Qq^Z-ABF9u%K01$_8ILP6Um)lm?VF^DTl`&eB&>=OWd-r=DFwFivZs( z6kKGi?MBwtE|p92WgOFsJeGWZz3vTIUG9C9dynTAL>{y_r#7JD0YP3a1eXt14EE;b zyzSz2E4a|Fz{P%gT#18)Uz4Bjz*udhUKIx--1-z*FIL!fX8GkhbBZ>B4sv}}uW|KX z4cqk6KyIZF(BTO`C|1!Z2$fm^;og4?@)+H@00uowe|#DX`SP|UHeVv zY&rX@zmUChd&TXxj?R+8^q#97zrS(6*y0>&LaH(fY_{xsl!fh2>8#NC`;oNq3ee)F z&73!W#&c84J%gJvv`D_QCprSGe>ViQ!=_?O&tZj7>7_Twi;2~wO>ePS|2esA$17Zx z7xzu~?a4kXMQ9-rgPKp*D8{2Rt;;2}fF7enU~X3?Gh%;r;^=R4t{cZ$eCcWjFbU!? z3t&bfH2cHo!$H}_XW#0oQa`uR61DGvM&AqTd4Qb59Uym5UII-xl!C7bWy= z4Ne|YV>}mR<4tpVDIK+D0LLW)v`;g`QR0{SOYuiQHc_kn^Hv+}cucKtHj$DiZsqN~ z8Ib2FmN_fL44vsP|J(|{q*Ij@@#{rwF-w3z_u3w&JB9#U!F?8SF0#yK`kDvx=H2FN z+(y_&k+!cx%b4J$E8D7aM&_$ZfJ)G<-rh|&HG|Q(TE@X4H$tXY&7T94U{nGkk;2LX zLRTNHfNe=V#*!Uxr-j;&mLo5kcm@C=wfmQ|r%Re*z3xqeMF>B6u_n5TsI;Tet8-BU zj$C&@!^@BoT50zjTpKXoWs@pB33gk0J%xc<0>7HEvrs|JfKY8fNymr3N%VBP|S-Di8 zf57vy$uCx9R|?Ir*@;(eq^Uc)T8$^Bn*3p@r-$Cd$F_+;1f82MUG@1 zNZ4u7J7)!Da=5WMgLG{4f9TD;xChwnEb0LD@JqO4rsipQ2hH3zY&UqtL@^!E-c65Q z{wUj$(OtYubzeNBex$T+SVd=cofT<{f9Ln69(2%t{deh66ywc`9dZLhU-|KCdOoBk z8hT7eJCgw{VvD55Pn*Cpr4v9(s6lrmwmUL zcIVA`XK0LLOz?D(y6sHLG=SJ2c~GY z52KG1emo>9HZFPY`M8R8h$hr35I1$i^2^?YPyS-lgkDzH+23FH{~p{3mmA+z&kEA$ z+1%v0FAg8k`IQVG&2KRSV+x>SC8Egyt8Nc+A&2)sl3(|H7ONU8&5S7c38?JZfD>tR zkZSvh(w{;3PV<+=@gI&IL$OtKIfdGRq7)TIx*1Q7+wc7!VW-1(dSkJC^R*>yo+agx{y8LHcn;krM#u;+h6y!p6M}^lUn)b?b+*qksfuZn8rB z%SjJq`_eQ+)z(Ouz*s1EVs(eq0O~#`q-HnixH)!W@V0zhs3|iRE8e5%4k?!{`{Z_s z`x2^wHrTnD-UDgNhG5O5aM*QS`NY2O6>8zTGyYZY`VWvd``WHG@|DbtE}`B+R-K|a zjga7}K^B3gKH*YY3U1n;y~8z^B`1`KQd*>O_qH|939IynNcAe3WYocYi|8w=Tf&Uf zXrDTs^f{$$cZ0%<)=97SU&*rjS_^(NN1dJ;#uY1M_d}MMHQY!Uny!YN;ny$9x zKuwEw8oS>2qiR`sJI%5eZDk8S&(gUTV#NKgdk1~Z8ib4#et)yx;UU0uq>=hDm>F}x zNRRb%7DPA*S5vT32ki#1Rw!w16Y|`ZEnS6R5a>6g{48rQO-8i;;0H8$P z?&p+1hh-GKz-=VQS;~w`7dQkCmk?+>bd65&cT`k6!{)$IrK%~XT%eKs<$Vh)M%U>S z8|E?$TitK8#>$Zs!TI_;2D+oWiyhWdbsag8w>vS=k@9v;R2CT?%LMm#3JJBk5iH)m zJ9d!LnEMkf5!RkmnqU-4EaB!-xLv(`)=<&Id#21H8v5w@UsBVr?r$YKGDmuvz0tI( z-HelSY)x%Aw4M$VkrQvcxSsDvc$4J=Hr*gAS{tR@T_Tg(@7A#rly4wGRgs_{bJ<-O zJ(nzXx!68Iz{Zzzm9rSl`F1iX=n`&# z0imH&4O8XseBUun++EgE*q3(&wdAA6MfmVVf#-g0394PUC_y#PY0f&o9sNr_u^F^!WO5Hr=9OMJtPY)4+_jLnMKIre|pE z#qt3qN*H3jD=(kC@QF1nOd-rjt>saAqFy}A z0}aT}>?)R+d!FKEzo6*Tr?DTeJ_hq2b@D5P1$!n;Udq#r;Z1V8q462m?P!!64(I{@ z*y!3uROSfbnA5tK>#Qwc0iqfsee{n`FQTjXbj~y!G?VwW>B9qJW93a@-zW^Zr)_&x zq=7RTLrdR2qjHyc?*Z?Ys^U z2H1KT!0#Xe$~P%C&BldXuO_ON)gUZY;CP$Bx+W?us9VC^tow_1f1btamhgV#vH}bngp+n2LVCJu~7QqrM769i?vYJr}rodv$)J znG3_|^xgTF0n|*FR59W$H;>X)R^q(gJ&s%nVeA_kCAOxn=`vHm{u5m!?tBP(4o1f5 z#FRlYF29ji<-`L+M5-@kM6*5}%{$mR>1I0SZ6@S$G{44vOiQ}3#VkKZKbJYUFdHK# zPx63FFH0@d9EewGYr0tY`c^iw?Wey#$4DN{CmS=iZvaQJ>c%ds(sg*LL?Op;G*h#< zw;Q}v9TX8cD?0IWbj78__Ux?5^s)VYY*K76=?1nv`|%S-nh5Ce(Rl=v>xFYn7X3dU zr2w82@MP#bRLFXQO8Ui1WeXkxCdJWi7Q7aQ!C?>1HanT4w~tvPQeG;sHR*g)s$VBU z-{;IHc*W8k9ZZ?o9R0ZK-FyzB#BZVCP?E%!CIsivM)JBr{^GzJq1Q+AR)4o>C|64G z=-3lYKe_^rLn`UaiSmv+h9hmAAOPTzM z#@2u9dFE#k`uW;o1KVQq;R$d?s|r3d)A;<_E>CB%LL46 zykrHrRe|j5;P;M136`eeg25uZP-n3_7A|-MH0Z=w)MIEGb7K%d{sEZT+NQ@qx`0)k#4DCP3ZXS>CZ2Q>WB)pE;wM5nQfZubEo9z`-lcQ|WGQ-C zQ^3%(SClJ5HK5z|MuQu;njb5;D&=DJd-;K z7Js6u!NVMoj^jGVVQA-=#AvjSLBK$WNJa^F=-%9;>Su_ADS|Z%;Kmbql;33e@OC%# z@KUGv3I=;&x{6HQ7va!xnP-Qfzb(nuKt-bq>_oZXc2yo3$ao>c!o-mmY^rYRh%T~+ z_eU$h>SO7axuzqF^E`z<0Zg@00CB;*j>{ys_+nfSOro&WutI*Wi}$PvMGaQh2&dg8 zHF8)avC^Y^vhq*MTykG69eoviE~*$Z#n8Zt4D3wM&B4D}>oiwo1oDIh?80Zzqmr5^ z1}L;WF+LEmfMmkHI|Pxhpt8wkM%aqpvcSVZ8e>BL9XK&%m7KY2@Ot#N$eQ81P3*sNzf;#~BG0oZY`dd{P#^2IdY|0Z9O zr#lkix_;I&7b0R~iFU|}FRBr5Gs35*hZr{>*Ih`yA8oBR@I#=#qcZJOjsfqIrSPBM z-Ddf0wO@>rIPwO+-$#U!IBeoEVFS+UFLCey^hS}K2JG=14tx6yuI^gfK9=)wg|>8z zeJo{D^H%??h%-Qex1cd_)@G#)wddj4kxUXsNyGRiyn_wnX1xdGC7!@BkOG(g2HYUDS*dy{SU0C{ILG_cg zhTKX?PBt8ULt?e*qOznA4#nEslCfkW6(zCho}q=cxQR?=sJh0D$8Fa5K>Z9d)$&DO zvAR2i<-qaPKIAiXd+#fTx{E`O8LL8#H~`SYWly$D2_$O?e=3T1_^p}5#_!xEWB5j1 zEzDfMi((1Yn(!u;v{j&VEgIm?`yp+RqGZPzjza9pHR2__caKs0YxJdzXVlV#x%h`5 zO%5}YYjhGe9>_QZeiMZOEC)^G#wr<*#F=YgjA*X!$cGRG_R?$|%bF7mC6`2Prs{8A z;jEy-p+Tg?WP9moD!t7I0|F}$Ke6?D3ai_yMF!B;Q|T)sNbY{|DG8!0mh0t}bRoN8 z+=DnhUEG+HMV|=hc#~UfG2uOT`Su8$RJ9 zVEnLs{b(IZ7J$6jvcB5Htn^1fW>OO&c?i14Fg@kzY_GQoB&za2Al1&ZhJ3K)Tc3>9 zc~JVeIp2|PnfJ(i@=WOk0zCb5s_|CJXmsx?p6VVrk0E+X&_5>7mE%TcS!W!oQh?VA z%)bIG5LP5G?%FNXW4|7{Z~N5kj;e{`G;xk5SO6nC%NNxhaU&hc+l|`=N>$@1-O4Uw zpsQz(WX5GIX&$sXZolXFClH5P(~>obFy`+$Cp%`>Gd*hUUQ|`vlzxpz%VIA*_HP@__p?lSfE>LB3j}cHyB1tY5lm zTzB4}8}l^JWRfyB(vImRlg`s$qNUh zvwl3?X>Vc|vmr?JQrf!KCP|o-O|qq4ykji%a(K>9!%0h4UyD5TT=eVMpV?@fRbjIb zi446y9$Cn-MxnU}#-q;aduk^#yn3OEx@#fLDnw{9M%g=054cz!8^rcT19VI4;bDVW$YIy3nrs*!6^jBbu!#cxkN|bNO|1MF3C`sAvYWE zu|%v8klMxK5t`?|yMZ%($7|u$_`urTWX#CmKN72Tnyz8sKv3Cb$qZVX6nrLGdfbh; zFJm=kSoVqm7)neBBrW)Ae!tld|32fUJv0{Hj?z+``8w2#K;7wo9faIrke~y zexNW^SN-#-8z;&Yx`8PlkvGT2er(AaL~%Tg1@P|x6(7#6VUHPbmy@Q*1e^|PMX zzz{!46$jt7Oh!9V((7jCP#%KB_I)D-=04mndTSv3)VnWu553#;f~VWC^>a7jdKeEa z&fJF7c-50~cUh(9nXEz4-{PJR=$^h9P6sca-M^=|sq;CrN*XY+QD<5+)LYqMycydK z2Z?SiN$jVnlNJdDZM4e{zME?1U2@!`UIK)_?YY~)*1a#YRXjo@kOSg|UsmW6bF-UC zInQ}q0K{{ER6>0skr4#~H4g$Nn*o*MaoI8LDN|phzB!WxZR(_>Zz7;r*?5jgxWF{< z8k2!zfRxPxIt=W8rr7oiC1oHsuQxqmq9mU^+&z;&9K!Y%I418UmEn~N#Q@*^aI(Zy z50EK_di&0%tC!b4jGG|zacKkk(HYHjd3acLe+7W4nCbGsZ$4DxwU(DlQy%?OhWvU> z7KZ7?PL%q|GH)tohp}Z)lkLBcEzT72j3{7a&gU#CHZ8_p)Vx&WZ`!BkO5XW{GON36aYs_XBuG(%4HL+akc68?m3W74u7CTWgd(WI`O;H{lW z$72iYubSVc)w9)t8)d&wIy>}-E5w)KRR>R>9?HuDm&ISV9zS|$*FGf)4C~@Zzb6x^ zw|NLi2;C)r0LTx;_dk&)i7%bFcQ#K|8uU^s9Zc%o6uteVH!hizV*KDusmpXB5A(V_Y^pFq8#_)?tOg%xTv7@Lx5%(Om`iO!82qbgJBO#=N#;-@Qg0Ho^#XvSEVj$ z%Ve1!gDD@BMpl&f7TMP=e_6hPK;y{JbU+DnFKx9JhX=P#%@3(U-ZZS=ITR^SpL(oN zKeX}30n>LxhB7beW&7#7)Av=^!>T#=(O%78@4q>SHbMa>X(czsJ<>{tNo%u*P4bY; zojEYnl?nb?YLFeBf^T#49UGTU?~PuW3q>)a4F(4suNp=UT=Z1Ehwsl;0{a>SywtDr z2ikYY4#40)v)-kM_!5{D4PXDy&-595{ax;-LzOxQ#xkM5X?QifT58V_W`Jvq97)}m zZ~KAH`-h-;^85EtEl>T+&S7t-uCg;FMgTN-7`O=nL2{O+fp^(#y_x=j%Grcm=E$NZ zQ{LF2zPIR^+99qoo}}peiM_e{gq-lWzsJ{ap;&>Ji!YlW+}m$yINvdQcsVme%#YHAPgkA6sGHK8{nYXy^Ko%BEvYQp$ewcm}NV z$s(4_21cHs9k`b!qT=u70Hu5-P4(DeZqZ#2`uSm#@pj~_f|c$NOg1F4?zlB)znsy}91p8dQ0&Nxh)+t=}-Zg3XoVthm6azlM*Gh5=l*NN}0P3i;9?|oH0 z0w~Bccs0YnCjeysgW-IfGr^A(H`Ni%;=qpx*PajBOYzSLgvZ1%vv5A)Vi=9mlz7)+ zNwxFYN{iAY^5(o+lS{Gr9|=HQbl&kX)}kN_KeJaQc=sAn=Oc|mUBT~`P5>j_AB}yk z?;ug}4VH~%^&h{zgX~*##>VRtnRoKdfBS7?bU&z;B=5(f&ov!%>z?Kx%g%{z!wi&{ z+R6&mH!nRJSV`;R&&F6V2&j1TUuIi*%a z$#`C4=S-Ubc&cGf`p!AbUfR024i~pF>LKCWzIAhfDxx3M^mTkuOVTW#+84n_0z`lj zY{%!m_LrbtRvMSkaqoEX>lMctAx;t%%*lGBwz69nsS!k zGX)}T9DqwLaaD2%G{Z|?S;6WbVt~|t8kDcl2{Y!qk86hT@ihtZr zGk8`Peoam+s>~CZ!eucIO0gnaBr3V;eZ(Mb&fuUujn!O?B7(zqq+(B3HO1 z5oKud$SuP)RHnGfH8&CNYs!>JWERRp85+bTMW)OdLPDm5$`Gjxxl)KyB6|0^&-1R| zde?f_Z&*Knuzb(7&p!L?eTKb1ry#C6isO@=dm8s5bx}iPG%~&UhO9b=Q0@O{7gl&q`yJcYVJ^NEAn$zNWuy zE2k3Je{2cej*BV_>)v8tqiDb?*= zyZoz$>W^4gjb82O$WUC{#{iYY|G_$0ulYv*mFVCaI}tMr){(qbosUFC?NFx;w21X5g9~=22D2Yci3G`IR?o=|;NJx-+xD-I?wZjOj3F$TCkq^p zwij}h+Iiq#-j*5mw5b7;66ckiuyDKwCttm4z)k{&b!_VvKF{bF33R#IRp3(Um~`yy zm-4<5o}f+bN#{wn?urriytw7d8McGacE-6p=|?|174~X=x7Fg5^-tCFAK=efhrj6S zlsvAbxrL+hQD<7=(RlpI@+>a^*=Gz8F#4kfyWT=`z9S?v$ExF;vo;2RYT_20^PO+j zh5YpxduNr-CqnF*)i3!EXIAG-Z@a$|n+Gi%$$H_1Val*iX$RasgxyhKESzVDL!7tECbbWp2rwEEijIH7``kdb%B=&F|<~dcIowARYXCga`z*BcAYk$y%q}*?u}M!_3T1^ntb)MRqVpsq;sfuSz#rO3yArA-~TQq1!W51UJZ+TfY*^%gwpwY5fIsA8<#>i(>Gnh&YD zU~MAi+0^kk-%pu(6~X#>Eis8cxfW~~xDI|G)Q(CEWpQUZt^l4hY#?}v_x1@)akqce zyXc#uS5sk?zwUs&Qqpo}>u*>%QX4fJRVf&FJ!g+O)MzB&2(*K2>A*zpz#Lr&+%(Hh z9UMJWd`Bg3u!}}7F?-z~B0DF6-syYLe5{uDP2tWr>Y}!3)Gp<&UDV)moR9r_BT2_0 zlbSvulRyq2C_(OO(MXiHy_n-h%bRDlEtf-I!3kmZ_S8C~S$)&&iwkjQaDl;dJ4_dC zze=(}08Qzo&Wd3QpG-Lq?mI?x?wgjnVPSu;MB!xx<6ga|Qh31GmJfiOa$+?N58&In zrt>9!;;~oeLdnOn6TiB@p3F2XTu774d%2D-3pZWbEHNSlmoV)|$tv^ze6(xSXp1n^jTgb9f zYiar^$uYs&wI}aY-UnT(i^18FAx)RK6R$Qscjbi_5teeL?p64SZ{+x_Do}-Rcf1P% zFXdHU>E~Z07!{bFn7As}SX3w@$I1`S=y*ozMOF;=@VehH&!{!^+PbjQnd;h`;MPmy zjw$_g?xMiuwX#)Ff!U!WA{r*gwGh8!1fZjKi%(jUoeW59p|XOrPGSqUO;+@k3Uyy} zyMj>f89Z6$7wGvT$cNDr1%y&$TVglFX~ zt9LLet8WPAYZbRQIJ;%oX7$;;V~wi0{%$-HC0=0Ge%LdCF9Gf7fm;r|CXP0%{X#R6 zeu9NAs_sO@{{2?9yfZ`o8#yB0e0{#QCyW6@Stu(O$_^uG(>UZ#YeDeNLHsxuwPXk0 z`z7aQ^Q>6AQgon4nV}!K9Gk1vE%5Hj+PpY%KhR?|*xfPY zUR=E*V0p7|wuywhaWKEyJ-@sA*Q8&(1TaKaTe@k;-T&vAwdJ6=h98ksAm*c4?7_6} zS0DiRJ(HHO;jaZF?28XBI(&IoG%wp_=$P4u_l~R-lK$WoehV{&t=}U&_Y4;gVIRS{W!URNW)fS(@-nEO)_Ir})#PG7amD9spF+vJbngq9 zJDaWPVPp_fJEHM`heF=vajKoVqUNabx((MJwmvT?8b3&9!2%9mx2ip6VsSEo?E`|I@mrv8Kf@}9rO*=S&8e0fp=7DhCYdWZD>Zvp@b*rQ>jqA9J#Hm4DY~QzV;Sy zx1M<6AQYk@`6*X&^H|o}*(T$;ct+bXTf*A5Rw1ddluViRQ(&e>)mR}Wq``2D>qBl6 zjZRXc+Fyfe6he@XRgNKVs*0^e*!(}lc)eiSM3mMDeJ5S}!P|4i-^hF`&PL-E@emAo zAl~(%cCJmDFPZYQi)a+0EZ<~p=4*hnQIaAWVG}pPd&+FT9eap(vF2*cuky7Cv*!wU zhi&67w;@~ILoZ`bdi45;*S`mBocn6|Gtq-OA+OfeR2oMr(m?)yIaK-G$}I_FqHxu; zd2g*0phvS7D$=q(g9`W(-8JMMZ|Q|x=16c#I;ex;S(R8!qV2b?^jDKv6q*8T3qioq(Iu&m8ch|Iq3rVJl^zY3yC zdvDLl^-%#66`@^KgC;NWyFScpM9)C_ypWaWNo1YSp&N`L<-+IEuoFV&;DRZ|!NSfe zj5T2k+JSp<9lFD{3U*NK9_WsZkD*G4VffvrT$*MLdAzxz6+$&Vh0k3^Dotg>)1jHL zJNvm5wOPpYa0mt)zYY%f32yS28y|!<32wk}H??(uw3?GOezr{x#0P(!W>yI>&`DVH zJZ@^&+-I#j+v^42XA2gdYIgXvkq^-L8>J72Hb5Ce0VQ@Bn8_2#3OnhED zMeR%xNvS)Zua`94AeSY=L%v&~0B(6Ce|0vdH0>WBS=!XZ)_i1pu6k8OdfGwMNhx%s z*ljrTE}qT-S6%&yfKE=sJHt2nyVHEndb*mZ7(h!)XVpUdQSq-K}{N(svE{{~!I-f}) zq9r8mv}#T$@vD9BruArEJ%x^ug&p@QG`&tH=kqT&w~>gpAov4Nf&H7HlTfiW;0qMp zagPuZEQI$P2oTz$0Gh>XVrgv;bb0hSj?B`#?0&A(ye%A{|9y5mhg4MSxmOQAAECFS zk6&@F4;vSxW4RSEf6EH{&n9%&fS&2X$w3$v>!^z1lL6~n))6pc6iZAJrUgCF<)-oC z$mwOAQ0_ak-1UfI`P!Rgt^I)s4iGoy9E+sTc}A7P(ukr$Yn#W(Z?kEbQSK<(+5@N6 za0>?-1Hy1-Nvf_7&(#_8$uU@sDA?njF}hDa)o^v$oB>9pqE4o9OLPk<9Ub*&4at#- zze%2hD@W8q&U3)>(z4(FT=Aj2YEcTkI9&oeVlYO(!iEKyAWOi;d$AO^4tw-*3|P|;S$Ql$ti#=JzrMaW9$WaFarf5p>>um1z{ja3{@UHaVkpP8=dZ*! zy4E_E3?JX#GN25@h<&>Z^6K;UX=Yxf_dQZQ)>g)igbQW@cH<;q>K$LE|3Pn?herfn zCdfwQE?rk{M#Zwj*w-#_e1jXDJBYye$d5zrF?(De#$Cymm5(J&K=1aHCwdOQvXtOf z0gKsI*03FPR@|SEtk}td?RZr7n}?s9N*jk+SZ6M3U3<*a_tb=R=MB`CVa>m~XF@wr zdS9)~qC~l~~k)z;FA&CR0 zX?XdC(7KVHz3>bsK0R&=DxRrUIjgfHs7G*0VvnEsK$K4!OUIV(f{`e8CKQ!DCqj}* z?*RIYM|V7rKcy40yB!#k*@(=BZ{i1I-_6)*u?m|dm+_O=1z>B2>XsUH1ZE~h#S}*H z2!U{Vtk?i2F4!q)n|0z_g)n_)UQcG;$Dl~$HDD=Tvp3Y~x`5R01-CLkTkfO&jd6#A ztW*-!u03YOst>snf>ZK#8gnE#2RO~B>Y>3R3xNmF>Fb~%DkV4^X8brQ6>1+tq&O8Z zivH6xkDlHl?=j|R^BHA-vVA&w@_@4Hw5eYSE>imlCa(y76ElGNdJ1srx%UWwq7!`Y z!pRk$jZwH>xs3W;r(AvR1u=HE*JI0eX9Re~UD|>d%{E!aJo{%GzUb#n%g~jMq3y=I5?kE1G@RMQuF+R9nd>|JJj}5o^5T+`F z13%vTq8lPo{smNwj+Qz`z71Qw^X}t4{Y`K*(^vuoI0(~T2zG>?`oss*4s%O*v+O#4 zvV;rfyOEWYQYJAs6)cr&B3G**M(16#2s|1Ih(QCio_ysa1tZEVBQ}1<^g=vFXEa5a zXR-v$%A)gIuf{klrf5(eZ&&$L2bkoZ-3a8i6NVy0(jqeh+-?UJ-#*arl88L{{jTTUeisJvz))dRyQYtRw~p-p(YHW| z{{ubE9razqe?2Oet7FSq-XEQ@kreF!Q9emrApaO8(nO|L%xc04$Z;em+k=-&#~+C1 zCi#c2bI1z2O?v}~uCThzMcRgbdZ{bYsbw$J>jqleY#$yNFXc=d?9L&V*{uU&#DH*l z{+rOBgrghwJ_KW-XbAxXbZ$gk$WhvS41r#Za)z`c!{WyuFN={Izeu?L0HuvM6lK>4 z!+=d)vbeA!F0U>MK-|2o2-AKY)I2p;hNzHXi>$EV!=cV^vN`?)`olj-@upiurCr|pbVoAgb+bZJ^JwNQXYzBiao8mEDn~H`d;k7xl z);47GG3<=KKls>=>Sa}2`7%?ohXnY|y4?t~RF;`MM?6LvFwjzA1!jI@GLsCB{KGA& zGy}C(L4bIOFbxJ^t)OK_ z+_ql1{5n|C!CFDCD22|HK3G3tYNK!@n4f$)Fh)}poSty40tnXzR4=+#R)j&r(g0gr z!JbDry#Q@C0O!`I9Cx58h{^kBUtxdTXU^*rqiNlhG&u+;Kt*7fVXw?rdpJ@qU-uGm zFD#w5!F#qNOqRAOLAdFzB%n4le^3J!OwA1Rx{3oTvw=0n>oDEaZv(AewUrx?+a1B} z`X{p;9YbG+AwUm+rsGO*-sy-oaLf+MdN9pyd(I3Y;T6J-G=CCPt2zT|Nzu zYNdK!2B7rH&j`v{Wb6@h(+OOYvdpDAcsGxb;|bF3fh-67rykBSZR&&)(BZ`~igXmrSi`CJKsEXhc|i0TEFP0N zyXJB5VM3HEu5zse#14J}qLg73iy-%_VPy-Xrf2q`IfRnf*`|#sf(Kq~>yL+-f&p(g zh@tLauyr{ZV&NnwA#j@6s8lyG;z=3Oq+TFLeL~T1!Bj#v)DjFly3z~(yLJ*sq$6^a z`uFCMc#+ak&22uXkVB;?Q+9!xMoh$rg7#9~C8$O)1iVN~z$|dy`54yc5Lo9iYK8hK z)g5_owcP-Z13>lKR3^c&a!k)=3;S1HMxohz4f>Fgho3f|`}$Jd$vJyL?7Mm3EP!D;gO6Bin5%}Xluo1J* z4k;SnpK9>Afc}M82%V;oMa?O26rA!xb--&1eCf|DNl51%#Q|@$9u%-0R+JhpMZ}6BE)9VqjnpD=NrnVqoC>#K6FM z3c>^4`857K1NcQ?ub_v-z#t;O{=vjZNxOrAfro3Q{nY8Hin6eYoeigvshzPIr<;vE z&>90nRKm^P$mEro6V%wu!pc^RVYi`$0cvF`#-Piu!mVO2ZDwhu@W#y4_m$(vUu za8m{eaj2-9Fff3PnUfLJ&E~Z&QrJz5;bvT6;P30Vxfq}~O`KkdF-Trd2z{!e4wbfZ zG=mCoa&wq)a|=KP;ha1IFhPDkb|^15FAo=hKd&$kAM~Gp48UxTrsl$$ zGIIaS1-uetuyk^=7v|z}b#>)*<>Rz-wBX`_!{OIs@bYp1EjW?FnjJn7#h*x0M6{Ci+qtbf>^zZI~=>Ok4 z|7#volYh6fcXoVzBPLT5F00BH%U zIa&cqWAs|a&cyk8NJSYj2H+D;Q!7(pK_hcPU|;z;cujeYI0Q^!MjUW+UQ-SpULIp! z9upycZXv;cjq^YDhfB&z^T1@}xOt^{cw}L40V!aI<)nF~c%@*H0`PzJRkTGq8QGec z{cCP3U~VCPK>;BlxFClB(2c_k1~cV=^P2K=2pGeK;QZ!rxB%SzroXVXqnVMDoujs$ z-Rpm8s`|eq0hN{pG?NDgWzn^=HMMg^KKiddW->-jW?~H2n#;ir}|2#6BkJsEpz(|P0oSRn=Z~X$jZChs99X6iu#)S?xPJ40 zTE_pLqWtaeYH0=x`L7NCA9nF?Go+olldF-VnWP0^5dU|b;^pP!`)`H%+sVYz$kxIP z@VZ<#%jCNDPk-0N^>zsEYrlC5aFEx3{@XJHFaGV@&1`|89Rbg6O8r|7 z1IuJnQASeR4Rh-ozORLu`>(6r!)Da^)bID{lXI?<`2h-X=9nEcvL@jVYGlYwa(qnQ z>|7v#KhHs7gzdI)XpN{_}$p0gp|D!qoKedjhfjphb zj1~t^BHVlRF+0nH7VV@>Fgyv~%whF_^WtJ|NsAIq4F>g0e@%Khe)r|CSKM#l+5(a^ zFV}Y^CyE#54&9Qm2AIFjoU{(M1QilHBD0T_V??uj_dXposqY3HT=;%18fyD>V)Scs z*omS4iumVI?Ltb{w*H+{Joa;ztxKxpBjG(2u&eZy4`TDZ`cu3qjCm}f!d(nq|3X|j z&H&u|e%a;HU42>2K+^5(I%-K%tb$3P-lbfk- zU-4|6iVRac@uUTo)5#5Uk#y!eV}YgPXi&-ATTuFhz8K!uOg{5YZlvxk_dg~w+6w;k zyWD6+Bt})*8`G3rdEi3qa=WIbi-3JwI4WV5nGe=gUA@6Ye zxg6cgs>WcU-Z*pO*phEyJ8^ZkeYHZ~gYRF{eTg=CqnaQ8YAw-5VqwOt+(;2s@mtN- zB1fQg*oiAzow(mRMPBz%KhcG5=$=UV(q;2q_^Y0d-zu+j?Up1Byjnf(aFA*$7OZE^ zM3KvDl_kKK`mHm%#S4MY7J?vF{XKz5)lemMPiXpBSg7zNXn|l{j`SjZ)DQmpM?|ctp z*z@2zM;-+(W3o)ZqpGF-(Uxhox$KP`Jqm3w=O38l)4MwjgUx!#LnGX%bdVa7l79mn z-@m5fXP`ncBs~{+axddWNSNLI@-030^^_rYD%0i=X?}H;-Vk4??;Z$ZRL%r@%tER` zVaBDCzMUrF^U|96B2EO9V$&}lG|RYp`Qk3#?rAgGPM>_owyOTUn;46H%J6qVqqKFj zA@~CbPx7V2fLECBae0HiaAs8P;}&Q_rg0(|Ntp1-Fnbprm+Y6o4jtXHT=Tq6^9L}d z-Hf8hYK+6iaG5{UkYFkjMKG9-0VF|x9v`yMUfL^FV}14uujW>{yNyz_*UA@;`BRO2 z91Xojo9N|k47qVzLvX?}4Dmj4*3Tbp;fcd;)N!>LJz}UK>CJS@5NP;! z*cwF3b^M!Ih?ceseLc^}$Fq-OZp1wq4fY)l`VM#EnRD+5YN!>X-#lyjRdaN8QS;`R zyBA}z2=kmf)xL6wzVgaajohjw{Q8I3g3qO`oKg9E z)f*9VK`(6GI?Q=TVh}!gy-M8-hzj8?fUGGvd3M&aekGQlY)sL$&wl{?;j^6F- zK40rMf@o&nPr5{_#LT?ai!ul4qpvS!*(`1^i7xZ$EBMxM^`pVk zb`a$*;IQQpiigh?x5h~^BL)@egna?qDtEVy+1$t>gCGP@Hc?=qnOAdhYvV=iJ-KAEHv5bu7 zSB~e)m`15y-`6|wIc&DSd!vPK|5<-RxP`|3KNNswM1tu>;l1L$%LHd2wTw0%2NY4N z{I2IBm;60X5#e{2CGVeN`8z`2n+xHfaumnxU(mCT-F7XV<1U8TeR?qOjfxiVHsdA= zJ>gWfsAW%Ep=XGa(>$uq8`1x$c1AhNj9gnv;+Pbxa6VF~_Zj@Ua@-MDy>HItoj?{v zL?2@nmIQ(KmTbB5jghSMnikQ2C| zrfDjd+Y^02kU^dddJ$6x@4gzEBp{Xt_sCQ*KZCYMSYqt6#?l78|?IAC$^x4^9n)l0NBp7lG z>~dvN2;=Cj;l->+9B7iLb+~hJjxPSdowO-g*HL}f?;Ex34K`h*LqFj)?henhH~T}U zhT&RAp~q=lGODy{OpZKy-5K+O_1jhD^JnEB8qw}8hl`qJ)$dIC|5;gC=--u1Da@$m z?%w}++>G@N$wCO?f2KC+`|6ATftZLTJU8i>N?c*os%gbSE&JQM2+EH$5=p&ldhxsO zrJbjxrUv2f52pA&zJ3-&w&-R|c(1v);n|Lfw{sXi_ed$l<6aQn%t2vz% zBx?BgPGr%-11X&zsmCe&3YEfY%Al0*3a|3?0@(8k@no1*a?Wp$eKLD;D9ZWlXsxDL z(93zOcSlQg9$vF1Z}c=9(WcvraXSuVr13TyLsEW?7V&Hcnn*lQ-BPH5tbvGuAR`NjU8DczR2|D z;vBYv3Qf@EQ1#ZinwknWkirFLB>S4jsIX?&+?}XO z9VrsoSMgCiDK;EvueM{L_Tul6A?W({D9vyNv*@*r&#pw0F%l$FRs@E;|jPRZy-KbY@B)ZOR5ZkNveB`Ow zuXH^Hb9X8cbrPoglt0BPjsh}UwujEt-uui+3|gl=AAl{ZJ8Jmt_kvYL)q=ZMm%3Ml zyI4Km6!rWrZVZoZGTL-awVQI8RMM^{(57(SvH&6@E&&5?Y|z%*HP6i-fb9=Bd7TH( z$w~(m!tS7HQ&|2Ah3v*R9)_!m)-AEdhPGtSoe)CT)Ul+>);B}W#V4J@3VgYdm{RG% zd6vu5RV{x+V5bHuHq&;Rb9!jtiw1=UvKFVJKXa}MMhA@G{~ zcI)|pt>fFzo(WqjWK7iV_!g2I{>rMZzjuJFf0dW{5fBt@bry_*LcSnu2?WAa$I+41 zaW7%d+hP4_JQ~dUA*ZZDd03y7wnuq=q$f{UU|R+3Qoi< zWj5@HmAC+BYjg^J8=i1`W+hGEpB}!v@J8Y!IH-Osl9}T& zV0ZcX(~;(gAd}3_4}v4^-rhTU6i5%9CHOtJPM33-uSn`Mam1Q{#-i^O0vO+sg*q{e- zkMd57LN^LeI9X*myDkHzA%U3?2t(*Sd;NT#4zZ?*%*2xp*R4C#ze~&3>ILOEFI`ra z_F+snAZCl}uTfFGTY=t7mq+`Na{uWd1y>PuW#eYKk2$lSZMw#0N`#t2A(jj4R0^;u zxXSeOI(n5#(|e)(y#ex}KUVAVfbqec1jEOfu&PKhK_0;*M9tkwy6)Qu5ExoyV~*-_T>6;5N_jy(J>OV|JnGWH z?)77-Hce^EW_cIxuw%7KlpJ5{8=@wJ=%oODAStx-j?`PS)HZtk|o?OI&k`74$6z|E(ZCw6U= zXWgvejVxksgFxR=y!Ov!W;-797@iO?Njv7~rXgZ?{)%fv!|0D@@)S-P?w)Aa3g+Uz zF(#y`T@NCb5@8xbvh;Y{*&UB+7kel%GFRNjx zBm0x+zIFLQ!g%Yg>pRuk`?M)okJAgrbUz&|@8VI*ZX*0Flm&?MO+4VMUAw4n(at>H zD7Jmk4E$rywU_z-uMXy-I@JEk$6zNpq-8Abz2`g3UW)s-t+a{%11B0f{1ZK zmITu3|gj>n? zmp(om?c;iJ_&)kbWy_7t61jCqOD#2sqS|`D@q$~EE{(s%YjR>F#(OZl{N)Wqh6P^( z$^OqN{_WsuXI`(N=kLFqJ$}o1g)wOg>B@ezu=FS;3XP+&c{gNAoJou0F7FAbIT-r07axx=HFKI?UPd^en5yY3UmD z^dofvYUFxlvA%Bh`5_yLwS33RwR{en;oz_P?N|#+ZT;TM_cbT?;8J4JS~u$=&LY&K z%sFUMttk-olA0 zr%cCfx;7EDe4dMg1{eJ%?$OtGS*S^Z9UY8_JETY@-w1I_w)<_2@L$w6mfAUXO=~+_ z4WiJGa53ZGYs5F<7!}9_Di}}l&7SQ%duFx6K5!Wbt-TI-$*8=)K-_{7cOGZ`X=sTf zq~Y?|weaW#A`z6qEbrGk!@+*Kd=eY^qU(2)?_NIy#4lBtTLx+-fCZ`Jt9(t`$z5Gh z<94~2m)a9e#Ap@ovBU?yd&wx&zhV!zwR8A=Y$#ID@1Q&${&inEhr;GHW9rU>d((<0 zFYiwNwtaca!I`OSnb6tu5u-J>?!qty6F%s07Ceh4p(_!Li%#7|RAW``-SLkJd^016 zeyLk9S!0cd%hg!nL^?}R*e!*a%*<&Qj|OoL(AaII&Nw)vjLrY@(sx=)4$bm|F@XSm z1|+~hC5U0DRxCb1)_5osx;Kcd0}}oZ)+Tl;m2$R=v|0f%?AlhG;zRly@ z^tQ>EdKNcon*E|rBFkw;POcdnG<0VGu{rE`TUIbLNNG?mWr|)q z%V5!{jQaM~(FS`%lR%(HMn~p`8?gA6bixyxT*%`nzAY3#^YSTr*k?Da)o+E1!#~cYs6NO z{Ic};=#f)wHCMn?Y*^#rSuBj&CksN`^qm!KF5?bI)t4%%-76-!r&Xr*`{8C~4X^gD7S- zOx-)Ca}8G+y=zxc?XKZKi};5znWP$QuyiRA>g^OMljJUk1Ob?gsLpksZE0TKsm>Rf zz544S%NL7e527s)G5qVU$-y{}oX@A!-Y>I4R=&UeHl@#P+jr#-JiP1IqZDZl>%UaC zcL^cfs(h(3mky4SIN{-kQ+=Px?mIn-e!$Q!KEbPT&->_P!u#@KEYH(m>rhmWL24KQ z!h{r6aLsskRuYw~RjwQ~_mnQ9*geJuLpSW5r@NmKmW4J^9R?@$J!eGfKAe16 zI`x}wh)zXz`iqS=?Rwjr4pitRX83{O`=ZoyvisUz=PIwx>`FOb8=`{;(HhsG;4lsH z7gXZsshOggCz% z?|9O|f_hRha09VpEgxmiweulHScyIzItd}_*%bBTJouWM2y)h>DWZJ!d3$?8*wVlY9YB)|)|7X?p#NcG->hbW~vKHgYduHj$T%O@qtu$Mm;c(5N~;LO?cv-l@Enh0{R^}u(z zr_Wbv=wXW5Df8{ixt5CU==hR;J|*Y`u^z5IiFK3jL124ru2qx;5oTc5D2~)pk0n-$ zFDK4p&gHyTC_eA|PVE;+rRTy&7PqwNvc?;Tj0hc;>)fjDtm0M1SYQ1Pu$$sg)(#U6 zbfL18-?8Os^ zyW*lUWO+Slu?;ctg-D_gLI`Ke&mX39UEJ*~(^o3Q?B#pR*Ug1x=c zSR-!C1o``hSLsLk`rF~n$1+o=$h%(<(gaw5tu3&KLhOHEgmdp%k>-gqXxD1ZJHu1- z!)3G-(iXzB6zF}iTHEx?s6!p0Dqz}b{AhY=cLGjV;n9<-idAW3Pmx$49<1{#W=2~Q zW_=Cseo65!?`3BD?_(5+I8q4~`U1qwI4aEkZX~Jg&mohzv~AyeF-gD(BbEF|Crt|=z9-a7#009e{$Rxjay1$<9C;eD%9v8UpUq1{&kydAPs>es zv7nGDP};{UNTOPja&*)8jfEza`a}(#j%!CNUw#v&X=mG|e>A5o?xsna>>WiIx{Ehu z+H_&I4&|9;-D(xb(iY6@KW_1+jG`esBDdB8*U)QVu|f$!M{_}Waod&xq&6#)2O7~} z#;rJIUkofzFc*e_wNu*Ri8zTpke1a~^ z&mU#vCVjPkwzM(DYx|J{DjTAY5E8Yr9FBk0@TGbfecyu19c?yYhaS|v&3jB1=&7BT zF)rlwT^7igy4{>Zv~KGo2B``^==kFuCk0W!V&394bk)X0r`j)B_P7qm+nKoZF&rzO zR3_yx(XUGspnkLrb#)xP{nj9!c!+*N@@+BavB^fh#MGX|u8_xipM-`ID*?lu!^6s) zGgH9R(!wFvnLL~j9&@LiE2sJJLV5O(ruTW21sACsothALFn&tmN$Jb-gEcJ;Iu#7e zKrh9Ykdw14(6-t>^`3()1-(Z4`27GwHf zBiJbMzf$N0#qf{bxdeMO|E81jqL%!2_ycqXk}#xR@NI1sUrO9eK6*R!Zma(GL~Lvn zcJF7YCw_&LFmA>oXtSKdm|^7t;}yYTg7Qq2fA5zEfpSCxebWR9@W5x}*;C4elmx^e z1O^Tmfw4F#nEyU8$?4zNxz&uggk?uNWj7W?>`WrDeeA2nUB8Q-Ou z6&tTN;x5V&r25c0mq{<3sWi?sa;kSHPND_*dbIW9=^uPXDhF;=+A%qIo%!~f!)t2P zW@RbshS!0g%G}_TUrU6=cTSHp`5dP2+HWnp9TOoabl2+^ST`;tjOWhE#GzT=-+xp*%Y$ z?QTMvaE8(_5KQe2cu|!WpSvDt_QRC}2=DawcJt1p6;F`Pp;P!08-I6Z>8XH^$#B3pm=x+?Qc;JeaXtan*tHsA z&sjP+Sd4x(u9jcc0^I3E4pVWt;}RSgIAVfy=5kK!cG}eufd1abmfReN{7Zk{)ctWP zdM+;M^~;HN$N&?Jpk07k8_1*BnmgKw=L^mvQ}3WJVUtXCWLf8)1eS!8FjyvtNCIor zReIin{*aNn-m$ z6;$~f*@=6^{C~fp$_A_OKOCGA__8C|6rO@6V9u!67~ZTQDW4n}ZCvn?nTc`DP}aH+ z^8gMr>2`BGBti7jVAT{4lJ^CLtR5U2`qj22m8fXjx#IvI`#G*PC=NZrkxuII%!QIk z!nYxF`i|tx;0G_d04ijy`-WWa|1OzhVs*TJ?pR8^w)3wGc33V;!l@;~K&T8!dn zZ!7=u7K?upz#2#hJ=YJS$y<&|=nH&9t%8_TUcY1M11a=pLp*VSoicv?d>Vc)uoH`w zls%`?n`f-_@Z;;Jfozha2lb{}hoCWY;J~6ppD8Z}6AJ|38qtie+KJ28?!J&SrvOrc zgR^Q6tE364Tkix;8e85h%^)w&)@+iZAL^xFgbKC80nuGUfQ1wqy^8<<2z$(b@e>)* z8#pZ6U>~IWVty#7TJ&Hw{BulVqZ@!f3*X|Vp3I!>Z!>Pr34CzwA@0yeqEk=24yxpy zc)VYri}1SS_%JB3TLv@rWdP|VYN`}yWFT8tN3+CwjCmu2~pbNq-)-bl*OXyqY7!!d*CJ7r7P`973ey`1!1x>!)8k zG57(Hc>j8?AUrOaJL3mru&sWN00f3b$l~z`UBmNCwIQ6n-ft>#oBhvrgVn9l{N1<( zLMVyUJ@pI+JxcQ?JUPyw*ECX*!El67pm2mCY3_vd$*b(`Tb3gDBM$1g@fO;ah$nB= zv2A<{Fsr^9lxYVQlJ?9;wL?j;hO2Hp@oH{wSNZ(0Y&ZK$et2l=?U>Bb_L7O;>htx1 zrd6q?mI6Hrg6o!oei$+!sJ)#HiSBq}h1fbYF+Rb+(e?wBvb)~d`Djo$V}Ty=#jBRjL{Z?)HkV}h4ZRZ)=8zGz~|GJULR zKNJDrqNUENvXDd;bB8SWmVPWO+CFg8q=qSp@ zos!cQ1(kskuUoZ^dNEtjH{jn$-T6l9@D$^It%q3Tf)}?(MGTY!?YRksNdJ^N8Mujc zP#P9o&7Y`0<&m7OH~CX=YyWYR#L!CQw#>F{qW4SOG2$-G*}B-?0?HpXT&x@*fC=?$>it=^vQQIC}3bf-!Iqn5!RPh$m%W>*?W60T^znq!ADMsq~!| z)xr{+0!KrlgaH+++>sLG+|!XnEs+nMJDyjhF1v3!?yZVG;&E4m(-u93#+(E>vo)w) zv>Z+)>QCvVXszFy_s^kK;ITG$Ih10!e;D!;wd`n9DMB1+RxuRd3x!58OUr;oK@yBv zMSb$U*q>zsFZf4jB(W{CGPHkj4!q#|;JojO|G}k+?-)*^T=-#Z*(Ji(ZBDj$&Qp!C z_*%Tlxk~>O@!XDZf2?P`;^jceG>?{)j#wL^Facwj;(psCew zACfEF;`m^P_|03XSh#(gVyKAADQ+|LyS96vo&UzT(Rd@Hq@!OQTa4kYfgx_7u>BD)VbQDkvl!Z105rg;$>aq9g?{H8q%0Hf-Vx za{g$K_oKD&`mlc=+ijK!%#?3E5`=`uGA`Sjrtlk6MY~d3_*`~$ogerpPjm@JKRJ$h zizDgAF3BSJaFTCKiT}|uUl(IzAF%~}lU6&C8kG*f^^G8tn%1nD>C}%M2P+)*I3E_r z2|2LD9HO(MG*8CbRxe#0LG-3SMmHR`J8VDZQ~pKF3D<~OUe$`Svp)@6#rW70Ep2*a zPK$rra@c(?!KvvW`u&$paTx?Tpfy55LF(6RmR}Ykto=fP#Qr>f1z~)wF?0P?7?UtdLXaAeWCrJPzafq=z|6Ae`V$DZ6F%VMyxm#3e#<_s8O7;&3SJ0T+xefPsguE}cW4|agB*QCJIro>GXqL2lXFj>BI zKy5UfJ-lBM4Bi`De$j4_uTNB8hygld`M~M6c+}8!zwtw?a{5L)5;`ZVEcnpCxvQ-B zl64@~D8fC3V@E&ox+shp;BorjX*~_&;d=;youYUE>eHS!87nC0N*dMCqUf#hJ~Z{K z;NcIJEZ+k@LY5XGEK59)1XYyRTh5@+`_c|@_CFvQn}t*;8*&9_n1%&Ptsukyk)htC zuDOzI!iipNANTdFJ5ep^G4fesY?P33Rpa4IF}~eZw?h3c17u>W11SVx5ZB8=pa{#b zx$q)ct^96dE*CLDFazlEOMsAhSi~s9*=6wlVZW_GJG{?87N{-a$F6;QgzXx#=ccFN zu;eOoe|BUHRx3f42~bx9#3>vl`C~|=_>f5`$YgABr^b`YA>N{GA${h{1tDVH%Ah-_ zcut0f4DnMb=H6G~1#Obn(A>oM)N#@o9>E@(Hc+Q%sX<>kphth>H*)3ml}W^VIR4VS z|8S=t%VUTA7qnNUq)X5HA`CD=LpH5LAPHAUj7r-NuTML=*_%?o8o|$0gG;bj0GjYC z?w&i|a-6~v)~Xy^S?pf=wluBC8H{xVBR=tzB_Z#zN0|cSdwqa-cRN|j_Ta)3n{G&M z%ckj;66OJjcz!VsqDw{XGLCi?oB<(NK3LG`z|F+KuCq0ZwTs@|Sa3=r_{vaB*PRSXrVUEHP|+1uzz= zANcNpgTCMY_A@$bIbj$r^~;SQ1m6LG9L@kH0-QKb<+-QrPDAw08gf!ozg2y_uk)LT zkj09mBPSLXy#Jq=f9gDqzgMU(O}40QBMmU-0x zt+iL_syfyw{(bJpi%74GENVqd^|0qcR+n(#wA;fS^}Z;&yxw`5bbk=ZU0u~$@mVdJ z^Xa~DQKS{%*6$#HhX8U!uJn5|0|Mk~{fc^~4p5pHFpl|%S6>n?hkQYKal=lcuw&mu z%vHFgR>)KqiUZ6_s{vRbS8&hf%N37d7ZOuSsPDKWWxJmprXiLtMyMn$Dbjt9VJo0Z$x{N^9(n_RrW-)1i`ilj$#;aPMzQb>*5btsF?)Sy!s0G&C7dlbPf|xGDe1 z?KaWy@D<~(N@W$}F*>;o4AVm8^yqOQFWCw&H`5YjQ#Y*=vZ$kVUd1bZjtBCM&t6Vq zZ06}9Qe5Xl*}3qiHY z<8qKd-^wIwsHL2%l>s`Tt7UUkx8!Q%y;WiwBg2+m->}#H15V+Z+#g74`v>Y#`pQ=; z0;(B4B+UI{;c`!y9eLVD8w6)6x6gc0FKNr_6XOlJpU|BO@=b~yJoa~ z@7{P8mdf>fxcQ(Z(dC}UI#6C&R6xI2F*2ORG2de&Qf68yK*&&NzLHBuBF|VHXC+5N zMyJ%y@l(`kS3)=LAP6xSYT^?{cBYSAXVaF^Q22lnv9|t1&X|%zC-SY08>v z#edW2Yc6}O+v?WK43lHE&FMGCInqGPKg)@dy2|3V4 zDQjuBy#?y0yxo<`miclM#O~@~^Otm~_#6Y#&o=c-39bjUSIaoSf z4&)LL$T71*x0Fjs$O_J4g*J9+hu-p->6?R;fq5Ajmi7k>_cea2I8k_9mswq{xHN{p zpRaj6+WF06Z)q|U3f-#4vOf`lQCLw<;ob^Biu|`fBzJz9A>H1#Qp)W`^~XG< zA^Q`>!J#A}*ws%4ilrCCyh3QApf88H_#H<<{!MaYsSL07B7_sa3@4j#^(?!RV9Jn? zd_qzHw+y2c<&W1rfSZIJiWxM#Ko#Ks3NKVrQ~?tZY#0Uve+{Ecytl1!Jfw$32F|dk zh+I+_d85lw+USMcZ7Nsz+$mczgcS0})0Q6B*lM{-_)8HW8S!A~)`Jkz6tkkRkiDl2QPw6!HbuhY zWav9OW+jcmlchxa;>K0H3R-2v-{^&UBYRvRi!VoFz-RimS`8RT{ubQ2%iMrhdD=C& z48yQ+o=FzqvZZY92U2$m(NZE)e+{)MCZlVNxT$favy}F|3_%!Z%e<06{_R45`XCn4bB?ek}Fs)!DC8 zv7;(Epp^0_o8{Xa*y>brQS`g;u-_`83dpi_rdRe*|6!2xl+r8?u~WSHs7N#J*e!_s zu(}P0lXvz^vYQ3}qZ1iUTN4R?^)j_i3y$VG^dEPN06gzcm*GGp0BX4`-ATFh(B|=o z+atg3o?LFeUflOL$27IK-5lxbJqmqJDGT;D5AhA*#jeO<3A@9arHzmB*Z;cZ`WitA`g9hjzKh$l z&%M93jDasi_mCu({!R;t_4BMcnkmCudX!6?2ua#Pf1#K=V7h`wP~QV?;w);Ys8vd3 zG!~})7CC|z3Y^EuWYrNmeuhq9OV9g`^Ks*^wUgJo?H7ohG&=w^$OUjcwK4pF7Eec( zAdUllTwY7nAYPwk)6o=JRRl0Eds+-`ROH(0>;vW#f6Rg6H;PqtZS0`BP`FJv-1!^P zWFyKz;MSaEJx^%sOV_^h7U$8OGn=46L%OsL;QT&^^O#(|zJR0cq{Sjf-0_u%(UX)z z_mP-N-4$aXM2QMjzJ=wLmp&Xtg$o@gSv{7oKphn5PhUO%;n08a>eTL@&VYh+Yg*z1 z*y=QO+LYpLtastbg;7qSpx~UMgrBH!SO~8G2z*_I3gW|Xdji;`W-uM7z;4NSbZZA->nu!92+Zuh-wdt2 z%7Rji4s;7o7f09Ml&Gp1Lm#u|ibr_{;~p301eOMo@(ifd!pK`rgMmsbBy2yR?Ug~L zjp_DPimh_S&VvJ0(O|}&jdpRL)r!wUe^imp7cDLkWtqwVtr!i4$cTX9RAu(hZ4@4G2bSLB@5CR*V-HgK2G-p6MWr+v z+qIa7L{7+odi+-b=DwA>jK#oOr@Lur^oYS}LQ>sP@GI|W0hF9p}zHA$G#_4_+ry%K@41@?>0 z^g1jx#X{g_ixh4wBn0(!&o!%=SlAG=wD{$>uB?;YEGPE(-M1tA+?!;DC(=JiH10yx zo9_cSy^y$I*MCMIim<`&cPHIKlL2hov!Ng{!=S+=slJb&&J3Z}z{vV81 zL-(ubGk~0Zzw@Hn!+2WWCCWy0zQN6T#h4`68ai6ygD#2VwCSz&epxgWL+n1ZO1EQm=f7-+)jo+^*X- z(Rp0I_T1yy+Es_*p~2qrw~y%wjwXb%lZIOdzoYE3^M|9zqeGUz;>c1LZ|MySR%~y- zFZf_x5Eyf>!TFD0ZONASsvY28_gISj*z?k0yR<0>r9VapPmT?Imau^W8g42|^rOWO z44K#E5u0QS2>>8)Qg{=$-f7x(Po(Viplnd=f*ZT+y4Cv@=eC7eeh`ojvHyCiI2=L6 z?u84SR7iFIl;0P3JUN>EQO45hhf5s4WNc>C750uD=LYLL{Uw7xXX4qrgPfBaao@~= z&=0aAeOFp~_wsics11FW_i@yC4;%%qIuo24S4cy?c!$WuS*B-l;p*aqVq(&gjz$1S z6oIUkcx4zV2i*I<*t$4L*c8Y=#+k@D*{)dt3bzP6qxQ5LR*$$2b3w2k`HssPyZG-6(*;gwZTmfyuk);V_us$3k_$VX}6Zh@{EAHfN%s-i^zXq4eJ9{OFDq&6^_fgl070({j*>t$VW9W}NO zZb{hjU0RLdw8P?hcdc}F(hh+e8TiZ*2`Bwyc^)J+WJyorJ64oH#u?zK%u5oK?C{z9)-!%nY!ZLZGZ zVyf-Ak1khld7_o7GChd(R@qkGlwsEdyo|aX<_f788kiKX+=&gH+7qb+M>#KrUHi!a zn$YRc&1`ej`C)2mgV;{1fqj8xdYr2n+s50vMx*g!n^3|k2nTbFv^2WmPb3N~^BB>A+lfub7iI9{zIo`;(z zGMsYuz6W5*759YGl`BD5)7jB;`SG=9MCmQFX?Ce}oF^xFdby1EDcwuDWtAtG2OGRM zT?f}$j()G@7~8nLInkGWuAT7anVI55g+v|tTi;bqV&YJge*f|#No=6P`z=r&kmhzw z<^UTx-3PMt#Yz9y3(VR^8Ymt>mjL0s3%7`Tf@iR6Py2WfMfv?*v7k?S7N$vttx`kO ze=d_H8*&qpN&X-iD^;H*>BuL@AG`mMI$6nUND0h9(zzdl5t&T|J-~7~&zu;oI<hTvH8b-!n#GAz}6N8hRWM~a&)e^}`TXSVN z87#ZqsW5vPD`R$Sd#j_;Di_YnBjfRH*R50dxL@3t$WGCo`+{_8L%$nx{*=jXYQ@=G zE@6Ir*jzw=UI?Zt){}qJ3KVYHFxaBPqutwfS3QjwEZ;&|xL@4;0H1hE9t^#e;3}V+ z@Xb|dAEE|zsjs*UwR!#x^Di*}>y+GGAoyh%3V{!)7Q)I=-z46LhbP6{8lu-ul?=+% zlpN=Rcty(DKav&L2dsYQL#ZU6n&MB`F0XplG6XS1s+y%9whyzH z3lB3C!H_`_Dj7FXfhxXIHhF_d2hM21QLihl@n!4#ob)>%Tj^jBQXkR=fkEq<>ur=c zJr)m?E{#;K22wYyaAo1Jj!V}5`JMC*u|{Ar z14j~Ix@;DfhN-a6%>bvamfmpA?o5gJ-`Ex;yUA37>!6?GT^nm-fd4 z0`T|z7hOIJ?e!M3zY+7LKwk5K>&vgp%O0C~hywtn6P`UYAGVVE;tLKz}yj*zB?RiAMj|OS(VNC*ky) z&|7=li!UFupcaLq_c!@KB#V3SW2*=Ojr(5w2}fMm7k3=GqKCH*|BMqabh4aDA_-4!!srSM#^f1t+*#6>&0QRKnN)WHkG zZR?cO2YT4x422cPhzD&>iRPn|F#KQ>t_LxPxWbRcWH=x8Y&6);dUpUNEp;6YAzi(I zR9W-&m2_eNb~Tm8iX+TRd?+r9rEn)@O!VroV#up8QM=Px@qHGiq@}5I7^kkm&x(Ur z*l{9r>Po%LA}E3s-g29D3r_g@g&=Uap9`=p5sv|ZDvlS1015kXFIp6!GxGGXQKE|D zz}o;59Cfae(mfmua6Yny4pck;ShE8%vNhBSj zFO6r?0Q9zxD=3i=td+PoNa11 zqo=i9OJp#HK8Kr>(=OLGk`1w~U-hfT?(@e-HHE2P;gOvz5>m4akr1LE3}*z~^C4iM zjRygDB28CCTR%r*5KhOsH0$bhbjneYJYc2{X0*hJk1EJeN=4dSeJVK%d@e{jms-fG z_7=L5%W$&Y{0{aCTn_>tqh3I%DC>ZGO#t=8FvV?;^3bl<0Usxs5(6CJNl#5-~c^;mEt=g^4(PlLjl~Dg0^&qNZ2YEY^*r*hnS#Yx)%7E^dgt)Q}j>eG+9O0WeMg~#!mzT2(}cHJxp{|3PU z*OA;(QpazpW-zA;^3-%D^bHuA=aUb7h}I;RRAt6E4s}-ZD&t`H1jJS55)!UGgAk4Z zjy!N=5J(ZI_~!z{nS5}&QX!?qPWJ4qFkPiAgBA5&Zsqx zc)RWt7>>js?EZntgpNF>N?M!-4@5&Lff&C)( z2$ps;a=`lC{nq~LTyOc=0Msl$0PJEX zhT4v!rs_UF9O#~m#MQ;-N3jYixvZuBKgJ|>DPqfeJR0!*`^3vop4<*7x^1W(3tXfC z*bquNC`?P(N`B3q&x1?xop_@+b51*x#gtpUX-m6VOVDqH+)=vT9-FW@QGV%!alT%q z-7`YLP2HNj*J%DK-$k%9f;AGf7x&Yrrku%w?mb9`>~Hl8`M~4U|K1|!dC*JyL6_cM zOGt}^28%~mF+|oR3Ja!g8pPp97gVa~Gu0jet40wyuU+)bBt`I4BOd-@ zFosyE4n>z$^Vrn-I}`NxmF|)}j>X4smg&1DTPEV|$4-XkL+(Je+A$--hZkGoz<^E!zAZ zAg{p6R3q^la3B-_(Ch;To$T%HpbKmv(pTnNI(%eU;tl9vuD9RjGUsN_Z=8Xr%P4sNt%F%|Vo%WpFE9~p0dTuo%kw^SgCRo( zEKY0G(pVTY=j*b3d?-8^now{T5|y|%il(pVYSnTzHH;<#xFd35`GCQYe1K`Qw$^T+ zds^o;)4%Pq7aR*fH6@LifV7BwXpj`rTM7)?I9M66dJFrt#CV0pp-n-35?)42uP_|& ziqacZKG}_`)JeWeFWNXkHU9EaGjU=o>CbbXA7UG1m2)%|{Axpnm6OBK4vTg%HK#wG zc>`_bg$0#99uKJjuT6{Jk>7&JlU|{fYf9&q&^WIs_Y)BEf@;Ckn*M?;`jH{g(!?p1 znt2P@{Xti2tVF-dPm^ss%#qj@vf;g114>!Unic0!RH_N6uF;1k290Cxr{U z@h0e^;VV+2Aj>oQ%Ih$Y$5XJ6M*2y>oN}`48M^W8P#K&DXc%v6w>1G@n1X-rz1_Bl zGcH!TEnjTc5!;VX&&Zl+3T~$vEBD>asmp#N{7NFK7~zGcU+Ycw82fQ{VF5s&Yj7?$}F!^=Ex|qXE0s z^P!}+pvb^wgs!?}>v!-FrY(`4x0L(*vv=n>x%$fc#E7~pDEITWp)#$#vy`Df;~m$h z%$7rQQ+q-=*ALydOqnnuDz|B2aI}3D*VATuGlFpFbTf$#MObOSv(l+CyJBWfD)4En>lKn#aW?KEB!wbpjLS-abhxYre!WIB42mGs@HlP72$hiiAY`h z7XTYSf9J4~S6CX777MBbb`A2!fJGHF#WSjRDNsi5s4XSmu#t{O_IvtY!TNG{TD1sV zWYtYK@?D;m2-M|6)1DtlkW_utA8TCC4MQLc06HkJL-{YvL`t#TB+d;(v^r}C?1O8^ zK}j4_XgXlGtgQQtk*P>*`pjUiC`^QPoR#4^YF=vpg5WasG4iUjTcQ(eo46Ai0u^WR z4v|MVDdNbLmaX+%+!*sEuZHDf@XWF(?aMO_Vf%MzQgI(VO=4PW)E44=0Z$Acc4@Sf z8)aRTmpl*NQDw}&-bJ@5+N=*)jSHit14haOiUAE`208;{mZ3>d~ z_Obvwfp`c96`kxG)wzV3RgSDBQGB&n)`Mn7leG(NMV&v!=SQ8n!1V#P7l`dbwI*zI zyj+TUlL2 zPhEgOq!QvFV5{Vz+~W*Lw0dO=IUOc9eG5E0F`iR@xdj(E`U5&zVbA_>=`ssS;%tih zIe;_pEj9@b;Ug1ZtfxncmGQZh)Xw#%L^be1(}8qzZ?73hn!R|^1?{blLSxLJC5~dt zlZHDI2OD_O2OB)VW>+Pm-LZR~Y*@N+?-m4I~pu(mpq$~$A;J3Id69N&=7M#jAU z#;#o3l#+(u!CJt<7A9YYjr}-sj5b(RA$7e%R9l(_T zO|cQKPe=^K)u0AelXw6)o$Zl%eWu%Vd;K@zY-;Y*dg|~b_FEWI{O-V$q_zQ6ht2Sc zq_TuK5}_kdzn#w%q*Z;Cc>$ujB~y06Z~`Qz*kUrh_* zQyJ`X5#Z>Eg8K$sSlc2g9ROu_=yYaj*#5!j_S?1A@)M=LVum!EGtB(a!YJmSjpq|F zwa)KOy9fN2#26CDFlWR^ow=W3sY9QlFNHWCqF z)fh@?3ew?($FU^guj|>t=L;$k)>HdHV%Pz5ZsaIO}Zi{=<5R*^^UA(f2 ztP^|t5SI%}&~}d0z~n5JzP|(b#=*+8(S-uvg>I~fUKZ)?*oZds>t*}9YZ()BGbA;6sF(!{R|w|?}a?66&h0lKZRapp$ILExrY2&m36wj`cV|B`;L*Z)q>2O}9>_%66EB_#{q zTOkPHj)o{4j1QWH=U@-rKf_^>DyhvR4}*HHf5GK*Simw)L*CRN`+U6-%W8F{C>Y&O7hQdS3*YSdyXyxx z=EmJq(&E=29oIjy2Z-Z7m@cji!&bE^JuNtT-uX*>Z01L$x01#R$xuZH$Q8%kb$rLQ zxc4$*z*3aCVx;dT|K;HZFz#+;SH^Zu@q#Jy0AE!(Lq@3wJ~B1^^0jqCi!0!Yc zgFEa3I`2p%;55~>xNydo{4J10eOFIU_I`2@Ab#r-+cgqNF$7QnO&jR9np_u84i56uTyp&n8?)Shi>31d-5Kd^i7rtz-zPPD`Gl~Lva$Avk;B8S?x!$!^b~LZqOY8M zozVhMD!7X?%h?XyE`X)Rj$d;5U7qR9HQpre<*Aa2GW=Hsz{hECL;pqI{@sS7>ddLY zOyG~SuHE3jfeT;+^nmRFa+t06cQ_oiLbSO-%#YP#cLw!<*$l${>8$|y?E?))5@1zK zPhV>~H2}zpJRzg04E~z+i!C^Go_`*ap}$*ayw1)pEK>BEAuXvp!UTm+jt@liA6g{u= zV_x33xa_7H7?lr$|Fj4yYt1)d&f3$_a2sc(S`W$o|=|Mk4Ge8zkSW+g9L#; zC82D307?6|f8)0A4X(KB1 zHurqf6fwb^{t&9HR;bl3{2FzD0|_j@#;zZekl(r?B%J?oAs{&CG~+}^0z0@5gcMwU zD7Q0^>U4j<7+aPYGeLLpaPB@D@cc+9~K40+tZGyes#Yq&4t0pjvHLC~G7pknQpq zO=;N@Z3qhjmY56m2p;1+1A$K@e*HDoTMy`l8SbF?l+Z7gSZQv#Y>?+}(%enoBjr|q zHgx2#;|d)3+TFg-**}KGG$5|7-zI7}JYRP(qdO33#nb&Nnloi$@W%lK znTvlk@2C&|I!4xP2O($XJ3v2WzG@|vVD7LRPU+THsygJq~X8@e0^TJiHd|+ zN(TDU4gDyDPB#q@N|sB){hGgh9+oWyUmzgDZh45smV7xgjVU}FmbqfU6%Cz3(5|W_ zKdRTJ7bgz4Pt2T?%kL*!B2<4H=+!^b<+h*Y&H7R1E}5vTgJ;Ho()V`{P$_PY9EKtw zOY{e;wo-TWIk#WzW6he=WpD^92VdA)+1iTW#&~^A5>|1@g&bzwH($HNMdnD~kGm}8 z2)HD%zOPe@f@Qvbfc(65#xPlNPOuhH$)@(#8Pb5qr!~`+-R^!yHIJqYM5tr~wpex` zN)K@#+@_?ta~0Ydc^<#T|^cC}tZ0 z<`$>dsO7m&=@QES&+@p`)QDMnQ3B5h!(qYC{$8Y+FVA+T56m+$v~PNvgAqnbc?#$1 zg#CK8b&VJmhF?e+r~Pq?H1$QfTtD6vya8^}P@R%1k$O|_O!KCQ-)3Y(_JdNxN3hqy z>!WXst{1Nn;c=&DrqXEL^Bzfz4;b#4|3G=QB|>?W-SyB(SaP1Vy2azoSYTwZt#!b0 z913HZZRyedS%Y3}s-C|mrjtd+?KLc=0lZb=_eAIEUu0VA3gnq?Mf-tCTxYF^!70Vh z){8TMk{M2kYDM_8J`i-9lJ|j|=HtA6W@8nQOCc6SHjx~mJkgjCnk>sEBiBU&8dlpM z0Fp|_t49AIy2UxPLG3?mzCiwlt(%+qUYu<~x~4sU{`t7(4WGJMf?AGMXN0^&m1_Ax zhGTM|eTcxD*>Erj9{wxC9RJ$W`Na9342y%KY2L$E{}21F)a|IzsO@s+Cnz5E z+PVeg8$OeLQ+Qh+oqy7Ab@`rfsxa0-^__o%3*pKEkKFp0SX!U7RLaeXaPc`!J!pO^ z!j8@O#Ps=*uSUxkp6oLY*%XTwiOI>mb<~XvOp>UIXch&DDL?q6{Yb(00o@-&JNv~3 z2Fu8wiixQ#_;l*Pb{Jp3<2g1BSd+1+CDe4xya-uY1hEp-g>XqwGpNMBPqtB;IOBn# z?5oc5@7t|0IhuA5#ZnbPD8rb(7MQ-y?S=uqb_AC-!Gj;9dltQfq0Hiw33HgcQx`a9 zBFd!5Ekn0K|Juq09j@u*=eMXsoCL)ZlQ91bzLdQeWZpJ|mB$!E;qOaZFOZ~$kVq&HwAI#$E zGV#+r2#$=N1zlh)C6KT=J_SiTZa=j*+;aR6d%K;{w3wO>vv%us4JKXNLWIabtx#d{ z!B6K6ANw~}Z;aEn7cQSrUq~AjmPoc9K( zv+TKpeB)1Sf#_C?nv|j1XB@0{K8i4Bj!|*5bP2uTTK4XY(J{JUwKdDJ21;WVV<+K@Qsy%QWW2dH{K~lybfzd|ni{&7$10i=Q9u6L=YCnXx z{9H|bI-m&H$pDc-SqE?Ql&HJwO3z$0ColWNK5jGDqT3`u5yl6GQ72@g-$1jVV{wS7 z!X-mS17Wb)kAFtWNqj2ZL=wS#*>g|&v8`)2rS7`Rs588rT~^7ABtP=%c?=Wi$jGsgIo;DI-5Hi|aK&)GpCky)U9S z6G{USsX(ET=WwdccYJzFuLfTqNz_pEHe3zy_wR`%2_b9wW}iy>`P&4}HyYtEYqU$O z8aalOGt9_#nKeU4;x&@H#^Pv_AC}-eat}Ro56`f-fv+S2vn-p}$!%|xZ>0lkIpghO zREA&GdIH{yuptm$670|9Z(9e*&D`@5e$th4dv#g}HxS;*6)J4;;uRfX>U+f@P2<2( zA{lIgJQJ+u-r;=l&1-V$3Jq}&fCjBRSpDuoD`d6o#$pkW^i1ZVY0Q|+NMq5LXJwG1 zSB%3UH1f0Hew$_8V63Fa>9I`2pmI6a6Y@6XC7&lP#-eYCabEkt=U}0g`PHw0i1_)X8Nlo!75h%lG;b@@#q`yYqIOJ3+c1S0z zQiQz}Q8AI@nc9QxGGCaPKVKkne-v<(VwI&3C8981yImsFd+OCZFuZv>Cc+}K^ln$UVA^Gkd9^;# z?|{h`wcsI7;f}kiz6(mtT%;O{fD53aC=~JivEThVp5Au$aYl)3hjS%0{gEu@6{#}I z@W4P+0GURtI1U|040l8RlQ~nVzYpg)(MfTPVayJ zL3sSD^8$w_OK^F)t8I>IoD6#$I~7z+G%WPk_;{jUsSMYasxs<*jx7aY3&*P$HT2o=er?(jT1v z3jDhW7OojSs5h#Fb$$%>00Qmq@Ps$+tuzp^j~s|BgSa~M^l0zZzf`yQj&7;UJd_Ks zHZPmTTA{YO%=0njkolosshY6E#JeE#Fqs#>-qn^Cd4G|%Yy1h1Wt67pjVv-(zQ!}!qQ50WIN+x;|6&0?g|k4@17AYC z5fQl0ykH5_n4GXMH*MmqhjRrD(0yod zOe6o6k3qd*r{N_V9;+$%&nD128LG+h3H_OdJB>Cq9!maxd;H?^mIGJq$ph362lB%? z>^k^94-=ux?N>wSLivO#o_xmmv+4FF%~lwJ3Mz3?1a%Fj{JajMHd=y?h&i$It1ORX zk{^_i8GfsJ(l{LYdi^B> z6aVFRY52DknilvrFvhV^y?@WW0Qd;$ZEq=c@%Q(1+h^G;r1n|KIEU~`e2 zn2(*4D|AMe9AdO^qC~Afi0Zp7w>;pp>j6ilvp3q(V^1Pa? znG-+S74;lzQCJN6FdYKbN7)ejO!A$^))yplQpU0xPhph1K^FxQQHCRDp_d$orHxHR z*z7cMzD9+?nc_5Fc~==VZ~F3eUhzdnN^BaR=6w;7uu8I^iUtKf04C@dR3f$2shwDX zgSi`y>6ePn><_yU`{TDBM>J4zUn9}ixBS`Jweg+FA_(TVk~+H~2Xb8T)z5|%`swe| zS$@gjO0W6m+tu6fvL0;Xq=R zs@GL257f=JkC$uM`0w!2171>E;6SZU5t~W=3(59R=3I-lzH9f|rOgw=gu#Ub05)X* zwn7R@f^LICr6UW78cE0FCrEc3$TSR+iXae2`&Y$1p@DCky-7MzcRp14DSkuWjouMf zeA5y4H6$YZ;f{hGFe#!M_!S&9Dmst+jA=|}8CaJma`JZDI$uK>J_&XWX_h4%V_!wa zh<|m^fJShyJ^9lVZS%!6y}%c~n)--=!2JwX;cN%TF-e={&RMXpH5+vF-)stqvpS&3$gbCl{>$u~PXY{gF48BBr4qo@^+qni}Ic`u85 z-rocr0ZsQ@9d9refy?*$l70GhDD_ffd7wt0JMrKsN)HZZUI*WBV0)pCSrRQ$&bCDV zKKSX$;bG5NUBH0MZlGQ$n?``*+&25RGwjQ}|D>g!K!uRF>y|)hnJM@KP!x={^)KFY7)|3+!OxO~bh3D|4|q!7 zK=tL)uOJBLe?(#mLia~;c_rltst*_yRfQrBM}V#levkk4f}F|&wbP#?X{>D-XP>$F zxhG@5HP{G(-2R!t_q(t&JFwWq-sA*J7mq!+HoTnk!}%hvS+npe8eS%xYw%TCS9hW` z6QPuQ`eDJ;^^|C}mfS$85~**KN5OKm!KLri z9sfyzkzsn1t?5x9yz5U{RTo=-lwht@^08V30U8VvMPHJHjG%^6oZsv+axBS}a?Z_fS{=cqp*Zse)5JKWHEoLm-cT+x2`KOjU#g(>xTL>o6 z8Ep()FAQUZ9|J)<77KuufetH^_yCEAQ})496=b>6OMfLT2gA7rTo54AA*KcK&1eg) zNXq#6WwR#!}XICp_75;dFrEn;EN>;)zwZ8RK^uuD>nvKNcG8Kz zCSIRQ%@)i5q-rd-;}-{gNx~b)fx)>_7l-Q&x_}U{itHAq{r$A$nbIwHhb{ExKOB>f zUo7YEA_)FLou@6z|DaA-cO+1D0^Sy0mTTa?JD0?|rJ8y-x~-`=%(W2{@|-H17#_A~ z_)Lhz5503&WLU4ffuPph`{%Cb;7(-tef~!%nDh^Z&^rnF034F36{2jvNHfKs2>gYP z=66CN-;&&tCLvygnk>I+2aOoc@w{3P)rKKZ@bJ%;Pgf& z@>L>Fb4kdoq6H$yKTf7rZE*@LLd;EU`OMe_v`!0Wr^2l6I7>4jYnd0oN*qufn1iX! z*o%WdL`H*HPh&Z`J}lBQzXCrfRD29<4v`@}i7l!qRenqNd-T`F@ng!eUiqj+VBp~o znRIx|@aLrhG*1Iy{gEGxX6)t1twd6!A6<%D_Ex?mJn4>^pCkNlG;jWITpTrszZ0N- zv-{i`(#jyi8+{>!teoY8etF;g^-nBTAd)ncF*J0YfHxZOS}X#@j8&EkUZi%z17Mju z5(udU;)#Mqac1CV7_^@#HoiX~P;T*t{yE)?l-!cB8zv?bUg3sKUUE{scR8PA0=E4n z$ojg<`Lf$cCNr8AHxzydIgPEOeqZD3DkW`4(il#v5M^2v)|{6Ium?MSM-21&tw>y+ zCzB$HB93^7MG{Evr+Fsn`ooFlje_m{nzMQ)XoY1m2>>}iDg@VFDtOPv{fKEB86S=b zfRbxAz@~fJPasCkKtXUz-B3}Qla#eZNZV*4nq}@^&TvyKDOMR79p{0X!E)Cq%J^<$ z&3$i8uCc;B`9#eH7N_Zo7zgwXt{0eUIYnP55Z%_VG!L1&{z$2)B5Gvw;r{PB{%`Ca zWg7A(Ma^vbnp|Uc{F+97n(-;?=;^nRN(b1i*dks<3sVN3FxAl!Nn8x;u;5H!<y~qU(!!(rd@qUBVKeh`y1+H)x{UP) z2MmJXRiJ-RfR51Rd(PEU#P@t?MqW-EJn?-ynY&+y=qjiy<1G4GLsD%KV=LZ#tNYbQ zlPk+NlKR7_AGY$*_*N`=0gLqmSn#V{yeBtft74b)lh8(snU8Dbn-m=hc|(PsUef_C z9)&lXEj!@`NOpYstS=3Dk}^5AD-pndWcOe9zn1!MAd!x6r&Gg%mI?kW?3v6rgG2>S z=S{uCvkI@NqU}qnZDXv2ro8FMCUQM2t>BG0yMil&{CTXmfDAe!)D$}rd%K5A%nXMk z4~+|Pma5phCq;w=F+Mv`chs~NKKbwE!v@CK>-A$dr&}l1;HafL!c$@0yGMNFb^FEbZoaw|L&qV zWnNkRnRtjVN`~nDrS>?o`EoHd zN~)Zejv4oCUT?a(h#>KGM_Q*}vD=Y)9mm%3on}D}R3yJzp3nXFbI+EOS^%KEVgQUk za5gY*D#=pop}Wo%VWK)U?)l0j;PgtxFHzEZvn4@aDuBm4V!tAS06Xmiom6P|@8lzh z(ZFWxUv|iIn*aX;v+hVZur(-2&7#?eS+Hp7xYBRNY>XcHjjoo3(V9RF2uv^`Qmt3G zc8C6fz2ot)gsblrSg(riW@=4oT1&vgrtbM;5S1x-?zpQ~|R3Q$aYa2=gP%!ZB2uU;*Rh#$As1CXS12w)|?B`}VFQApZfGqEE z7_$_rNy7S)%)GVbJ})g;;k=FX>BCJ+klOx{EQh(|cn8>)#K2djOMnj`P`9wNhZgo2 zfKl9eG^+VW%M$_Mkju!ceq=Byfd=G(2KrpGfO?0@xD^Q*rbTrCIWMOjCuQM(A#L0V zS!M1psb_1u0Y=fLCF7roOSV#-x$42%P8KcS?!*=I{AYu7xFLT|U!R8tt+E7N3fY`Z zEmbAOSMWhr6~l{~7+(?j>E|RdY}_$hgdp+qbn)(8{n-<$x9-X z!uegWL2j0O*bGEHgu)^?!aYrX;iV=9(+e-meYF;SlpGRHXH`z;(lh=AXN7rK@%X&I z=%i7opfurKx5uy=#9q^s-ytLgP6&`e?>qJVkn7PPrx(%fh(GOfSAN%mUCnIj09UT$ ztT;ZkGuJ2Q$NG8YD6!aQ<6->uLJHWk{u~RyhB!f|CDdaSJU0&(hR+TFlZ`{=EGzn*aXHPVXE1!y~H-ef3PK27F>v+m;S;Jt>X`$Mv zQY)5#LQ@Khv-A~Uoewr$i?{zemNOqaD(TR`BO7o}QUYX{;9mIGwnDP;7 z!-1wT1-u(m9##Y)WlBb$PIj;8UDk(dbndEoE6)i)CZ520KmuwOuf=SY$87yFyEfrA zk^2kk-Q89UC-f27cv3|W5}o%arAj9z+n;RJp6A>!M4L_rL2~C0vtoJEI>=VioPexD z7gb1=nSV?%L&rjnUXdD}bKDPTjI8Y@M_+ZMG`mg5SB{&9YCaBUl9|5yhI}gS`CGx= z0kSx>WP8{hOcmAtpVAQi_f`TT5IHn17O6>oJ+k~8Tgu|n;1EN0&-}*b&|ITo_0v2HY7MwdnD(krwN$gtff7a{$ z;g~8^&l1PN-5-tl3>eTqKtk`f7257aR_WE~~Qm#wy zbX=z2PbvGgtLP-)b~0Y=tFRfxbz&>~rB#Zlh$gkYG_>OTekWFVY2jSnXg2$^!y|iq zT1bad&Y(y_R?ZL^?Ub2Mr-&o$bS$mgaaDd)R?T5t!?<(>-pJj$NKIDw!F)t!p^3Ta zx;mGO(=|WOVI!9<{=asG^&gZEBuCgqHpI4tJ-z?%r;9XGDY)ee|0=J)6vrcdewHt* zKR8&Udxs0Y0{cKptv!aElsJ^wX?ijPiBN=_wqd-+O&_2ao#wEksE-BpiWW4Y)qArL@qY$u(MJT2}mrgVlG z=d-r_UCYJuTHLJVu6#4;d-Xs`UQDvvL6_H|RN_tl9l7yH2rr;-Xab}$Np(h?LoUZ% zAM;z*m!w73W2cnJE4uE_F7SYY2t3#-H40xX`XVdIa=@i2)qe$Jl<%( zkS%+R9{S?VjMtkl-K6qRjU<5i!A}hlT?!!Kj>r?B)J4!NvlDc#T*qt-WRt-XE9}sc z{*Ph0?&qlZcc%2_n`snd!J#FwHowH_Oqf;?N<|k!}MEOn!#}((NU8csEuX-N@pto2s7DL-ewTBW=g*e>C{BqR@Su>;~Dr}msY)UC>9n~*9l~}$V_G$o>@{vj@G69VotOC#?AXlNdPpmYhnUn-45w?zTwa1~YN5U!gdt?KBmpUL*EyexqL zt(*=(IY2;l{9EbkjbHx4_MMyjQ21@`e{CUNd;~(*f^WOvaLrT@K zp6t!8fGNIT+~zXL;EelLBv0-eXt;uUSMm!ZT~4K)SA$uvbB+A1VN+{qB)V`8)_@>n za(YoSSotTlmFKh>FVYq^X~6jcgI()@k_m;(K?;A#gZmCDc?(-wp*wt`ArG_<3GuD4 z*B6k%js6f z$y=%7>9;iy)}6W0=3#2IJj>l=%D0RzZ`ayNn8FN*)x|TACNEu2jaL1UO6v#)3iCZs zClIaaYb@A5*fkGG2OI5Wm3z!@EV+zVa@4{Lzi=u-`~b|jTW(dh;d^qBS4cMv52#sy zo@FssLFvSr;`R0E(ZT28v*(44it2O-SIVxHs)jK>Xl1(;f1>+7YSIML0H^&CBb>69 z+$yU;JqvChZ5s`wA~CL*^gcE{M-hi`o{=L&0oNu85Q=K)E1g2o`!Nj%jAJFR0A7nV zG8(`zCD&ZzIl%m$o89ED~_z3moH%939ZtSi6J>6rFVY{C-!~R$s%$(O4?L6XHyRA4 z_{pwx#`T9mBa>%@XbZtHCJ2%yGT?%P)S1P_PLud71rb#@wyh1F4V|BrY83w_a&J6_ zx5&l`f=G8V-#+z*8g@-Uwk_Ee8q5_b4c2-$BM6S20u@X!O{jPnS#HHONX-TkES;Y_ zU$}kC%RFy~YKAg=<=W!AkGo!pl+-zBDeQnpiHi~e9;WWs9AmQ`sZK_XUB=Kbh$3|rTHJF#tJcL?6FPbiO?-a1B|A)Q>=yTKtfBzTGMk3 zT}31Hu_z_i;CylmflW}Pgr1baY_=Wb`+@D#0r1OX(!!6dvqwpEzVH7&vM?0y3rDnn zO48Q#D~c!(;KkeT8|n?!d*7AE98cr>a5Hhj0|V-3`Ws`$szqYvwg&V^9Gra-Le*c_j-Nov;k1s4#HYfOa4!E6+_*nm&ITs_GQZ3VKQW-aCl^4 zlLXv>JuEjdRVdZ~SOusZ_j1@Zv}$I!>Z^rcpWOWX_{UU31l17tIe!2j2cvDMa6xgE zfrcP~1-HWrgCzM)0Wl-@a?bFhoy$IOLB4PCbqxVx!~0Zc-{Vt*Z?8jZikU9G{)!Gc zkbaF|_tfacNF@TIVhJ>i@RS5zl5x64+A;@X&xSE?u@P+hl%zco=Kkx>Y>+l@~fs7K1C5we~}7g8~8uI8R- z&Cl~(n;d@V`jd(1{;VCnC=-|KN3;B`GkajLoMFGbXJ+B{TJB~PKj4B6G^shnM8xn% zFRMPILv0vG9MFaV8Rs){g(Nj`TwIvGc_U*n>2k%O2HZ|dh6Tj9e*{)&GEGXK*?1+X z2M*U7=llI+YMyUp?gCfvwrBTuoI~CJNQM72`#UuHbhP*piUUCCLcW$@UE{_j|8#wZbJ7pQWM&l>hjEg3%gHQ&elC<|Frq?!G<)9Sv1=bF z*-d|!Qpp88>glt5c?VzkB|qd7BQ3%8mreR!rqygY?j!f;3a`MHAqUFXo!e%7zCj@lTBx{R^)G&V4J9ZTR=MMX0h!;7uL2-~KAghwBTN(Ow7lV(e)JPs`3}<)GJm)&cpypvo zt3YAW7&GQG&6pTE0I7~X|MY%7@Y4McsQ2sqyGQ7AsbM>TnyQi*Dxwbk-Q6z;AZ$t z&4Yk9OvxG-?2IffAWTcHuxm&&oc&4-q7jho;T^7>D4UOPGa zX0DFL&Vr{UMia^j>(5_qGk3hVIJMrQ!uLj)xkq6SE?Vn|f$^2{+-LV2i@okXJ0aFZ zV}%@MR#M_~%_dsWI4vH)OIO7vjH0Y$x~gl zAEyRMNoPSgNm5pO7|Pm~pzd#oNr)YQ;~Py%0yS{<3-DeZ&}m_=0cONvaB50Z@)hji z`MVH+9*k;>m$6w=nl+#KeWvLpCsrC#Jt5`;ewgJyq8SE%Ql*rK05Zlm*b8GdXe|7Eu-k+z@06Y7lr8|7v*Pc9(rVeYs&Nkp=37~Nyc-=7o zg@BC?)BK`Fbrsxp7JKN7dH*191L0`U@O24#FtcPWgi2W<0iRa!5jj3g*Z;B+Wh*(Q z5EWEhVQI-xMis_sr(!Z6|IP4M&Y!)%_tF&{B#0(E-CdYuTqxb-tg^e@icTMYx+a>g z8D6{=M{7rdp}798^HhCDBJ{N0rD|8-&A80jPM8AO252z|o!iYf(0CFxQ=C|qw&yX> zS7>Cdx8!s=j&y_OL-YWzg~om>1%>v| zoUGoAUFIn-j(u2HgF^9~T5IR?*EsYQgH2{Pk(Z84U@YQ@e(?&dE$DGq=}97`ySc$} zBJ@bhWgeIm5CD{|N~it4f(knu9X1l1b1;w-RpPaS2{%eucRKY~n4YlKd2TF~Kj~)t zEnsaTR+;f7p}^l6hXh@4fDk7WHwybFE+9EatKgQ!4Nwd4hlrb0Iw5Odkimn1a=)7W zJ?8nYpWnfudN8F3Hp#1{sNnAQy!36J?oXG#F#w@a%%+ES^}%nWCSur<}Wr3tB0AVY(?J zVO?VnqG3*TQUE}p21g$1KBbgAI3eI{@1q*Sz< zJ0AaIzc`Qou1tZyH}9-NY=naIo>y%8jW8>_*l=ns4;3d3-G8D_WHbZml%i04mZ#G2 zk1KPkZ!O1Ro8#L4rjN@?cPBd<3Fb{r!Cv}(Q4SX|T;)>cae2O!1+vqr`!s)r6$?=9 zIO5?lxDq^2Rk68WT}9D$(*!T} z^zRJx_~hBY&O;p^y~+<4zvEtcujrheJU2v|G2W7XjIaLOMjrRIDAY7& zRK|mf-j_;68Y5zRf+m3gHgrcFauAXqJHYsq)EW2mI?9&=?hA!_l8s_o84W2| zW(^J-7Z2sDh?$Rk#0paLY%*6(=qUi;j?4Tzzv zYOm|)`5gBBAMs_uKl-gT#CvO6z(WZ&7)WRe0hBBPeV>PC!i|A6?h*ljX1X&I{?HVJn^P%znlY3(i1>efxy#*4+_c&qfC*OpFGcfa)BhkO&#Xg{oU@0^QeD5d6 zLzoep0DZi;8)YvdCGCA`kSyQypX!x^XdO$Pc1#2n4caALB_ky_RxM_o+Own-L%+4F zQ&;=Z5CQQ2<0QG8RxH9E{y44tFb|$Z-tVl16LCpgzzpMS6`e&{w_RK{+RnchBzx~u zr@_|1=oJZp^)9AkWr`eROS{azKJ-#+@hV>MAHk-&|8cg^XD9ViDg@@@oPAmX2~;cYbAU)RRY>n{e@mjD~9u>G}Gr0b|!l3q}cKx6y?;W^v)1j`dJ4% zfEaz|SP|r4|7LD%sWy!E|$%fE0LMtm$JHSlfdr~KR{A|=H;8i)29VEsT^J-Ts(3R93y7I6Tx;D^@^LH zm(b06qTCsokj5_~JS$g6BT^g5kuK6wb<(M=P_u&yHCVaf;vxvWZxBA2+Yo=cRsUsh z(NlVHnCIp3%g!GScM%OsWgNHJ-4vi8dM_>Xwjtpd-Bvd^d>UIRfUJ8slk@4|3v zd*c{%MZ8zM<8~c;8{-|?s$@$9kz23pQL}+;zardx_E4b6Q$uDWj#Sn-3g#7* zlgq+?QiU1~|h0nDPS@F((~&UK#myEwF`y9?gp_ zbmRwZ`t|lV0!m@hf{ZtjCoLgTi6*qB9ht#rXhF%Qdt-;aRPSWD{X`l);qg`j7cfCb z5wRga`z%owNR|2Un~o}!)HvL~h#w~9W%i!+v=e-%xOAq2q3LxomaM@m6ooW?i2clj zRU<5xaD#n(Kf0#9HDyr0oZ8y)e3|22<@S?C@5oP78U_We{wsil~wbY{SSVuK!U^Zxx00V#2`tb)D*4gyRAD(x};#nUy9pQ*M z6!rSGpB!zf-Wym3Q8UBNA?Tnka5hG5Z1Sp5nk!E5zop1~uh_W?Y#^>YW7n6!%TO-$ z+>a`%5K3&S>Z*gvICG}4NwZiJIAMlj8vy;+hS&cOuPHQceUlub^45Og=3BhlsvBHb znY5?E!ne3pKA*VaYl_|-R6%IWW1_S`{q|K~>?h<`(&Pg(hgA9P&Pcx}C0v95 z-W>T1m_9y~+h)mIE$fFwqdLW5+Eevw@+Ree%e`H9?G0W2$R0ns{ZU2C(~U$08BF@z zsJU}czPu)Wc)UsGYbEYkWt#B0pio%ljuC_uT3gg=;!Q+=DVxEP^ZlQrCASsFC{{wc zb=)8$#U`ItZjTJYJA0& zs;3)@8%4GZXk4CcFIs#(y$rU3o%h!D?Xip7PU(tG@gt8|W2B5)rLt4k)cjmP|Z%oTaesP~$NpR@5H4pSe7;pF^YdzsMT&(V7IZ(*hU)uMU=f#L7Tyw2UPEMAqK%Kq zC$2WD6ZPP#hFB@!rqPlrncv6}aEQNw-Yo4XEVrJXok+taS;LwW(bB(qOX2@u=6Zj0 zWjl^ZfjP~VR~eIoZ{v~;IiQiLFSP$G(KlPa^lT-UZnFCBJnMsdlQV)bkyyDzUs3sQ zjx`(p7ZQEBH|i5Sd)!r z@Jh+U1D=C7PFP01DoLCNn-QW>NCPxD@Fj3mW2j-;EXJY%hKeE`e42h5lt}r25Ce&k ziVoeUmH64hGe?@g1^|4sO)%$q;KY~$?5UEaI^f-kpJ|s%Yl0KqL_YZElwuFMkhafh zoZWnGGOAPehe{oAf7Np#biHwz<%6h+;?+va)d*@gT+rpHMi;w?U3|VzA1;dhb6Y6q^(D_t*ip9`a@UX01tGEi z1e{(6BVrtQ6XV}DPibdY__YT)aJzA+LpDcXc0Y5PPWsjx?GRHQwW2;6+Fv%}d;0b0 zuw|nXH2d0!^nLgU8CB3@8RW%DlF#Q9nOeBcMabIZtiP{6dR8wZf0DLGr@3tjvlR*uH8Seo4$> zt@dr^ZprE^uv9@zR9sQux?cn9J*Z``BEMh|HsZEKNZ{u}OkyC?q_q(!-i5z+a{Cwe z0r^IknNVjHm*dIn{-Gt6i|AbtPwI}X(6^e86Q#q@7YBj3!G(%J3h*?P1$*g?*y>nl z#2i1`9&WYu@GokJlqeQ8-WdD+QY~^+d+)DhPwD8kjrHx)YbbQb zAF2D0Nv#B_rH8GmjR)QvNJbVOHF%j6wGZAWp=~>Ovy?*P2m~uP|Yu7TpZV{ST z!rFVY25C7#qbonVON5bet-m>bJ+$Cz-&tpmI^lctb+^@pS(Xxq@;R#5j3T`(u1qJs zZe7k+O8NCTZ6C!es8?9TNt2tTA+IJGm0i5|BX7;dS51R>8hgTzq4#r+z_!IIx`Mq# z>cvZ3`?SveScuyaBaKSqcC^&h^5j>?dA44co7CRocm3E=NuOd>Aj_ed@f#O62E`H2 z-e%O*zy0~NKo#RSp$%NNpj0$`vE4HbRE3BL*yPSq;7W-}3mXi<1nA-SFida)BgcVY zWIOKSEU?ULqro`yTL?IhL~mHA-CRXI90oq~E3%s`=0Ga=E9L_Tyyq=@qo6bEreG;a1$Erzd)c5X<+}APu7yWsf6@H|&zbPC zqJ}e_%|RoWjR`uyB`QK#OA5HDj9=@$c0!_f-<1xcWzg%2UH=`<9tfNyE)a-@o zT#dpmj!_F5o?1;!Q!Mp8(aH^l{M>|zK0~1Gj!8xQL&bM~P`wJiqkyFN0GxHS^e<=2 zSoK~x%o|XATV)0=O~Z1j5_KC{*FZ?OsjX2rHsQW{lDt>klM=!F5hbH-OCxDY8kh>x z(D1viya{c`9{Hem+m4?4?rOuZ>S3+}&@98#VyO}oMzIu-ZEjB2XXzh6LnAvmMv+Ghd(O>m?CK*4+krnNvDA`M>03+K8=zgQviY zTEFYp^q;m|etI>X1uEBqqZUXp77o^W>?#Xj7*}v2!gyKCyE@B%-lY%S{q&`r{5k3L zvTzy@Fl+Emw!%9clz3S4K&R`CzeK>2ag_p}q{r=st1PKX+D)Iyd8qIC#PD{(lVD8X zzeOzM@^2BxBY1=p%XTfeuPJd0koBmelL9=djYN@h=WSU&YJUDDMbpx+^oRL`Cs*tg zSNYwx3*sT{w#2ES5{N;05FF6tPV}A;ciiwK&ncH39@xWZL&OM^U^xylf^^ueIs@!< zI>*KzNVa3sRLKsy&n{d#jykLae0fgkAor=X(xQ6AMk;^%qc`4F;kzv7?Sk(}bZe~4 zwhh7XZ`(1bn7}tFf<%Ae%VwtCmW_xu>jfWTe=c%2D-CBGUdp4*?0QZxm)^5g?w$pI zuz$b!^m`f6m;qI6z6 zRseK@S>}6aYT5H?07msX6y!ZO7^t(deGWuZs zS%2%ku!H`JI*Z>&L@dAcPp50ARQwLtUyWEB2I0yV@Qwuw`H!BhCh3UytXb&|Xi-os z5wxfSbdfCn_v@n`rmS`Wb1q-tT`}@H_kqLbRQt_fNRrWRZaYgRi2*r?RF|e7S@qdG zIJb{U6tr?W$S?t>S*A>rLQYWlfK5sQgC^*|o;W=2f8JEvPN8H*gi+@~!#iDsVRc!R z(vDq2Oa5Eq1|)zJRAFSE9NOC+gwc-DhBMv7O+kg`knhPg-$+r?6`m!1$5rN4S#)_Z8(VGu z&=NicR<;xH;~>S1=pOk}%mKHf1QJ%^)oDgx8X|2+q1O{MMr$?HkYw2%G*;B! z#MNQ0#ZuKenHex(9#GHlq9?`b`;S@0j7A$~RjUsbyq?VwW**tN(_FgbO$(V0>e5wZ zY&9GH^IO*OJYB;c**s$VSCOu4Ex?Ov=rh-?eP5_E{Imu}JKZ}9-cyOY4zuMFn$shl?jc)%&G5qw3&}_gn8&{sy)}(3T>vfe~$L*8G3OOxo%cp_a z@7r8T_X|N)gxZy4&3XKh>66U~(>v{eliey2)52W6Tmr^%RKRR_Dd zALla3@(6*@WlDtV`fZrG#yDw+YtojXMn(&$RMvvt2mFhJK$YsdC8+Hu=7=DM!^cZc zFp$822$La*&2G%p${*0U$s$^T9};WT(7qgLa2S*e?zoeGXUXzYc)#TWG#7dbvonBJ zu69`b&Xq@0@nde-br_v^b(~cma}hC!9kXC;6O@>e|4AcH_j)?T@UdP_LvSfGV5LH^ z&RD%KbG>nL3TBtR2ONYi_XPrN7Y2d(3lNpp>41^$5TG#QI(T!i>3S|0cfAVsmR{MB zTw>GTc?+WcezaqKBm2U5{|PHtcK@?zxWTR#h*Mi)mtV5<3Dkf(nRjKp;p-FfD1$Pt zav;nQExAh@o*ed@w)kLiiu`=srXlt!9|1+?d}B$r?=wD2hE7ODYaJnbaees|>z%M+ zZ=zw~nsgbqV{?A@6Eeo*f;1+KJL$lhZxZv&k7&zYuXK@Xg{5Fi@@`@#Bt=J#Dr*@X z41rVbP-m=iE)+B^UU~r5DFBYQ#|WM-Zoqk#^K_M{f4SF^?D&ywbtlJ^xmUBG4NC&% zH4D}netKYmKedk0Rv+2rx=LEP)QM?6DN2aDslp}rBujwKd7~2#;TL(w;yo7_bT*g? zvYX(9ya|QYMT0-UArcN%Q?}-QzXSlEaMw3~zzF1??CJ`Ab<{uAGr-xjYB6&z3ylz;1O>3{334(nLOxa)J~8!&N2 zQD&KSV{m-5Kywd@zNRqAZ^qp-AL+=Pe?LlhZ)^v~Em^>r(|bKH+=bGprv z6gNM^jjx12gJAx?iSA=%*sSPXkJCH$Mf-f$1Q-=jSsbMFQ4|A&-h)UU*qc2@D7Z6( zmPOosdW4F*I5U-CU;P+UA$^0xr1$0bH0eiSLrTwl0L`_PSnho)(cK`Ie2)^3`!Qn< z!C${T&R&1Uccd9`QGRMb`zocJUlPwstturEA!s^2vYX%JE~qa^8#6c0#g z02Um^aI&(v2~e<(+$;`Nw|g&NXNr8GH?jvo8N!96ge@;V(g3Q@$Ua7=6pEii+xJLm z)6KFAk*?*HEyx@owfV4kz12aPz4W+~JPM}EP(U}h0eJjr*s*?$NxP5+4h#qq>zL?= zXfKpMnDq?4AqFjq=)YOV1kt~;_LY6Fki>!o(E0SE^q%3KXuKG?k7lDrio%BNe)-me)Q}%xUW~rk;-uq6=z; z+YKFkX6+&U_o*-(gt{c9SqTv$at}C%{s@i_mBeKo^ml$pc$dlG9fHQpBP^LvJqr$N220b}3WnA_kGW zKCddJm-~=eh_6HDMD~ZLrI@)JcZ;BxS}$9OYXRb6OYWII`^NoaQ@TQWkxrI`>c0|F z_+JS*-W%%?j*=BR75pA@kOh~qYhx*Jjud1u5z;nAOow=hTmAuId!i6aMYK!v>!!8d zt{37@`&_AE5-twRUtAYo((t#-s7E^c@&h(b3WZCJC*Qbq?2I$La)GbHD8;4wsY?1$ zCJMF`7v~%}c)5*-2ZJvZZClIzoqB9`8reEXuix>`5+7zSiCe0Xb371uW&N^MpT%Bl z-esWDykHc=h_5#pXOZsXQ`C|YAzixAju~W%8Y2Xf3PRbb{5;0$ir4LZ+Pk%n`)ya< z=GE_;CX`t!5->?|Lf`>3R-!^dD@UUymf7TJ-+WuhF6g>A6EYAmLl-o1^$y2QLgUSjB^O?pqRKF2mG&k z-x7fmMIdSoy%|(+XsN&(=Vc(~|HgFx0fH35Zw&i{BqBytsC=ozeAV+0yKR_Ws|;v* zTB9|>PSrzZvA*+%vj!F;$QlRis3W5Y9a*s7xO=f?g)(;pMUp8!w-t)o+v$_QdI=$4 z!h;O*XKMMNZnF)Ju&MgsaGnRk?7=5wASZQL=pCgb2R*BtTg<_IQ^4zZQ92p^#OO4e z2C`Lt1vTpbL4V)Cdapx2_?f$3CH_SO2iQHTY-GOra2S$2>?bRZt0fyqC}>yk-Z1Qk z9o;Fuf$lcS+3~G^rPTHo96p5Ro)!4_W^EUAhQly##97uTpMTM}oKAhElB}yi zkIx&!SF+3u0E$8uWz4B&=6lpIkXq@jjwCfdk~UK+SMi28FDNyd5?bL)NqTP7b@W`S24(9L|o5lJ$!<55)t-|UV9yE(+ z6NQ7^i!R`b=stO_zFm&{f_5*M{md6-DgRDU z%zB$@cd)ZFQBHE`{WD$@Jl_sqoKTY5&OpeksDI|Jy&DP{?rBxYsswx%S`;Pz3a|Eb$(_ zF=?^Kz)-KflC5JyU(zsqn3 zIE;CD%$Mkt_Uw5|Y_IDH?g~YlU4!mN9|(>R@p50IPqK%QlxqvLGR9A#BzAjs zS6wRj5AapkKPl_mkx~$~g?waYqpuhXEDxvKQ4I?oF3!Ka@SeO?Or8&K$R?>h?3s8V zoe;FdNQ6V6Gm<)-x2;R7iN*y+#ad67=O96+-KJ^cPya;eOQ5HBTGg2uS?~K-QF)$} zZ*0c7&u>Cme+y=Aw=vAt8E;94qd&Y-+Cq=jp`3?va(Vuujmvy`f4R;eZ!`q67)1iuPn_>cJ+q8tuoupFV_uJf9?UbmTbqJ(sOxzrtuFj z{))hc4M@uRUf(~jzDWXUMejt^_I?4s)$}sA_vIwlI|sW0-bwvPIZvCQx7yXWOWweN zVlQ3tce!W~Cff*s?;Y)6TyLMo78=UMHlIp)tf}HZS}eTdUju0+h{8~HF-Ltck&e1Z(TQsjOJ+<_i=`gRQTElDG--nEKU#z!I)T_=QW&zUGB z)dX{NpI&aFfZF;`BB$+B8urGIwF!@(Z<4hQWG8$W=-c3zn@9lA%=rPMtAJQkR01St zupN%udzc%E4<~^GpBa?EO->-Uf%G|#L`ZKR2q@8_doO$&Wpy1WlBaNp#dB6h<%$0bG{51$=9P?Fe*}(FygAZ_Fuqmk|yChI2&m`*c zK3tE7l{P-0ns72@8M{Yq>T}Lc@*iHMD%|;(*xqI)E2=9)g$qbiEET>cD`$Fl{jpy@ zt3S_~c9snBQZrW?m@;HN5_q)Glm;A5m84}5Lz4Nd2> z6%dw)6EJ;2k8X)?X=PdVbarkG&bb-AHyPd5Z#v-Q6a#0?ziBDe|LVwA(*GWRWQHiZ za-Z2yajCW=;Z@d)g_jEcEC`1IXN-#1ECU;Tfpf5$bUKlrD$T}3M6I@++{->(yg9zGXYHwl=hFoPQKQQ%>{RlFKR02Da%0V zHdbsK1+YDkcu()kU?aE>8kj(HAvBn#Oh@(KxP_y7fqu<;#~SRkL{FCDpB!1OOZ0IGM21#1Gy-P@^PG}0RwWX+*r zs#)t5w_|8RnVL2lUK5`{P#h3_B&9U3gTTt5fN)Tljg$NUQ8hSigIK9gRsvf>3io^X zE))W3`P=3(57)LcEWIg04jha|9#`PvtWV-rE8>kl*CM;^KZ$L(kU19pRNOdBNUCFM zE1tRzb|y8cpb{nZ@c00YiQ?Iq>8>JNvqs61pKTgpRl?VxP$CRB1+2ay#fyv4EXMd& z04>c`Z0d{4mztKr0b(TqwT^Kpu#_>fpAiiuoQyWCw~rw<1!;9A&F~3L%G<7v#6r0coWRq@du@Hugn;%Wxu4phHK6#ackDSWjZMXk8ypDIZ*);XPXL z!W{Neh6(H}MFGk=LQ46JMl>@+FKZ@c3!@6Rd^W zMW!SCJFQ9noz_KB?u;rb7|P-42uW_1Ic3tYK(FRPzkQ^rI~SvvX%w%4vxTSQ!9h2u zMnVNlJH4MOUf_@i!;etNa=2q$(il`3P4IO3ELnGX-j** zeIPIq%c-|YilxedpVI^^j5`e$|L>z@e%GsBYC=m9k~kpAswow1$`l=h={Kqj`vW{? zs(NoBZ9x(x=&y}wZ|0EO&LBFs!pLJxRw5$dUa!FQPCe3a;e52+4C28e#>jT)n?ee{?0Svgf zFH>u$Af_c^;GQ6|sMUB*eoYep@@FX>6iYMggQ6*%{~BHWfA1wJC*B^Mp-hz z3>rJsFQspl=!^H)!U^IZG}s^k8>)$$s(aV|bOB2+3i`*oO>_DU-}!gLJL~>xA;P4LIIZ_d5|99g zb<}*ct@-xxMrqZx3F-FxecT6Wqjt!F?54?~Rp#aXTf68FF8sL)nz$S8bgYz`u0@g2 z6@7$Q++sM%gPNWm>%8JwfUn~;0a4vJxF)g7Ma5UQibc$9k%_n83KUPxfNz?;YXy+( zkEc;2Y}XfUzI;FTWif#XI}^r6jlg<~0E#ax2XRCN01|liK;g(-PY37t&m7=O;^TMS zohbEe)=06|V5Jb+Kfq=^59;i2r0o>$V8s?aj|yHmv3SDM=tIl`LHY%vJrU z<`7~!{!=MXgf*2bjlpkhG z3NMN+tcKGcqW!Txngk1PV$pEkyfk$0a zfR&h7_?^Ki*Zyj2gVZXT!SgGXEtyI+bU&@ftZSx zY6G7so6Ze@5l=J73d1f6m`^qfPgi#YzK+`(oJ=lA@|6X@RKmaNt5A!J0zpXSeVQuU zPqJ|)dA|7iJb1&A<#MYmT=692!Q=n$VWR$vXB(yJ6*6Pw zRqxVVWQN^K`piw)642;O31O|1#tZl)`iL|^%ubGDA`0+ol!(Ac!|suepw#dJ7d97t zI7Noeh4C&6(UO<{4zlmM@S&?9MXW zAuExCKWfj`y~ELkRtc6gvLd#3)m$ZHUmbnOz5F~8k~bQL>Au#w5xx>h&ql>^IcxwVT z-_+w?DFt-DV(VU@TBiXcXIO$nID(_lAGiT0m7G=+f=#3|ZlcG_M%P&???84JMv7tp z>@tc8EW8Od6YLOZb~TgD_QXizJrjOxQn5QKBHIy-3@i+%H*L^$_j^igy`n=y!pRi~ zB{FNQXWd(0UE-cfJVB5|Rp9?tbC-Vnv%BAkr>celFk}HIwvKx!cBF`)QtV|F$H5|! zikV3qdb{nl!Lqeo;4EhG7h(r)K-CI?<~6p=wjLPZ8Y`=PCM6&GL3b{QK2I9&d18r=YQY6MG-4&2=;3iExkulf;)N zJ5DCZzCpYP152LHjng@Y4MG69$w!^#;3fpY-E6cdOGX0&Vi*lM*!UfA+Ci3ZONIzy z$ocCp$Zrw!2@~rIzcY$$F_NxGZq-ga3{C%j`uWz3i1Ll+D2WDADRsaGNelniTt!u( z=a?LfE&OQ{i~L*O!`@0wC8XL5_+m1N>AL#VWV|P~fFfDq{?as5SXCsu2-YPQau81D z%nxgQ&&eFUYH#m@LesxFqK=MWgmkNv?t3(_S^W6fB_T({RhS|w5!I=I?;;Vk&V^gS z6zH(Ll_ag++d!WJGq2nzAdo{Zc*i#ix9v^d9!GvVUcEE4&w?uIb8C_6d3!fcyc=Y`Z@`nY^|wg|99;AKab?%|75FgB|r^aMwzv9H!UwJ#<@}mU=)duv{_S_ zFQMw06{QHFP-()B`V(LUgUWB&3kS!a5Fi~XYW}J>2?z7dpDgegVc`v`LCzUguak}n zGJj{_rxmFQFS7bos)?sb+TXtCa6>ka0g?M-&skj|+#m+2;S%9F>!97wp-tS7O&kKr zJEe5jBlm216RgC)-JlnkeK8{+89Dx`WgIF{!l|sCN!&x!>(^>4(r3#yjyWX2b^A55 z!Cg>hHTMU|t5hPMN1=aKS~sNm6+N0YC^8_!r}g986(PJ|I2-W+4{ML&CRMlLPGORLGz!!EN;VG)P64w%Q2ped@ z6&AbgDQo-QL|4DM8eiit^OZGZsrr8*N{~_Jo{ti-tqK+Ge#FIT2`x4M#8fGOWPF^Q zP@C5lxHDY^L(x6kxdWjL?`})T?4p*1>kQC|7%<+{p12a184rDY3bHy5sUef;EQT4_ z=n+$kaJ)pe^8X&3J`z8;_G9S4onriY+)&>2?o>j3z{takKuP}3xkFnx&m}9|=O(cI zcjSUf-9pmy1r$qCAOVkPGI8HTYuO|W%~!`%;DTuvB2Qf0Qf27AE%Y~Ia(F?KB@p$- zAWB_Z8F>*IXcO(5F^FkCkBy_+^H9}{_u{HUs<2`UXb1Fa57q%fLCxi5!$@= zletJeU>g@2m#PphyLds8Qof)bDfjuZ*g`xhQTjv!4qq*H=)K`hCxeJ%Z$r|Pht(fc zd?ozWUuA%p_;a#3+_St{^Jf6mfH|I$+_8~qTdWL^|HTE7k02Q@-Iu2B_6U?O z#d7JzxVTs$5`bhf0BlGIv~Z7~JcQSdFHYFw3W%is;37+rxy=0M?9?sl1e%A+ix=C` z&G9#H=`EXBYOL@SJxceg#xy+1aW^Vlct&KDa_%;L2nnNuu;Kr@i(5(uIU6FOjR!IlcbCXGa2u8YDNW5W%OeEZ0L z2Q1Op-K(f_`aTr8$314RV|1`=OvLaLU}m~z3?{DdEInaCr?4dgi|QHUv@ii&8by9P zPs=SRqyr?^OKY^kJfVaY#(r|Sw)?f(V;}UK{9jd^UZ8fcm7&%~TYh(8FS4U94?3v? zTo;IDH>ssx&tNw}vE}#v^>c2%nzZTMPH82(Gvq)?Rb!=?rwd+MQRI*eSpL?O^@U6J zR9uDCp+ix-WgoHXgkOo%THPI^z z$9`2*cMnZP(;^SUAmO#GiEVp|bq^*{2ynkFcCmWtE$M6v5dfw|$yr-@hL0rl^E(xxq1ylOUQ{5M;yVr?3)lPe*1kkO0 zsVLu$F{I1*7eig_Ca0f|<5R*}pDy>F9_xKv?|p)eVh2{Un+HkNKU8O(uFW=GP<{R; zYx6a}YRgh3Ij*^)m$Yb)pSWFdS5|%OX?3hN)*0X@Y_UA;r^Qw0ehJlaD*|c<_BT^2 zRPK7xb4GoMS9Ro33zD;yhF_~*PoGVXHCu_0v0heX&pSpfzi!U8qunnLG4GduBjFfP zIJ1csC|kg|T@wLDOu{7ugiw~nI83P#X?mWKrt8`qcVFv5POn^h_$z4~aqX-|SF_nq znRTC;V-|2VpMR90!;9>l-1_&49v37VC=1Ks9f4eenIJ?7eYO5obOLFTA99Z!n_L?G zn6lX%9e|V@`Ds>t>6WAaL)M!Qr|%Qiao@2ca0fNPBnEZ&OkByGWEyXN5G~k>4S;tQ z7D2Vd)JNn-!YsHP>M-8S<#L$y6vhuFnpL)~Zk&ChuX-KlaMEBBsUbiv1>AfH3<|Ha zCT1N-&u!0Qj<-J*`HN`$e#I5@i9yfw?er5n8FE_3O$0sTQVfS&|; z-#5%W4S=WDJ`<5)+IQyi5#3;E__35@<;;-5CC7I-;R>L0vyM{S{d3m2V80S=7dZF79Ps=YO7wP9rHKafrsn!m%i@0=RZE`YEb`wuOky!86seD89#^I z)fzEIaN{mqkxqxa>zWLWF&tfJ!q?&55!5a`Na#W!q&s3`(I^%f>M@5+xp20R?GkTy3qOu@NrR+W zV-m@o?f*1q=x^t?d|EBZ3QjC;T!{ ztgnLiy z(eFN$CC<%2EUXnENb@D&siv{qFKvGCJHvhqYidZ*uz;y{M5w(#!e=LOFfYFfVh%>Y ziGMRph?6FYVTph;pzrnUngR!_Hhfg{sMs(ur#WnBYzy~F875Yjq~n-ovwI6d&aEm~ z6cCf8RIJWVECmb$a>u>TXo!q^Pi%2G054o2@fGP z5CpG8Y?W8&Gq*Og&eqVlIm&uOZ7vf8Dvo+sE{`7XlC0gn)|@9;;OMr*uZKt z>gM-)+q`-dDVEe`Wb!$`YqE_e<&qm0SgAo9`6wX$Q&4!HFE;g7WI?EQ`!G=PP6`8= z*@-&$RGP>w_skskE~Vdgc?`;|9t|}MLb7OlX~e!Zs$>4U&`HN5uls&5G$#4BLp%Bf zGdvl_Tp?O*bcDW)z)K?_olm5H*y3S$;K&N2WY8K=sl^rpE?6L^EuBu`ub#G3iCpzj zLHG1=YY&1s-Zi_M?B9Gu7vd^yAGcDV`EMZ=_0azJxu%C^V(cR@!xG9w1xvtg1ihL|?1Ol8~bzS&sLR$&~O2iNbMvvIwnH(?7k{ti&?as{? zGhRfKE=)~m;f0bk@21&PkmX!^_xRZh@KS%1tceqc6LXLo1OX1i-iPvspU}!y7OJha zEK8L_?OacV9#4tm)qA-wk)yeoZXZbA`8E?ztHchK#ifLy8pQT%pwk4sSO508=aV6? z%J0W%H9Mb19>1iB?XOHq2KK(qH#X5NV=eSi%r;2qZTztUOD3_vpD~$j!>~2~@ydx@ z7!d(Mjn{y5#t>bfPiOZTq8@Gv=7uY=N!k!VQO7+5P1& zqAcdFL~f@hLeF1qZIHyT-Zy@_Jzs7&Ow;uVh6qbaz=(k(rYFMO@0XPhMLR(#(5-m3Yli<;*TMf?U1KotA_21Y z$S)xfxY%C?Z|+hCxI7;6U}3|DP7t)MOiUI9VpxQbv58xJvp0ukLmrlmSJm{lStkZ? z$V{d<=;0YVl4b(63YL&7tW;LuShPj;5kA8rvFGECzt9f;VZvAigRA0~Mcj7{uF-oI z+3$>U_lrPndMW*u8fAc=yPNxy?dl`3CQ&_`lBwwTYXLYmpzDIU9$n=r;KC4Wgb`!~ zVyhfp@H%aLR$94EtROP_+!sZ$CeT=+g4Odf!Z3EopfinBo71Y%iZ zc-mLF{HSA?dzDl`Yx1hvmOdP zt7+%bCH`A)(&5toeWKR52EY~Wdi25XI1}YxpXV`Ck=|M}vGtTVSTWX*lg3O_4Zp#pJ#H1oI&YtmWo^1!d1($gFA5gBjgca7$U9vsQK0kkV z_dbctqG~rIeMG|CV}xrJvy+OHL%w-{&lk^Js9PWx)hTq3_}7@?VGM>w`)AAA|S+9&srF-Dn(uw?S@pR^mOx)a@mpH(l?&ka)Gd@6d%`QfV)*e zneaV!y&3pMTHEbSmcNU>x?2ZI0_iX!=9++W|F#Gz>(#1ytXy$xLgdhI*_84NBKHsX zi-hfpuLO(CyLwV;(r-43@`Tu?P6*s^IfVNnPKS**5|{b(y*~^MuL^&1-Pn4#p|Bfv zTlF;l*^L++x_aEYku2hADBoB_+!C<@Hq*}f*Y0+$SZhcTD1nOAye3re??(I>qd45O z^j4Dfe|FP=Qx9ySacJ@XUa~UIFl8gG)Q2FUxj?P?JG_-3EDm|zFsjFr4@xmZp4BL%*^5??iLP#^a7bvDDYvOwna6R-|oJ=cnqP(spP~=#u zCNi@W44{#Nq2!qDiuHxR{7QL7O9ZAj*4lP&`9Kt#VcyvkO1FpkHT16Whl;@u*DESO z`JCgYe00sZoVL#@f7zk`Q8qs>WgH8Xm?YbHp-wL4!ynVY|?_wfgwXCEvZB|?Cr+&crTJWskq!@iDw159Lh=Rz9WKsA3Y7;UvdUW2e2}Au>5wG$r5BgB*Bk5_h+Bo64VXW%s#5mfa`vuf7naH zkhX6WVPUo5I!K1}@*iEwZIL=C>YQO<3AlFxdf^fJKLqMxgFIvR5Fm{)j>GnNd#D=A;CrQi#3B-!lA}fO671>M4OS!Af45KNTilanFYWVu8 zN&EhwpJ%OvG-Xk-SEW2o747`M=_{@f9=>CP1Zxaf`VY5#&W0&$;gW7#CK=^1HGW1U zb2?WzZ&;xJho|cfr1E|H86jK99#LlY-egsFi0qN8tMkL;PfWgJDw-VRR4 zieqo@-M4=4KmAv#=Xvh?x<0cE8$QiIk}mFFJB`R@`*)rZ{yoo3_Aq(PYARoyCMS~; zv?q)nv;Tqty8g~4NJjMguhVBoxYe`UEKZgvl06{(eu)=%X0|meHICCJc;X7 zE!^13`%;cvEJwr^4OMCSvXE=OY(mW+l=WA1-_HdhgT$~P>L+S}E3U*CI7JuUAlRrLrL5Dl`ygk9OP!2U)!3* z#*c|T$Ih{0ju;!W=iP_H+}n~nAK|KV^>tT7r1syd@3v4D#^lKfvbbtJL{9l`{Vb-y zUn|W^tT&pvYRWcm8>7_id&Bg&IH|7*`n)_qC<%~R$(6gN=Nu#h?L{0+OFASZnM^nu z>*FKu-_TWRG)T7lE%8~vP|@K|V~5dBD|)3J5!UFKnz9P2vjfzGvRV7&Hg~E$Kl^)D0=}(nu!S0wTZ+<|F2@PWw_JeRP?|Jg~l|Q6z z!ywpI+{R=v?wmyHI*1tz49mXXh(7%&dLFa*8}X`~z1dc0K4XQP7lzK;0M1~2=m8ja zv zRAOJZQZ1sZ{4>|UxCGUVw{CPb;p1^QWTz9;)%ffu6WPOP`+)t&OMUj*|b!O54*#bES?)+hA=M+!fT`>!6x1;+w&^AdOK-m1`haG~?>-9SN&;)45g z=Dqcgwz-6WWGp{_@ToD^YHir&UB<^d%Xo`US*BAD1{v`& zF=J*x1(DnjG-?-p2aK}D+_;q&Rg$E)HAwp6B4*aIU>3v{G0{tD0pQ+5t~6D$>{xS_ z^e;xI6nxc1$Y{}TIQDxQO_~16*)OkXDjK0f)z&Vxh=g2erl zb9Vu?R8R4(!b%gF(`hjexiMdivy4!1PNeF{1RpoEE4X~65-@pOEc_)^z!YTiMQ~bjp3&tzirkMUa=`SkJ@oPHLzb$J(hKR&SCb5>wu90D_uMW8U$>bU|H3Y z$=J!Ww;fhn-k#CB4-mblf1b+9N#Nh@hKCZp{(kQs&voF4_YEc&URci}CUNI2Ek2dT zH}|WE?JLX%SQlXk6k{r~J@S;uVryU0Gy>bQBk&Nv(^cQ0BD0YfZ@H6f?_*f8gzYUZ zw+Bq2(&~@3Lb}(f5TdY_XXfVD=Ydw7Ky41ZD}w8+u^tHD811(aB;D~JnJC(PvZtk5 zvytO6(q5al5k?|a+v9fneof$2&9_Y7WC(S>wc^r=-t|SR$^$PVtnfgU45xW=>^QPqfs|G_aOdHt z7asWvVn&mYMTplath;wn=Ip4%$vm2(a=Y!u4fwRK_W+(>;ahg`TP2zR5=pWZn;eE{ zcVFL$9kMswhXFA=1y)|B_>u!-A9v8LAnm?IVE>z(f3Ws8y=!e*_i+6!Bc*4t+g*X@ z)IQZX@hlw7@#*lJrL+WXS`8O!W((&{ViM}na!EOokDxGCpc45C{tQFaJ$f{KhjC|B z(*rb-M7maCexZ&9>xl%Jy`<7JjGvs$5IF1Td)79;jhMOXSZxssOp@h|&wg*#&2ru@ zAf--zWFh2chnL6i<3xV;bEc|}iZDKeI%x~t4!N=F{Wu-E4of&6qGdnIK+Y^>FnzAq zq|2iw|Aytk)(;Lz))H|A{EJ++Oaec#Jg+ZLe%jGegIJIjm|mEsZhdTpweBv4>YMbZ zLL51p#C-qGH~4?&Ti^TlqPRUl#iiDlvmKVFNhg-Pv>aB55ClV)_9k0}4D9lJtSGJF z-aPD8?9J`3J5X$#VZ4>VFkVkq_f|qX=4>It$U)gz03&Q%fyT^c88dLLhC@>N9xBGFKBK>~2PucsbtxVS|i z8d_IFf6@2tLVA6#Oy|GbC*~97_4DPO?zLpU*a}*Y^7xpkVwMY_KV{7veprFPIWqjUuWY;1oj}<3IKBSGe z_&Kwep4&m-g>8QhQFEXzB-00sNYMLZw_wMnZ@vHlSGSiuX0e#=#eR)ZXP{#)w{C01 zf8v2@f{Va%pf?z~XCK0fc45)`yks@cwEVolO_VUyjSpZQ7BFS@@9_sT(_+nN!v&C_ z_y5sCyPW^lM}vnh`IswU7(PM^b2=mL`r;<}1#9V($`eg^eq^H^UD1*q)r!wYptZcU zd=h-?9$STJKvjUOGkl;sW~` zx;^>cj%C#2Q#*f7cpVEPwA|1Yc*9(5~r^~qX9Ygj#J*ZLbt6ctLJ7)R| zW(%9IwfKZ&p1HJ-dK=igiXN-HxhqfFCYVnR$|Wse*nbzE%l3o+9%;4qqQVMJMCeGG zY0odGYufHFTAAjL;H_*5HD-_PKDrYy^md!9UURtWdtebPH~y8to6UqV#F{|n3#_5CCH63G5BrS zoYH%G{906v)G3+oA=-YGoGO#tRD}g!cy^x9_Hs*3}XYX z?ezOfgqVvt-J1%=Z5F0+qoZD;H!Wv3-)$vOP6B=lQ_4|SeN;Ri552WKPKA4; zlS1{8S|zLOFIagkpvFCi1zz?vqg+{PQ)+`s+&)(Re%8q(^4qx%TxCzn;#|pe*lP^? zUqf0iOcE9navt+AF*1SganQLs93=Wriyn$jLcpY;gr8HY710l-3&^XBa(wc4V6sr( z7N@Y6q#hl_C->g4OHow5a%a-(jtpOcuDtiHhRZ8J#O0Fe)>!<#8>cVsD$GVxX0@@0 zxNyCl2@=6-C$O_zHGiXj#N|0KrDQwg?)q(h>N#Ol8G}!mui~(;N4pxzJ*N~VQeasB z^Ahf~UTTR9`V#q&W?YL$&C?2jQMk&j;sYbFb4Cfcc+m82C)^|lM49guIz8;y=yEp0 zWed(PScn!UOcUL7h(Yc=cz!pJR(kl9h|K;hD`9``dNe+ukdhBT2NE)ukP|7+;S`q{ z9(ld10WhrI)RIf2u~OlyBa`phBV!q+JXb^vT{BGe7cQ18>|2W^zX?cpf0FiVJUsCE z73BYgny4^lp$u}k-Y{%4PBq@} zAI_~Z(%5GZmF6Ghy{0p~DM@R@tiZ&%_(Zr8 zkRM2M5i=?U=nA~ z&OK{7aU`2+rRHPESw3XQ8xfj@(=kdG_JrGs^myTD+>XCZa&3xke)9mU{f0Xvc+C0S zF<}xvk1xDZX)Fp6a43ENlvDMRkj@7uDo@UW-9oD7hx>b?&3P{`XL|LPc`VlgR5d_DMq;HsQeWe!Pvff*oOw)paA_KK; zi;tf($`ok7tRh2@rI4rA{_vcm%Arx4ZS1NO2>V+st-9Vd-H_m zzUh0t4}2_gz|Z<05Tjs$ko=E^!|#1S7!T2;(U-ODP9r8%MME8^UU%ORQTW|S(*@cz zc`$lG@s{j#9V#LbeljfHG6tdSH-&LFmt^Pd?IB^k0xqB2*vgHcl&8qwLJOfFM0>RK z%%gL|;pTGV^oXHgLs15+jS7jt?~!CB>%oW*3fz_Jqxm8n%!!ie37WbkagD+VS+&*A zOhqr}xe+hk$iAgP|wD;q6xC^yq&n$1n%VSLi)$tEIr<-A4Rx!4) z>5(%(oom-wKwRyeYB((y=+=ONE7*rd^Ugp|MdTQCA)1nj;seSpzwJ@-cW@P4;b+52<|Ee>@S z&|vLLP%Hj)1cM6Cu_JGMp$j)*p$O0EanO)9Yk?qLUu5QmKL0BE$C{mhD)&CeKB-CH z6GPv$H%}bCva;&IZtRgfbQ5|}0M6uJvU4{ZTMecu7dEB(f-)T?& z@d|GQ(S&1V;iwGFKww0M*_vqwUFAk$G~y1mn@$l1>{cH=bxhv!PUGf|dplK08=X%5 zpxG?L5EE@{3Tke+KvU|WX}JHi0F5+Y5Mj0$1d}=C}k#T zJsJyr$f&rDH~F-nw@&@z>*X4%Ce#8@PhhyZO+BA!P2UvOT&;R(uKW#ku*e_P%x(7l zodYE#8YDfvobi?c3zw_WTm%5|T3#Y^HladrQldgaMXzVuw3CpxtIuJGl%nYLNBWr- zJ>zOR%8TcF^@cBaKKiUt+;h*oK8bbcsC%h9{N8w4o<$61s$CRw^4(EpBOW9I@l^iy z{)JzNO8ql<6uBAI9J;k0ly$6Kt^0~!Z~FQxZZmN*ZNKg@6{_24lu%Fe`=-ZfZmXaG zsRuDnx?xdmq8>QI^nlO-eY2QfisiMKC{_enJnySZzOLiWt?{EKa%>4b!iXhlHUJ5& zvS+42uX?5x?avvmb!G<=r%rfiaE-YPi(*zSC`2xVL7k@CW|4|eQox|f+eJ_XH!{Nu zTXSHoD^fMnE|BR!#-_WmdQX0q(K52M8=KEkbNVO&Iz7xn5e3_8nihK9pwa!$cOCbH zmiFI3ztQx75TK%cph9DPM?W*r^wYtSzee|r%%?pZM#&4X4mXb8q9)MvKkwFQxQ0e} z^MAil5?Cdm;6Ftk$gZvQM?sY&B5>&mc?0%niHV5>e-_>CL|?X%+It38?q^DG&Uv}? zuJHA)x$FJtUQ04@1AQcsU7MypE?07Jb%3m(aO#&V|FBtzM40tjK+-_F#+*GI3Kw-i zKVw@PLD5CO_|3ZWiG7lVl5IOX&yQL{X=?1nlp^~h=e{s|F|SQUQ3^|#GWSHMW>a`= z7BkIw9^mjm6A>T_mdhrQl}*0gb%h?Wj_;zZFCS@qwh#atn<))sLk)Co+>~%n?17H1 zC-F|&2XZrmP)B<9BY)?YC&mNnDeh|?;F{&ZPd>laS;FkJrWnS=r#Nr4-8q5md?3o$ zU&fPZK#tHgWVC-?zm7NDWFbMJ2lz>AohQ(x7I36JM(M zE3`d~wHpdDhBReFL$aocNPL)^dO_og1BXOm9!{8bEG03K=J5|`-ZMzhBxA{7;f*pw z-$x?;!-Fm2U2)eaCp0Cm7i>^$76MAy&R1M{9cT6>zUx4thMR8~_EfDS)ETF?-(2gq zJ>*sXlLu6imYQUoSi`4KN*@}t-rUV1MNq^0d)A#!o7&oCvaA#Wxe$7k=}I3Q3Nlds z^lH_bYE%mcl2`J!*)Fc1v)1#VOEHA7;!I8-0AjuU?YD#j2I=apc_*N6@H_`tvgj~` zUgPcq-KhRuYBu+`B35&L;`-BK-=HTAOe+WZ30dY~-gY0?0Bv34Q4ADuX^P(mGa;ue zvbqsQ1cfo(tEmC53D}`WmRsP=@E`}=dIiwK9wGpB`!mWQdT#cfzHYeeXG3!(U@)r&AvBvMegc1J@qH0&Cw(S*P?&SX{r1q zJQ^1FRCK*2&Dq@s-vFz6`@SuZ*PyKy-IXOCU;TBnkyf?OvLCys_->6Z+f@EC1C)a) zXHZrh{W$of!3XJPFc*Ws*8M0dSLHYi^JPQtS_TI(4?I;yrV-$p3lmyM@P!2PlcCh9kd}i?sQ@ zKDbPqbu~s($%KROe8OaK)TP7AfT%tb#g#6w_3Xv5^jBcbRJE0i5smSR1Pa-JJs;Pf%db{n`_U#;g!2$06OT| zjF}TXJ?$GXM?JTfjKy%Kt~BI7>aut9LpB~*knsX=j@N<@{ytXuKfIX9<@E0`wViJb zo*v7@ZFiJv5c^wX!+Zp%eBCW3GY|)lHFpcA2susqgL1`(TyG&nuOni9C7gKI^od73 ziMwy~?2@el2599qkc^>+c?DS#83J6SCqRkTBgvTTSsHhC^O2DbLfvkXt8uddWtbF9 zg|s0-Gqm2gKItetxnSsXb|(9(IyaOM>w_z&MHpL0W)#!zO!bNFLHr8zRQOiHLb`Za zH9(Yx1YIwG*7(&~y*jc6ljf=RFr=IjJk6|S3xuMr(^bp*+swav#TA8(^At ziXV>g=@3TE_;{2JHlVc}W&oL*zu2dZ#`a|ko{6Gy zubU)OU%OVxOIJjJ=zHD@{x+*Gg92$3i&i~L&Xm=n6sR-;8J6f$BmP~FzXOmc|9>(G zQP1<6w4R*jRZa2Ep-ng!tO=>dtT%zh*cN_KVZ1xTx3JGvv-=Ms#huAJLzj+nN3urG z!mv0DdAdU@UmZ^Iu$D}k6UR_n#flOEXJIy|q<R{l{n-QN`b5?U zN&@6&sgg=C&FogQ-(oUivTQR(z+$Z`Di`Oo%k!)6(z@Y%Va?eQ1r9WpiT4Q;Nd}%Y z#b!oufu9JtvEjEt#M5K|Z__Z6sX82Ph$(C8sgX+tcFkUHj#t6w1T}N&ryt1ui=lCy zSQL)*CP&SWJ+@T=5_zx5*%`3TpVT&vE5SI%d5}1=7UsScI;S*c(2)B?QM40AuIMX|8+m*R?{A-| z|9xXW|9xZbtr0!E zpT|2rY}vbj8e8rzaDZn#z)&qX(M?gGM;fx$3l;pAiq}VlxOX z@1YvLJDHA3)mV-A6RNrom-J3FytLe!RwULEE%mp!_#>)4KDAHwS!y<%ymChA+b%gN zMDtmQ&`{pSUpe+gti1$Egq`OoOTaJ|QC+`F!tW;qgl#Rg(hEMw{Y>xcVtuNPe#(J2aix6a zwu>;gSqgu~ttkx$+IQ)y?~#`?Jl>3pWPYC>O4wc|m$u7!UyTbi;Fn)VEn5t8Y74`1 zX`yZ;@gHCN19D1Ok-JAk8pznFz@MUBvI_7r;(yoO|HMkEU^tDN!e3GA6XOMmU@(gL zfv+%fqeSa*AF4)T&CCu=!4Oe~`-^t1a1GwGwwuR-msnU8ZM1340sYQ+Si~`RZxhIc zNgQeaBu;743iqE7>#jmED8xC=0;sI_fONGXFjgq_&ql>5h0+p8E zlBbBIJpKmr5GZK-bsgq#p$0sg z+7?Xd;WSw%%$u|&{kxI1$zPyiXOkXNK2;q*u7uG@A-2Z_Z0g8}$@!lxK3l$g z6yu0T7C<#Et4TXi^w{`EPAv^Dhq<`$Q@p8Izh1nt&j$-aJ{kzLpz)ce_qS*5v!gI%`t;)e`dG2IzGY8eDhlqzQ|KXu_;$pJAt&II?F^a^VkkU7-Cq;b zClRE5mc%gUY<|T$`gw`9pQz>xIvE?{;ut10xhDwXpj&mDbh`Z? zeRQ9#d>j2{nzjjN7$T{t<%6_@^+m7Uo^qsl`PNqKQ6_QAk0G$2*3USymbq;HDoX3h z58Ei)@ea{#BjPpM&Yhz#$&Q<;6`Z2$_^a6)t2s3 ziB%y^+93L!ln;u-^oR4t0l!%McOeD@V(dkN4>6Cb@vZ zHx`1gBlci2k1|wpye;}Efwq`983GGac%iD~B=9ZxKRKy3FmgPI1`Sc~=BArvGR66= zw}N7{J7`*<`gqy>;{{D;L+2ZaR?F_X^=Mrs?m7!D4Sow2CrYDhmI;WP-dOq;fJ)a_ zOD!1=qKDt$ih2w+$dwy$2H^xbH%3#Ip`ga9EH)2ztTbsm06kG1rM^prxU3++h;3V> zt{kBrSWFiun@T>~+7-2)Of)r_xcJd#ZsZpE**{WyiVm`IlH3&}3RBfC@Gaw8Fqjc- zOb5cQuG?-ESYJrvMDQstOhHZD!D{BwnB>#MD_3e{+EO1V%JKPDO!H_8cboEMAK+#` zJC9Or-))7-^ch{N$#ab(I5fp+TZ zfDivcy(|7+{|OhSBf_52GL?JTJnRl+GvmjA5HNNL2rSw0x)TT*1F+!FPeDVtR6p^iWP{3>q>MNk~+5-!3|HQbO_@gk6S>Zo^?6w7mDlaTrL>%LdP@A}OHzdSw(0)O^Ru9L;Z z!ywgzvf;5i*_Xn);g4@@$9S$c57*90-$px{Io{*}&+HTLmy*c0w~h?M^fc%n9k(m! zQh?y3VAHbGS)U(Gl7o|RLV!^?#yM4+9eDEa(ecT8LuE!$w9!;bYK=fuv5Vs0kq7PX zj2e~zCREu_3=-K=?Fbd(WHDZB7K~sSOubcqcE)U>z1f_`ySaSt1(&in6qlZv`TVhs z>C4K}WlNr53Zm;-QuHSJ!}H%>Mqe^p^SU4up;z*eY3odoZ5G;xxD{RWAm2gtRs}Ab za-y@lShmYIk9_MJ1|zYbnv}72WG=(!Y5IIsA5|z?1M}p1mZ*kf60s4d`omHTczK(5 z?IknS6*N7J&-$mc@Gc3e)OAsgvckHWONgU${>5$7xmVjE|mn&k;XvCT}~r z$1VPQVi))u_azv%+PCuLLo?4DJ&aZUNFU`vA*q}w?H{Ra7vM)8?Y5_FSbvxI@*^dY zL<$&ewm3JA->`xKb$GuV!EP~~mfOQ!BKX>%((#-6`F`#%Br? z)?!`1qHM%EZzn9*t9Byn!9ZnCVpH0*5(~Ft6WcTs3x*i*n0+b5zSD^rfWend0?cE> zbZB~5dOlFIetF0dB4>4#g5ULOu9zTGMKBIjO^)R09&6sNW<+b`XAD4kb)#8iUqx0j z7RxBxdl80Go*%T8(J)xpBA!X2$%#H!dZc9ph>U^V4Z7K5*Iqg&Sl=}?B?+XCl%DU; zO@4nPff{>O4pzkG?7#wd8js>I9`MQz|Du|^G#SQ{*4S6=92$WY9;!RMY^^$o{=>|l z=a9Pyy#U8LkZ8S;uGOq=w27YlQEi1+mckCvKpyE?-nKpZ~9~W@J;h%uOwT=Z%^4r)b3vX1_W8FqS^D=2ib$*{?Q+ zKe!Scn(lD{XXx;+`f)%VnqZBd8SyzPkS!*+S*N>>J?*S3{WzX}P*17JdyFT@D??=n zgiE4UxR^^TN_y)QG0x~Rt$ot=`DqE6u`Dt0zR!r&yAb{gZPG#dvZpoGh|OJRbQXw2 z;r!#*7g7KC^|yB;UG4wzGh#erUgu7Vm3QRlO|7R069+H-Pj+;3#QA5V4i%;{%C0~U|j_0 z_APrQu9h7ee9USk58pAvPgFY>0S=nC3}kk1K%%klBGmUsgKfI_v9hl1_uA2PTjuqt zK(Hc#ysMR$MC%qhE5-7?i*JwD8%#IGGhV~2LxLYFxYUh)OuHOR<%+uYZJe$-AIWH# zx-ES4AtB4F?>um|9Nn4&fIHScG4~Ky+aF3oK1FewZ**DQOg9}BCpqp4@9RcYhG1+bN8GucszA;qtry z`y*eXGjdj@S2Jp&?`pAdp+sNEo(zXXU^5cR-CAzSk^JH`quyP-n}4+0z<lX&qG;f#yl_2dl(n z3$pU-E4FtnhVv}6U$Yh(TF#MMHFV}PloL_wz395TS``3wZdAYw{!(l?_tgOSMkGo1 zd{`{@RDaYJ+{88D-}7E1g(ni)mkpbcDe9u48w$AQjw%aP+kO=SyUa-3=&h0%3>RvU zc1!Zf0IjDg4Z3_MD8M?pDHn(|E-r;36Z(=>$3exVfU;is$Z z;?j4!{%6j`H_U-*B9wgFERx=Tk`mO9Mq5No-@dkNb{qk=_=`ZHMPPaVClLEK zSgC5G`^O3;euH?#s$t%*2h8j%t7mSIH)^{~jS!2F9AKKtd zpgmCwMqc09A28b{WOKs4{b-o*HYV>36U_RWHtotjcZJ31HZfr&C7Jp9^o!q%C^lBL zCSvBUxP8X}a1nr^{>BU-yA2n@t2EWL!1k?6Zvw!~6K>PfB!2|&seaieBr;djLlg!& z+#FKm^v1Sn_7g{9B^TWgTcak&Js_ZdXi3ZkHCw>pYF z{5I~y9VQBko_!w{CKIj-Ba@<-HkbVIo4d>f6HqIsYIsreGC0?GOayNTZrWYU&PIXQ zxfm&%4q8eZMzusj!8459ch5v^Q0@Bd#EcMRxln5yNAJ4e05@7f@>)JSMP>h~2ZQ0n zML;rY3jtK4SDNgP9zC0h9_AySc9(A#Kemo_xEa)irB1%h;6GXk?{0kdpWUy6=zkzg zJFLh2{W$-A?C%Ht!xsJtO6Tn;zt_HN^z$h}LFn~pxC3T;1~&c#!(wR|C|PExQce}E z(e2mQx5@OXlMD|;Kcc2I>FboHcuLuEFkT7`A&sX zQY)j4uK?AEKsq0kqae*+LlccOJA9Y(1+KmFr{6ll2Vi0_F-p+aTOU)Qs5?VpSw_ZT zSqU{39Hfp7{+7_1Lvi#;gCV)UHB_Ed1}+^LXv=0av)JdN=&bE6?|tN5m8DFSlcF^(OL||17|> zZT>~5ilurhboIxLF)vk&7)ll&8ro0DCW(bRo`pVwDQJw@s~dohHI6EKj*V_pi|)Z$ zB(pr1UyvU5v@Lib)Gsd*)ayV?j^9| zWCtwSv>dWf4`1Hko$vZeMzLoPR8_cg~wHF zyJ3&Iu!R?kxltZKpSDo(L#H}Uesc@eN}?XL_=+wdF@;$jNdg+FD0LMQunG>%BqA?CTI(b0@VdaNWweSf}Rs6`_56oy4!9Kw3r~wb*~Vuk8bf-8k+2 zSjod3+S`jxX(?u;PM6KrQiP6+17!>_BPJnCB2n4SMf$g$&mp$x5SQofnhkH%=PWQW z*dna^e!^4#?qmNZ1pz-Ez{=6r8eJR1cRO&4EKMJw*4fjE=L@3_aYnPyjfEWM?JTzysTHb>k{c{GZHA` z@$<0-1%D-y%%tx0YP>M*v^TQy;8)BXjxnsWKn%<^5k|0tWEUzKk!7k5CX00I%g@kX z+;^LJ^EOo}r#6A1r?dp#fQH>o9s5jQe{ZSYP+GJN?0GCx!_y)9vVUd%pmHOjKg&J(zP7q~hIje$ht@pmSnN_uhrr@cKn;mdn3vxV_XP4Q}E23_30^Morc_ zD)mp3cy0>|jS5tUT7DCtXG+p-I~fzH&gfJ*@L8pjsWacJ<`gCTebzG zTX*|Qu0Di#%T9=YNk}hnAA=MPP4;KpHb9B$!u?q5xEHE8(r-IvdWdK!zd;R@Xq`cT z#;sJz>SGOEtIeXlnEfQVZ|M^re7h-LhI%fE zVcDuvhS~yBxH||H-{*-Of9LU5;(y@BQ#DqX6bIuw1Re4x4cF8I*DtegBp5Kq25Mvd zQxDz!SX1#6UdXx-EOk1C!d1+cB(`%%mLQWhm~1w6;n@cW+xDLl2~+6`-6*G5E7y9t zs0XxWqV8Bw&Z-R!N=#Qc7SK@wK0kPk)m#3jBD!ur{5=cqnqbtCHW z{M^*-lWD-@Eo^Fx{`;gDaLcWpTOt*0Nd@yd>P2Z^mhbXG;CZy<$&&R4zh$__;U-KL zvt`wi;B;boJqE;qS!qT1{u0slUc;xfDsTw!<@ap1hwnK8RktJq72xmEz)mzV2dFuJ z2iVl>p3fq>iX(D}Q~TG#JeTKp;)l;|`v>lUJQLXo7f}le(Ao+YQ|77wK-HJ3#;w*m zDWu`G7eF&_;QA8rtcn#_IIJ2i&}4=iLb6o}BHxdFExWyxfUBd$1%D%Wj-+V0*N{|q z@Aa-)NtQHZ^80}IMY7Y>bZ-wgQxf!RC{&b*0{$Ohq8&A0xK_v0)J?q$^izY!(KpHx zeZrXpuDL=<7}XYYKy$SVEL1~QH3k&dqOK(W?ZyB9=!#{)Ji*T%?s&@G-Qg!NagF4q zeZpMguOT=eVh;jd;inmSjM6E$jP6`|vOT(Oh`l1mOXYyk$iXOCDj3!%O6W=<*C$om zdMGgc-H@u|=2J*;AxR=8T1YT!fcB73>}O`TyF@w#AChpQx+5(`6mj^*$2D~r)*o+< zaoG=Nx^Bjh=lLn3>v zqq_(!+UT#L5V)zw>>-6Olk4)ZvI<5&-@RU;%^)lgV^_{>uRrZYJl);Jqa2t*&KF4*)uqq5dcn_^{VN zc!BDh6fZUVH>2dBm@suxUxyB0y+$6FbE$JK{6vl&scBO_S&uz}It%{XOC>9UB@=~) zzn%JP5#tHASLR$L4h(VEMbx@QO5|j#sW^`*r=UiHAMiGn(RmK0=a1vLx4?y59nt?4 zKx%0HXti(X4O~1_>aXrwwmO#l9sGC%|M8`lgm=SLayGhPKqct^dQRpBuTh*(p*G_8 z&87F|y^N@oET-3#@v|Z2TXI3>nwfxtzhnt`EQxkEfU`Tlq5D+oeJWlB4%_e@J&%;_ z7neyId?!&^R$Di1)E>#2GlzCv7E-_u`ksHUf7>8z<&k06Yo7?O$ZQ-9EvA(nu%#>s z;EAg*YPrW$C&^?B84Q@$*uIFx-|HMw7WJL&#S{j|VmKpZb>BkG1_eMCPEVD6coL5s zJHLRLYySP4#l00Tr_%uIOXVp-?p6IrV+BgR)H%PqP1$J70Id|Ij@BjuDKD)wUrgj7AM8^}r9r>UKi$Opz0xyxQ(&J#E`RX7dpik?jZJkuz~xF@cp zR~I;Z9(ym4!JlC;(k9rdxs`exP|LUsoZA~{IRd-Y&Cmcv`&sWqqtD9J?<>qSGnd(&^Nu`Pb02Rt4}P1ztqfEP$pYbVrzb1Sa2T7*PSVVa>ZhOI&o zmRe6U^wFcYWb4J{x*q(QeDZ~`nSU87r3kceSX*qxS~p}?)ler|{AJxB_y0~Kd}Q&W z=oL6KX9(trYXgoe9-!04Vk>LEyZp>fiZ57Z!)klT#Lkzds!8j|giS3iOc>(|>ha_j z3x);S>Y3sxgF&bPQHmg$UO+iE*@IgN*2zKQ&WY$1`*hSijbVpnJWR(6V6>rz8fwV` zK@hCIKh2f%^dw@8-3B*!-(8)Ks^j+}$Y7`_RV3GWWP?LV2ty}dfc&HP*&Y-3l;( z!BUgVzI6s*gF_6D+;6nFDu$f7kNv9mX+#q3NT&>uH<*};B%a#G$_m6i;uIar%Z?%) zb!7Lr@fe&TvUpYOt2Rn zE7IuuH*Fp!Q@Y!?nUf;=*)s1u@v@DkJTAPa2eJhnTHc|&7mvnPP0uQUa-1J<>U|<| zKcwn67QjX_KQSTdE$aF2)O`P+_ibgG-H{RHjti6rW^(eHK#Ns@NlBdfz|8e_!Obe` z^raqN1Zy)f;rG3eqE`{mwApu4BAvzIoqLt$Ka;3`5Ji*1oN_-~v7d!Au+lCDJ&m;- zMM4PjdeE{ZD^u`wgdYoH*7@0F5N=TMdQw0^zyR$qcVHv&iU?1ylOK=3_3%1X^KVer z>@Ni5;9UaRDccl{94&FXjBDDxV@~KWg zm6XJ0Ue-CnDF1YE5?SKaK z>&x2{Me}IqXWQ@W&hERD*koVS$FHG0KqHIX>He=}>(-9T&koWHJlcti48j`&eao-3DjMz#0isUHUorfd_cR%J+G63YS`2$X0g z5N_tmdnkY-o?TC1P>B_f4g(Db%pl&KBjvpAr#b|?n0-pXbGI+zpzyvvVHbO`$?sBi zOOfAO5S$}7oKo;R`JbYTfF@_fo`Tlo2Qnq&00mq?c?5SG<++QLdtQT? zfFTPIJNcrL$OQ-3N%0R|W;tMC=W@NzgcWX?E2%2PG4}qAqOO*%!gRN7bV)Z9EMsBr z2Qfoowx;vK&A$iQF=5-`PQe?T-n;%s#bexOFh;h2cQV<(JNW@P1+d)FOXhNF>4UzR z)qr=wfIB>s2MtK-Z{JqMH6p)UWBB2&E|J&Zf0sg-kyZ>Xr0`VdqCk5iZD=}gz1ont z^DB(`Cj%wpM}6242LJ)e%e!@xFeFGwndPFt1waD!=e39#h@nwGAZYl;cwBmqug!_^ zL^b4L>X@bl+8vG32v$7k9K{eb` zt<*vsO-+@$Wue-hx6IqI@@@E>SPj({g84OsJ|u+UBvDQnN-9@Qt+s2$!@ zndIj3Kyazcu4StZhU$Zg<#=qdtf@`Nd?lXZR7cob` z9$DA+xw+ltv>+0TKewibxfQdK<5z)kqRcP&M zV>7&01<|H&wYGD?kD!HWW3$aKut7B+)~ z)5X{Gw`k?t{95#>3loreI=4BE<{dC1t|V+w)T9A5ItT>fq(AFtYtq4hrM`f3$SZKa zGU@vUOozZQKunSjf8)7z=PfW&rGd!O$~rjd@l#5kSXF}`UIzW79VP#kBh9~e1?BU* z8ifG?5VPk2RpC!D2ssR8pZ~a#Dl$Z`qqp(9W3#>YQCj1j5^3TNL+`{UNenj{Ca>g| z2}XLG9PuAPRkuheJLurMn5r^8w{yD)InwBvZE;yEY|Vhi;HA>E=)(AkqTTof0A-aOmz5=?*2Ok?w8~K|qi$38g#Ev-JOa zKfGf&{OE9;z4uyo%y~_cvRN4AEFNbCEeGy9uXSMd1^%j3K^t+&tc!1=-CVn)PW#p7 zjt2$X<`r~_d&N^yHQDoWpB#$J+Ms7;twQ$)vh^h{wSpuv^9JS40QhmqbM7nEQ%4c1VH_Y(>LsmYV>+B?Yy$cTe}7gB{5quC)NJuS6Rh2eRIx1 zdcQUY*hgppmAKwQ3?Bx+1oOrY8QVF7dF`V7tnrrN&pmH8_s??47oef2%vf^ox&K%g zSW5>C2_G(8YokvXA&)n<$T;5tqBU#)cvZ~|3#B@Pm!8p8|HyGr_ZYQRG#-6GXZ>>m zj7v{=%u|Cuhj{SFu{10=`sl!&%Qp79^ut-(SOFY@$V0G+>=%5XLJWw^6=x>Qu-)*uc{6?;AKR}WP7z+BH8k)re zuZJ&_Rzsj-UHE4J{Q3p?if>51zRnypf%kIB>q(_Mbh0bT<&_-^WiJU)zdrl{AT~M} z%&XUHxN-3q5N&bZ9^?x?SF@384!j-U&r13{ID#S{(hHd!}XqQ`e0wD@P?s7?ep$%Nz-J@vBW zf$MbxVCb^M&ey>rpe8pi>1M_1FSPbEF(r6y-_5ApSLr>8rujv)vUzhVZZad$;n}V0 zSu)u8K%H|gyIQ_DYvQdpd6nXEZQP{^-gq$4KWz8yRilSAOH`M7YZ{C3zoLO|EhDefuTkXm zwOM@{=j+!_bbm+5gK_`86Nw=b%9wotpJhBb#%{iR5Z|3X^EG~5m{P2bMX(7rAE z-A$(J zdPA+pU$!TbLex)@dur1eRHRG^gmr6CM$Z-Q1xVa;K;*Q|4)-gc-;bjARwr1Leo#Q(0M{<7Kd{`dYxjDxHzs0Rr$4kge$MY2u0P~>!5=jzv?sB z9S$**zncg4oZ~}%zOA5Ko4XeHvSiB}#%~#CagObl(_cr_l(oVpRlW6^9ee8yV$xt= z1b8Y4l3fE;Fw{24xm&@@o(pp2kcBI*m)(me05ei~NwUQl$P)3!Z1u>H8xeWcUV;cr zv#C$hfY6dXBzK_lo*1m?I@>9dxd<;*vOB zw$>kW~>M%u3AC-BsaWEE&#E#U=_HdM0L@Ia2*D(&Uk88|Te9-E4T1b_QpsN#pn} z>~sfe*fTFr*$Q1Yqb+{ElnieuN#N{-4HQsO$YD5u;g{NUUdNBpINt)I|T)PXGdbg|WcynZIA#&T=QjvP^J! zek?^!>a)^!|5C2+S0#dyMzM7m8*d*bYE=BSF|bIj@5J0GIp0lM0Dn11i}y#$BM86|udrl{ zj>i)mn-zpwR1oR+cV@}_sDb8=#vHktaii^-bU2^vyo*Sthbd zb)d>e0Fx%G}YX}*hV9r^gibXq7-$Y zP1zQhWO0G8W&Qy}K7p58{(%3miji~tBeM)J+LN1qvz&v{tG%!d8_%IV!3|jn!y&2| ztL+OhFI5EHe--)vdkCuP)q40+q4G)*VatmT7plzG@6Z3u2 zUe_T0#bmc)?0IjZ!8gipTi~RmN<-kS7qQ&B5@Fk4!(a`cponL!bc-Rng9XC=fgF;J2(IYhlZC^!V(K7jd z!)HNyqa7KzFRCM4aUq3IgwtPW^)!}F0k^Irn1d;aMp3+cBJ4J+Mv1vW@t3QTa#1%^ zn2GKX1rSsJR-k=^|5nopuw_jiz0s@oR7mUt+qG3Ooj`s7LJBF#D50J2DLUN$Vij4v zt`<6Tao={Rzt7QnDdFuEZpQk}8zLh^1mOKsw&fZYBZ{gqEG#VkGmI(EI5jM0=EWmQ zBF>i619yGh4}UM37;O1I{2-!sMkTX;KUKa@VHoHFaT~0(*Ig1C#3U2QTdS`q4o_gQ>P@7Ky^^5}aR(o6*&MYE^ebZXLUJbnf%ha%v4u3X?qxv3a49rNq1~z}c}CI%<5q zV^NrI6udC*%C=#}CdY4iPx056m|uqe^e_1y2)nX6uFUQDaX`MGjjW(qfj|_(!2G~d ztM$o2>l>3N<}OhanOyOL+rcg23wApX+BWw=`BUqwCi*oM(21zYqWoLEpKVb}@qUzb zH_VN$zXz(0hq{(TVu3Sj4xw<7BpPUFgP1Ue7XXH1g|F@AxiU(J-l;e|Up{M<*|5^EF-V58 zV$Exg&|inh5Nce&_)OcgHYQgVA0!W9mTIvlzqrpieqQ*pRBP`oGl_!{$Ce7M zq9oc=eCYn1g5o*e?Ag*q3TtJKL+q9`>j+KjiOla*wG4RAWW)CfO6siLzZg>84KSZD z*0x}Cv;27C z%;Eh;>bvjltySKWJw*&s#<`9UdzP=iC^@GFk6GbCy7?uA9q%P81dX)T3FaIhm^BME zkhr6XDGf9#1;8MHmGP>!{9G4_8vwfLf41I|a>Z~&px@G? zlS>&eCBFbqZ-t-c-@~M?R7UuoQ}^q7zEfkt1*r}j&W~XlxSnExAD4e?;WYTUJ-P_1 zBPflsx?VHlQ7laLH4SQ1c^Ms?z=}{~~ZZVTFt$BC=6Eyjgp~7oT zG>X$1ssw$SVJ^B}RI14=urDPEH*njSJ-px2@;t+lHU$rjkxRbM!Q@-Z4PofWRce`H z{kp(fvuPhbjJ(V_{T$h&&g{sTOZOTLs2dqFXlorUpPXjAs;+*`G`bkq%P(0I4Kix0 zpM`AfWRFf9#}2=x*s;tfo-a+@p7+!o~WKWty>WYw*q5jpw4DdFpl z8xc`YIjbPH-Eys^$pr+gf`64gp(L4OHXpM2t`J%SEWh$1oC8L0q1 z&BB-A498vC%QBY=QqNw#?tTl?ltx4h*@;`@oqEnOH8jfVzvjc2-AZ;lOse>z(R7~% zWlNNWCLVH>(e)X*3Zut({z~jEFNnFr$kPOtyZ{c$sQngcPrEpkH^hZS`Y7N#%UF`= z*!@NgxFDp=-!-8d2Ds`47z6X;#auqeD+oGjNnuGl5rQ=Q-(MGvSWpS>XuVnTBc9c@ zz830=U{VI>;_N7-8NV1nID@wWN(tsUJH}^_K5J!zo0~1(j>nPW5p0n0zw%=I&`$r2pR3aI+!b=yvK_#(zKo%#t71M46B!`PU=m2?_+&- zzBXq_X%}_-GBehE(saG!V>x;xy8)bFNg;h)pD0pgKHbVGwEf|ZUenqDGW;!h2kQ9K z7=?VXYZ#to z!Jp@^r_|mbQuWw3f5>2{Lc2y>M-1D^V$Q>`C8n4Nd`raahiWcOtu~Hu%(I4$ep}4@ zOw%(b&|p28D*Qy5yhe9p(qP(qG1r0G=$5ntXAclr^0JsML_4j2%PDjm`|sQ@+zMf@ zOuEW=D%Xgq9Bv8;;YbXXO(cTb!^}yKd(d~Ov#U{(|2rGLwCAfB-lSghorQ-*Nn{tU zh)UX~%N-W(mLsQ0-Mep2KbtDHVV+J}BHRUmT}U z%BQ5Az6Gp$pT*P$UO%;WBt?oLMteQhnD{r>x(sOq9L0g^NqXSy%wnd(3|bY)e?0fp zu_$3d8Cj9QtluI9GM!=Tvs`(M!_5(gC_642j27Vflt!9eagwBLv_H>^2q96os*L1TMB$@ zO7u1WF=PaE=-SJI*;ej~EgwXT>9<$nsYA9sdhheo>wb>7DmxZI7*gyE&EIVBm0t;LW{{`v z7E8`OHRT6HxyUZ-W5=$HSMy-daQeQ}FprIt9|QM7Un0&7K5d#L+$x z)5gy2UY$xj8HA$t3ATbn347U#0*w1a@ur&uZi0biN6*emeHCz$8@tFWzbO#78|bn& zabAr3%>Af6Qi6cgb*fBw3jDwO`XkWg9sHKMj0Oj|Qo8gn21^%>F|lNGV5~3x9r>Ny z(0?by-SM8HgerCu`xvx3XxSgGR@|iI{siiHc6=Rqu4J5**8-lym^C& zHb+6gSZz?r-ue4=$URocJ8qVYN*Tn_I#RXnS*crL5Q)k(9Z$epTXZ^UzUi2^B(0J@Br?9V^(?;R$4))7ODOW5m9J4U zq<3g#7x(FMEISzk(A2Wxk-*_*T8GhW)oa@$`8xE)gO-rC{?s?FoDB2659g;i?TL#f zm(rKx{vQjXfs9S4hcQcUq2(q~P^NcB-rDQ7_tQxJr;M-qi~Y|$)6(C5Xjo_l8zpl< z$c`#N5ejxfW`5BN9?Wv&(lbS384-N?fzR?=sW$C~PvTFN!8_Kmo6z0*M%-&+*JQsW z^RfmoOHyxyTtf=R_{>j2_cr&1aF)Eib$Y)!%~?}+&Wkr!;B0Zy_0o)3fFnZqkkiO;(n{-D-n|!*M=1U5N6kT{t6_GN~827L6Lc;t}U&h z&1akwetY}$gxD~s zKD|(JC~#gSH<=Ib>whQ6x$BvCIl!Z8p2aM%wOER=S2Jq^D+;e1U>ZAdED|&P^?NsS z!S9oePtF*Bhe#~2mL9}^;WsCa- zl`**4X15(Z{qI%!TUE@QvP{eEIj_qKq?rBs>@VYK%9K)EJcfB}ceCp=9$#`{96NqK zb=_d>1#f@uiI45gx++Z_5y}KdnnI6(w?%hza~C{(QRQYSItTXbwz4& zk!XF`?TnDm+=Xore=)>9MoAJ54zm*IAg@?feuDwSvC;6qkyBo|U@q%50`k_kM(9iHtv67HUPT7+fzH-5Ydecp$^FB?jo_$0xI zFD&dp>C=()mozGd5UAj!H5u0#RlED@1>S|qZ&(6xl^#BBQh`XSa*hbRt#jW__vE|d zN4&|m5s~PHwqXN?lnng$;5c7x+p1cZ#!y!op^`c@9M}&h=Q^XKXRS-J>50mX89Q4R z)gzZ!Zj_;pCx{{A*P!y#A=8=7u3o*%MCOJUj`!j{XqxgP#uG9YmpQS8^CyDl!0%6{ z=^H`z+}EIXnGikkqkbaj3UG=G9g9chYUPmeYteQa&W_FXp->}X$Lrg(sUGahb82v1|hrKe{dDKD(}ENVAVs;o1h zC$aPH&%!moIVnAQlx*MX%wwoG@S@I^%J!XD%5#Q}SZ2CL9txC-sfZNZqga<|ZrT-xA>1Xkl^J(}RD76TL%if&SzrHn&Q6__ z#!G4u&$ZB%oVhPqA{dJQn#BJK(;TVqk}u==^-2yzBGbp622ReXR=0${dR?coO5QQ; zspXjJ=e1ycK(g)g>rcd23+A}o7`dM*4?4J`4YJQ$`CE>+!xbb*7) zG!P~>*hgJuy8V#)c-i~4$Ugg5ZVUSxeD0?VxNM1m>EZcb5SjgOr^rxTrJ*!TNL(Rr ze-W(jUW4K&U|3Dl^^C5v#|eMXwC1^!Ve}x+twkTfe0ha@f9leg-?#o6C92uP^VpMN z)ANBpVIu`tQvQ2A(H))6SCUDx49>hAI79QC$xS`a^HXDnKaB5SIHcGp;RB^0ILj6~ z3`E`k`~U|SZwmPB1lCGn1MxnTJ{2A=w_B0&9I?9Akz|vl;=h-d=6sKaCKBPlz+Vp* zO>W}DH;E^5E8}!XVH`r)&1c`LBxYPsk1YzjJ@jhG!5ukh)LIFq=xjS& zomu53SeTes19-7%`5AeYc73ezQz96?Arc|7rRwRc2_53c4qf90RhGV+SSjGaUrjz3+#<&%#h%Z3hHM`JE zC9$J5i?_Vk;OZb7E=Z$B!t^*WwY{d@eR&+TeTzx9A)4XDN(xIz(0vP@^5329_X!WJ zToW+S`1`jRj4Ia`f-21o=X#k8B=LX86@`Aeu)h`6-Zj4)R;eBmIGWDx@oivYxVFu! z`?hD0zLfyo=U{FQN*6?(&`;wq8Lo;B~sOEs;WQHmLz@&VbjL)&iA8{^4tYq+_>sO zWMvVsn#$0=TadN76A$>)63&^#W;PS}{~7OM437yK4jPszq+EB_z4E8~g%sOmnODm& zStOjRW=M>!HoomOTyZc!d`*mK{&e^>yJC*FQ}pQ%VTQ1mx@nExKGV0TSWBrC$FER? zdg~yqtPVr@qs@)r;`udBXB z2U9Rsu%MN7FqVn(WZ$cW{T*Hnsv@q%XR}rLM8x=yEU+~Q%wius zLQ$t-FpX_ointVJ;ex_HJq%MH{>u4z^NJ&-9pjsBEQkL>k`sKiYjhnXA{AqhXBJ8> zD(CY(2<7FlM1J5g2IYoS<_Wb41=rcn-1F1Fbwt`+Q%rfTLSXs0Mv3yB;z0q|r44k$^5rbo232s_DT4kC?sSs1sF(ADyVJlisW6lIq@7$ zuE<}8bF6}7;W!h>Se?@De@aU_B5OW#BRg)UKQFLmmw-p2RP||l;bW3R2bwZpFYN+_kWjJk-D1rv0Nk$CRiuvwbLW-?X+KSM~T5AIa?p}-~eW|It_)eB6 zbEOhw+7~pGetB*PuS`hq00uxCX-^?QjIRunThagKHPZ6@6tUocl;bqEuz9>KEC?y(wRO8qO@Mn z9cH-0y)F1;kx5tDlS^-7TB0NJg%;ol77=Y>lto26RxLZonePkQ-U7{`ZP{y^A~8iK zE)7xvKC$V^J<;MR@p>E?Y0spH?q(E-LYkKCu*Y&^%jwKi)$-*eR&Ub{y*;N|^+1D1 zyp!LlZ)?>G$^4kV=Kx*>Xrb50X;*H3pn1RXI|Y~XidBrxq;VGWX7IuTDVP7b0vPxm zlBX>wuG7cVlsky$w3*13V-OZTp1oMQ>B-)pT(*gw>-H-VJ4wGOD_d;vJ%jAbB>WxV z%^Xtx_ky85B+dX?wkt2=Ddb`j@tR5a>%&dwKq#>x27rj}DD!DQ{?$U>xl2-u)j7JF z`VeQiEkG1p?T^apAR0ML`4E!v@c~gs?w$$nPfNc;#pJnqqlD1~pQ<^_SIb=SWS3y#N3@}_o%ICasqM2PyHLUHbM zgMRXLx$|5l$FIML1sm^Yi?lw3YjcXqhg!)msmz{Ts{~Ddsw7kGv?_zTv(ek23E4}F zs*7Pgsc`V`-cd7#bxZxBS`pcr0U9qcV2-c=HAlP+bbE$-pp>DSoM@|=k>0W$nAK(Z zC3H7LI7tbdlC<^K**7<~$0FZsBtjRmlo$ z;1mM3PJR1U*xHGXE0|bS@}p+r4gd-y{M z>;CBq2?+-201AL?0|`mrBLX;(e1cSrHf+!hidgK9HhJ%;iN0ADC1NK8XL1f~GZ=U- zN(Pd%aemBZf-pmFb38;Md=$v*4v$MWTD!7ck&hK`{?sRK)fhlG5{^#>9YOxpNW#+< z5H{?!Hpj$eZM;!iFI6=!eI2!YtdyB4}QeD%d{llWIZ*Y44MoOJWv2=~tVsI38 ziM+TK#ynnIzTg2V^NB_O5N4LI9{pA@oGMGN-wEh+R1`fH0;s}u0X6n3QAb{Tst=Om zq<2`%x_Beqnh`eAM*PzrcUW6FA9o%N|FVXfUrBOha2cC@-A_{k@X%wa&ii<0TSj`clKs&>GBThC?hC>Aa)sd*WiN_8DprK~N_P>g{li=QR7R~yTi!J`dE>DpP$ zC1N>vImh53LEK}V7%g1KUh66|aq(93=9jWvxhUjLQ=LgTtaErr6MeuZMXT_@rc_8D8plWS6Z19+L)D_aoEQOny@<*G; znlKFc(AdOm(!nZ@M!pS&R|zLP=xDa!mW)H<1`h8NtrA(X-m*Ij~)C2ie}JVSLYM=>E0 zTe|p=)RUnJ*;zyA&3_DiJUG+t^oj2s7uOwK!`f$HRY|ZJx9r|-O>4O~No%^t<3(3v zK@{VD5c2a5`pl=)&%2&+z1t=G<@?0WFj6Kjh$U+C>0OoZmom!M1*Wzz8#Z@{9=HGG z-8M08Hu$+%mCI_%P8=`*8ZJ!>tXbm)NrL|ZeE>K6uW5lSYgr{Jgwx(={3g&__nQk5 zI@tF4sCy_V+y}w;GJpE9nuFswV)aLW1j+FiFsI`aS!&M%jY8xANUI!wd!OQ@5zB#M z9JcoKu(c6e>P(nC^PJeq-<-6j`a0r}+g|)4?inF=%KxfuTF?Jg+nR<-c6bKU(l2$x zj%N1aI^#rt5C61jv z?%{rogtOCgRuOPAgCY?2=}YE-rU(D&DxPigTfwP$69U{^x%tijMx@?+i-5g9*YEt# zq-?#W9-$b)pSyRz>H{NE#_FWT9L3``|GcIxD(s$VXK6oUVYgx*NEOIQws<-o=wlj{*f>2vH+z{cx%h4a`>|)6I(Ph` z-mf5WZDeLEC=rm>1@a)vKCTNIvhsi`w%nAp1hfo4 z2Ie$=cu}Z=Su%FrNsI{`71P65`jlxUbW>h=Tunw6psi5VyFiwEJl_ur?W z-pf%+F6e4%h&8;_PFE=B#fNn1NW98@VXX>I-8amdK>B%EEVIPN?q z8$ejEHpJ#Osm)PWTfy>3QyAUasYt&bw1DQ$&m7RIQk%*6R& zbjE^5*P?f0JNvXsb8%pSL*v+oL1^+L3PZ!|0_aV{OWmu*ZJ*m<-~#N}cm~YZuppbe zi}7H*w&IFPds&6wL7BD251l|l|AgK}ApW$k;SII%=}EcCsbF`Lo#ECGO=x016|t`H zTVcG5Wo3mWpOkv)aPT?D=*H+0$pJi2?vN-hsXQk+_gr();l&(|^6xu)i!myOFcuIH z1!E?%N}(I89RO9iPUUW^W9jr&V9Ypgl^F&(w}N10n|Zm&Q8B&C2Rdl-klb-w(N^x8 z(%l0>Ncr(|3F1eBgjrcj{PUHIQm0JOzKHT~@wBD~`UpE`jCcav zIK=grXvizR-03Y+-J5UvH^ZlXaT)G%89HOCV4G7{*5c#r&_9r$`QD&^NZ0%uKurhb z$F$7+!;p3=2VUVqf9otGv#?t<;kP$ETp)$Eq=oK9LE`~g`(5%4{$Y)jQ^>8?w&$qNfp8`Oqu6OuRp0tF(`+0E~$7;&Z(xR6g?G zABT|3Yb#0&u$92*ByG{nkJYgsH=*|-Lq2>O3Azy#XhKYD!+5ceA!dxm-`F+t`>Tss zh=J)zYxU~V|E`6N|J9Z8D^J1gpd%ObIwuODP$4d_7E8b!PW7x;8tF$f{)G%5GCHH& zS9E;b2(hDuF8hF=d~da-5t04&?*+0i2?r{@`GcytkwV%BLG`G?n7A)Ga zJ}Hr*7I}miVxx-KSvmHz^J;}vF6uH6v$cq5oK|iYOI^B;&OGj_f7_|O7+jg+v1I$? zxi+J(gL?jKIS%@MA)54IdQnz5FNfX}2tF7ffM?-udVlNv##FVJz$Z}#-)|1%>A};H zDFM@8eJ3?IdFTso@s`O;YQ1%a_ zx^?7pSwXJ*we2-DCzJWwy-_0^CAj0@ua-pSkzN)tw*~Fat2L%43jU(BGh)RUK_C_^ zbPq+9dNK{&nE;Rosoj29^BKq48LoQ-3QA5VA6G_x`9x0>`ZKnm@v!NpA2cSo;gaj* zho`QTshV*k5ku>_!%!Td)T>-an(_hSB+MQ-6tl0) z)Md3SAdgw?W5v3{5sC{UfO8?)5vl-7=A3mqvKXdTZ(=M?wS8=qEj^@^eE(1Z^wjE)>DIjjH>rCS7 z#f!9#OohlbjXeab6(aSo>;hRB$0E-@-cck57m@lW)a)B$ZT=udPV(B;oc0h99IPDF z{!x6RN!LnL^k(A+N}Os3yGbmHS0MU8jFMDBAj;C8=#8#2gdi^ND$eGt9Y z#kwk(^jc)AiuZ>B?})nLVC)hekE6I~=>*>>#U#Hu_q<@knqzX)9l<0lB{&bnw24pX zzB|q}*uQr;Jqm`PDMNs<1Y6ak&fZ7jG&AL6S&5k696A!ZJZA?EMQj>F%zU_v(n0>j zV|jcOIlWo;gH$h;M(%8`c%wHljvLOe+ANCLKRSUmHD!E;>y1j_xG%tL1S?z%4V@~{ zM@GYYnm-jip1a%ij8$3@E;gI`u%H|~W0mno-0@frd8=fI(1-A=cyn^#ZZ?!KYCSr> zp5(7aafP^JJn!hkV#EEfY|Z2vCEv`oVJ+%N=EWW1C#@1kwYll+@yjgeU_|@ptUuMz zZSjIu8$?D`oy1I*_sLZ@7oCQ)jQdZmtgN{9%F8^TnM&Gk+V5d_$a7m-UD{YwpzY?T z$vHP}vVx5pU?vaic+Fm-s9&fN6H(iaH5vyVnI?q<(BD10w8o$dK*mOAMNJ4``hgk1djtoXz5wO`L<6*Al$d+`nd3~9uTM5poeG=Ib+KSsH#vNPZ9B$n$#O55QGj%0ov+zNu zg(+a7DCwuq;YLohIlI0JWT^%c`?m-A(0U#=ZB=8~8jGqPY%LZOMF@+vQ;iCVAb^<_ zAh+GX{i00brVUlJ#h7E*kSZ)%tH57EOaDm6C4Foc5sxw)xQU2GfIyQMaK!QS-zGu$ zzfD4-fy|!sHN&5R+SZuQoAacIA4Yt_I&QecRxTvh6~hMt0zifXAC~Fn;`_0HaU>)P z+5hgdb!W1Bn&+q~{xl!h$Q}@FA= zV?FTjd4GBOhGZO_3x|zQkD`YRfU_^G$Xk`18^_nQNX)GaGHu=G!edUF0yL+-n%{kE z*;YD0&pVkk9rBFOXI~T3=I^{aAzcz!2sa+1cXIepJ|D0aABaN!T@!8W@V<_Qys2(E zLX^o_aaNmvfRtZ%-goSp!`M|vkez?@?{w?A;Zxs+P}kIUm;IDAG%1(CID5&mA$o`z zfcJ=I>D5~}EZtJLIKt4*o#ikF~r+%sIU{YoWrA`!!WNVRdZTW99lwn*_FJpa7EGJqH z9BTXbxB#sg$x}&`+CXzZX~X6DgY-m3A~IToitcXWWq%|ZGg@U#2GmU~wDbU>3gdfP zmdKtZ!a!AErHAYavHFik*-n8l(k3!SEcQH9WgJt)f0D~issCgerBcB&oQOYThe%sB zUeOmFUb-N58U4coie>a;MxsB6Ag(E?m{Bq>AjmPG8y*zM(TyDDkDG&6r~(cq zMkZ;`7sj$#|U3I&s?B&XYh${L*enrI$CkjfIvaQXe^``B8}(p-)6 zFG*GXBYIp9d2D&?y7J?4V(%ouO zci}wN&M*TJkxCw#VK1fuPNmlszgrp#i%x$5E%b`_`Z0=q+asXOFen;fX#OascAeQ~ za@m3A<#Yp@C{;O)?`VsA+kO=lZ;W+gM`w2QO9rfRp8QQa7_inzT6si|x`L_zo-x;o z(9KaRwsoZ-jkhMz&WGW0le(>6mDBKc5Zx=Nniy1O;S@!W9zXR|;rE@tis7B7b|G^~ z6@u(6?10Q*@aI4wY{2HzSMP(acbDECF_o=D6jh^9R{kjJk3tke73+DbUjHbL%l6*3 z*8BZv#xTNU8=Xd%d#FsEnOel4jQcC*GFzrU8 zN&*pGPRKgy&=}gWC=Wo6VVfc#_d%3bka27RB3ZdIbv3o?QVBel9?i4*N<{~i2>pbhfB(2%0sdZjki}MH#}ZZY zmYLnR7^3q1alp|}=Kusjjz88Di_4=!!hhn?VV~xQg!JTeNXp698KHbJ9EYIVIi~Ng zs2*_P$r2+r+wQyOzFTCfQ1Epg9a>;Vdv5eJP3!eoz4PTCdkt%haE=vgaH$m9GTZct z|A_Lqc(Pb&$Vkr}Y4meJqDC%;Y(G8V{@6kKaPz|TRYPv|TfN1p{oW=_*4e8WYYOKK zI&_@$l=RU!&mH0w|6iIcYT5(F=COl><@4A3sDHdXW+&mRA&++8O+wR0mE!IXoAuO;ikBWY^78o5-{W>k3(Oj)&(tqg-H`F}gmK^J`$D?jGw1gM-qX(ZYca-CM~p zNYLF&^}c|cvL@H~>lc^7%9?X%x@NeI4-|03`y-g#*W`E1eYnGId_i&c0gqznMi5|f zaT51vD-Jt$w7-}57_VA+ijB}9MZJt2{m!tUc6Bszu^~m-3ZqEsO;5zOMKb3_GKQj3 zY%u0A4dKW5Qr-#8*!QH&T2QJ5@8(MPvZu9BoM3g&1YOZdK1Wse%YOg2`G)KLcf7pz zB`(#&WJVLDlp5?C_eVzoOsyBcrX38;ZIpSlQ5*A(xSFVX;e*^G508TaY&sw z1rWc)pgGG37JW!g1`OlFqez(kz}Hl7jCd`I2%E5B8!_^?q;)NSl+*kWCUaC|PhW@l z=H~M(C}jE*Tpvv7=BYAwdC@`MBhcKk01)!&;?R>NdFx~0T@av7c6VZ;LEV(JXA7>V z@HiygA#SS2oo5_<{Ira==q!c7t#zr+r(G&p`l;_PU6|dcl$;j*&To}8) zGeUBX-x$w&9oS5o9B0rv(s&|h4^BI0;5WbTvQ9vFhW))MWICkFx^#dTS6ELf-iiM_ zXlzBW!sz5Rw|zq9t)l;)#^XM`v`=0LwU4GFO`oX}ZcAKofy>L5r?+Y;yo+R$+- zupIdj0NU^Q(rE6RTgpbCMqcM*4Eg~ZJcw+PmR0rF`-OqySo_SA-#Umokz`2R!39*9 zf3GK0Inkeb8@!s?`d|~~KMH*LPEQMO!8&%kDqp4}ZA%3ce@{ zsBWAOCFA9E5)X6HvTPBNA<`)s7bs|n<|i>3Ye=XEYoP1AGS2NqiX|-sC{`ErphS`C&8tA_-`>J4&Zq5hBB!R(r zFIsE8#hRZ}zT%?>@xWRUz|s@%Ewq}>xg$L5;(DzsbkLMdTIEGKN*Ql$Zq1S2L!HF2 z7&-b`ly^~?znu<=F#wtB{gM4l;AbRU!(&N(F7GE>Dx?J`6wH;)Sxqw`h)Ka8r5o%6 zZd^M;bS@e025!kZGmQ8jRdQ1+DOfz|(D?f4wBwISn|-;+)gY#kJSQ5*i>Hob^$%Yj z&)pn$J&9y4VOLZ5KJ{{1(Wof!JlMne;AfqN8+y-LPn6sM%}u>nin&_S zmLnZ!tTNS;Vp1jSZ-4a`gM)8bKkkKVd5s>fbU~!oK&vR|(Znr=M=ROGrc2n-JKdrJ zbfsl}$O1h;PzLsRzd_9~N=ABoc1tppU)`Tz42rVGYDw~Uj7or49f0_s*(d$ze|OQ~ z><6!)ARUvUdpybhJ{+6%9%5h=u-tv<>x7Wnm5Ohf$RzCqk-bMSeB{8esdL1t^N0$D z!((Ll%y}+B_hJ&u^q@Fcc^SLxAXUVDu;OQ?FEY7Qd>)EW7X=n;9p7v(VRxP-Q^CL~ z#+Q&PCU%X`CuZWBg?`o1ztYwDI73PwhX}uoBpO~_OJ{~k;SnIlnSk>~+J#zW$5_X< zW%E$@41^%6OiMj{y!MOC>Z5~Nl&NdvBGvP|$t6g5OTKD54v+P97gKUO=@B-Pl+(y_WTD?C}2kx<^Lu`B0Kw6qJc% zeI6B9`tb_Tg-M^ZDwV&!oQ|Yp1$eYs*p*Q5G>Qdwa>c75|8aNyjX}YfP)dgcU(6W0I;eU3c;I04G$@Sqg#!qPl3}t)C zS4>Ze@DRu^6cDs?JGgz);v%h;w{vA!V3j33MZ#TClQJR*$xEyC(gL{rcx{BigAc6l zcgcz#zEA_O`avdeZEM0vwoU|Ig&8(XxCJN*siqDptaW7cZ=tto(3QM$jqkuF z*vQtxepLI{3r{2rd$tp~B5EmJFy zDRY*w>+FZrmDE!^g`TFM0?&QCRk&NrY*tkTw?a8|}h`jRuoT6Gw(z2CXt~*cszt5o+c^s4s z5T9@%0)P>FS=>{rtZNmHc^(+I20<-1Id^KTknme4@9d-Rn%rb_-#|OCxL1tIp@aVkX z&oj8LZ2FdmUFD$oc{d4swz2X0yK-cMuErI;l$|STyiCqZw4xCOdVHSE<47qRLNH5tFTj`}~U zzB(%E?)zF06r@XrP64Hn1}O>YmToDBM!Jzs1?f^ynxVV9L%K&80qK&i-{tYU-nHK4 zKQ2+38Sdwvv-jD1pNSwJ5P5Xpj^r{U_&0Fx*T;0&r-ikLf%%O9+#-gG^_0pHs86yu zRVf85bGdZ*)OPGo6^(&bJ`isZG_i%)bWb_dKroZZp`PKp zHs2z2tMUo;EsK{rKxY`$DLr0FdLMqa?q<$@P~YjOP!GlPjdtb)6XymS0-@fS%IsZt z+?5%0X-qE`zq$xcd#67h%auS4VDr)6l z{ehX~HPO-AeAZ>402mwcK1#6|`a>+{eL(tk_k@}ffE%n!AP-jg{f86rfA+A8~n#xN=?O+(r*Aj^-rDs$>#?3Fer?^OxJVNI!^7 z?j*nL#0iyG$A_6@q2!ulZx7H-p3`(VE9M_MPrm7+#}Za4UTc?W={!6(8vZORX)CNG zZ7PBE@%e?}dH`vf0bePn$dtfYCeYvfPy*pUByuB{!4*UOQ-F~nG^WUot)|l>a=dBIDsixW9)RsYOQm_PS?H6T;w=6 zh2pXkS*S)ZY1UQd3>IkBDX6z(n7X9G8Sc^T^dQ*Cs2(1n7`%0!l6h`vPhqgoX1%?2^k?WnPB&5} zmQ+E{8oi?qAZXyAWcN;Y{+6a@HfqlohiZ;kg^_X~Ow)Fr!~bd-YK>W5LH zK9URQRA;sa7s12Kpk11K`Rc?x^>7ObGF{e zCe}lkVffK^|3G{a$5d7G=%?LQ zZwt^InJPZwM4p(D7%n$9d{Bd~!olPJAN-j-9{!(QDxR*I>cn!fBfHg02rRZot(p%z zm_!L<5Cme7JJqv5d5(6!PX>;39DUyyo@&JA-eF{!SR6msK2=5%h{{?Mw95L2 zErf=?AszkEbBycT=&ibHm0JG(v-Xh<+N+wFX^z?>j^orsgnnRQTwQ)DApA#!R;SM3 zEg(P~xKH*;GdG36XpP|%h`zz2QtHOTRzDGDQpnYzV9L?MX!g>e`~Auk&IkD47)ba!3m8J)Cm_n(ZA=dIGe;^p;JNKzru`+hT4XnEk z-kIoUKZhT7qAD_rx{Xw5U9W=Xm?4T;IK>|MUR4|v&tlIX12hAmuTDIy_^V(e;MzNT ziSt)^S9p-rJ_dMEA|4Es^1E=BK>;#=1G7Nsm0=lb5Jv$m+GrvHRoCk&RYpyP72USZ z2Z{+-G!sZKW5qm}-G_hW2C&TXa#R~TQUA{r=feL#62I^BJaND~()Y@jlm_;HvhP|& zFn@apb`)by;ADhzTB=dhr3@`n1$a{oG2uT5u~ZflR%s6UynpAX5gOZhG)b5*dPADs zzGT&5A3^fTTwmxMjoo(DgN|046GHyz8Sct$CYb~OQ(g)rw90e_4TO`UIOxK-*L3ae z3sRitM#`~DWw}Mrr_#ZKhQbJ*+Xgy8rSrKz3UI5lbA|@eq`2b>%r7A$kmUJ8;vZ!W zFrJ#Zu=~E>Symako8D;XI;nSCK~Ch=EB8=1WdcQt)3ooxg<4MFg<6(vPnZ;Lru?*f z7=*HRymoG4=5$G9Cd_T_Kw-2)=Fy%VmdzumFlZTR{T<5g@9SxIewQ?$$A)pb8zH$C z@9_Ixb^5r`hcozt6QGJMQyytulp$}B`?>Qou&)kJ!pjki_OpNogM;^#XCL_Bi;*g! z!xk@WOL%Qd(^;wBwD%9)O*saVxqTot8q*L|zvp8!UuDG&3a~zggXL;i6AAr%hK+}5 z_G~gQ8P9n;UxJheB?_g42Ahc~f!6hiob`04(bvtjZ_{6V6;^*iS%~+>ANM0ezB{+p z%xV%}w)kV7dN#-vm$AFXF2)0l)qr!b;mn`rpS?BXe?I1Cz=n8Ts62i-{#M%Wh|fRv z;4h{ZKa*RQJii0mw$YVHVD5>A+Z~!#6Y7LO07K4K;a8{x{v{{n7eBzXpFO1sp;#9e zyHWtQ_|hH?iUu(U^jwpo&uR7_qPhIO@wb!**_AZgYoHk#J#XRRj7kUImvxAntK`In~c+Pvvudq7?t~6@dd&z98YQZNcuPlNoG{VAth1 zuO>{lxd0YYvvj)Y2yGGTF_;Hc7=v>~Zq zvAVw%k}H9L+5!d2R%dTSmSRFLTXhfb{bE=~@Uke%dhRZOceiEX?aO`3==!&`#1*xG zG5J>Q%0?F~!i%}oy9HA}jKX13#syT1?dqyJZ0Y<&6lA$I;p4(B_;Ei+9(1*~=D?1< z?%T&C`vu40H#}?)2Y~J>ELQX3DnVCge*ZTUQGhtnpVS7zLrzHB5&}rjw%VpY#{H8t z3;%O$U|Y(Pa2<;%Z2x%H<9p<0rT_6@2m%&aFg_(vX0hnKYeu0%9UHbfXMG>rimq3S zM4;ipb=W@5YqI@ReX%NTYizLK)KJn|i{jD8gGoYM99_f9(sPOhMy24nC*$0Cb6%rwr3a)7p0}}gE$!=XdgnJx+cu44Vro?F1 zx>tISkMvHJ{YSfY?2i?EpgYO|=HFmc5Qb<_lk#4F9lbpAAgXmC;tZ!~Bi;2#!R4p~ ztOIPBG~Ouu1IyV+zuYWNnrJdoe)a-Z=duvH-0Wp~Ec7s~A5u>Kq!8@0^8>hnN=g4Z znuASQ2FUq#hQk2n?D^@eWY)yr1vt^)JLXA;`oQb=^JRM+@DnBr8IbsuOuU;aS%4Mt zt+En{fiUIKb75k9;?On~==ETFQ_=BUaPS^Y_yJ?fd?pg zF^S%f0m;D$K>>mTpfeGFqu*q6_IrH>NUA-nvt@M4JCL3rwj9h_Y?q#6uwOR_@0xh{rPlV_ z_)_$g}%~{_w=5`eQ~JMJ)!yCNER<9HO*i z8-K8ui<(?li9myB)SYRu_PfgoMeslu9~hgQ%vh#gUFNyn8={pcTIDMYvA}Dx0941O zyx~AQaMp5y)s-Obq-B`elwU=fCG*}5mR{+2aN7z=UUq?5UVGAofYg(SM6!xuEmXt3 zi0)w-*k;;dCey%j6ws$-)6*YR>`=lbonaaC3IyQvjGm*>QkO!K_gcKqx)Qa3M8UzI zcBtxcD}Mz7Rdn={N2|m})b3sHAJQ?%L&*_GN!yrU%iHK%x6h$oSHyP-<%LFdbCeGjH6Ija4U;=u|`)-crn#wR~~|4C6_xXco~vG{sYQFNg9c=lo=i#k<+ zsQbVMLaDx)@w&hb`w_0Ml)nSY3p(QmNGzlJ$iInqjOR9%V-79E9;~UFI;3)Fyupp` zgNV;j(HvAj%5B%`+=uqU6-%2-H+m{F7zT5`zt4SvaPR31qbVaPBgu^EMmUQ6(n6>$ zwSD;ZTGI&FBw_HQjBL(RVvsu1z~lN8$0v;hJzfs|i;gsAOVSF^fdk<$GL%KhOaoBS z&)78ejtuzN!4YxQS>QYcUtSknOuJ%qYhwQS4#p!ADwi$WAJM#iolx3r3QSjS!dwo- zt=VA1IIq=rk%=Lfw3hBUd3Gt)C# z%|mse@*cYFH4io^*|4ynllnxHj~6Cdo!K&m9B1iNHjoB;F30j7**7~9C@XHNJ%i=u zziI3i9C^U~24?7m2(fUqOsp-8sl%K?)lIDO$Rhwfcs2giOYzjhNRtX_Lo5eK z>~zWS*Gw6Icp&;RMv~;IR*PO#a!e!^kV>@H_DsyKoo)T*g6v@H z@mR7EzBr!UmY&Qz(&UA)wp(q4xSD|LP1`Ht5XTD_=+&N8MUNhfKk!50YY(3xJ}Eq(L{xbdL@4Om@fCFZX$ut01EoxX#?dm__4u+nWKWU+F;(!lFIxTFa(qFR>w3|;4`eA@k0B-g( z;ds=-uQdFq8y|}T&;4=O9w9aP_cHyLfpnw%KX!81O0Dzm11&BCjj9^Rr^u%N4jIPn zHh(eYxZ0Paw%cWrA7wE34pL#>&^)L7{mzPgRQ_nes)9%*)9=Y7l^eT({T;z4nXwnf z?q47lH>PJFZP=q6C7~FtO5hbnOLb9JTmQKolv^1h13ld!a@rwCz+hJ*zz4$2P$C>j zTuCJJtjYWr_fa;qfkZe!D?v?d+zmz2t%(-#4zdiCXB@~8)gP-`)g3DmMrfg~paZ^z zct|M8Nxv)1%%ZA3K9@3pm)~K`AMWftv$* znd#w#&}PQ`BU-c&ok9@l2VxqY(|@2x1P356gQP(5N8HSllz_ zX}7iNd0wBKdC)qRfts?(W&xP$yb!QM5Z@ThT+%Y^z9Xfo(tXB-Q~O&;RG`(dTT@ky z1n^=xOv(kG(ZwEz1*Qje?*H;SVkzdNk2xUuL1)Uh4s#>}x@&H&DaHfD!Zp zACBk;pw>n??Q<8%9I}>xXdT$#@~!L20CZ2rIA|6t3BzZD3Rxf)L)MxDl1lOgI}I_j z3D#B;OX#3lz|ttR&c_NZ>Pd*VER1(%b`(J9+xVoJ*tZNn&=u7o^*B~A-^wn|^3t?i zT2^gsL#Xr$a6tv+nkFU{&bt zV)L-x{~dz56t5Q}uP@A}P^f)a))RMfbj=$iiwZ~SPD~xKZA$>@XI@qSQf2Lt!Xb|h zL1q`=mimqwm2fSvh&}HE5S%n5yNshl(Sl?Xgxqd}070Expu{-{FtjiN34~^w=fB9r8Zd~Kry^m;W&@o)10C-y2<8bCIEgIfU0wQYB`Ls0gQm=3`f>Bte=`nA?y?K8>@37t9B+#$5WWT1F$ z4;*Ra_1#J6v@+#gZ@nB{vZx#XSR_OKVd6>kqkpqEX%%ql+8#)^g&9j7bbW$+WDIUk)k8N=uY{08duKc)EN$Z908=W0RP1SVusrFp&g}#a! zGdlEmG1p&3yUtpYe`89LG$~v|k43LPnX}_Ay{AR7 z*iHIgGP_O0pnAB!P1YbQaX&!=qSk45CRh&PQ$v@|#C^*6Gid9tv>|1bxh@2-ho=(#&9t$Juh&0#Y=ad)>ySkn8pNkdub+a@d-ffMQ(R;L>8;e%1Zi5fkS4cq`4=$qXoi5;rWC@uNVs=CyMFClLnioDaAX?*{#}}Zp zcV}oLjcwK`2kvDEI~GVmXy*gsYDZIIPK`g(nsc$v=?vAoAfO`8l3Svr(*G(jeg4bS~A~lgvuC-Kykl9z6GJh)!9(69n!qCXQ z+-XSV+tn4C8MssF&l!xxkL5_6OYY})pp^zY4N7=!bsBs4nt=!25JA#90zMvo#euii z88WWv=Lw%p_iIr-xu3t@*7I$fY*xqg+ZVE`PSNQ=tO^bYDWkT87cB>Bow;;fQL51Y zN5V{s{70$3a7iY>LlJPYvH0clW9u&!#LQWEG~e?(93%N z-8-xuhwF z6lqX1D|zHP?tBJonC}dJ(xKvIegk1r$6AaAAW`(aG z5EoxR%tRkO2Yz2%vU-P1`;X3)JM|_hJh$?ZQ=4ma!M6|k&UvX3Ywm&6!bybBlxT$! zCQ)u_mQ5?bJLGdxvr^4R4iW?VfbzBj4E-EAD}levG&tlwz&UCJQzgdYz&7MY zmfJ#n0xzBW&f7cfo0k*DR9RO;dm~5B>SVx+Sp2fp0Io9MgG{y6IAJfs&P|w{Mj>nP zM8*>ck`z@YORQ&)HlV7D_xMpqQKB?2jhy_>u>5!pGK3ex`Xj-94sLOdshU)ny&l5v zz4i7_oHOO!U;SXQH+rOQ%y$O$(J=+S!hv`Y(hjS1d%qxr0Z75O*{kFr&l}r+0tI(Q zZQ;Z~xk;HF3^RU>Dbym+f%UT~^XpoI)wN<_r!&A@$!n^M-XgxYq#A!-q>2 z_#YFbv8DB&nkhjr3LUxcsHK2npH+jw&^|iJjEXDn7w+Y%r|VncCnffmqJI3fE4-Vx zcgulJw6G7{ssS=2*y+gF2bG`n%Fwk8mB(&5n|c}@HGzHPoX1p$kEeU2gI;G_-HFHo z=rI0M#R9he=E_N%e<4f@7{3Sze~>0w7j4c@0yQ+8J=txfwl-S0sfh3?FoESuJ_8Rp zG*>X({^1tau*KCMx_xk#miI_TH)Me-UK-jMCq+i)#CirWKd^z&0yDaa8Y^kJ&`aOj z_;$Y*t0D(&k#SC{u^2=3vN!4PY0r*ubtBD>T zF?hkFP7#f`{ixw=(P(NkI;Zx zLmtKf`!qVaB$#Kn!l$I?eW+zWd$a`p^(^C5T0hJA!%y}qB&m@rGbGe(9&HyQ^9={I_>U}87MCPdMof+(Lk{X z_Ee~b63aesb5+TL(w%e8nA30qb!gF#R+h63spIx}EGP2Cvn7;BUnTS7j3J-V=)Zm~ zX*ytMp}pLn5>JJ$M{vmL(^(t4-r0u1`-EHN!iFx=EF)EX#lG2{b+f1Ghif(Su%aXJ zn{_61$NT#DjFt%-j`CM|{{g0|zJT4#c`n8)#Kq3XFq2#^#~m?~GgNu5q8U5Nme$o2 z%qO6b;fl%XV={r`RAl7cMP=CN_^0Lgzibyk##Fu{n?&niVSd_0*=qL-Hl?2MGiKep z*Aiup35|rk_w=WX_M9WKVm&W@(wOc>OB;F ze!oCK=gq`kehZ;2WyVCnmli6epZ9fSo%tQ;)eq(ZzK=8 za`2PD^-F!DF66*wB6WqKJ?AUDmXE@8mDj~)YKU+;@@3U&1;Ku+U(qzO@olROe%}aM zNU{CiAZs02ot`2~s-bXR`uK`3YmKZG6>pXPR0<@+wDj*p>7RF}3`i!QIFXEAvd;@& z|4JMDIW#Ct@Xj4y^O@_krLc`s*m4`o`)*KU%TMrsT>AuAua>+|aKnQb>0Dqx$iLTK$!XfWDR(HBGE3&aE`z1lcE&DB{UKwvy5FI?Zi+Z<{z5JQo&w z%uD^sHgfqi5d$eLCrBo5f0=)5>EGRF(O_Hv^oS^1U-Qn27YQ%Ut3Fu_!yvrZ^26i} zq=|&bzDsu(;un>+U=kx=?0!FOgIOeYfuG@R)D?)8P7>tMj* zYh}K02w&tn`jtB6tVEH)f}x4B^!> zC8J4>C304C{tIlGks=+TR=aK);NiLw2O~+jyT90(U%^;_W7To-+If=_-q)u>(hTpl9DjAT^?oa?9+)boq({_fSZ-#$SAhWW6n(JY*h|fT;OdZoqg5Uwf{qnSE^Ra>S4l>>fsKq~cC(2xPwmGRX z*_6HcHl|dtE$=&~&zzLBfoR3mZVG?J)2qc;v)HUu6O~%DvA=q2!d`+Lal+z3wEH_yA9Dsw9az<9is{; zBH-+x%*3(*!M{$LJk=?eu{n#ZXz^=!p1Cy@`4?~SiNOY;cQ@W})r`FBV{irW(5I#| zy@~1VW}`){?HT>N4UCN%`FmGJKEk2#$K>jd;E4VaR}=&}OO zf0b4WU!QIGW;&0|7}hp9+Q;*{5bMf)Lyc&}gpifds6#lC%XUL=dLdkpy|-VjLZ8m7 zZKZO{A~Ks`Mxqy(m0+C@fxI>Eq`KE@}mGn7q;M^m zPMuGAhAJEJ@JP|QeyqaV0kTm+ z999?eLBIbUSBk>=nSvNYJos%aHEm$~2YCI)d@E`4@?qY$VIqFCQo|f-Hy``KMI2Hy zzn!ULe=E#Xf6q2Yc2pE@RH~2el(;3F)0f=2X;QiRa@5#mi@jmH`P~!t5Vn1v>aZbV zyuBaaMKb=_>$wm9U^cqU{kE9_-KYU00VnZ*5;Hev{ks$!GCi4kPFX9ud!W48!(Y(z z#m38VqKhJlH*U-ETQole8h8r29Jb7*8ixc1=C32cH_PRj z5vO_oqtP5Y_-mDq$xK8m_(MYjXyRSd=V_%f2IG(fYNP19tQ~Lss&yea#^SrK?85JC z?P21$>27FFub;oa>eDd0{)mPu?y&qb4%)cV)UABC?c{v4-mI>dVi#2o?Lc@BG^605 zDb!VMlJ?%b>(q*&da>{6$;!rFXE9hSgiKZq;au!Z^$$(WzK(cNpv-q#HAJaB=CP9$ zI?%Z9zIDiMZDAv-5!exL#DsQN;H5 z$5jJjHm~WcP-ZW`-`={XTNhLvQIm{a)*n$bnDcwo-CeH1Iu|ykQyc|bzdZx5(i>>0 zZ+L?LYcRmgveGKJ(_>Y=>Qzehx;+tv|Baq3LL59lcYn1T>&01f?#N*8Ashl%;uq6P zsXNs{`N8-J(Hg~0&e7%ftXMNTjJ2# zxI<46!-uMz;ku@f77d32m9PEHX6&4LdgOO(=7AejhCW5UUZYp~%U3eATt>JS`JNgs z-bz<-$}GEvC$NHfD~~F{KJ=RnhhrF(^WJJ6r|z80^Y>=oo02Sa>8b?w%%aVEXCGNq zztzIlbiE7ULBfgpx}_DPaoS8>RbM@g^7qR+$7@`R9Y|{^Mxsc3|0P;?8Bu9W`MXcI z(^A(q6Ei+EEIwPw%kge7in`6LTrz@zq2jst-gpDs?0LGgLS?Q8spUS~z8YBI zE8P*w;nG-^dRc;)I(B$z8Wt!ljTu}f`Lcww^%(N@Z-%r8%MtjN@-Is!Qui4gIlqOA zQ9CM%p(zBZ_qL<(cC5^CI}uy5HGx!D@LaE1q0@h@ob6pMU}a>qcJ`%tZz4@dI1B!Y zR`D%bDgW{Amo$QFSmc5Sro_3Chz8w-Y>lO0=Lw=A4 zsrsdhZaL?&BmYC8M9 zpT%*u7`xnXTo}%8>(ph{5WZ*GisF=Ia@4?R#?Sw-?mZb|rZr?M*Yc-R$INr`V_*73 zY`K4zn+sCP{UH-ZhH&O5AIuMHHF+$|&eyI7O7uPaHD&(-rT(lJ<`|6p2wVutNWH3z z9C4zt%@tu{Y5p62Oy8nAer~lS?SoN)AasZpT+|WAc1}`v*82w2&Z{yTZsd9wU08m8 zdjgSJO%sT->D4DMi_s6Z${EDE9N4=_<=-7IRex`?aq!$IO0~{m=w*hOZ4R`h_|DtH%v+;R zo$YzY*g8^oSoD_cZrsm-7EiqvFVc6fo*<*(uR8qhr2Q8C_k7OM&!$R{L;lmxIm&WuhPXCzoB%v}WR*>YvR7q{)RFd<>1$>Wyj(f|N^&XUYi=udg(M?5SZ7`OKbj zpFG?~2;HO77`4eB6%XQYsA<<%CZ;g7P&r)Mw1;1Eo>vHzGb9(~L&_hjpOjCAoj^Ko z)&h~;_AXEjx^+M;7!3I))Q9SkO+8vF?=4~Z?JRY~6z&z9k66sM{6(wpwYpN;TToCpD_3j;u(kquW8zq&A!Z`3mQd`<{unbt=6 zmcyT9Eitbl@PZrFmIJ@|opLV~ex2iY$eT)YwVH;=6K^zDH?oU6fep`~C~OOn^Emgkf)P@_Z}1qlU@rs@LmD9_D+TaCp1 zeYJqk`a9e2kmRp@G#sWW@1wF1Q$EsD`xL3mCmAsk`y~bPEv&Rd_ZkXF`R~qEM?Gn+ ztZFx>LG_~H&11lxSFCgiY&4%Ix5V>($xckVbGRWE<^ajEvnFI&J#x3BVfL=mycdLvkk#A~JI+gL z9&Yi^H+h1*axpv*^@3TLxi@Z8ct|MJ!>1CRSLbs!r7$U7_a3oE&t?Jt>-u&?@Zr=W zrB^ROS>*-^g)|%{3&TQw*S%osXBbY)SD)p593-&eT~_L{T*9iVm)<~+kGDtH7A@o} z=G79auOcQ{Ct6BL7Xn*ldFsjr7vgS~v4{JdsIv*2KCAsMLK0~ca5&Eqfqy|B{XHTK ziBPIul9)~HLo~Zj^BuGml`4%mK9gyvQLLiW~P*vqT)f=1UGhOQ>ZufqvP0{^? zoZ<cg{CdxBkF;fwmJ9y57k2DhKIoTf0?4SQq{5)Ke@jk{V^YTM9xCt75^N{t}`+3Ll zQYKvnwMlCeIPgb7I8EoJnXl%X8WQ49$}?0yd5Md#_;iFdH!qU!Yq%&kx^CBwL{F^8 zzd!t-ypxJQM?ST#ahGK0Gn!=Nd6{NZmw$C`Fv@>8Ra&Mz+uT{jD`VWEb`yX`2%F*7aCSr5Z*ds59ftG_Nmass% z+_XRR2Wxm_sgT`iN>OyO{Y?D8uZm29)ik%;WNF>ksxeQ+LC35f8rEKv1F1Hqr+(su zCSm2AFKD-L56^ra@%vnl~(f?rc+-5};sb&H@l#D=^D;o-JdfBNd; zE2JDQ>2rR*L_h{*w#+(gxu6&{Z1LI26n#AMK;o2ub8__wt12V7-V`Q7#89MU4HRU) zCF!eBPkq69T`M|M;1@u&-Rd|KYUkH+w9(p=>JWL(ZPDuF949drh}T(KX=?qwngGZ- zZyV%ico38`!k3$JHB&0#;_I7d%!YqIPv&*O`b*Wr!yL$UkmtX% z+3x5c2s8;IyZ9q__(-DUwYb42Px*Ka%wP%rSNWHR^}F&S&IuPY z*N2Tx;;NwScw;QFT1CPWcZu4QjM3sT6Ka%N8N9p0r?FhE@l~@6cb;4(kOwKzzl(>M zp{3s8xX-{6toM~^^_YpLMltn0P7B@lwA~@CP3OD|hhy1%FQgQ=8g?5`+&2Z?_`H(=lV>l^ zjGu27USn74Cz*(@ZvU8}_j(7B1(&nR%IVH~A>WQNjkF1@M3_|UlyDmvWI!*4@Rr*l zn=5%R`V23_&rktUgl*wc;dtA%+A*{KgqaXZo1*@k2mOG&gWBd93Cj_ zI8S}bIq0eMPQ2G?Z{CYyBHA%(HV}<|%Zhhv!=QfeC0u{nYn6;n@0^Ay+q6(DTf^cIR?#AwxMS5=8ri(z;@S_Y2>I>K*(bu*`B^bJ1%h%M)3l`GLJyWw}gd z6l?puawFcp-N_2`D<}OS38wEJ{rsp09_-q_D&vOkUwMo|>-!H=qFFaQDp0n{jftjjNB z5K2L;_w@-o5hLO}-R~o4{SQP5p%OJQ%QuDnmwgx#Y0!-a8x$914#VS_1h+08`~4Gl z)qBo<&VwUVcdgzk9M`0H?Gff73143w9`^58b~#jqp}myc8JBZ*DgYX&gM}d8UTxch z?9#>47WSKV68npf=C2qR8=S8*&uqyXZm60r6F{3vZTjT(MB^Qc>o7=%(cYg#OycD! zf~}LrZ?`4DB7%x~+#3CfH&FSY&{(Zdu&9ao?M_CKMOJezZeq)ysa6L$;d+(m&aOf_{(Ab!?Dz*uVC+QNT|CuTwf3e?U1z^&Y z;e=1ZI=y3g0CgBdf{Y84{koq6%dLw-^}E?^(izg2p|mIHv=y$JcXL{&wd|L(Kyf9M z;U?@&s86)sdQy_CAK!d;h{FU@b4{eXen%^R_ulrP&w)!UwbK3E&1bwP7gA&@|AD-i zPyZoHkkYS229OPSPS$!*MtUa^q*GN2>65bFEVA?7>mQs~e|#P$a(|F&{pywLbisa$ z!<_T&u*ZfJi%gb3@+O3?!hhkYx8qz|(oF2!1-x5u`LZu^cwfO$cx}MhP(L!UJ~>wM z?Mz!ZHZT)iI-lZ$*C8J74+l$8qKUgRg+nOA`qm+(SccbY3%9N8%?Dpv-7n(yG?TQ_ z)Q?@2Y%aCvLP(?)V4pQI4wjTeV!j@y7eRWXH5^!Wh!17TTa z-@57-04J-zOQiGW_rw$CxW;7pV4u_}Xq8iGDsK^_D}#Bki}2h07va!V?zKCWGTy3y z@J#oaWuvC$qQ(ykvkk1rLa`TTr`{VI8!jwY?YZBC;J*(cm@iSRWygCW?Uzm}p-)|4 z=L$xHi^_><@dgns(w}G_b595s4je0Ayaa6odLsjGg~_?=k@)AyXLOMbTDS7A3JmW# z5clmr4LDCKAZrC*sq6<`%Imh>dx{=HIJ>NKS~E3_KzPoLx_VY7!900rN6~9d1Z=f< z`>AWmxgRKXGk|7s5LsEtyOvw1zv~;*Dm=ezbaeUX@CWnP1Tvkd`*U755sD38D)d_- z^;y*a)gtNtSBt1=A)r^)CNNeMGnSB~u6q7?9rsk;-9jM4J0sy2GPc|s{hXGnjUXIR zyUmyIUGMQKQ~pa7ZzAI1?Bx?v*Hp7VHt3x6{s(@~fn>AF7VHjVENs!Fe;1-9W0iwN z%<8pACKTzTC+g8Dnx0X&F1j9w9C%bf3n_t@sw3g8yRhYz+9Dxq6O60RT{Y{u-tJUCeS7#x zWwlDyD#yTCDACugiTA^?KxAfv=WfgPjI?+rM;{38?CJ)Vf8at?M<)9wCh|fpLiage zZ-3}B-q_`CN!uVQ*d4Mo@*W*pIrP`$O1fDHUZ+`fA>)%HmQ5Wg5vFfUXO>+mk<69T zJ2z`aJmd3Hvk6=K>@y4X-@Q0JiClg{FfkF9K?66A!Z zYR%mhdk-r|X^9ET82WSw(!Dk^p|@3w$=)@byqLCK-yB3TUP!WDdCED990je7-fS6r z%(zzz1Rt09AN2idpAq|gms8dxVYdDFO%YAUH-febBWD@{t=1T;>6iXEW5-dYw6352 zVJ`FkVJFifHEjd9{7{8ZD!{y%(f4cftj};}_;9-LnWGn|Db2Ru zD=ZU;I?Vv}lQ$xC<*JfPn&Wx8n%4wv65)2s<~b&Dh@T9R`;XmS=^1{j=)wknhfRD^4f|01r60 zpp3GLW1Dol{(^?#YVvU2_$GN-{q}>${`1KLy~v)(mj7ViarCChVvT@!J1@ix#ycK)5}nPbtY(e+<1;pdL?{H_xR2JC5e zQFp4V2yAHJr`Nxx9_ntgo%sDAtoHk0GE=^tYOUDpNm>8pMnrBiDETt+3_sSD^EJP4 zAPuE%+pIENS@^F+$H<*nHaktozaKj5|9zr z-&f9Q8FVBg4!^#nEi{k^u-3HC%LF6!O$v_qHhJoiz^<G8Qcv$}9n3miGL{++B76U4UW??}%@%I_!9Q@p9dy5%C?FhZyL==K^*?C* z9f&+*f7Nl1#23e;ulc3|)|we_pfoHOlX+lsmhtzBq-pPsrHiushzM%o)B;b7YIa>d z9V!aKpf*WusDSk{!jD&f?rI7Q8VoI?Or+UZe$VVQ-%c@KD&5&VpW$7Z!h3}0#lUOU zWvuuneVXrSPU374J9@{*Z-rg36fFCem~~Zb$xEfEf*aTr&K$`sHjoe_%rk; z=z#}fppVR;SFDkT6p6P?rWS|?8Y>A&b;L4|fJ5?=<+f%NR-Duvc!%OodxxR2<|zIFcE1;%R18eX04an>w*`{{1Wu3F)1ge9H})vf)LA z7A)0yB%au%#JyDO%x7bw8Fc?hYqw3FK<`Hj`u}{-CeJS<9j`vta`HFFOBwW*7oSNg zrJT7V6MSxfs5A*$Fb!Zz^$R;7qcBKnqAT>tI*%d%Ials9O%mP9>NBl%rAO?|?!tLy z8NIt8TyZ(~aYAU+XxwK}ajE+j=Lg$d-%S{&eBQR1Up=tkd+Y}9RaeeGy_VFhbr5~Q zp+mJxQHm9lS$`l)<#ihFcbN^y3em*M;Qh1ek*kBvW44CJLHorQ=g+TlYg+lMeoEkV zK3tnZG%x6d>9({s?f;(1;@D_vwHtOTaS@SHrOXh{e{6I`$y$`z8|T&%k?%%~#uTdj z0KQ}VH_zS_p6Ay#$>SGei~i|>%0Gzs9sM6fWU9c&&5M2s9G$l{(rT?kq=W7Jie#X3 zG)jZlUmFp%0)B=PDY{*2Hoi5izeBw}K*RN@jp;{z^vTCseL+Jqkspv6j?SW-FVKbN zGUqkE?5|?aG8v|VyjAF{1T=iAi^jY*KKSeiQ+79b%BgO<8+QmvwT018CHBoBzZkfV zF;9z0bLm+tI=ej@R{cbL`m*OsO%%*``tZimw|SG4?$K*wXLmxRrpxDML!|$G3M=08 zENk;*^H$3R8)W2$1$$K zT=i4uMVE~DN>cBr$hOSI*FGy3Dsa>IjT>y;$r^1pU4sR(%r()a%??e1LC9dVN;r}? ztglVJ1x-0Fx0pYd^lE_?f1W6bE(i~Pb^L+@Tln8CuJ(_$bpE1Epb|OA2!t$~`&+UnB-1G5QCdcJ!!Cvb zrDmI6O=o192|04xli6!g8_Fw`wS+19qu)483m6loy+Z7~G)JBWJxq7|TRn6qEmQ7x z<8F&4CF`T`3ij2XCsBR<)ot2B@4g4g*hr4Xswv=pcOUNtXD-E`aB94&UguWjj4kY) zN6uq+U+o3^Wp43H?OMXxjSG6$81F|%7yu{TJMRVs5g18yRt~B;#0-f zJ#wB0(WA>!(3bem1C)is&v9uEIe}vXimZ_^^fRxJ9@Z~uo2&+lp4Ml4yOUZYF%v31 z;FYLj_SDHgEF645sA(a45JAU1#PWxg3d_6B*l9oOx2tK&oTjX;v;uUe^=m!ucLcE> z?SmH8EbfCbhh8557{O?ezuA6bGAN^Qk_5U>=b2@w4$l?&dJTI?ZAdrE$6Q->Fy zUKcfaY8MX_+~}pl)<&0e^}CVwbjJ*8qpK37?7InkYf%hm`&wS63O8 zRkwr{Q9@EsP*PArkPzvT7NlDNK{}+nkp>A7q`NzmPU#M%TUuYb8}6XrueO!vSs+l^Pcs3 z!*AMNyWrBkps{vIR#9B!==7(vRVJ@D#Wic3fB80af;!2tIx{ntxFUIXOr5uY?dIHt z;yx8_6_MWkCih*$79!w%$hjH9T+PaPEl!gLIb+(ID-sJs{g?XOer)RJZV1f5Kq{`qoNqyVKNAQ!=&7M>@eb-}(Cgp$BHA zTu-;RHLIs)D{#c69byHmtlyb;*H)|W7aLgJepMZsgcq6+PR^u^$|(LboL+CVeLw zFt=I%IoSq_WW^o#2!~4Z`s2Tsu%E&|{fAh@ooN4@<=;)K6|R>WgTVnSK5X+^wI>pM z^cU%@v-@tpq-8@wkWr(bBm|CP6&46{G~lJF$$AUvwG^9ZFMPa#$FSHy`?RXO7nNOV zxIG#-`V*upk1@Mp!y>l<$<>6nuKuWEpH;*V3bpn$qyjk1s(3ijpC~*1hkxwMgs|RV zALB6P5Wp>=U+23n5`%lwkv+@xhmxA;Xl>JJsZ0w_tgLTW&0EXv!X%f+=sRkPye!Dg z7`O{C6x2Ac{+^b(+mXR1pkx9!-gd__qj|S|0k^@nLSd~*e;H+2df*|JA}+2(6&w70 zN_2D{+a)@I9#k|Yf&Jcb-#yK_ArxZp_^)z z(!I(=d$;v_;J`8m{#%k$DaJLPgGtllK5RRD=S|5$LZ$vqlG(jQ0uAxW7?nY*d7}Fb z%Sw;JcT0%*ZXY4gsR~c1cXpGcS7R>yJ1>zV{tZ?P{~cU`lul++?Ed5Nw(eQp>1ceff?uRcB63)LUQ`|yj5p=%Z0Zs}L}tC4 zdVYICz`OYoM^gFQhV!n4Ak{gKp{yl^70tae?J)@i9`Y8#U*iVO#^W{O*`r(l>SOze!?;x!g5?vX*)HKE^P8_`peiJvJMYae}*SUwCEEj!uA_f=5*}KST-T z?fBrc6%@HolS@Nhhih>&qO`_h!#5=CjSes~)F+1(%6<^M0h~y3wEfMlYlaSiJz2wJ zJ1Ko(DkSgkw*XYFx9%S>jq+wgB+Qn$xFW(C4W!^y7*dzLhU~@khN#J? zOHn5%Vc~Eq2=A>FE38ZRpwQkzh`TmHq2GAS^Em*O0#XxQg)v}f8ac(3m@p35@s7xl zP#a>jrC#7KTJkONDI*CI-MxWl_kcO^hOlq}nw9ALq*PIyCHFWK)fb%KV*xZOzWmcx zM7rQI(SF_2aB%q5(z0%7qXQNWu9QoB9$Qv5-e{2Q$So?T@ZCSch&z#o36iwNddjPw zys)HiM9kf(UxiU|_$CE3_so4+1T(xA3!c!#*8hobjjB5&P^;&4Ph~qh`|kY?5$}UqA zx71D^Mcb19o8V+`|LgDkWs!)UDUq3;{_!oUH>l-1n~(2JqiOi4fRbCosCN9*J#nyp zv2Q5LA61ziaCRnbCaUk`gm_x8;)00~e~BGe%HO&>+m^>GmFT8ab~>~D2ti5R{m*%C zy>@=RW;V!09HTa*<}P|p$(kGWmDLsO0<&-zAS@P+Iy}mIIJMPF+*EApNIx6BQnR0o zAU6X^a%T3baKRe-WxM>}+_nyHM@x+CQ<6H{m~@68vSH5th&<69ncrAQbZg(p(@ae7 z4d)5OZJv9ky{4;UBT~h=-BWLP;n$i)-lXUn|D)?#8=))?^OwZ=wX&tQmfh>kZX@37 zlwVvKi>Z#nR5r)@10P#TK`KSB>s5{JcBZaSA0Fj0f1#B1WE=n1L-d`gudCE>JUr%e zTJLuCqA7x$jorHOt3euqGnOKb5`71RSJ)3raX+Bpg09TJG4>iPLWn#CT$Fi@V8ca7d6p1&GA8uQAnsBM$EL{`WioNxnha4&5hLu2A*{K<% zLJ;-uAtsK^Q*%Ohb6%mNcDdsz*$S-1K2{Pwnyo!7@Fav+RpPs%>yT#6k{Tz@hKz8r zw%mpcE;59IkhU+#&c@yZPvi6$ySC+j1#mwNdG_E&Ga%Y6R~GU}+J5F->Ek`r|-4k8rIyFs1K_Xo%Oe!$25==yJNax!_8;3&~*p`bu!(>Cfyd&HN5 z6H#eAxFl29rm!Ny*6%gv5*ul?&d+1CvA}nC{I@gWT`2fh!bRoNNEHnqvBnxDw6qRZ zB{NOOZn|6^ze?N=cD`lqx^AJ@-+gB^-azX6T;Tgc+tc4CQKbB*YyEyyvG;I6a|V$9 zZSK(4oOb_#mk6--XdcQ7C>JNO3Y6L#uQEpwpU%6e)z{?Gd|Ac^+WLVG{Y^X!TYRU> zG?=24NrZ)&w8way2vRU(@`GhxJwery`VO@ZRGNZgo_D)lksI@<3Gn@YIvKV+K_M*R zE0y~ZoBT*S;)XDW=zG*sq+7BVer9B9vvR0v%Z@yUX`o51H|80BNVs$jce|`|>aCG< zKbtl&iobuG5oJ-XwZ}DCtd5&E-M(&jQxGk^C;#P!kCD9m5xhYCf`l(o+5>p?GF)k zkyG)zM!f5c(Y15^*%0G@4Z!S;yV!+Vvsss3J0voV<#l*!)wuuNzUcp6!ZT%03l9qq zCZQv;5pSTse9Q|j`rU~N*IY&VmN_{<1+*EiT>E<%y1`!r`{_uiV)DP9NS5=332-JB z<6D?Tt-K6;&v4Rs(tk+BK=qYVpCic_3Vp8LGm|mm?iz>@3t@&1y~dhNQ(7Glbe1QN7s^ub?u^!U&dK@! z-sa_@)ub3+Z)N>;(%%RV7askO@1i#;_3s_(w8+ZjZipSaSSB9+k-vz`PL=bEOZS&g3kQ^b>)1`EPVc9mRPfI_9Q(z~$Xtn|Q1ljlZr~Me()Xr@ z4FR-sh%qe)lI(1%C6$@lUFv>ubr)@DaeWm0JPykH&XvXLS9o7JD^HiZzQ2*1*pq@Y zK&Wm@XS#BRR(NptxhwlpOHGgB3p9V@IR5m zH35GBC33)NsQ)HwDn31C#OTpogr$$MdfRaXh!icQK9`O^s98>u9ud2EgudgkQY*kRUkkuO38 z6K5&-F<$<=-Fh;r-u-l}+Wrk*1P6vEPEFe}>7`gk_W8tssM_7f&vBWPyAqD!U2d7WS8A%`9qFTJXBkZk7O#xbm z4j%oNlm!91wB#IQ-`@SUlTLJg$otgVf-fU%$gtb?Lfdgud~*ht%1V84aMI(WSwqnF zUL0Nl@)_A*4qOO&(`Pa*E-%SUQ2|2`9vIL*Ipr>+BL^;{Syx>I<5cB3%CP<$ zv0+NonC8XYUvZ;fk2F@E9mTNA*Y7jtm?rtnZJ{3S?0+M?I6$G2@By2*dKqyOeH0Y2wXi1K%c)t~q^ z^*HJw1+h^|z!-D=!v@>E4W?3D7DbXOa`y$$o%n6e*z>XksUklt{jmVUxuZ63&Y1vf z;>K-B)n69bcg75V4IPJG8k*Ewdz@bp`^UvCx~_ym-y5@?f>fnr>>mP{DX6+QbWGsZ zbh_thy0DsvH_qcHA#9kwkH?x*kG-T{v=R3Ktq|*dsc9{n@Vw4}w3*)FVrELmviFTz zE*N=Ero!Kv*K%o^Nn5NI<`v(;iDsf@r=q?o(DKP~O&%W~f9Y-D6IC5?brvq?9~nS~ z`46>wz%cG$tBNMO-2(v|_BoeUbdA-+H%9vr<{C_{KWp2kt1OQWZ1gT)6PC1_l4^k5 z`lMr5Bu1~*iUz+mj|^1XZccC%iy~4FYVe|d4Tp2e^B5w@Z8rR{?UV`2y9{bOP?^KS z!Ag?V-D_vmJ&9zYVK|nN+_P+n6!2L)Fb>V+G(G|){DBA z_mZT2FX7}kGf(09Q)0|q36=uOo%r^5L34&3C?avBP7^mg|FqS~|K>7- z^&9s+*SrSXxlya~;+zV-!VN-AO`}d*N#)pZhzp_+M11~eCuN4%ox!B47pFBA5=NEk z^InXPB3Kyo_IHl64<< z)E?X_`fo;|kQt&%wy2tVtm~|znRfiRbIb955w@o8V;U>a7HD>#O$Vo=cWf&Jm++4> z*Uts~Qc3m)uSKK^za^r!-Tf-?PrKL#%x)06K6AHMmY3Gavm9lx3q$M z*)ZKUB*}I;bQI(cN#{iiuq6fj zsGYL+D~0BoFE(r6 zEtdOK1l|DFuT^jG@t>q%615ha{xoqq&79-zZq2S6nXT3;Wu1K;GhD7kLst6yo-Jt& zHHOu;SdlXwAVTx8L*eKkm~N4mZm$A2MD#FM61UxD{43>)>&;6Vr36k}G%`E~KKUe- z0leXAGDJBWuBV2MvoURBRadC|40mY9R@Vg!Usi5X4~mazjtP>)vLW68ep6x6&tq>Q zqmAR+nVU`|+hfG^eqv*cAC`YDjP0F}4LD7>|Fk<0`(%Mf^AC|H{15d(qGO9U4&t?U za5^-RlNRQnS(*O+bq0^0sX=Fa<<4l(4TVKR9Ojn7zVaV6;C9k!u_{GoD}~10OgK7) zMp>A^j`W*OdUYuDMn#15n=VpXO~iyaq|dWL5+lcJZe`kU5a(h28ny;`;eNUx?dS)E zb})1RSgYUNVGKw@0&d(vc~6}wOp1~r*XSbe=Q>Tni@V1nw=vOFw+zCsAOZ)$Qf&7u5(nn4R2J}Ze& z;+%_We)&?3-|crfQ=eC(;k4uxja#*<&c}i`M%h_yMHx&)Wr>lFU&>t!T;*0IMqkna zzv^{A5X{nnz-+eXt&H9;@n+NR{f;@sVncVED^#F`sX5jI=-K8kyjRjM_ooc}hbwXQ z+kU;JZcbXzRphqkq#4oR_>nF+3TK4c|C$Pm{|NAFukpmIst#|~P_bW>CQuec>9J1}8I+7wkg zHV>@Beb+k-g51g58V_z&WzHYpy}qfz^qR=@6>DRjy#E^uzQ<(vXr>XLINt-eDW_D+ zg}=r3xH!d^irT|hVCdR*3Z@D9gNbZVi4%NTPG@O5xft;|-4RG(%QKzZP?yc`H`Czw zbfUWgy{}d;Azemx+4$#G3s5psn;tVbsV)C}9o-6Jo!|Z3z}=7`>PLm*ppK(fiZu#G zkpMLe^K`t{e#olqU5Yp{Igm!l$)XC7*-wvb*1!A8wu5n#2tX~Ev6nrYGDS#UH8_9@ z%I&PWU^W4U>u1<3wm3HVnUy=(KlW-QXV2JTon=I>H_tJ@u-!#Bj++(hMw6jPa6>6y zH^ceYIVk=IA6)x@X5GBc8?{b2yG7*_E`ouQmg{9b5#>^w^?U^{MQYhkiRYPKD?A)>M9^eN|4z&c*UN9 z2-TF~^^on_bcqUDo^Dv$Q0TsUBfi;Wyvgc^3eES&2+#s7fdx_IP&) z@Uk%B2~f7eInkLMdt)}XeFFq5?T1OduK1vi$8T_`tX)xB_>$6%qkO+and5nm3>92d zE1~P$OWeQ;m{F>ZtgIQVOi6DL-R3DI_V}2yO}^Q~Hjm z6L7`}$+;0w-uv)Q>zd(0M>v2$2xTlBOSB9ii1w*KCh2q)9c)rFuse^x$V?wya!S~D;^YL(f(kaJ|01YGQA-IJH}K}Dykp?uW;f>$!u!-hAd$F zJMZKiBCKYv2dem`I&2DnZi$y1F6%)5+mb`Y+ILKvd~s{^zw*^`?~50L-KTy;eZ|J0 z#5_H1fO{ltGjYvCqxewGgpUh2mhfdy7ts1kOy1_LZ!mpmDu?p1My15n=4pK6r04XE}zJufZnZs8|M7YuZLs?g*Ut?>hRtunaOkpmT zFLHZlXw75cxr;V}T;`+E?lK~=MfPoC*&GDNVc<~OvVECn|7=x{F>^I%R(BKS!e{xH zl|HIpJ5pIfRLKH~!JuPjgPiKwJIQ*af6CZ~SN}-5hOj#mJP;tJX#q<22JA&$N?$Lz z;YRo&mtdN^@%Eev8#Zoef#v8unWhZw`-K#8inqc%pv@-7GN^kZ=7lQ+1IqovHIQGQ zu?1?kJgab}ElZbJiv>d!QyV#<8_|`)ZUbf6+B?U|>fHx|gp*PAs*7({r-e!3*dM3F zhHszVFLAI1#s$10ZT@#jKfp|YqEzbyzcu^c4}9Nv8$7}09sW|UyLL0=dX*SNkk1^ z<`NNJAk<#^z7>)0eD@assJVZ!+%Vv_f!EP{i6Z$&^zV5%Ci(9?VD1P61UK6!9(Nba zx+kSltCbK3?f%gMsTFVO4`=OJLJU+(zE<%-1wR!(sG^~{sWizvgcQEU)`6xvtG`WR zKtU(e7)`FUUuJCm0M|`KE{8QsZN5|*F*pD=(7Bh)+V_hvpH8q)%w}z$5r(wx$0mD1=-mjrb)+H^#ANpXv)^>09`&xy1V~72W z$nn9qn1{q%*O9vyF=f)r&2B!;mLBOAttvY@WC`~Rav8K+k{MR z9}qMPrht!tffXi z!?|>k%OP78ukwv`HOQ|ihtt(*ydQ(+0z%ZSc6FNOUxkGcqhF!Frn4$)m0Q6VFZ6nFA_QrHF8pnQ$pJ`!tr!y@mfo0fSmTXoO^3gc% z$R`zRa%GuzPV{MO7DPr^^8LZX-OynwBrG4g3k@*v6vF9Yl^hSH1UMeOCCLp`2~Bmd z&33X9c*uMwn#mub{GK?v_?^@zWGX{%Hg=Bb=*ohh@fchmUGV^%K>=^y(#FrVxpMWD zq1ppIFO!35rsHr-%@FuPJ?m&pgq3NJvBpcaLN6Z;x^dpBn?;HD`?5Gn{`O;rkCg62 zZJl=IiM22(PmAF%Ue$5J!nKqvJuGNlaieie1UF>hs=dCVA@ek+UO)Tm%AKN%E3gV( zNhbG?%|jXu%bls)^}LER$C^2>YE{IRnOjC-AER*~9YdeW6>wh6Eg9x zq@dcrXdjNNcU%D-boVIc%norfHPb_EUvi*)NDDSx&Dj3g|LRQLtmQh$6J}#K4q{!e z+9+Y_7=HC`Qdld^33@#qvPe5K;%d`fVN+rKvR<-P`n?EewPh)ois*PVE^-{#yYu*K zS8ktKO&;RlBH`i0`qOlT-wwo2Q%)uKOQnGub(a?IXLU)Ig78YJn9I50IhR1(R|Y9@ z0TVbC>u0ndFk?omh_9R}$aCxg@A)P;Y)%&{LJOTw6?N8xO+2wEBZcN_O@!Gds*FcC z$;gT@HOyK!6e4aD`uA)-{vKN%eKaJB9^lu2^cJX$^6q=sKfajopZ*zR?L(LBXyi!xj2+0% zw~{_uZ}qnQtH!Xy0|AF@2V0xFrvZZxD17}S46Q(crTeDt28e6l)dfc$BQc~X#7))O8F$M7U(n2#$#?L?u~aW zyNv<+3uz=(&cAMfkcA7Z*Q6%&EcmSwIEN9-A$eRlpzIcZ0NY=5^3sMsII$FPnjoP} zeW})chG8WxQ{qle7MYunQU9T1IS%wm&Q|42TWOe@4+`4`ZSbAC3w-(<>{e5aX-7%> z*Hu%eTgQVU4w>GJ`{e?u-~y5iXyI#ay(J;<0Urb;G(q%8uEerEya(DXspuerf=&Pp zxN$)DKyAdE()%u0MCsU67{l{58(6}23erq83lRiwV0{R@gS)N;)(vk^KVE_^^^d)J z#kw<%#PXpB)vs0iAIB{O3z;KY#O(m*Yo;-Q(H1DWSL{!Nnb{U446Ramiw(hM|U zli4flYuMfUHP6pydLcsAVALL}$qKxm-P(h7Pj6xhO1PO3dvv32%THJ6-MVJQ*pjZA zJkSe)`NDxbADKg{%5o)CbMW?O*{xr!NI(KfNq`?STN0!_CTd8bc((`(==ae_c9;*ugPr6X^KN+e zgk|M=z^Vo>@R+`QoG9u6BEy<<{aS#S-3V}nbkj!OSfBh%dVkiXIWphnh(vhx0IQ9e z-`82Yt?cwC)E&_#osPE^Rq4N>-gWL!(jF)({7yX>LUCkn2j^^ zDi@SjH1KGOH4!@1f!|W25-+GSLXK~iV`g&R8V>bkzBCp?*eYCEkJu|}Ug@mQ$777zVEEsDicBk3vkM`K> zEZUEFDIt@v%}ByI#gAlx=(lM?yP|8lZEM5BrSBfnL7OuJY>&1@5;YAf0K@bGdK7>&}WgOxQagSl)a_SnKqxp?&DO zzDM%8O!Q?Y-TljPwV3J)bqqhTYbvYSi>I4ZF|~xA?v42FXo6Q7O*j6(P|`B91P(Ig zEpU;*)S@L=>x6`dJAofc`JAhPRORi;whW6lC^l(7pl#N|Q@GGoUOnRm?SZ=NuN3@o zByMW9t!~p<%CC;3#-j9tz1x+KjbHK9gElTw^bNlOWKn7Cr?Zhpf9jmTfuZR-I?PED zz(gYgv}XrwT=RzsyHlQNgBi@dxty%_^ejUr&zq_`w)rZ!{a_k0rrgI_s+PvXdbhQD zR#olvOoo`jC>+tGtVr^fw=XOH*`**r5FmW`Q{y}vOhtCDDzxdAmsGHWzCXB?r4VAz5O6Lm#F zFs^1{tyRX&8g$o_+N0@)f~3aM3LyP~`^ZZ{42F^9spxEJ_O?l3dS#?cL>e71Z)IOu zM=k4MvW3m`67G`};A4+3`4!-tg-DydpNCOPYk*FSWdcs2q3zN47b6DxWltSs7<$|} zw=I28ggbBE#8~#8wA0uRh1ZIg{VOLaq_hm{oJ!XjuZ~Uc;jhT{lzpo9&grx?8{bzz z!n+dmSfM$ESWT*}Gj+(i27CNk>~_eXI!)l6w|PAMgRVbGyOoY0B^SmGYkL6L8=jC9^yNrP*E)# ze;VBAYJT|jcpa~7P7@**G!64bgn{TUv$=P&d^P+HEj**}g?NR4lUu~J!Rexgset7> ziZRfy$zQ4K=8CDv?RrH(uvI@8SXWu0w_zaB8c7BwyQ{dcD-9qyAv2_?OtGF8y3ZVx zl)1k(lca}GHWY9pqz#;Y1S!PqoeAPV17DSP3q5QSpSSrXj~M#a2^&`MO@!vI6}fGq zS@$&*5|%-OCey+S#2LS<_Px?-d#y=)nO=FL^!ae#d#%qW9XySo> z!^xjtm(eE&6$-OesLd&OS4xF_+97tvESs|$rmFtGo}5{te;+mPBf=7p(*IDA9ud9h zh)quNlHFI;8O=xVpC)mm*YQhe;0cnlfw#ZcmV(D6m7Hv)`DZUV@Z}Gl8meW^8Rt>OaSHpLuPx4kXXJkc!5LCh4GLQooz1 z|K`%@Y2ka@*hnIAR-7=$Kz=vKN?LHY>Q|8gc?@5#e{1X~6go@Gr8NlFkjk}7J%W5r?5z@tYkk=DI;-JZ!N7jO&|`0bmgd$6 z-4nd*K(cGM>{uX7V`|(+kJ{d4iIbs*b#_MnU=8KA-`3LrQ%_I^L*s+)_+@Rg$$b_$ zl9aw2rq8bo*gX>;;-t%qqfuzlcZR}^YjWMqz}vetopi$OEv`f|##x?%O0NrvH(9hP zy_Sz4L{6EH^9Fh~<|NHJ^YJf|LKEx`qzMic{#K>T7%?G_#iV(zP+jhM|9D)7Pf zJBo>=_M)r2>J55Ri}+w*abUtK9`; z&Q6GBnj5}R%}#({51;LBeb{Yuc7kT*c$rRJtT?uZYct|zGu<(#zL(nb2A41O)+LZ} zu!67EGX!bwqFbG3$<>^$N1q)E`~`<~RQ}>(ZbiscYh!$F{bbmZn+{&AjqkAphjoHA zYKpB}PhZKc+9$|39HD)CLogusTcBlY3%53teWrZXpyG)-m4|=I0~y8{&>q)j=D9N3 zqQQDB`gP9hN_xJmk$;w3h9M;62{nVLumcGGaJ(Sf&lu&UALy2ZQ6DY7w2Xb0XFGTI zLvWWuF!Kf_1^t?OqpM(C_iX(sVz7=YAGzn{PyKTUR%&pb%K!E=Gtb&RS3*lDs3iLd zh2V0B{C>|Cq(c;ILtqBDaCLiUG_9^8>Y5?a=LLs4h3|l9#-!c(SrrlZVsuy;$cUnu z+8@f|Z%*s-(VKGBU-n>|L-Ezj<+^G%!a8|4kYYWHUaa1aQc$<#ZPs)nTH@9W&bx)` zCkk>E6dA2mHHNIE7Hr(wv${$I@)b$wD2aYW%J*#E1QTf?=u8S#)(C4>%#n!t=E;F< z`{o8A5!g|w<&0dL@vINAvj#+AA5%haS{|C@HB@YB%4fVau0NI`u`k}gY>gl~+hVdX z3A)Pmx;1BiEu32WQi2-VB`#S|9MJj}tOta?0wnk$v8ksaBK8|yuy_u&k_fU=I~cNI z^{`knVCq(QTs0^hMAZb*dO$NUc<+ECguxeIJMXVm421;LjoSG zKk^@hJRfky({zPtwfs`II)Maz_vad9&L#fqsFEFEN^gzTauQf!CR13{fj)b>N^g(h zSq!Dj3k8coXG6|?+ebQ@D3=1pYBItKS1%g^Jz~@4w%V) zV}))~Y!rITwL1rR-rExcIgsihFJp9I49Xgz49;Fd+iPBpgxx?eYyPfNGnV?Erlds) zu*-2q!Es;zlIJ{M5vc&JaKRMlFg?K~#ho`5zxMHc$o&8r8@bUgM$a`EEUDb^if9vj z+(16Oj~0U>B#Te!D`EW^MuHW_`XJ0^`%kw6Q9W}hAY6eM7NW@E?3oiypY4_1V6W>u z-Xk;-LY|X-KKOvdXT}^vKL_2^z0OniMdLO%OH7aisjT-pDzA3gC6>EhWZ<0d{iK)x;;&GOnUegQU$eGaJpR& zL{B>ReUm;4AKp**OoeHV+Q8a@CnezMhc9D7b6Wh}ZbMs5ckmS)gF@}#F~~V|`djYd zhq7M(vOILQJ@M-m5}wm{8VOx%Rc0dlpn^O{+cT;_D8@ntDWN0kC^14Q4*LK&$IJM? zPXs4de5SAf7L7e3twpqvB?Qi-uiD)YQ*fN z-j6NRLDLlD7vfnh&g9;mA9d!@HF4R#XiGruVPS~zN%}Bcx*@8OF`pTi9UZ5$;YJeeF`yn@3Bk-L)eN) zMU1-bDJgj5Rq=|`4TfddL#8anAW*NG_4)`h=*6RE>o!mLe?RGSQbB0XDk0Kt5G2)}uHnYFMaezd<(*h#uPhT0)y2kdXAec{#Y_Gtwu%o4=OlFM_H$!L|vK24w9 z(@$gg-))}Gid!EE!U)rb6kM0bwBz`s!X2aJ@>bB_u1~Ds->0~YD#%A;)qHSSy*84- zfBb@><8b#HD9S(9gkJvsFGgqD2!W?hgN`1E6bMWPu%BIS08;))N945X31j4T2?^j_ z5M0L>Mh0}L_G8Roy~FBR$dcx3ew)cZk{r9jx~WZdU(5TvNuVN{$AQ zkXIo3Ae`RKWcC=?ii zieK8FDc!_}3u7B`P0!cAF%aOmE4D*S2`1~o2k?v{e+-j*vO+S${oKT~PJfW;z)btMGiBApp;l%mqnd zq8P_>q-;B;t&ED#Nv=o+$iVRrup=T0m+m@09D9y>28-vmBP zuF%5@Wq@F=9GNWyvo`a*xT`14RWw;j@KtCmeU1!`h^YgyDAEg~M@pFw7LeIeyQ$T` z&S$K}j|uAvvIR{w4h%_y#PQxj8RX{6hA_0odUPz`hGZdr^UB)OV3-Zlzk8!Lr5I+~ zqRVw-%S5}*E$wnex~v!0jk4nrfTXjBGRh;A+KBf&K~nS58ufy|%RWAo3Noc`JV#;B zIh{=syri4;ed==m<=@6HP2z9kNBTq9`#vm)_6KAF2^Ead!qM*@|Ee~ft@*tY*KpiP z)6she17%Q>sAog7rt|3vAs#&zbVpl=G4uYe*9I;I%9Cf{B*8DZhA}QQMf4~bVr>n#0PG__yd*`KbSfaXdnJ7$ie?g2?d(xV1&NBfhcc5 zSUTndaI>%)W!l0#pa?B)z(;Y79yf#8l9gCSHN2jC-d>Ok&7v zjL7^?*WOt6>$Nw`Gbl}$>Z~OixXzUyy3~-WNZ&SXN&5m6Y!VNAlZ%ZAM*`4qIdQ9r zjedoc1b!^(O$Px6nq*LPAYPBv?S#X-x%ocR)?4VIgKbOU2Y-u4IZpVEH$DU~X*-b1 zlYvnBQ!8&?cB|e4qhQlClX32{FCrRr(b=Jp2t)!^(*P9DFsXmF*2e3jrr+QT0k~m% z0_R3J_gDcDr~S49t!M$NC-B04si12Fg7gYw1diB(QGjCt8LVEof0Xu)A@b8nZhpS~ zCfmF$@INPYPpb}UK#F(TsIaW*Fsy3JM3RSTMTf z98!+!Lj;CvZoFPe+&=XL4Y+vI!hhS1yZ_n^|BT$0dNfjFOCM4B%%Aa@VTuq~s7R!c z{iLiEIH19o#w!s-;pVb7<+#n8RF4V;WQ_XQ88nVj-0$D4nj2~trjl9yP(r0UJ7hOs z8j^cwkbL`(h5KYG;|8JH;Ukfnn~f4L=jWGH3eVU4uEZ&+I?giF&Jg)tqiNYT%XfOa zqW)B^tkT6vcbBHCNI^+kg}T%+sxlMP6pPX~jn+;oU)44?5LZZx!VOO;R7Hi)WG=&8 zll3${bR-;IXZZRz02}Bkf(xAm@E7GG?$6Zd%dAdqs#~qSsyA*)?t0hhb2HItitgxQ zI%&R99=|9=U6q2G_VL2~C+48nPsK0WJqy1i&Z32WPHz7_k!JTviduATXc+dZh*iAj zpC9Z_Mt#%K=KbOjXr*)Y^b%T00WO1{AiMo;yv#OKO1W)F^f|^CfCs3B<1O~&IzDE1 za3}Rt-6lXkg~v8ZWH+f6A@xW6_B$hU_tmD*mcs3vKFES|l5fqU4tE?Hq*`2_e)(=Y zyx6BgPUCc?rFk7jHIF~6D|a@J9~}E^elK^!D*4+@hxPu&#KfKp;NV`ZGrr>0$(bIe z1pjSqgv%|ASqd7i@BIfmwG)(qx0orIPkAnSRzvh2=WSrZY&Ics___DwT#FBC9B=!IFRM)>J2 z0)j|I89Fw(95-%~#Z1;OE@kz(pYbnxo|S`I-f#=ni32_xmZc`nDx z4F=}}1^7*OT8n+uWxv1t4ypFfKR*cw#l^*cyw42D`$|_w%>*glzNc6l7nigS-vlW& zx!9q3i^Tk5j#u+Yo5hrez+V^=5bc6Rol{m=+7A*=Q0Vj%E{aM_B!PGAXT_xdrI~zQ$-P^oDWNI6$U7|}$NEvyV#CvpYFE1aP@8X=dpL2zOgS4t@Jp55m zaTw;js2n2yhKePAf%B;`Y~U?>Vm!>1oiS2J{lwps;_D&CL+6#{jcv`9_?6>2WXX(s z;;Emeh!Xq3M+#dhU&uxT*m#Hhd>-H5KG{9UH_2XdoZZ8k2su;XtmUqgW4=-OM77R? zpA*yg)cfvuehGMhZBDWhg|S?-Es zzl@~RPwZJMZ=IcDE5DeUEPs29Pigld*Uo7lQo0|<_ru}=nX-bRZF8DrXX`OUdFJwS`DI(xv;K+63OTlj8 zv_+?%!l>%Km}rfkwaVOh=H5+1+Jpc*gd9PpuR(MQ6dtM1zN~a-5(KWLu`}U^VM6MZWkc| zQs#vDdnETK(*x>~X|gG_3;8TB1{+=nbtYF(_?foEvTrDCKx+v^we(P&2L@N z)mqbU+>tIvpKBV}X7eC-fE+a}AZ~NaZr?exqEEwlBDLXIIfJ<=9})}`-G_)S4;l(j zVez8zfzc>qf?E%J;hWQMU8#l5QzUAIsfj8Ud|97Em!w2%%!L@Cgl%qk*g51-+Ecf%xR_3yw^sV@#`oIc2k`-Uf2JKYl zuALZaX4Ub)UCzc!{T6wt_DGe%?cI^!*>i_hGU7?^y1D1={&jiy?3Y&CrOgd&b$WdT z`?a1bGB`Z?*&(uAN6pX4+-}~1KAK3nZH0WT3YD;K`~Gvb{$~7{VABgu0UYGUbXY+t zfFmjHX_2Hy`)*s#tudo2KJw6m7T%PBYw@fIm)|qs) zwB@-^ND(odd*qU0O18+&aULGbo_r{@+LWo|s&i{D;;`EY|7{%GxVKz23aBGOht7WL zj8uvDr7#Yzwwht}+03RZ!!z;q-<(;O4#{5=TJDX~oOE@x;HN!%OOj)fOjCm@xWQr- zrTyqZaN1F7$0LIM@?O_Jysqr74@+93c^6%zY0awlZ;I9Z$;i89rlu$5{l$N1_&CXX z%3zVNSz?GrcxlyRH3(HooMk|WvZz;*8nH=MfSEuXgDPvcgSgc#-pvRq5?8)M$H#~F z-Jin1Wx*$ea}h!AV7thWh7q@0+pn$LOtT-|`Af9C4Bu||NZ2Wb1lgoDPQ+v=G5~3YYXrcki&f+!Xb*b0&N2Q7>CPdoEYK;V;PmP zHhV3Xg!pa|fep!-9OVI5QR1)uZ`yy7#=5#lDvIrXVJRO>w*=M`#ev(^H8GdeRLYxG z&U)h~C8Or?G~-OoLZr%<@JMamysf-1v#F6%*J9c4zG)bQ1PUZvSJ$A*5(9WaBNAZUDm1sM6nK;r4z>=PG_6w43Akv4A8)Ww+U~oP7GT!C z@Fu*c}4Z4N5;2^u-M{ zWRL7Uva*uBS90uRWY6qPj!ig5){%K^60%q3!TCLTf3Dy4y{_nwROj`2KJWFoANS*) zgyqX>`?E>kIgiUj`5`#2%1Q_jLM2t*4STEM@?e> zG*n2P+5k2LP+tJ<5eX}Z@iCNN0gjtLkJ_|5rVS-FzMOi5`gsosOef`S2hoF$64-3q z!y@Jern%fNQw58xh+PHY-|EJHF2Mu@9xe`awD$he-~Ps8YX)?d?zJ~;v6)m@5*Jc( z2Uf*{q`m&U7_0q|JxobrcX*s1Ebj6hrq9XL@|tU5;$0vwNK(#bu4WmLs7|32yiV1a zQ}P&7g2q&IpX1RdE#Ql zDI5@5PB^7+PRkPe6Vi3D`gl|Dfp-0s(c9l2=hcoYz%eCHiXw?+2Q5o7P2mvoC~~^A z_y5v+j|RJjsYGmM;v|Z!A5jkiu?d?suy$*a$B@cX)jmE2Xd>Z?;IE!}sTPZQZA6Om zHe3AU)R;0QqyK~;(XTKG*pQoixNvU9W|hMYmVY2f8?EL!$xHET-S;_q-briLIBR^> z80z6Rw_$fR?bd*of|}@e?`p$2Yh~vAPa}P?w>>NVYLJMu8{Ue7Jn>kXb*-%pgB{l1 z+cNP!8;8$r2SanMJHkDiU9_~=)ym|>J7;M$b0_CC4>X|}jD$3_f&|QjK&ZE2;0_P(IFf zN_Zx*WYxGJ4ZMHqI=#P~vy+b)7|FKDr<+i(zy)?J2|LYsPK!We%6z2X-nVp@R(Epn zb(3pcKbk~jm9lm$aQA#!eIOHho`Ka&ye_fB3qqtZqR;MO8iuMLI z4`;7(->YHLf{9K^PO8_C;3olTn{bkMt&SYM_MtCdY3+xI(&}!yHje@KsOHQ*bLx zdqfZ#_iN_Pq%N3^0AcLrdtpU!rq+VrY*HyIKS|{Y;p|7FbojyMl!V)~qH$x{DI#*T z1(P}A@HOGb52KxRTO4NJCRGiJ)2c5Bz}kDlj$I0Fm_SFV$!Om@nijW#L>j6hdmjz^ zFVqAl34k44Uy~<#1z@Qd|8p~5l{4KZj|7UngJ}`yj(2BNkZ4qe5-Bmg0a!%9GojTi zr`TUlagHF))WKyBzUl{;oj?g}5tdZcsYIR|2*j588xTDrQgiP;zl6d_#DDeKNtCT? zJ@(4rtBh~NOi}#l_vuK;7|=|>EWYUEjWrS(*cV$*NP8&R>sQzyk0}FQF;LNXZg#A< zSjfZGvko`I9%)^t(e@3_Syx{D+#&Pz>pfee=h0c8Vrw5Nh|_Wv94g~yDtEGDar4(p z&?@QY(6)~syPR$}y6WOQjdk);HOH-u)}>ZbH%}u-NxlvrDw}iWmDi*dz$sC%ezS)^ z6EV-$Dhz0Ox4*Q08uow5q;DTr-<(cI0x5U}i;s3wCWF8Vp0S$24hz2&B^UJ*2RNVV zwAEVeSHu=ImFi*i*HYG3IUPM_7ZC?YTHR&5(L-xFUQgz@oR1XRc1i& z(tR4|Ppyx3@SGk>3-IZ%@%!sn(j>~m4Z^cte*TF6(Oe7z4O`Eujvzz1AaLR(fJo${ z@I&V*&20ZavbN89>#bjk{Ma(ZtnXw&x!rdRZZg`FQUJk$^p=-g=Gnzi>!J_*#(k(m z6q4rE5}rG0sv5puBeVKGj0)F@5xR4m7k$fPLLFv0`EEe;3VnZ+BD*~oiTV$$aauQ%uYAD z+N|vN*L%7tM(Mf}VXW7BT@f2Ba+qgosHCFu%Eylf=JL@mDJEfMG)-wjJBkn%&7_kj z$J1$oCfvN$_f}P3WXXxG3i(AgeKko(M)kpT!x0)rT`F^<* z+ohP^#KD$?HQ*<(U}%H7{=M5J;Xl4TroEkvz+;a6)(49k$Lc%8tha9qe#V+x0&@RU zNMDbfN&B+S`oCx=(Mp2E2w6NIY4sM55USNoTvAu+!}1SvzUw7Hv-_Y1S>nvkrv8Y^ zJ(91Fdk~PYJdimE7S`g3Sl$F}q!tjYlH#(}vmoR?9C&0BfK2TWS$q?fN~cC0lgoFg z@BaI;u>IT?tNov%>~mu(5tjc0^G5^+=ZdDv;2oDKh^5^jJRze``gK9;wUF)POD{bk zUKS2fdU71?bTQHs=aXd+)vrq@fLH0e`r0qMmc{mJif!upUqn1vrWTt_H)rDSiVHQj z-YuTR7n2Z6GCOmSn>2v;d5{xo6y^?IL0hAxYjh^`%;_f2>YY_IGD%%L7c8w@+#iUY zsOeXy!<4%7w8nWoCVVJ1*8anxTHPKQma@npofc{yLE2MZoX0E@j@<}vblBRXu*0jh zpZVpPg;LT2tukIV!fNIH&DTcgg~JKI3uLXmyiqm|kj07%w1EN|X}jtSEMD`fo}LAy zG~jw4N4yib9{hDN(g|ZEuigfmGqPrKcUQ9<6!ay&B3Mp{2LTC$1rzP)844h3SAJUp#@<-e)w8-@*OJvr0Vt7v< ze5^(NIF24WSPtS{wQ9gjb@}AoX&Z&$iSg(!qT3L1A97<`j12Uoug+E@oLaVa+bG2~ zqxwk`=H-v{uabqVTaM%vQ74Lxiq4zKN_e02jVzKG{kbEI=|If>xadKonInBFR*6SSoq&8BkN9XZ`w&!$fOPbVynJ9J(# z+CCz5k5Gy#iDi16XT1nrJuU1J5b_x4n~8MEy8iY=uoA1MA(k-Y6bMRl z%E1x5ySSMU6{_By|3FXy+RO-N{n=$yp4g1N(7{;9S30BGF6OL;4OL{zZD|4Yy7C>U$_`TV7(q~q2KC!xoz?h1<)!MQ5OTg~C&DPb62kqW|o11cx$v4gb z_8|+Tt|~1bhE!Fb%jQp=LWfYrIsuUoJtt+?5D1=b_oU*p82H1Q*5GKPEYK(dVv3aOJ||%s%wrbS4P!j$GBe~GO>e;$u^r-9!`hxQQ{En z2G{1?7T!LrDA+&=7;d!#a*GxrwGdsWO1;B5Ra%%1cfAXXHeK*MF`*1zTsRq@;ZE7j z6Gre=(l{u?7SsSce9Jr4dU3&c^ZMULWY$sI4R|oT&I}?`EZtBx7gEEj?OFhuj*=i(m z@))TEa%|Z8U6~~hXd%|H5=X1cB)hf=0;Pf(h_1BF7{x9uj+&j7jH@;47Z}#lgkr33U^o@Y%N+INBAkR|ka`$=! zV)i{r>p$IY*nsJ4r;PP^kOSQM?s7n%UytAS@^QC`!O455QN7)B zH*O9=Ox9V?Z{g%E9&;@lAE2>LbS`dX;W+N9u%(vTWBcFR2GGmhM|CZSeCpKZOX+t77+r2?W|9c|K7RGmgMfV9tYOp)! zeT?kglAiDWwz0Uo(d;}+fhFcNUyF}IehoktsJ1bo%l*2YbWl}p zdVAG0n`sEofpUY2KalCdFKZ8?5D!+rowwpPKNRyD_&YP!dhr$9kJdP4{d06Fh(o7J zbeVpIWn!Uz^}kprv)(f+$LW6t2}mI+Z2=|+9?cyWGQ+FujURkwOlW8TPARq|hLF<{ z9~Ekf9k;A`8?4WZ0*Go|RewJ!tBj(-!LvpDr9E!oKG1=p8`^r2^=63iwLRK8uO!a3 z=&NvtAOvG%g}%$LMTaNG=du>LR`i%3#R`}k2YU1)cF3stkq3*F-|}=~HIdHZSRX;A z#*a3X(6BD@jMtGq<+?J;5UGhlaFa{RKLfkJXc10PU@j1}7XZ4>=yDMi?z%leTZq%S z`?kV3W6`Z|JthqaJ95bqFpo}AlEJez28f|K>`v#~r{>JE`J)a7{sHbNSkjcw@l0Q- zgzl)zxT@pq1@ai=Ru!3(qNOu^c6B+MG3&C797kBe1k>LvR`y#fw;VI4laT+2kIQN} zhU~8Lznx#k0I8tazfDuYDfD#PM6+~Vb=S3f3+_gu0G?!ebhT4989Hc_rrI^p;NO)m zBhYBBKUP*sS>f(1XFKC^(IY7Kt5ie*CQ|}5998Hr2WY?`5%y{AkEfSGgk93y=AK-D zJwPbETdU>JU7^gxDY|7h6ndiAlxFQ%x%#NZo7$ER)9!glqQhL{vHlH^92bs#%>*o_ zGZh=?!DC9jwy$=bI@uaF7Hs(43UHQt)yk>UxDmfw73nD#y$?IVW@p3sgOxeUu98d; z!_kH$w@yb6zORpYcg`XX&rg>|F>Wh$`CD8iJ{Ur{UTghN)!skkbQg!t91%UvKMKmi zfZd|$!T^|;AR&b%52zL!6F~g{A;&P|33urH0fWXnPG2_1QpQb#)JUbxu`AyiEF{_t zDOPlXGB&w6_KxC{K?s_uc}YXfC>sPnq6-(PxAZq8K~`J9jF`t4s% zW?Eos?>1~08S9yL*C@U<7nvmYx7vKHY^qOqGBYIO9S_1l!^enH?6&Pg&KY2A-+MAxI(i!TbUz z3lX&Ur0jQjDN0VqtEChmuBH4 zls@ajzM`>MrNy*X>4lTSzwd)>+09-(C#93u+wsO%FX=xSmC1ao@Nd%D(U)*N6(zhX zJBsnj7$7gQ?<%z}oU@L8X}G}gzT;n#5ZUt#|84H63S_q#mK%-ph?+z1n@^>FM?6y_ zbL(T};b0hqlyEr*42ZHCQ#FEq!uX>0CUwRF&*|FoX3PLcwP$Ar#wzth-unc&I`Sy_iOCkg2b#tY+zXj~i9p+>XDD*9wm;}<^fKs~wqZngSCE%vB!$Zs+p@zM)<*7I+%(tGi4wt);n9`;^> z5YW1!=d4AVQoWrr062A|YJAa|b@`!tO8!VV8zfrtjW}wjxK`~40KA}(J#KJY z`?KEqtI8-{4V{2aP=}*FpZ^P&#cPg7+M9#cloLm)JEAwkBkhr84I$xUz38BRZ2-Tf zM3sg2`8D;ggt5EsW5tCR7g(sy@H9cm(;5;Gov}cGs zP8tY+jquz4>{ec{bGu}nWfr{LiVb5Gxm>PQxt8~_o!QT4Ydh#LtX&P>_=AsOQT`t0 zwiR$*0xIuH9)zMMiROlV>M+0;0Ux6_KKDh|q9#N^P|S7%x6$^W0uV{_X&|v$Jk>k!KWGD<51H35FQ% z5sop??a+O}<{^gNsl5-?Y;l>ba|9=}GTJh!KE%3HvcPxv&Tg&d|pBf;XgPKnLo@kH#E*_Bzc7sYkkD=5$ja zh)0MeVsuOtmw=HTc-<49Qlygv)2W`^TXRt3J0uCJl-lKU{UT3WZAHGMFXd}WweoKP zRmRcgVsg_3i)`6GR*!B=6N8{b({^5DA=NKEc!`NY^%a=>tyM)D5hWVyWM5W<_w2hw zg{OKE5DFn6ev?AIZAV`Q`S0YACpNmS3R09mI4mT|&(!(p2kkodm6P*&tXN3nS34E; zlsHYnqD;+l?mo)k&FIWu=F>kw#%3d~R>iWRDFj@%$6nxOV|TV?GlwLWU;6I=MgI-Q z)b49q?EHrC)B${|V*4!&Bb?t_Vjw&UyC^ryZb`eez;oXTaM#97rSfJ8p!4FY>+S6} zFO*ZXtk|p{8CQzmjXLtW3pw&4n!O7oLuze3AJGMaB1HCPFa<*H&MIqpl2qdX2GZ6n zx{J=`m^fY>QGy>dPHOz5no9@JGXDGLT!^(;UR0L9A}9r_O#Z86l*LM^J>Vyli?e;3 zs&zdzBF6K&2GvJQ;F0{tiw(+4l&lhauz}Jt!N;HPfRKG1sFRNT-Qe|{ef%OY1sKPN ztk=JZcW3;E2pgST**AnP76Ix_VXvUyZo=_h8;cRzR-76mF`fGQ44s~|o6~qKpw|aj zec^odaS10!Ce+tc8=2cIXNOM1!MGYuwUP$B)LehSnC`?Z)SRr?u4DK@ z1v)z*IkO>! zuIAt$rJ&JuYBSXMsO<$SL$XSgH-=?lA8b1YVp_e;2|8tJ*Uy1=d}d1dQTu}7-?Kqr zZS7YziHlMbN3Rb`JVVpTJBaAF6V9UwIfX+Y>6TPD!v4f{F_;XEnbJ+}BMEa-zxdv} zW9hw7sorvauAuU*+>#X60B+g6gxTWl?!5Wa_tP8IH6G1GTI}7t7~o1wQMZltleBlj z(7{y5{K00gqWV~OdH1kt(Fd#!dRYPu9c!!E&gL0~d6ZgI+Jd;+^vP(SOgZiL7n$z2 zNBf&olQjw;Q@Kds|3xJS7rtt;9jaY$oxd>A1}nL|r8<((ESU(UeuWm>wH$@j`z^GbAyO(>>2sa_{h+gREr#g@xz`|5+0ovt4oHg@)G3b(=qc1L>((oDZe0NN@n7YP+!t(2X-nj*{9 z=!$6F50z_Q?MxJLG}}UebxLL7o?P^w(51|A%V_jFT0uEojtB?qSj|j$%^?oHeUg@2 z(*TIO6zep!qjM*e6ygFByp*Z9^W$5J1{E&MqCh9ww)_2l&x`I5dZG*5eNGVcc%Rx3vq##P z3Cex?2C@RNDCAs2Pz*@AsHD1(P=1;mGoi|^FHU^3mL8>(pEUKerEvF2BP;FpH)av= zf8IC*T5M_|&CI+F z#+T#*j~tQ9EJ6WR<)r};gY)I2mj)=KStrlRN3-m7+veTSf(qx!o}9$kW>6TcA47+m zpSeW`by+<@^#J!eY}e3JI?-%N_sPiI;B6WAzwxa}6MgT|QL?ri7TZ>_BbJ+U#Y#Yr zgLIH9(pS37UnoKx;)Xxq2Ul@Y02z9#q8U_un(VHaQ;WFkH-3Oyy*x+1_mM?vB5(T} z7)&6N2f%Ttol5fQ_W%R2_sG?hfp?*Oc_rH{v7h6Ys&q-D};aJ6$F+iKv49E5rUP-wdyv+LS3FeBYk!6DBTw3iCB}&O-iR z`un)kqmah>)Tf?w)z}IjbBWBlgUNaLUxeQ{iKlO*bAyj=JOub9_UM+ypk@mdQ7+!svbTAfv zy7Nxppq?^pZ|4Ls01@2~_QDEr)TmFJ*D`1sp3ggU5AOkC$J$B#?F-kpD+fCklnZ}- z{gVj?&=dM#-zwZ^_5dW#KPiLy+=#i_kcghhPiQQ*a%|=}b4f{;W~vNp(}wgHZRSX{ zt|&Uq@igsfl`QBIA60$4QUTInh@Zt4OqCC{RPAx2`<`KH;;I+FiyA7Iv9-t5(h7L+ zw?t#~vTnD4Vry@wJya~eWV|KEafX>(F}5QA^Rsl_23!kmf@tF~Tamj(FO%*vyr=fX zfCbjT&!6}XU->3NUlKdyTdFPg@$FbGBOW|4X-6}d?dj;frgGnYr;^&1_+Yd%o!T@%bJ8{Fa4uVaGO_AsIri^gn-4Uy3%FBW4hcPeHZEVZ%5tyHGkf<#IuJc= z^ho&41FpCff#}J9C2tInrf~AT=->?KzKIVdsVZC(MXV01j*`ijB$b&j6d*>yw7gF9 zzN=W#++o9ex;>y#`$zm0tSXW)vf6#^0VO9A@q2f5EWY92>bP}C*wBlE&fS8PD-Va} z6O&N{eEVO|@HH1pU>o_~&t}zvzm7+N=i|Kv!;!#6;N*?k> z{mq$Szts4XAW#v+980t9&b?^Sz=i%TtRJRe?q-jMYD~eRChtkpX|$S8;P>2n3TQMj zHStR%Em&KL&m4dMOLA`dgo>25yytQ_@%agwj3nl}AL!1#&>v>*$iSg&T6%&8vA{4WvRLJ$b*X%FZk^qlJ^Vh?F9z1d7%l|rAtrAr7z4SR( zeHl_V3b~JDA~sl4S9q9?2Vcfp$wtf%I_>_cSRNXm`0Opmfm1B|Y+)tbwus?Pk&pBy zm5Nl*;CkTaCK51Qf%ZyG673$zEASfF)eA zR6gWl#srT<=&pfr?|DQvB(S44o}bXX-$TEAA){EJaG_ygvM~*o@V#`dwUvP*HsQBM zYoXWhUs zB2hy(@5s--n_%l?cyGg7_~@z1^95Xnfy=jy|E?ZyYbX10*f-u4d@t@k$<~MT@09xW zaK>kGu=Aqw=gysJ+8<>S zUV|@PS^?5$XnxF`LT+yw z(6b~+a*0G9XhHMDtsU3DESKkPeFEq*DT)0r=6)3*XQo7xjJT+oG@nWj3NPPFo#b<| zGsxLWEoeA?^mXBAXo}n-t8jB`61E782^A-UQ<4oJ(?#nAHWb%P75oe3$CtC&m*4NqPNVjPl;n{ToG zkV!9dxJC({O9-}#-l2f5$s6RVEiA0-N^eCfarx%c0ZUwi*|8JHde0+6#b?8)}ez_(?~kT+W@Y$;;u<)cyN@qaYL zkbQ0gRU}SPbSBrN6yp|?fKi&H^i-!iA}0s)Ad}f~b#UQfYDqf`VL3RI_$o3s z#GYW3E$2Pok|f%y_{*xV-|jHK#)Ab0K2}59lQdVu-weX$!@8&W!)N449?RJi#fRcu z5y1ttb4*wy^mDxyQDD|C@CiL>ANOxG0PGqRc>OC}f=Y{0VMH-w(*}m;Kp#T=aDH#l zasvpnTqk*;JU29#-2l(M4O-e{IRiE#QSVOO)AL?FvkVWvY_f0ZrixQ zfD(gza=Deb=sjN$H^J#4?i8*BTX-+NE>1b4INzQ&<+Xp0cV^AV@AV#z_thuGX?b-Z z2`P+sz1fI6+!*o8V4>rOs&P!|SLeWGIPVXbSfn~>e1h4S^<>U3{T5{6H-k3b%Ihuh z7bQJ^1vhq#AGU^dZB|NFKWJ(qH#s#kbVdvJB6YT;f-7+@MbT$Q#U*?8>Tt97TFk02 zIA-(|RPVI3x$qaPlFtaIvXFs2+D&T{NWEbM^HJNL0s@xd@! zoNQ4(T;^oDBJ}VM!8;7MiD$dgP0zK;geBrl{my<$;pNfgu5>$Sg#dti2?#iW{-jtb z*8;g!!%VM?fTOG(Iwy5H;)KU84}x`YcAzoptEYNYrb@x>u?Er~%`6v~*WSg&1Dg2} zlj#eE_4#Umdcp*9zNkE(7H?ag-pRK`?E=-W;UE|&$_n#GI?Q-gmns~la+!_AWS=7= zbQXm)r>`#`NVAzFH~u5B%j-*p02ldvL4R9Ur1>gaRhdt=eL};g613*LwU={>tW2Ay z)OGiT*RHcrrb}2(3_Agsb?iIjlAbo7uo_tZOx(l9{fpcr-auYpu?(4XoRv!iow0te zdO%b864#CI?$@y|^SGfzuOAtPaLm8fQN*GhX-Ch+d5!UfC+y)hFN`#Tv@C26je!;| z9K14W+H8tvV>vsTMdfHiw=Zys^Ok_Ut+UX~u2?|jbqyHpi-U$;j~wEbe$mqbBBL%{ znq)};uQ81{93mu3;I6I}#myF}es02(weT51t0%TFlE_(AmXtue1o<*Puon+MRg;sN0K+-IGq=Vy-Rc*6MOG`@e)(cMmhLM=#r~Yvy#J20#2~CIxbDXXn6D2Y|5Ay z0WyN0aM&^fOw+YG7R{XI>TByg0mNX=B5(JIyiSI~L6I%C^3VzzCvszTxZfw*ZGL5` zTDFZBI|``}uXTK{Lha87?IhQ}OktpX3}XshMLQlED{}M~PAcU65Nh!|X{e#v!Nwi; zyf5+WA13UfX@rHTC@K=L(o{PN)si2a(-z%;%GklJ|6LM6pp9b0RqoZ(Zp~531eK|B z(j^8oK&HjnfGs3A_G!p!Y{Hzibgao``V031)MMN9k1qQ<+egpAAvoW)q)?g;t-w6tKW`A!v0a8UV&_#{2$$v=IK{yL_g%K8g_hLW4Kpa_M#>YV}fLvBTJ0emy+Je`amf3?aZak9p^wn8EHU5NwOx8+y8lu__MQjW>?o@Yd%nx(XcovYwt7@pE^y5vC*q zeC%J6a=TxESZO9{3It2hXeOZZl6TSnPuZBi?f~1f0tir_G8PM9b#p7IA8fVMAK2D0 zY~3Y00wfgv5v|>w%JoO)lq(bTtUv|$6{w4b_Fg1c6i@&(FTqcWAc~wPi`x6BfXx_c z3&xhEtn|Rs12Edd0JK&YYQC-asa9;XU)3A83TIh#ANCQ9JmFgrr)YCWt6ltn*3~YW z`F8DR^5`_4iT`7e^alcaK`95inv(i0`f%@?+v6pQT>O;N=KeP@^lcW&%x)MW!^RaV z^4W&+l$VzD*4;ay&+!mYLDgW^d4mOcECpfRdm0vPYrMUsL2{|q!d^p}m za>tVC)lWZx_kW{SBzzH3#O+BL&K z+V5_~UB^q|)FhKI7Qb*;B%OYY7llZh8)*R-nF;&SBMgF*^gEsCd?6P}wwm=y(rCD6 zkJJow@=-or4Vy2ZEfglLUwu9AZJcN|96X@4fRsOV{=_oL#SrFjFP;D+o4~_G;(xBe z=O$B=dVhzI5F-RESE41C`G{b&r!-nTIcjb{OsT$DN~vbQ)6X&79Q4X4%I~G((G03Bex%D zDZe7$bWA;;&$G_DUQIIZEw6WM{BqmzpkJa4jImItCvuxp7{AtT8umx?Gw~xD8c6zl zEEaPSLnNYil6fad;?V8=G0*htl#Gv--~3d~|MFa?RSW5%^!aFH=Dn4QgDIQ8ZuU!k zWTiFj`Rw@_=_O?z#^NL$K|PjyM;7Oy+WpO^n@j$iH^g@Uu;2DEI?!GcyweMPC#=F= z%4JMbkf}WK{y{oCZ4z(px-qC9y8aCMBgD(i4>$?q7kLgHWFNAkgAR57OsEf(KACKT zyqXUK6Ho$;@M#_J-bkA!8=j8qz2P}3q&WpO-LHjn3gGVTIAhZ;qQc)_yoWOKHXiR^ijB!%MMzhzj!|466aSPICXhU*H`~KTrR~dY(!JaI`oo*N zc~ypFWG@iyIeuSQ_6H=_=^M1I*MbiBN*i49s&$_Jx<|W3fJ=n_@;$9OWTrzV`#-C` zZn?S6v@ZhRR&>Z%e2kl+y;?~lFUMCKDD4gkcW^2%Sh2o&z#^SR(BHjw)EWB+f02cM zM7}!lMnxY?NemxSFsVl=^3^;p$&^cjJcY_@0;xUG-$#1A$=RKSq1ZZ=@pr5PANM22#*SLX^ z8k&@O=wBb+8Pb1XK0dOsix$E2>Rj$KT(UR z%wTu~_9v{PzC4LY-l+wTvtAS5i*}Gg;2LKL5={Ua)1vrF z_PRgI>9m`l1tlQx(?0RUFucdN7`$finS4g&>S-z|`MDokc`wtT_tkRLV#DWZyOq8QD7x;Sc%PmMMd+vI7C&LQQ+A+G(N!BC9Wztdn?XUuI{7PRpm?WwW-zzkQW9 z6krdDmDnrpmorK4HFE8vLxlg!K+*npe&G)4Q2YhI$@$sJfXW|Ibe$XvB6RU{*W)2@ zAt!gF6r0_~i`YjI8gRzs3Fv2`9W3>zeh9f*x9xDAvJA6KzAZfS*@>s>$Na4D zGgR$*wL~Ggwn3X>VL=Du+D~L1hKLTUIX+_msM1sN&T;?|HSLeTbxfx5#5VRm?5hkk zvV*EP1=#m=LKoUs{M+uQ-n0cUV%=^}n5!F%@sVQytw$K>{Ss?CwyhQo>|HIiqutC2 z+)VxN3V)a^M!hKaTFWmkjhA`#P&4>5GK#NqY*sjy-a4ayWlcQg1?y64Ufk3)S%iAZ zAivf4Sijd+*sfRZZ`Fv~5b|MYba?b1C8@H=c1W<{jB)0tBZ>|aNvc2epJRhd@p6RD zT<;9sxi|DfFx!{FH52C?n|5i7mhd%(8TLFKi(UB^3a914X@vI~_O}tGJ!|wqK2SBPTbcAw<&%xAVtjXZU}1l= zho0CeYr1A>F*XAUbE4!<(>Y!QgS)gCv7~5O!D)AN&@g?L{*5jj{B&Gg-%< zLTWWgv+1yiX%|*bHT5mMajBa52B^j^zy>>}D4e3WG`6f8Cgo5tZ7`t5cQ_*jC>nd3 zmW}*L5*n`n<$&ijcJ&1gO zb+=vuGI|@)-#SKfC(mQ-8y<=;9CAK)St0GHXf)3NmE;O9!g345A{h^$3Ip>nUsX-6r$|)0#JGSZxn^jUPyV z4J-|`3cTr|V8k-~|J$ldOqlW!M#|Ey?7}$ut3D{*GD=n-x`q3jB*;w0yOrk>-6JiDmn&^tI5 zoT}~T23zeq7i|9U_d6c})t;|@J^*uDZ1KK=v!&P(C^6hkl@>3d^%(g8ql%(}#$C?r zEx*eExz4>!gZ0{roki>EP zDq%gOw`pAUEe{pDfQ!w2?Y%?qtXwHNoWIBYh!zZkOU=s}y8azpktqF4n#UNS9&T<} zKq45Axa&g?#Tg0}Ah8V4NXYn*MVR(+l~*-a$abYcNR{OP0_pqS(G-bq>X8Rkh1CEqm0w@=0;#ntNb2Y7C7A30Jc;$tLDrU=a2=C=y zLh4ksca&eNc3V+DgYh#SSdojO;w49M+tAwXS71&*>E%i{RFXl*7E zPYY~wI4<(meDrFXxCBh8rGC+F@jl^y_0td-OkDU+ersE}`V(H{!Jv(SC-$Bg?hq%6T zyIy)d1p^trHs^FQn~g%MwNj4XI#H~q|GY`Cc^b?PYu9&YZP~}f&S4I-6G)Zw0}|Uo zNG*QA5M_k(o7U8rJmvuQR|lKZ9vJIX#ihh)AHiN2z#%`Jqc>KS^Af(ROAMygPO#{q zV3_teO6$raT?fpPzpT5N>W@Q;vLiH5+cB@QC`<9LbQG)o3^q4)DbZeXP2ik8Uh2?k zjLmCU+Cgl6{k=Ir0M72B?ZCgs>72pb2{Y7}WIr${sTb|0V(duxAs{`D3G@d{B}VZg zT+B`kvUgLD6(DiQWXaXf}dCl*F_Ls+YI=c<$RMqURhqR5VK#1XbJ6zFte^_IV z4-A39NRuNzWQ|UbcYz77aOJ_WlWu^qEKlSGdOSGcr%!suIyf!dbg~Mj{9Q94gCuy6 zszMS5551X*apcg620V1YI@5K+NypD5!vh10U?}?vPqHJS(PY56RNg9MAW79k$=LRl zr%jtW-TaBz{o2gfHNiZgB{XTSX`HhJWL+l4^c}oQ44MCM$A>ci`G}tYXQ!pZ#sp(^ zY)P*zDh!Xt$QEnPBT!#uy0xic=jp)FamJ>d{y8Pf9o1iVF@IyqdbnB5xc2c}HLq?Y zbSnMkZUxf~0jBRz%zIWf*TLiONSF1XCJ7;hj> zlH>Pz;UPPypXj%3hZiHat>RdglK!{rd`xZ+K4bv~^dSHH1v6NUnN9amh4JZ;DiajJ zirwt#RsklIPDU1p#gh@8<-_YrTE^5L1{cc({l1%gidHm-IdcoYJmkB1_Z=3W-h`D{^ALaZ zHnz;JNsN0Z(N*XFiFLN1f#>`Mefh*VyyH{1nD0X@PwCJ0^?RO_c24 z<6st9Dc;>FZ=NV4v`tB|TlgURHVLFAP6wpYH$k-I)i+@#8Akfk*Zr_+E1;0DIUP%# zWZYy*WAiNPXqPO-Zpk+W=vgT-7>mV)>&>;Mf0zp%OTUsQ0N5c zGn|l|I`z)uLhQk}bW1=NVr-r-ByhWN45O9v z=?5?=uHwQN+1In0qp)a)WP-NMK~f%=H^lDmKlaixh@>*n6F>U)m0IK!XV2+R-B5}m z+EdTxYFw6FuL#hIf@Ek3AwfkHU-ZvF#5up8&8!N&6cs?`5T{UzC0jQ;-@CzdSxSg6W!dhZ`n1;C3rUvfHq(oQ^NCz zqI%AH7>JOxT7MJRH?**i!z#Ac3b5H*xn6vO@Bg!~1zv3ZNJEFo1yGFkH`TNl#kA<+ zt8Q+4!@WYG_*dMlwN^{R?Tt6X;sn*a_m%_HuhRhG$qwjygvt$zA5Y*m;h(=3vfVgJ zCC0#4d{Z^lp1tztlsJ(mK|=M8;KJ~XhhJp1opGoG@an7@U_H>$b7mSmC=MT(w**OG z?oF6l3j8ykQ=;@r7O!N+tLu|VYe4T=!Pg$B>6z2ZwavQj`2h)+i{I7(qEk=ul8WVD z8v)gzBU_H|08HM-zjcQ<?vkcLw>)c z#d7=aPTZo}Pu}0$iTE_yyTNxlRp^3E`+VuIuV%8^Jb;FT4x{?dz#7Hf$HyrSxb43G z(s_qH#4C%v3rfZ(lBc1c0p0=9azHyyvEz!1;W4H$`!4>PpNifkn%-&7^*jL5C)!bE z(Ah-cfXl&U-u^;k2avCEs8{%`;Vea1S;2=a_jyH%D!e4_W8*8|Iqpp2OjkV}vo`NX zVc8HUiET=~VII80y+jF$w_7B>AmYE*`+Fj<1iSNXKC`h)x{Ie9*kib-b}S=M{dFFh z5unfe9%%sB&63j$r+UKWmM2qRl_gFrjIRQ7m6Ts@zEg6_9N54`VcJ;$guo@*4 zPI%ehov4ajR=)*oEFFVEBg9~}k~GiDzdI*2~) zE*c(URKk3AAZq@f0AOX@8TuF$xga~h%^P<%Aqg-V4XjPGHM?w-52(Fv-H0jct@C@x zEDIVx@p`+wpw7WlwznvngxmN9{(2`d;o7P4%_2ZYUT)D4qR<)Q>9zvKh_VK4CI0$q zwM$L#YFT<^fVVE>_v;povPKa_k(Y(Pwl}-h^*du9UWHfnJa(raq8tPszed_S7CF@i zs~evvF4Q6j?tOl57K7Iqw_}i(O+b1VG4G#cP*AA0XB1n9Z(v} zjQ@&uxDbIkGA8Ge*z*pa`4m+I`jX!wG^RC?H&;FQN)oi@!Gk=nmRIwXr>|_&hsn@_ ziDn%I=cD|wRBQj26P20?#Q^UIt8P}tL#-{8KOPCi2SH37#%pcgP8fuh_;Es%<^~<# zis#oBujg7*yYB++bk4`BM(9#p=8fA6d)XzRgwsk5f^AdWbGyV}=m^HYLiZdv*=v71 zuxr_+YK07y$miO!O#YpL@h0ATgf#&_baOuYA>V)Og5;8zF(uX|1RrIM^9sEl7P5N_#DzPHTk`-FMIy4@ z8Sfp+8?g?tHn(LiId=^%7TZ!UEHXy%A8ZD zc8J9(26^iav-baM?=7RE{-SqrDM3I&5JkEKM5H97hHhy@LPADn5lp2Y`oW^+jIg%8pWw_c)s==~d`=-}_k6T)l)C-To6 z&i|0Ei7z%O9e9CYg((?}=nC%*^7rZUYrkPhd5y>~lr3Lx*e%C@@vCX%a$UdG{u1Oy z)2t^mYM0K+pLq?8!;haRYJvNp?zVvd5eVXru~TB!%fAd)$%3C_Z4?RO(PLCDk~UCn z%J>V8_CKKR!e@1+`M4N#mT4zX?`~+KIJ4Jy>0#V;;4s!f$yR-fVts91 z*s1cj0qT>o zqG?6=KYYMqVU8Gusz7y$vRza?~h@ALoZK z_9;d4j%br8nw00rLzCzvcU+x#?3;!R_{({krljXSn7wYs{~vXy7|6&7x2e4hqjkLQcK;|J-jC!{6N;7N@SYkOaCh!9 zUUXv-dM&(R5Xxecc@i2&C62Q16=P0~84DSs3|9*({_!b?mTyz{HASWOoKVnQ?AI*2 zP&@|7dpgD6QDWsSKYXa}H!i3R(m?=bfZnJJGKc6cUUew_M1KRr1qSq<6$ToFP&Mb|i(P|^{I+n;&JuiF zd!Uya2U-o2RY~i8CU2t)Kzj){KOdr_!ptR_P)X^|UDU`Z6~j zYuK=tXE45(v%A@x@qJFV9Ph0I`o!y{M;|r?7YPf^Db{|Ku$fUao(ivg5srT7xO12< z?xUK({|*M|brDUFVhp2*JLp$dc!LAvH2>K8#Q6d=h8f5313M&W*wv-JA9x#4~feW>I(w*_K#^_2(X-PL$# z_kX`DAwk6&ujurwJk$Ef$$@>@v!0zkdVC5m?_hlfQfWBgDDJyq2fgRD48MPRC7wcp zx<7X-pM$iT`0YL0;0wF!()}%PTOn8k?ysqyBXj1ii8KMOYoAgu{t3=IbhUTN_6<%t<4J*G@4%O-tAGBrv1DG{Y3 z`iR3f!@?+vGAA2>eP zLq4nGPinNJFD^_P{cYP)aVs^+JU}9fGO--GVqPxl3HTbL!Nx#vaVKUmii41L0pa?) zvB3Pf8mCiE-k7wFohWFp0t8Qv+RccZVglCVMh_=8I=^i4O{~^d&0~tU@x}vM8UD@1 z4Lv0|@$itGLhqotfo16&(!qDbxD=j#;lAHO_V#eevg$W1_Y!&Eoo!Y)!Won5eF@v- zvk22|urbmVWLsRGj3&E}j7gGk^!=$)_s?kNrBm zK%(>;s0)!!KEhmb2FgMn0hQ#pGqGp!ouF(;!NhM~)9Rw+E(rxWJ&6Cv#YU#ZHz}42 z*Na&n-ATn|ArGpkc^#)2{tu`%h!+nBvu5TVDz_4&cXV=b9PfMd-9QK)zC=aoYR!s zI9ebHp!fz6ce#i4%fs?E@X`XSlb)zXb-pKGL1YA^l{?e{eYlh__b_3&X zVpAY|mHt#iF|%q5&sp3N9EHkA_Z==XpeM+X+ClpwRPGK z)tr>1>)N6IHLBu(`h8ZF?#6oue)m2LurZwjHKA)(GszS#f$&u@2u?E!G{5wFh;S4`n^;Qt4vTMb1Cg19-zI@+) zLRue%8^^pJ$91*)3}z9Z$W(bl>j#l@Ln(mf6o;CM`WIv`xVp2hV7eM(WM8ZGqNOC$nz*1q>+#scDfx}|d^;CdSf zqz&Da+a9f0Yqc5j{u9N48S&gBjn^oAsQd_8m-S&%F-Qi$Op?6l;}c~hulR&osVD&!p+p&GzC-NdrFk2 znW_C@;G~CY_hik*T2|4~(cF8vDi6#$|Lws zJ)a%3%RhYW*?3L|#G!UU;{Hl)=TI87-{O2&3E1rrf+rfnHG=|GGxv? zB`|_lBz-PuChBHvph|S66;+!ee2-ZabFr^6j`@UU^&O$sM^N7(tuqLCXPsC; z1POd75u4%FV(=>?pKOCtXeaWQ+O5cg6^<@_W>*3v3;~D*g^hpzgcG!wD*Q+PM5ciXKb>sFAdlR2aN4tVge~C~fU;QO`?) zGS*GwYTxtMYL_B^$kg-*i_KEaCx{r6Zo7w>Cp&5?Pfc$` zE^((?pYb^`@>Ye9T1=ntYi(-g?H;!x z=y-%)+x(#EU5zIy<@%iFwb8*$Q_jWCT}3Hst8U2mdJjy;m0{404A3AbQiXgUWCq{A ztvHmuYqcZxqH?`5^LJFu>oEZ;P~jo+AoWR(Z+|N9^VyqhNfDI3gj!rx83bS9_@>v1 z)+@tnN9^yq5M()@J!cpJO@$GZgw}66tc-=*JaGzIOwt#x0uqTjK1=nzsfLm2v>G_Jg zcf~_Or@QLjE|vqONK|W->}C9yvcdF_t;|xuFJ59?8@b9iHEntGK*U%R56wWmnu5qvH1_uSb{l z%$6iCIBT8YZwHpf^#NS^Unrp(`}}k|g#ogAew>(L8m>|*9Nxh)C@4X1& z{{0YF4(?0#YQN=D0w48&^L*-W=wCH<5<8VigAFkvIBZElPw^?eO$grq4ZHE*kgnyD z7~c~VXMA*vSFwo9e#2l9CH*LhPr+VRw{pMWD9Z8D*pdhgvDh=T@Ur1qy6RP%%8^+4 z=egL}3!oDd+44{5oLxvjdmCK*JNBWbXoJ||F{ws6vwcIVjma30z3ZE@;glwuQv9XY zzJ_Y3F$dda*>&}+0X0~8zeZUU%6y4>6ls-(T%P3DlEj-44$`KO;(w1J4W|4bv)#fd zrjT7y7e|byb=!bOZNQi;Q`i6qe)*!jY&_ijo?fW|1-cn%XcR<_b?MTzuqc9xL}m(# z)ZeiE_BErs84i&@!A8-r%yAC?dymF|+Z{Bn;>7#)oTVw4$Ra3k;{*%<-yjHDhKi*@!)uPKfr{f}M>%&}?iFJnA3DOnp{}n8m1GR%ldEO3U z{c}*;v9+(D76{Q4M|K*1qRWg{^Np1z1CpFUWa9iFyx#f-ZvCDSGGy>ow_Mp>n&g32?Xi8e;11!^j_JPgIR3A_!hE4?gl-_~a*c!-ZDUI-8A708r# zTf9eIw~qT56nNkak8m?iU+GO~NMLV4m`Ad4bz(=deR;e61;9-nH?Q}u%YP|I;mDV| zr~}ZeHuFlkBh&mjtGH6iC=GkJ*x|H>@p;g$^%HryvCeRy!YEA!WQO<^h+jB#y_zid zv7bF%N$e2f+^YzgDyX7r@ZUd@HQ6Tx5b?8U&vlK@q8^r&=^HK&P(w#0_E1Qt&mJ_j z=8z0ew{O*?$?u0{zMiw;k=G$RiNx|P{nc-^+g6~cm2~_f*PpayIG0+@2kU9|uRrNo z7};&!Nh+zkh%Q+Gg< zEFXbPMGaw%Vu5HQ-w%M#d)fg1E*ai^Pbr?996a1z)RAqjs%UPy7Pbv_8DzC zkUbVG_&kiz(gQeC8$X4Ve>c-aVUll`?M(@05rhZN&t`P?m-8qP+E_#Y0z;6nndB|$ z<4fMB3^*y*op7Yra1R&y;qE8>?RxXpa>w4i70*<1&bo_!Fjd4tSuzp`R_ zJs<%M3NyE^QkOnV!g#%~_C@yVEd_&UXyEd^OvL*{j6R*UpCfU6-dUdR3V)Bl`n@_y3T zKNokg#i-cT<0v%xWDaMly7I}<@h&=wZ`Ife*{tKCL^^&;j8_vm{e<~W|7wld+r-9w z`*Q3vn`$y$>LanDsp2G7gba-vaYCV-5EpK#G^{;3>#|K7!D+thqqXOWvz=z6!C6u+ zZg=`=*M2Of!#meH@A3M#S1Pm21_V*1Vz;7Px+~2VRC!%Nt0%mqj8af_mTniElq#K+ z{K3`eHPlc;23@>*j0j9yg(9}O*4lT`NLv>=n{bokv0SK3HY2wKRvy;E&5h+~t78;8 zsW98+2%Es{eDa>a+hxeRQ=&e`D4bi|LU>9Q2UrygGA}(ymZ({k>*b@s&>{%Vw;$_N zh9x~v;~kjon;%DY6Bi`WtNr=26*yb#Gz&*5)I7M=tdW|!uJ?8GYU5O|pt(BU*CIP> z(ljDMs0KML_;&Fy#lr<2Ui_M*&T=Fgz?*^IA4o)zY`SP}VW1fkC*{U)c3i!bwBadX z{FS+ah94EzF0$OgXNbm@goj1M`&LquIm_hil~4kDtSx@tHN01n!qtGI zvs^~(HZCkTuT%k6W%&h0UF~Q6K}YR~)WytOc&PPb?@TA1h6HcZrgC~Qg>R11srVp>b;T6a6z#&f6Xs%K0jU)9_pDEPQUPpo;k1btlqAW zl9F=yWY&LVz-uUCu~?T|SPOn%>65IKnBL2`a8H+iA5B-qc)SEE#rjwR=GIuVp1Q25 zLOOoJJ$MpkSMlVK&I8O8F*b}*zsERvJsvGlGsduTzq+M72%{p;Rmv?~(|x7V8J)Vu z;AL~&&&dT^V)~V~6mpfM_P>IzQN%D{A z{)B{7aJj{Z>HE(85)ITFBSURnT`jFV61`$2EiI16tkM-(@-fT=cgR0JLa24qzdZR~ zGINN3QQ!%wHj26t%3^m=F<$H2WrcipB@HK4ON7O`;d8XoeXBp!7dh?h)0r6MtF&Ob ztH={z{W`L!#N=PK@J!;mi>+PW5*=O?CckB<3WNw5bo19cUveB(Afn^r%c26-G$S7*sO9XP?svF-B` zo#f2#wVX$Lxr$Fl+cak_D{@-*Y5m(J{==(dyxf_FEaCxXa?J;fX5)URo<8UY^{Gr? zu9*a3xooBCuO6OH?wl>tK=vnttxtj;AubDK;=(3*MAz9fJXi7$B}IqS2A@k1hK4>S zNDd#xCu+!1wKBo#2n`CmZA|FjXp$Ih7u zq>9DPBOM66tr3)L&(wE=8dx?4j958TM)+7nq;ho$+IWs~PNP$wg{#nA$#RAY2~X~N zZTXqLoj7OknaxUOBcQ5hyuZSPs=kJ6*T4ey4kC6NFMq%Uo-#ovKBTxoM&eu*m zF*R7^?W6wE_1wO_fs2P>J#wJbM^_7oaf0I?Tto4H;0u}CCV9f~3np&w?Im;VT|9^P z3p)2DoWw#WAJ!rQHN-z&^=b^z`g06m5gN*=Fua&y7=h3izYTxzR|&Rr{)ScAGesS- z+&fsJc(xN*GKxkCqqjQmNsp;Og3qgRje(#XlX^SHM&E;292Y+ku7e7&;j@71m~;G}fYdZ||JBpzLw z+Plal?DxQKfa|uKP-9}8$st>rU#}7Mjt>VO!Dn@sl9jz8-&Hnf$5;_mscD0hkuE5R zDmXy=b`cIuCh?+;G+H5xQMul}B$jpBu54=GYX@8|mW-p*Fk<|3^#JnhX(ie`y|@F} z#Ww3URjhOMe){zLF73+v(@#=l#D_7`lk5ak!Rm;`Uq?ImSCgN4npqQ1x+(7}YI6`z zw#T)q9~KSnfus1H|OADyDYsu~ic zFumaRxa`EaFR|R_CgdBTWE;yt4UBAj10O#o47ehd!(sAF~|y5aCP5r9gGvA{20!tG^`i4iG&`e z^_d{EN0+9iSn?uRI4M&+YInCR{4c-QI5+P#1$!jKK2?_<3>xlLueiKS{C<$rcbJ~o z6x$N012)av3w%i*rZD&=laS={&!d}(cM!OStk@~HUiv$WtQf@DWTj(cD-XWXh+gAlJG-yy>2S3o@5OGH4XH10Qp8yk6SVn>^o$HArZnZ- zf+$)l)&(Zj1O(D@XS?}rt?gW057^65za~?~FTX!RbhE8`>?+&WG_NoHv_ad!)444k zD-Oy~Y2MTy`8sXooIwFMn%pdyum2zBIH%S2p zWo|<*%;u&4j=cfuS6Jo26pu{MZ^yWRaT;NlMVhOCBCe~?^E(1cEK<^+q^MwHY5H*9~R zvF+P?RWuFJ&wE4RYWuFWI94z*vtgO3ytHJedZ3pd_^R*UYG9)7bzI|Bm$xQP0~8k>{gJ|fHoF@z39kY3Vh?`l_x#8XXh z)=rj~A<;x$RKTpVU@>$)%8SXV-^VHtKS4>QlbOp@ti3^sZXhGHo9 z&gm~(B`+T59lhdp-BeI6+WXLB~LyK;NbNcQm`&Zo6?>i`2;k`W`&kX*=1Ey zC1jFrQ^wy^9$e66Q66NDRaMQeAj50PN?)EkG9l^RS?=#Pd3X^904wO+EaO4HE!c3f zR1Xb59Vy!E^Xl379t9Qd#$n~gvLf(Wk^Sc1pZIY@eyee7Jl>cBR1%Jp4)k~xR?>p?_5+-Eq|2(!;0-q+M11cq@?%e(9BDfjAETIbwr-Jgs5Jaj5+6D zHrHs2T~(F4qdQlGgM)fm=@Zfqd~SA#?=Noo@0P6ZihMM}Rph~HZ7O+oS~SbvXDnkg z{Yi->Gcbgz!UH>DnnDHVLXtQS3wY??FE9i7qN@53GZ3=x8#H3@qsFE4RvnC+t%`eYhXRNzlO2yunegFv@xaeq-B?ux!-Ib}>QiSmJX;}r z-v8{A8xJ~(Nm=hG^3)m-;X|NIdaEo))s6HYoC9~%tEBLjBy|`2r-{=AHE$}xsH#I) zm5DTsFz(3`-0mpHs?DmcyG}F;T?(BfF}YApFP^j_c}`#P+HyOLNAmbB5A}8=1MSnw zr(Q~_G{D=k;e_Ua=*7_~*6kB8zsDQW68cl!7a2%g@6>W;*GaZ4;*Rl?gv57qLk#&3 z{3x});(bdGxqI(det|4!j15=>#+bF21x`zYC&}jYytd~@VM9;7esz@l&pI17U2yTN zy=Wp|0inr$??LqJ#px$gzCr4S>dxD+qhP#vtSSKpv+Y)fzxnKNEKxuHnpfD?&h_^i z&<8xvPCGrdqso~;@JaMsD&xb>+lmb=5TR$M;}XJhLkkpOxp;-@bW}OvX4br&8Q^wG zabF1^_8M0g4-MLkXM4G_l|H7DgVZI-vYd76FPi$&YdtpYMUVf&tLvm;D+x>r9{qGE z_Yu!QMW%IGKe62gy29i2ERkKkN+F{%oK&@W7+ zj8Rb7VkVN{#SD_oO_(m_C9|7|| z2IhUr!}(}pO5Ck)>BQ9jaPN2ceRGn!r61#HvqjzIuX%oht+kg_JUM;$)IO&CfYf5jr;n&vQM_1IH@r3sUqDXp97IE+ni#w#E5)j{-%bwy8g?(B zV7Rmpl05q;=ZKp11T{nfnU-Ul&8WS|txZB<1HmOGiNPG=pa!|r?5km);qVuv z(YE8+gg;27WXtp~2EX3`zp0_+--UFB%>O)zfmtcGQ2Tko#$c(!{q@Hd-Xh-*DD<1q zf?+mDlw5j!x7FB5>f(#cgKDCklfRJ1c~A2wS=UeW8S90AYy_6ifjHpLfvcp9UOQmJXtjogI8TT zm-}|4BGsIHWC}L0uY=p4PM1lZna%Sii7SKjfAi#FSACuRv>)EIjjq!nl}5xD0O{tR z+zsAQ*0e5$#`Hp+!#Ci!IO@N5Ou%5 z9_dcFd@oh}y`hR-+Os8C_7aqKJ+i5Jw%g=cHx35sxgAYR^*iTtQUa>Z&f~|HNx9{5 zYoASz>{aBOGgdqf%o8sPRBLxa6Zxj}hR{!rYFf<1h&@_d7@p#1Cx?g=SrOz(19quU z0me$F^<`tn65Su?NehHbe%VR8u!hQziS+dvvnzsXcqvoix3ax zBCV-nJ^jO?cJ(__aWJ|tJ?MU2O4a46!9}>|+dT$o=*paht&!5D%iW6IR!GM@GO zAW_*O*;{a!E4z|jlqSmruc=3~{KM0m=@|5po0kg)g3_EW?f__;w86ShKhsp@nS}g; zk_spBA>bc1d@cocp$8U{<4Yg3`Rgn(E_f*6W>5AWxbDaA5ql{l723Sw%#p{qt{59g zoQJ-(fyi7KGevQpT(+r#vw_x${L*DR+cc-rJLTztaSqNvU?J0^a6%=i8-W0XX~}@+ z3x~>-(_3}?Ifh*Ej6#nPbxQ&|te+-c9AW~EvzW(6lpQlIQ*qS zZH~3IpLOOQBG0oK*FEBG9<*2c2Yf-oc~Ud4m__ZIWm*4TdSb=jw01rfe1{g4`x3*d zj7|kUkeOL4FGbXS{e=Xe0P6OC2^RP*814GlKRNqGdDqoWwQ}?5Hu4G;H#)o6gtGo1 zBMqa<4-m)sL#YM-a18N-w)dSmwyQVAc9SNA@%r@;{T1M0f5fUh2rZ6fwYx=Y_@qNeVVoBfuq1cvx zD<{{Syz#!W!xLv#*agm(P4m)Cq&dl^9tDUKQ6$1c^hlF(Dz8X^yF))=QXagcuaZ5h z=K9`)0bD8keX;*IwQTIF?jAjen0}UtcIU-6+9THLk)^=5k31x0kIikv`028ohJCBZ z^tVD>JicOxh$hM`my#P3>nXvR{&&3=4CL@RlweiE0Fq*&-MiD?Zmn|YU#>PO>m8#- zl@ZV4VIK=6r6%O-;i@_SFwkLNn8;>BkBDDPZ4S5zHzv>Ug>{1A zdlYwNkit_|=Hiqj0M^|A9LF7L&4Qh=-d168zt!yBD{Vc5eUfY{je_W+>1k1A=2gSA z_fdo1uv_ty^kT)D4K0o}MST_X%@rcRYnIKTpR-PD5iYgdTQ5U1BYt@Dde;>2zdhrL z!RKOZ-TOu8aW!uAY)8Lf&FP8;^FF$m_W>+~pbz}~)94QB+_j|GgaTJ_aOJ}z_vVA} z2FP-9!8iD-dq2bQ$kAch7osQtlS`}1NwRTOBK(~Px`L9M{A%b%jv_f z7;qI~s;cRtrtq~ticKzy2aC-@VrkZ6B(?`JLc&Wh;A1ZATxFkd!*=8_JUeqnCt%jn z_A5I|<8@RBlBiwkVrK{VK8K*)*kYlK{_(vL(v&yt{#Zef(*Z`gV zs?_n?eUK)~A6 zwX0H&0!Tv(7{jVMndzmmHY>ph)O8gui3a2qyIZkS7z^Qt?Z-5U&R$53%)_+V?GcvB zJj>?U3c4&YDI)e#iBCf#==-x%$MUSo01xH>+fFhPObiY>TL)m{66ukVO+6-HWF~*+ z4tGIy_}h2PZ)Q#udDE@%I$V6Co;=kjeTK5}x6c(28d$lh3}aP3_s7h>LR}Rl;m1ER zdVinhvDI+bRV~4aO4Kih5YV%Q%@fpQdDO7QN5DpypZ(o{Lv};LPcP{vbecx)?P?Z6^EO7^LEa3Zf|8Y#-el@M0hK?=m0i_kRXxhb|s0FB-tm90)y1( zC2E>oRB`==@%YM3z)8SZ*WmyOxy8ThTpIk5gbNN-wX^m0`9A`|y5L-^TQZhMjX&qA zZj7CC#lXxemw1?+YcTj=71=QO9Od=r#&UHBmReeoYEwt{&z*WTVuM&XD4m3ACnp5Z zwg%42VeO(_Ywqo9xg_Mbrq6=1MyV|jW8T-+%mQx#j_l4ntM5hH&*8~+YZFcSmn&K8 zrY`|McPmI*K+JEKoAkUVbLyOk!S)>vC801^sEjmGYcfrr&1OE)X}3E=h&DJRU^{BS ztaO0JG&ZD46?IRdR?j&3;+W}u2FSJrQA9VGe)_b!^+tVD-+vaf{N1uDownwW*y2>B zfjJEcfO|W~D%RCenWy5s^GROiuKUIhs5kOl!}$10mHj-7engpWh2Qofm|`^Jto?BJ zWKZ~KUJrn27$e#OV;q_47Fi?z2;JN!CX=eTFZU~Z92K9Y51s!I-Ml=vm7(ZaLcTJ% zV*PIMfO~hme*IF_b&|H14d5qMWyKO;hh0FWZHG0tx?hxqXfp=2F*Bc@%y6}P(lzft zYpq6yI|%|H<;1QZRd!LrU83RVXf%-?8iaZNG!?)@%?0X$n6Lz~)5Xaqi~C8QGt^0N z5X--=r$?t)H(DUf*f9Kb?7edv%|*}F&*${Op8-P99Jnx7S&)SUJ1+rj=w|lB1QUsW zw@NhF^CH>+KrWlUI1bwuIZC&=QNSCfO{nMQRJ+>=*-shpzC19oNwaFY8|kUvU#if* z;PN{~;N^@_TNHj7#-{a^7^_II9P=w|@Qr+S&Z(%4^h|hr7L_UPXU*$AVe3h)sI8LE zye?R(vmcUrx|F$);jmGCwxob%a SMbh2?|CHs`<;rBtg8mnq(;0;T literal 0 HcmV?d00001 diff --git a/windows/MSRHoloLensSpatialMapping/Assets/Square150x150Logo.scale-200.png b/windows/MSRHoloLensSpatialMapping/Assets/Square150x150Logo.scale-200.png new file mode 100644 index 0000000000000000000000000000000000000000..dde32070b91fb58f0e700b61a76d0d2a7fed9a10 GIT binary patch literal 73266 zcma&N1zcOfvoMOg6nBcdyCk@_c(I~Ef?FX#f)puIoZ{~8QlJ#4MT)x=io08(_)GtG z@Atd+z4!4WCntMmXLn?0XJ_U_XlW?pVo_otARyqXswn6nARu!6{a~QMTVVdNp71YB zH7o$aRf5R{vD9cP+f~o-qjsUC&I(WZNO&^74y|i~q$TAixcW;P!yIKrEo#E*^~k#-IT9uyVI|gV?*e(EY_| zVd?4#0W!d6`cD#^-PG0pgV@F6UyOpYj2CL*#>>yc$Ls9;m#%+6dq8x+|22*O71~1= z<_6}~0eiT5x?6$a;Eey(SKzv!&!1$Ke_r#qbW|KFYeJ&v{2f8g9a-JSly zCTlBRuoKuBj?V*56aRk*ay|sj>g^eg&uEN{`)&dsXB342c+~PI@*4+F8{FVazR${_@Vxs@X^S||1 z5)~8@P-NQm3U#)?nWLQp_N&`S6p{Uzkx!4?o#cU@Okr+;gz*1tJH zCod1zOnxCcHUoPXYgca%_W#xgtY85F0~!8mE;pYLH@~nhzla3abPgH`B@1LOR zuGaQ8u>TWOKuDKgP(qMjf=~GW0EI6bYYT|Q|1Yq$m4uC}yR!vcgY2CxY{9&4F18GG z{}GUcysML|JA7dH>;(UNyQ;jrmbTZ7D7)#BD7uU}b3y7Pqki zi!kv1XNoHJ9&nk#{$&~7fZzS=&dDA=B7A8{SXljC>eE5N`{2u&gb7LHtjh5)j}K{O=0&&rVi$7B046xYgzT2bsKo z?bAQ$;{B&o{)^;)Jo|693{Lw$n&1ZV@9lpqGyKPYY&+Nmj@lh=xgReSG!PKUrd1VW zb)i3xvQbTv7H^(we^u7hEM>cR`x(rioSf*(>7bwxpc0Tc)k*HTkb}ZbP8y88e+isE z`<)1W_?}nx=f1XW^U%`_`P&F!TyV^PTzog@QasvYOsIrE#{TFn-)LqY{6-C#3x2Vp zoJM#JzoelV!Y}40%0RecMtfKMGNjXIKSerjq`Emr!zH+B&wwMd%tYlV^0bQ9kVQ=fR}$e?IEy(@j91bnm7O94W}2~$K_C*bKBw04G(9SY&#AO3pVLX=J@UHz z7d8wY8*W5@QFTR%_oX$;t9l(lhm@MReJDKi)9SM!tMyyBkY}T2&i({&b_BSzhP2@$ zk^u`R#A>q7ESZJ(+(s6ryuaYJA)b@2;pCV^AejdG2AFCQ?5gT;dQ;R{_Xt_tVMD%q z8z-*BQ@lD~mqsYv%xlr~$NzPb)a8%mA6tD=BT|0+9`XAPo)*{(=UXvOwpF2GUD^Dk zM{Wr~57l2>PqcCaJYV96rZklus}R+ZDRAqOx-(P;iY_|{Wx9Av=1(G5c*#mfM9NuD~w|7sU<)iaQO=4j z4)5GsrP_`l*3PcfQooj%T{SbsdA>MS|H-J-+Jj!fd;XleH{76Ob;Dt~i#UPRBmde& z(Wc%(N5c`F8^kWhw%_YNYy7{|_y*J*&S`#SF6_cgJn4FFVdm-hf(HygX#;NvN+fo# zt-Z*f_VBI(Pya#*w?e^$>vi|kLI9TGmTYqRq=#+$m|!@?<-&YIYx}e?k5yK9qGJ4y zB+~rPWhvfY3WnJwG^KN{wyARjcbL~dO`gYor)>Q7PNdpvP+c7d5Uy|6dd;$TRT+}t zbNC$Jg`YRSH+*h{(wMpPo~Rv@Rz8+hQV5vfREwAbU!eD{2#10XD`B>Ae7hHTwiP|> z7xX1aX;u8Y{JhEMGr0zrI-9B2{b`*Ar@*@j!qglj0pT7dmdxe_%#QVm|p$2~+0tkCQcE14Ns??EF5;0zJWUp6~P#$@kbH z#3*@-s%9z^H@id)wsR%>+Kp{d6to*Jh>)7{+Ew_BiZ0J~PyA}@?yOJnVvM<7a6VGF zdkSuio~1yKNT81IRuX*`p_-7)Ou$!v2~FsD_^yW8I5t`BmN*eL?1HSuWQ9LRuAkFk zz4!sh_(##@U^0^zLdE2+RnlqIppQN-u#(UB=;L`7P0Ff6y|^Og*t}4T?(uO3?7N{a zu(Z}1O{V}7SBvteF(whKZgu>b;ysTtPAf0-)A|S~kecTiM`tj4Dfgu{4bXf%$#SS^ z%I!d{x3!qpEs^#mg*gee5jmn6(j|rXBmUO*6#T9@2&IY{uB~tu&b>j^U$7T9Aq(6XeJYJiX{g%>va>t7EolaJ6dTN?G zRG3`)M9v|%=;5XvU)0(wN&+gxf~SsyZ_OpK>E>7DtN zY>NcKhyd423k}IZf@x$yeL;DMWiJ*aeui_?+MkH_q;`8!Sy;?!dGwsS1g7{K_C)k+ z_vLIM!VEGBzK5gk(o~YwA(T{4Ds8D!Y&2ia*=>%u3uLiQjK7`>8x^G!+n>JN@hLjp zYvpm8G)8H$xn9Rk$Cfoj=K8xJ98^FSqI>}-sU|BTHToJ@^rj=j#;_d(pAjLY6%t^r z^k%9*#WOJRJjzAKU*E`k-%~p?d5&lsFZY-F!_`FgAWM^6pZRuea`Fyki!_WUnkGsV z98Mx}l;?-}dTezpcF;2|)K;@uwEtuFN7l5^XxmDEw1%_xjuGHw)*`9~Xkf~lKhurd zE12{NEgg^hskm&w;fUHwwy(0g3jW+zyAD{?^cg2R@M4 z5Mg!&dPwFRY#V33F8%JteU<+fWq|6niEl(aaa-!yo}0-Lh|&kI4YUE|fOwv%Wg=rb zzF#15T*LsA{Y&0Nh>r2PqRFEE9C0VmniS=b2i^WPt9C!V*Pm90GA|H7o{2**bpn_Q zb1!Y{55+yGa@CK7V>l&JG0yaSf6=!6sTPFraFWBUA;4w`&y@#+O2QRs<@Vduc|nHC zyqinhmy#&{myPWvoGD4I!LTA{>r625d&RwmUlCMk#y|CUKGk?PDEOPr0wARM%v-uVG_n_3RzPb8ccMyuNO){3mmukCM} za1mObHuw`-=AY4E0X(q{#XzrtxAlywhyPfX$W_Y7q%@_5FFkdLd;NWrltrquJ&<&# z?r3)m7=NB8I%3K_`wD@!)ote+OB)-@APpyJ>8H^=@Gc&6T=6!((rZ?0|o>AW~rqZL`WEtGXc_;ZgwIB7m)q>w%( z-q5qx24etnao3H83)qRH84^kE1r(pmcG4}CSKfMpXjtNgg`Hm~`oF8(A&27qK!MVl z1#6?X*ZH!~M*ph2%58tNy9i7DHQn-eg~H7#K6(m8$BqkiDdRY0@xV6CSj8{QXeal$ zfzHmbT$9zL=M)(?!^eegiA06`t=kUh13IzM%FXBRC+nH0fD>+KpHa;A?|G8EB7Skh zOI;&^cg@>mz>rjyz-0OP_fK>*g)eEIk=b|k9pp|2mZEJZT6GPl9#88W>tEIN-lljYO-vOHDSbHQM4DSdsful1uAtDQ zbLI5F=pYjzY$rZe%sC!oCL=Xj`@!{L=LCUC*MbuET68YlF`${pBo+L9N|<=WMv7P; z$&i%|a5c8PIK$)AV-4R*T8G>;00y;aerFj40;|=}+;@+nJ`bMqwHB!H<)Be7XnGk#!FzVMY*5~vTwS#HO_9ImKhS`dQWuH3Q_iMbu>$(l&vbnF5O&NtFB1=}>VwX(^Pq40OJaV@_=p zil0O{Tt%qT&>_EK>qfG6GaqWfNH*Ikm&V^!HK)$wJ9G!%M}IZ#E=!q*?Pv++NH*j0 zn)d%;9~eN^|3nLn8)J54>%q35>d>#xnY!9P{b}x|7`}R-$NyaS>h6rPT6Q5O+Cfgn z_r%*rQ{x@1amK@A!=8yVW<$|%ccz&4!kb~Z+RH4h)-gYf4 zkaa@j@g7@k``XS&^p&Y@^Lb^icRy*`E=n0yuVeB^--YxJ_Obf#A(1kE4SpV>?6?3n35CFCkwOv6HEMU3Q_5>*R@WbzJ1?R9Uire-935|i#wAKL!j`6~Vot;OmvV7;&wdYuLX zlnl!vnW4rxjm?I==g?9V=^9Av{Jj}^8L-BBTx3GeJ{E~LqZZ&MFOq;y1>mf5jKs*IOO7AygdXG;VDiVFdqjx2F5 zun(lmrUXce4U${p%NzW)TQ5RPpbnzwIlz?!0LSZ`IY;EsSk^D?^5k*;9VP(%>%h*g zSFT0-rWfrGFo&C<_K}89cJ5(0vsTEC1;oK-5Zj04Cy65j7vqUTsJ@T#r?`p21udnC z3Jk~LmOH;;vM+h>jQszUDz4|keYphnPj}cNiU&<@v2VvrrbQUX`>wy&F!2uMpzcyD z>G@jukLQnS*SyFGh;A)*1?NymrWu4KvPCVts0keq{YeP^VzN|ydYqwptH}C(UDAp> zg-Ji8;Y))|jBubm-KB2eZ+;l{>kKV1v2ailM@Hx&))K=k8>7OEmRkJmx5JMPkLa2Y zBXPUYG-@j*jP>928`Q9V9iUc~6Q^{tBUUy{0ktmb+?>1mRc_|N^ZTc}*IqmO9r{{O zs@}qkk_a^WkO=M3B0oI^Ml)wt{(_)DrMx@N26lWbzf>yd)h_mOn7ipski$3W&v#W= zS?||C1;^o9{@t-FDR%PBVZBn_7=$9UC`?c-VyqhG7m7qlXo{q**cQDq7wt$M_zh=B z20K-JWMOl8>H@&1J|3V$XxJU?hl?M>2fBXzZA zAA(fv7Olb*^m3`DnUev6*g1mdR5{X>1fe#BMN{`uNOkWS_+pX)?7AJ_1i8$ao35Aw zI8B#M?NOLfd)V9YKrk|FEwL8$uECK)LuTN!yW0~reEmg+}8@y1vvxVLad?t(A1gH z7zEB>QjgfTJtB(x*dQ2KtYwL+B@$+PY@?hgdd(EK?>*z2eixe@O7;bCs^Eq-CW-T_ z*305{Al>zv)(g-VwB{KcxOEOrvDm?R$ zdTh@a&RrUs_VKy+(~<}`Jpw!dPYkA_9p0-x`m8a@cEN1 z9_9Bp?@hWJ`^7F643NLHJ4-xvB!P5!T(+I3zZCeRgueBK^~=1;nRF%AJp4^Mo;?); z5bM`;wL#(1CJVJ3Q${BZeMjQBce(?4R{H81qg#ckqNvZGPH1+a@#2xu?UwJ!m{6AE zpr>2z5)#pXLEPONYq@T6cdN(_2}2L}i17WeB29KD2^2liV-ca_K`%J}N|M?V@M%~5 zeQK)l)8Lyf@=Jq}rOO&{wCJnYyY-P*aV~yRp#eV~dZm9<20MITSnxle>&WY_3vVxF zELe3V`rs2H85+nsCGttMDZemc+)kWu`|SJY8K#4#!p(DHgt6kT?tb>nzxK_?TiD{Zi9VEG-AWU5m5()LD8JC8!u8~0GPh;Z zq{Y&(m<#Y&bI1YiC~9wEPJjp)N91ToyaAXnYZZz;lFBfvnH%24pQ4TWjs=drdpBaPE9^9LPt9MMQPI=)52f6=}GKjT?;qtb4Yw?bMf^s&um+;jO`D}!zJ zj8HYQn*=~ZX#V4}U8)m=8^JdwQzCKSPxAA3wQP=rbpj`Zov|h3L6=w^{fiFOz^itW zCn6fQ8S7?x58-PRrI!=$DSa&u@nt^mM8=BGUTFLXsUQu9_#i~}ey*ff zySfFEfVB5g?~pfHkN3rb;?S!q*5qoi`3MJ0>1VCisY$Y#$FV_bP=jFNm2d{6tPRw! ztGWo0y?|@q-rXa}EiGx9WsjU7P1=X$Naq+4+k3)!0+eQC6yA(`b;Igi{xgGPO4VZy z3o^QtQ@ZKw03n!vR0j&&c*`&BP+Mtq8;xG~)!L*WCN5$RxnFcdA}=^51)R`&?hHi=trtnCm9LVIP;pu9H+LCJT^^ZKVqS$dd zwjnTG)C}PQ!()^bA66FhxGtlExx$>IC-B~y6gSXz8xa8{!(vxAv< zpSLTK*+WL%S(a4``CIBE;wve~k;aNEaZP0cH^V;}ckoXl>mLH;>a&SAe$99t8{5_l zEjU8afbaiwewp2XX<5@vMBsZv^2wH%rfq#_KkWVHGE_OyZf3EI#n@D9SLT0{`!449 zGJ3JDzdzJ*i(B24todVi;kV{tb%ihJzfm*eThS|1xG_F{y=g4a(qX!q#x$&hpXHkZ znVAhpzX#;fW4T>Lu?HpCY#j?A^ietMD@ zTv(N%A@;zQOC68$8@yY}GA0D3Gogu8^xql}SwMXUE+xmY+II=8;TJ(is?o|Vl}J_V zH$kYH$1^_mQlJwd`x^}e#|RX5k~#$QEXElcEyggV?TR`FI}i}Z<{~AzJ9wax_kHpi z2%+j5G18s&v5Q7`8hB5FDO=7TBc@B2eueh~RUEjLH;MO*boM*+a zWDYHUCn0BU#X|*4;tM`$WMO?VB3CCMts38)(2U3s9#OX*NTkWwq=fJ9 zB~J8{hMt+M%pVb%)MU`Uul31rBjOIFe_;NTHz**FnO8+01KkJ@ubee!moQ~lUwf45wZI+*fy4_9Df%VKU)VJOWZ%-u@h|+$~O8FyF(IoQ_L4Sa*YDtr4tKt7OD|YRb&e5GB5bD$P2)u{gomiutRdEj;^=A4 zX8;@Jaq*1LC(N&(BT)6MZ8d&|jl67U*Xbf)(U2TUY39GAa#g)qO+*N()Ap8}QLIL` z%d0mO z5~&^VK#vs3ascDTU_&D&y?ZYai{Rms5Qy3`Z+qQJ!W@Zp?DYGDc0njC)F>e}G*_Dt zQA;+8=4Rb*t-QyvvMw2v0aP1ev{1%tEpo36psvGH*+x5dmfua^^TqjUqNn;qCk&Pjw5LVJOk27E}s619cyJjT$(Pc-Hr(42qN0#Vx@_eeMh-ssA`{!Ye>-CBh zMd`Ma=bGA1#@Ep7+oq)K$EN7wtb`8rmHFa>wh(`IrYsBIl8ZqIe0M4dnuZ_qFg8_l z1>eu9BB9d;JZWL)%nfwtua~tyG6%;~zzk2Z=|BQ85}TjVdN=p64xpJlQUeh^bu^$8Bn`NeRgaEnPiw8IJ;NP6^!$uRPPyj{@N6Y)J zgq9}jfZl`D>*>|~g+d(-B@lU^F+8UKX03H!k5fj^p~YYtc50s9RxqJstiKg2LKD2B zz4LlS4|GDm)nGG6orG9j{fH^DNw*%o)zMG8D&*$F0P?4A+C(6=mww&mMl#2HvFEku z5T2yeB=*{3^L?<2W`hkw?bSjzCH;@iyynXMK)rfAGgC$+eNKtfFj0#10>vn7@u-EG zFT%Xlm^mFeffsEO^nf3U`?z|c8!-ew1>trsBhMRO?_kTK-n2f&DRbE{iJ6YSQ@*}^ zzanoRZ7bptd?ZYr=sc8c>62U=zM1wXnnU=4(u-DWkvzZAF?2P=P!IgI?36I>aKJG| zvuudit?dlz?Nif?Jf_H@@QdrmxV4ilCvwT1zWRuj3YzJ+Mc{d*l+1!}pqx$&u+x6+ zYOp&4{|7lHp{jXj-!NCe&OXpKen2RbH9$PvHtujdv5R74`&eVHdUxguFV3Gk48X*g zv-oU^NIAnqU*-F=`zxth;6UKx?i(>tQG@~)NO)=U{ z^olZ(JDKCkpi)nJl2kEi!ckjRvFo*(m9|`49*?p>g^@FCfMU^RV z^6C^EJ(AYLLK@a$7i~A+x+{K(FX{PCyG!19x>r9xdqw#5&gPU9CYW{Ks7@oxEkxgr2?_&lHK4>+?d= z*CaBugUPO1>9uWqzzr>CNQ!|K&61mRIr;%&)AjA&1hp^b2ftm^NUHtBA%`SUTv2}}6MdE${!)cex znG}j9Udrbqp+YdD7~`e#jbZC?$yGn2&hXn6=2eRWCHk+L^JiF5vZ z!bLnJ%Mt8MAABQBUMH1=rSdLdYQQ@8SIZV}=0)0=wx*&}oQx-P0g3d{4F!xp0jPo1Yl zRM@EW^(AH8)v-B?UP#0gD)DDDg0lFyU;%a+3I*C6(*-0(Zefd}^6`cC?&S|O`Jl*b z)fiwpT)ccB@D&2r*R!ot&5xE7&)Ar2Wu&68WvX+C8g|Zgmn-y>#+&u+e37GwKrsFG zs#aj6bq8An-Eih|#z05*&%Bl7sme&~_c66+N9?*J5Zb&7(3bE>K)}Pn$sl?@&!JYZ zvoMIhCpP!^8yTjS_D3ZVb#mDglKZ+oC7+WIHHRF=w(vlo!cMNHeK?JRZe?LLW5q({ zqx-4$y8^8l`QWXgKz0I=p2jwED2@#p?T3YowM8yE-!3h4gl#Z2H7srF{2S- zg^d97VBzdU%u9G#Lxiz#crEU1a#!$sh2*M}@gLzj)+bHwc^#xtLo$0>g4baOh+6e43+ynu3*@E595C|0xa za5vhGBzFBSyQF-HtZNI;DrQTWUxsdJbHAg~Rn{>L(JcLuILUxtiu#HmPp?UGu7R|! zj#EX;a=2q4-axp1itB-epD0&*?5Ey^#lm7EW{zX%1cAIdfm8tw1KfMK`&E+h5S6yI z>?--wo6X7EsHWpP|F)u(6HU*%mHKDQeQT&`n3da%5BgI&i&cCxi}p>jSJnuJDAvZ#m2Bw{%9lpqNi+X$1%*+_DSX zfB@#m90-10Z{O;Wq6EiDY0XYt+MUp^^IcXm5t%m@;*oR$t}%J;*#{)STsr zDA`5al@XytWpv9;`OAM1G2Q{{AUL*;`wRZ2jk*`LU~^!u8~k8IBK8X}<1jF*(5W0@ zWwHp@uBCq3{a6o13ysa6*OHVUwCNYD`(IL&mCw{X|6l^NTbYVOhI zzQ66oNPg}`);YH#4T%rVOBAkX(hpbfjPSwo0*H6ZvR7j770-ZgMy+%qtqL#ZHb2Ge zO!zk)nOSd&i&`Js6!*vFBoIq3dnJx*itZAXeO{jR)x-FP0|>Kzfl>l3a&?S0;@XN4 zQQ(3h)Tu50jK3Y3a3mMJrtCo=Lk`A9kgx62M^z8#5dd9S{;e3$bsrq|ANXDsH*xR< z9vC;)to5f`L9?(x$0B)CEL&c%ymry=c5LsJkG+(68%su;nSLtvuId+mN`b}*t0S4m z#|eTTP^i6G`j|T0>lkG*WT~V&XHM3+>T+YVH+9`}Vvp<)&a>A7$&zbW>8U9vT#Ql+ z)RI<(xZ4ew96fk9szto8uUd#gA#f$b)p70>Ps%lHOQ$O6qGeA2fS{QLbjJ=0$|&@@Ih(-!Osiog4G*zJ43IotPr z%UD0?ji_q^w?C1y@B*R&O`;E|nxs3}f`#sZJYMe9%cXje_U>Y%^4&MS` zIPGTM)aNO$Lyz$p@2WPv?wMS8D88eSd1$YcGgW*0dcA<4#aAPL~e8D|>bN9NDPcfbymHSG@Oqv2S~FGv^uOaM1V$eIre zLG1;Jn$8b;dO#@bp2}o}K5C$A^IK#8+p|C3wlCt_E{`T%FZY_szu!^IwsLDeRRA^b z9!Sh=RbVK+1Of30kNPAZhB z@jn5SAc4D|-z8*wxDztDAPq)nNGO6QI^uCXCup+zsM{SdWk*k$K_d_t&w` zManARzrwBAfTh^zp_lYVO?kY$A`6Ws8@#-$Jh-KgYm&AYMVirpN4+q=@nM#dm+v_G zevUvO^WhClx>8w>CQ?4GW_5!b z?2-NfQUNoVBCqB|Y0M2VLh`xSN=#nar0>q4!+oi^pjU)ii#z(GmXK~IalUx%)99&? zVZxIvk=OV5sQxcuOC~F~gmDh~V^&|S&%eNZUbS5=EM85WG-F@)m@~GvtX6!@?9~0Oln&kd&&}?_aSXutas&oL>W5 z6!EV0#5tqzLXMa49V^s+zWyUz^K3ddADcN-0^+EX48jCGR1WKepbHOgwrI zPB$(PwKVYm^vfa{UL0E>DJVk9XU+B?gJ)`+(}D}fJgTN@Jif75kG*0Ieam_z*UJc} zzTC%fSXkeF=f&bZ+zY*}_Sv}YYiwUWP^a%lrr0w}%t$%d4{B++{f1vr-2xdpf$#ohw`su57bUHMz~w)VN}%RpvR6|w(m^tg9m&aKPmC)VBrEZWrWC-ggk@F#m0@` z@MlqS`t8+r{?B$E5WO`#ol_wg)EgUnlUYH6p0k4W9MJ=hlu5DRR|x~(Q)W-Qezioe zU#-sO-|>K#hcrngw0B~MCius))VgxTl!y}4#^{7TMmW;F5&T>1_~)xpcu4rp&nPP2 zxacK%(PM1PZRab>cf|S|65fNU{Hs|Vc4UMJf`eB1;*^(o@O&5xw^WR3*yK^D(PhOf zqw3G2@Q^z;ELFWQ0%I+_P!yc4n3w2=flOF3`5$<^4sE0dut}pgFi&CUWnNwL*d}FP zQ@u9;9^|{sN+N*A)LfX+={vx2>Ti>kl_*e(8to=KkE=&AZ9rnpuGul>wED?8+=paS z;40SQ58NG{*cLBb?R?uA7HTWbcN1+oD2dDR;sEC1)0x+E$0v5UJ2UvI6{N_y~K zhDif33syCdv@vWqo4VWQt<^z&oMXqG?JF+)m#iipQ%{JA?%Q+J8}%< z_dkfF>$fAxB592%^RZSLGN0f%FKm`tXS8w3xtv}@dq4g4jnw_!xV?9)mkD6tpVp4Y z+w|jvY-zs0(x)rzpaTyxmvf}?qn;-o5zDs}cSoRT{-w+>*VVJKg4vil0hQ_%ZK|rC zDkRezxpm@0G9dv2S|}MChOBjY4-s8f-uT=+tU5F(YX?ZAN%GztBW6uFX`dt7OQhpp zeyjgv%^Ekf3o01h#TYpIx`i6Kvp3Oh6|Z(8cDfgr+g9YVk1<+-tfiLcMpzK^<(J&< z>)jcMRme3!ew?1!$a8B`*Q!g+PpNgnqbuwtHsypqQ+XZm7sMP zJTn|&=4wq+OewD)5VE(hR}%V>vDC$bz@p#GN8{xeBQ4?v`D z=T$^NNV=AQ`eE2S^b<%hvAyWbCs}DQ3Dc|Z5)3#|M~A0xeF?tGQS)7sTrdF1pBq1N z<({t!Qgp$T9*%jk@B94ZQ?dl&V9XhU;VOwXj&fvb0vFU7yn12tf=jtE6M%~1s3qo{Tp3EzAv*LFQH!W(qAdW zhF0G@{dI9YR8q)7%jE5d_(ey2Ap4gz4ix0<(CfAcm5Zft-X{pSn;0L9^>l7qZ~YFp zBP^vBH@gdDTLt4(VJW2UO^MxPnod;lxh@op_RjstuReUV!U{$f5E)Xo{Kw^6Dy`lg4${`w^`89b(6 zkm8uN)l=;4s$>Sjhg&+qxD&UU_iMekEw@nv0c$^|eQ`?N>O;k7@6h>QpWWzsUA7SG zCxN@K6~=7uH`s(;p;$Xfzuf_DAP`O;v~$dgabXb@4i=KL{nR6L;+K8P^nHDwT63}6 zL`NioNyMS7UBSg63V}3X8DZdCV5k&uJo>n{>g?sI%D|(1ser+3s_~uXHFNC&)r>?d zyG1e5+(F*k-VaE1T4=KKbZhLq*91C4VysxmO9W!-d!C#J)b8{!J@2XyHnb8c?d$R~ zSmSVg?S+>&*TZWWEDn3g>gpagkqier5JM+BHumv>bHRy9|~;U~^(GM^YF z41RV00pf@Rq-29_{<0Asr~GTY+l!sD#oj}GRML{2HR_4QxGZ#;pr0JnRE*mM70wY; zr{EJ&se&56tcvl;1xE!A8b>B~i!(xk6AOlMc+yS%2cx3~pJOMz<-5W%27IJB=)3Br zegD4>0una1s#QY%6tJ+?s_6n@D{QEmHFDB8)xRRGme|ZgWh2}apw9{;$h8uA$I)&o(cN8(^dV5xn7BoUuqbG*L*GmP_ zpEi9GY7mb{Td8W>(FQjepAUgqDuM1mrua#4-vWjYxoOy=qMJC2x9kU?5R;!`t zgZ^-5uVq$xr=A)ZIv^!d*RL{8CXJtZwSH;quOwsgW1FU-a^G`yb}Vsj7Xh(S9dsR( z0*~P@PFp^zo7xp!h+F}~k`_WnOzU`@ECfTmRZhX@ydMppg`D?}q@pxY9ue;HnGJgT5wy8M~6?o1Fs zzxO_zY-KeDIeHz{B}RbqwbqX+M@Sm63s&t=>e%{{)eowrg|LxhR}!&N+`?V@2Xy?} zA?xg+UHXAg57a%lOkqwj0$ED)^Mvyyi2Crd8mmen77EY@CQseNuF94z2*-}CcV~Ak zN}}zyCMg{*XCFCt86yIhLy)i@65c@@0?$@`-csyds4>d?up91r} z?n+^Xlp_>9M;uzgruot3(IA_aOeRZs2CP}Ny|Os){{6(*f~g96V)z9;-DeR<4#pB5 zr?Him)BdN<4;Bp3MKk-l=ygs9C@F%WPUwX5?HwZ4E3`;MG}~*K>yz+O5Ag=(p*14# zr!oXRbr7Og4=ntx-P1efvLfTaVP@w`V|a%3n{k_-0peZ(QPy`qW@+a?8E&(1ht1EaZo+u5bTyxT=< z1o_HZTNQUR$c8pL1yljZCR1&yXT6)l)x~baZP37yz@@qYggHz00o0E>mhaaCm98%F z0VlY|SY)+xs5J_U-hQ8!+|2yBl8c}+IT{S1?>3jGn}wC6u(TR*vpEwsRJ<5%Kiq2# zhw#1Vz8G^WSxueCHe66uIA;k{gIDOXllUB+B!db2wr)p%G8zBGxqNtm*4w6o&XpDS z>b9|BU8-&3_MT5j&fr*PPRj48{`uW~og$!p?YlPIwf43;CCJe+TyDvUr_{1FPDpuO z8wC$E*|+tt`z;lay$cnTAB*+v%}aQ_VUni_n?g2+DjnR*K@H+m zp!s~FD7@Z=e18#I^P#di^P!mq+8m=km__zt2NwCgmBu65BvL$pA)mW&0{fO_xkYs` zK3Yx2lV%eAl{llcX) zI!#1pP`$|nlL+n#;VmC_i!NlxAjnmz`q$`J)B!t5#@3@8tg8+dK6BkZ}hBh zY-&(aQS;6PQd@W{tLG+eiO2T@wV(#fKAIR+ZwaAw#^JjWpDu|o`Emu`dxg(jBkO4g z;$-MUX$kM*kgD2$Y{~hnjXzR!wd`Wb#pIKI9vfcW3^ObI6HElmm#uM2$o#F)3spZ; zLnOrqrz3WUY<+28c!Xb$JGA@PgFe8Z-U`Z-BTGOIQ)Pes=;1YruwD)o2ytmY+CX3d2z4;vRfTANVSvp8%C- z7Do%0S8N61IT6h`6*w0(#BchGk385mJ7#k$G#~H*VXk9r3eDMmc>$Fu_tPho^=kMz zk+cRcLwIq<`zTs3NDy-Ljf|$$kw;gyddCJ8W>h@zhB|;_o;X%SW_>U8+cQnuUhf}f zZ&hJ>*8-s^-hk%Mndq(LO#QFbif;YHi9T~A&g)gKFlIi(otWxf)XP-@dTXC9G^9B< zRa=^FiDS0VGAK^M`JgYNhTOSD-V`Gh=cCC>P<}Mxz{uV`HOy$eDYGc^q6$*InMpDy z2o%U#I*n|y^xdfD2nsFwYJ4X`FgJ*SbHTt%--k4AV^vhcR)E9nX5ZH98tiu-L2H*N zUU@uqANy&(&Z9vtu7;fz%&?EA4M3Vh=X_wLEsj6Tsqit0YUij7+`q?^d%5vWPJ(6Z zAirCVLXkYwpHHn$mbNm(qC))%6Y6h@NnJWQWCefuftTsj&O)RoGVcf3i}nhv^L;(+ zC|{3YoiOJ?6Mrmo=>~k`1wbbN1KAiJ|AWQbuwc}Jl;4Qd#Rz1lQd__F#E2|)#4mgS zjOB+H4mtBVvu=Ktvx>97`t7sUWknXNI)Ox8mqu?FuHb#H0|vvq?ddpVbSy`pz4sbO zMh9MtTjQp5<6s)#E~kC)C4%a61$|KHE+Yl6nRkyr#=7AjnsLNIS`@CmmfW9gxUc(4 zdKR;D2_cocpW_3^X*;>|XEGJZXu-7QR103g!$aNnmaH#m)l^paKQ&^}i^-Hmf+jLR zbD8Z?<1a)cI7d3^cs~G|EK2vDyxAdupyu@71V-3eTt0jj&Tp{Lcj2jCo=N=*HWjnk zx(9A;C8BIAE=qBNk8bUE$c`OnR}9#|^r~*tYDLm7^=X#oN0zZ>CxSmC$1cH0zj%NW z^PvtM6;B2AZ&&@bFlh`1ggu8n!uRgzj>7$D2=C&}!Z_GNN3Oo6^!h^RG>NE?iCF?{ z4kTGxSU!^`-h74U2=sO9S+Pknktlts;U)j5Tq;;m?USNYmgAH^6H0IPdWocC${PVP zTg^sKW1A}%>-NC@^JP`%KDHV(^f{CtM8x9N?{uO@(~qYf?YcD{%_tG|aSb1fwI9DbYM(sml%`f(X^DAz6?i)869=UjI1wC{OEjgmoy3j%N=`mk9 zks@vxQq4npcRHbmQc~${l028R5%$BP&T>1n-??OH=A{g7`rmqbCUHN;%PATdeZOH! zx7IdRG@G6IrNLiP`%<+zRc>f+I}V2n>Z7fggTitnF%r|4iWYIlb(lvnI{MK6l}F-y z*!eff1H(g`YTS|qnZ&98OeppNnSE4^>>(6>A9HyJmFkTOeiV{OW}JROcE)seXnu#s86r~NTAKmU%e4qKKC zA8dQI&Y%4THuBo`fHg%q$8dQG{szR2d+ZGZjjZyUt4dGiBwIiey zJ?%$pRic6{X#j%6W+?4NU@1oIb^-6scENr>ESO#w@4IAO>1w3X;-ygT33#MYr-<;@ zm?0FrrAHAhUpXeSeX_BM==h;&8LWE^L z^Xv{l^Uj@YoO&uzW=f$f4ao!-tLnGiBs~I+Rx=iEs z=lbNa#(YA#>XUmjn^W=SA5L$U*BtmPc7~Ycq!)FRt}!BWB9~NTRup`&8vljfQ^@jN zYFWkyI9pyOl6)1#9TERC4KJJ(#1Ig`?ow@0Y;34NpQs+^o`DcVuY?!`M~t$)h5CW2 z$>K47Na{!i=rN{}yqb{19)-VIi@fjmT*c8F{$o4^@l6#xSPuC<#t75AY*yqwd_Az| zKqa7QK41N;SB&oE3Qy7dqtv~Gm-7c`?6#!kTp|XB0$%3DW~*Y{5-^!hd%V;&n;n+J zi!t+H2n@H>|H~}zpwM%}ZGBVdP>V6tdUy$!L(im~_U9H}T!4Wr$Ved%rpI)not*O& zg_4JcIQM?vGcPR?NjIbkfyhfr(C2lR?NzyD2f>Ndz~<_Y3Oz@Co8nP%+Zz{i3;2t` zbs-mS&Aek7)i_yLyc_aH3!(`B4@GAc7Udd6VY)j8l?AZboLtAg?Z8B4Ad9brY^yQ}Vs) zA7tFBDMq*LnyOtL&SjessMlE^bJo9t-gv7VMUY@nyYrlp&8F{ha>LC%pokD^C9NY> zk!EZNa*{%^8>fqX#FV656T3mNE3LNV>whQ=kefvmtD(V%GOz z7l+f$>YhYBuf1LkW9LC<&ftL6Z?599wNkw%uzNYO_i|(JJ4aFY7rZ51VYCjpE+@2k zAwxd4;0fvgUsO=G;?k!mk&x#*fA^sv(8ER*^kYgls$K3ptF=vW9$pmp=>1p9M-N(+ z`(3zk(rW)b<(F{(Ss9{2Mn4Xig9;X#r0oDKgvl-O7VuJ+1+-Md-Kt`EBS5-i=J14RAoHEP7myzoXX~ z+uCBS!az>_(6;!=pWCXr=tJ9{c$`suDjMwFz7Y1@eh_TD+vRG#+CBL1(qieC`qyJv8 z{4%t2as{2@m-X!S4r!Zd5|-E}j;oU;MYTeyI{~v+2bYh2dsvO8-jVMTrCr?}*Hb-u zC@^>#jlk}JS$mv*BNg^(M>yf{nP|yJnwiDM*I%^>82c&xl=7>7ryubABBR!-4&hW2$X6b`Ht8GH25$`;c&wJiRG{^SNu?fb)3#ZmWinMEfmKh`9&jDXHI$F zk58XWXuP%bR%AnZqEY5I`=v2%gM+ypZZ0zJj6rdgP=vYBvGN1r_g9Gm+^4nIu#*C0 z?_zY7=X)tWz7RV~)dXSi4wFtce>)X0d8AR!14pUF%#?k1AZH_!ptC!?GoG~0=M+tn!%XKnjx8}=ur3S&ZWXx!b6c#nnZ zQSju&b{ZOk8Um_oEIY%r6)J&tM6kEH9+$*B_26n-OBSY{p&xBp3dE9??<&~;<)hO`m(`eSwd^rew3H%ZJpTz^n5!I{`nTT1btw`>P>105WE zLIs-C_loot>pOy519-f1=e;pOo^BCW<}1nN0SUK!*jMnxMnrBnWCsfx(EH&^w+?pc z)JNb)E#5DW$XI(pBTTSM;za5wGN9=1{q;g{=FJG7&(8&!HHy|>V(e>Tn(Ca}(y8%Z zr{^YIZDLtfr1PdkHT^Q~BkQ|*tym1n4XgQ<&PDY16-ip3x`7dJ*p{1#F3(3`$QRVz zkv=+%`%B!}TbFd0h?=1`n;L~P98Ar9&a0}|@89e7Ih+b=($Q_M_#6x}zxvGqhIYtrD@1Bnj^3#zSS~r1%#^{ZnPe{H5p^+D>7U*9iOd%<6W4USTA;G zFDUF@f1c+-&^Z77V2}3V%J!l8*d?0OOl41cf}2DH#w-dO!Gg%LePQzq_EwD-@8SDg z@G%swUdq${Xz&=ujz5t<;RK7e?;Jju$X5{i7H+WCY^mngpodkaI~40D9AD=<_IKE_ zWtfbN%yO5fatp;vBsgaqCa67XV%9jZ;4P)SyO`?HlzmwSjW-%9IC__l*Cyo|Ah3R8 zrr3J{$JV8ZSYFx%QQPcXkZ9ZrA6XJ(!OKWG5(HH6}dkUzo$;H$TyY%yHT7^PIML=u~ zG^wrU0DM|uS-^Bp^gf>HVHs+Y>?*2dlk1J&gofn6Qin+dai2mMr6+Au z-rTg5SI|4oG^#~Qy%uDDYOFJQ+%7w;J?;THDb#tR3u!GRB{&{^ z*sj~a|6L}bIAIn@;DJXIg+*gV;#U~J& zaye=OvYkj8Vi!ZkdN?d=PcCBhwdhZq*?2f^ktPcE$*7L-PWbC}su%FoSNBiOI3F)rcq(4B~R zjp|;gWq-ma3z-_-zNBP`5u7>zBSoY>ruN4V+0FWJCo7bjM&}7f3>Bra@F2@h(|=62{&g}sVggQ zrPx84obM+Mdo=}TFN#*@UAT8mvHc1hdo{)8oNDEJIkhPiN_wx{?A_C)tKt~wM(Ajx z+W(YRisHHFT&alayZy{9EUNH(4xIfW@=A>*$0<~tKX-zYSq+y1861?dyAbevE?G&SSM;|=j86Hcv`0aMC5 zbm1*sk74j6Jj&m7WOlc?v=m8`(Yiel z_@On~@S~dnbGXN@4kS?_|AnA>!&U@T-LLrUn;-96`ojSxV+F_NJ!5d4dI8?a5HVa6 zjghTyy3!=LD}4jQ$6cK4UEf-h+hjngLXSDVM!B6|d`2o`OZKA)N+PT_S3v9~N{8F| z&|cf^hQ+?ynS^;>=|1t%;!<>J-y0`d2NrP6Pv##0kz(>1F#$H4=(F&8yKp1kU>ko# z-ua+QoOxTo%l%H=R%?SdFoq_p2R_a<@F)Ex7+Ak+hr>mf)ul_|h*VrOJ&nEO=eMhcyd|c?1!QL+WTo#2+cQ&%4`giFQ zb824-T;2KP$Ea{oAT!I6i=ul24{8hdt0g|d`&e{1yY!~_tXX63{9Qn#iCd@B!mX?Y z_obK$1{-&9eihMs$W&3cKC9v&z40nCrui3~bqiuJCjY6x+?AkI+$P&_Mckx@87IJ@`ufpq zmVaB#P=~S1=`6hV7h@Q>lN<6F8in7Ib=R+7^MLTqKbnT~0@Uj4KYf^+mY=w33x_G} zx-AI#+dNw&hbVIScDxK?nDo(g)_k(mCp4Z-*~v3~XF%ga2Q6e2?Ic^M@|i;?r#DF9 z)i`B;rDIr#tVdl%IxGsVEeDO};3l=?Oc%TQ5W9SVz@t*~?1WjP>oG zbzW6StBqxO1a)|8Fg~toK>c>4dw5pWK!(9q!r7r-fMwaSp#t!dDE_!-eMGkb1HvL7G&#IFM;8PF`Gta(u?H50A$Jph~-)b98 z5Y6f(6cg+MOpm*9qo;i2ZEszL1}ebTf6KrJ7U-#hZcl-4jzLg;7NqiP9`3=aI=;Is zyu7#f$Z^7efk*gupvn$bEZkKDK(`mE5>IE{{z4c>Bs3yal*VqO>+vTW8Exx#u1i;hF=Wf6IVvDFq#jc9lGFWLSd!j$sDTr`AJ^lk*mY zC`3+M*XNEP2S~`;Q>%CD4my$s7r}QfWjo)`UCrkOj6cn(BP_e{efqvaA|b1ymr{rX zS~ALQU(4+}tRlbSQzF<7$`4wAX5JuBREbg8Q^ff2MawomU4@sOAeZN~{wB^U@SGbY z27mqb?izQEb;|mpP?W80B5F~Vt;WRdsiTQv7=N%fy^{F?ztvqXgb)uzSbnM?nB7sV z_pmhML~gLlqcEeChd@!#MTx>jzo90~&~PzyHOP2&2xz*$xUN@nlzjR_O8m>|&@tAk z(bH-@?CZ>|>F+0B5an(5ZSXU9IfY&nn*k3(%t&pGQVn4kcm_BhpOv3yG?^$y-XH4N zcfo4r!)S%>VpQ{@uiO(4@|*Py#i9eUfNzTippHg8OJgtkVpmgQu+5&s{K}H5yyCjM zHR_2zX!v3fAgXafgD>?a0#K`6m=xWW;FA5d#D*jRe366%5uTJ2 zP5iCDrG8^F*uJ;%njbOy+!qj%-A`+-jDNAdHNJ2f^88&+(6pA#UmLhuIPfDAlP_s{{?7pducj ziHxc2*F+#c5Cy|f5P1;5z_fW>)bKoZMm{57vzgd;Lx{ilZnYXg3C}& zTyMh^Pm#_BUTY_WYE*Qizm-imF(4eNy8)wsO38%YDJ7nMJroag7zc0@pMRPovtAqE zVYLD=DvDZ$r7x?cU2iym#OErSZXS_2>cqv@ExrShlMZgfR^m!rxM{eu&I zUdD8PN=u#dHxjzLocl<4q~23L9P7%-^`1oa+L?F>W+a)6;UlLP$NJ$_ zZ)m~m3lkN6)ZSq9Ld^kHdrXf{MQ8f*^Q>R|V$hNaXLmn)eFtlqb5kCdJS62a_FSz{ zFf|ikTe7_Et0WLQg&SCFN)k)GkH%K@va&Os&B*YK;rQYD?AXeibKxKqQdu*9{y)=< z#4X81m{r7E%Mn;R)twz**U@ubgt8ZF60x0}@arw#ny#X1*KBq!bGZu^DMqHF3lJkE zk-&_F9L364HoZR1~q778Ue(pkYGLQ z47~O40{Z|ItOPT}kf+lb1LMX^;^ta+3gv>FxEe1TGS;tFB$;c#%G)}4<>l+J55^1} zA-=gBe%4HS!f&-;H~D!49a?c(5fVDJb+F?6bhFyiqQn=eHSS{?V6@Qv#(PVfPll%n zMHf!{DdW|}JK|zNN5qbEW%sM+;;?bP``(jT2@F-eAMLTXyz7F19thpF5IFYyDB-;y zzPPeEf!|kNlHd3(S5rr+-c1SD%_fBU`x{}l|OnYZyI*Bc+k0T-h^*Gz+tj; zop(^D1g?So5b!Vj+5%?Vq?zCdb^`eemKbPKcXt-by=8pk>q-rj2F6($VN9l+kSNK|YbfURO znet*(n>AI5b5jqcc4}^iW)%AwS#5awpWi((N?T{D)k&RVY*J&1N!l$u;`_tMaWtjj zv(XSV#}<)j;x2jpVKfzE7*{Daam%?z#p*vJOf3MFX;`rT$!{S}vVi-$Kp6riI`o*< zd}aaInv+8M0h6I6Z-5RmvADqNzj0=a9U|5%z=@|9lHHSEZ}_+}t(CB>4pp&94r%al z=ep4x`Zwc+^8f=B7LmFE(Psv0<|4;pC#F{S_rh%x%vWQyKOviNE&51~&i_pwUPA zS7&xK37Q^5JNg@;qPw@lglp^L1^TO6m>hx08GbsVM^ZW7NP+0hNGwForEG*|X3_#d z+Zf$Nq41b4T)=aEAZWJzTWH89hFZc*F_y)D6?CZXo?(~TuU1Rze3)x6E>>TpU=V~O0T*E z-*`tA>r(Iv2e0vaKP;=an5>U{ZR3VjhXP4)Nc679tldMYa6Mq}5N1~RMwSOp_KNx{ zUGQapf#FaiV{z07O{RCaRj{Ww=~c+pDE#1R1*{);5IJt#cw;)(LGrxTLKIylNduP% z{{#FBCJX(dEO|?opMB(jK#Mi@PB zuaew#w@uDU#^WgY!zePSOPvX%bG<0Dg+U=U@updmD0EcGie-r zGOAa;1kf{&edv!hu|&$^{)Pzjk%B^L1DOpLo+LKwV>E;rk$UvK)D#VL`pz)v^;}AA zqpr6l!J7QGOKx6Hwn99{BpVQBCVxIX3Xl1z7E@KR6C4cLt)s)c1`(?5v z6;mFg+1H3IxWB4oYHg)=Eh$mcqDAptlgBd<`6O5=A|Ay42@`?Z+!;4n0W)?3gsJ`Wjmkf+YUTRLV(re0runZIKdSoU8*eCo z7d88%4wI_d-^}>eiz8@X&QBd7X!{d+5XT*LbH|<$;CVw#CH8U0;WzR$z2-_VW1#g? z6?QQ1}HAnUnaZ#lDg@OrB`N3$QkBR2$5C* zv#f8yTSNHbIaJ-$nV?kxHmt#R&3e-Jnq`l>$1p=BCj?7dC216`Gin#jZFeoaSkUL_ z8OhP)CSwf#$EjwNC8Tj9czj5V8`GsYd$1krc3KUMv%sWsTaKQ!IhpWavJkt+ff^5Q z+d)cwqlqZ&FzqMttKj1uyrO2oYd#wT>0ncN94{B~){=_TOYA_0vGz|$Ae;`*Sb?zN z&c#_j;YI_2<)^EI>>Hh@jUO0tb9B)SbxT|jfW~yOug3kMl>c=kDrdZlx5><;N zaestj&0A{Iyg*-r>tDOSp|S>fsWTreMZvf_Y~LR4H2^6LF^=jNMy4G$G%X0d0k4_N z2{3vn8l=;*$1eb6-mywdgYunnE+_b0njgJeM~G}THhJ5$iP5;@sueqwL=!C;8T`sSk%uPJU`oz4%o|rpmiVaGDyR&ew?48NHmhgzj|W9ml3at(a$(% zCTif9Z@YjZI4*p{yNAG8cD2~vSM@Yk4f#})8DPDV!o5z5S4Y!L(T|NG58dv9P@>i^ zCMuMR+f#^*|H^Q}W2tXZW4!r-20Fe4ix-a84tQ)eCkSK4FkEP$o1P!OCD#qPUT~h; zCO`JT*eFkQRO1LxyN2oCz$JGix(zTQdq@|Wk*jO@mE2Qv*newG?)P44MSl9>V_lOM z5I|ygtPR6nrfLs6QE{k=Sxlv@*_q29O*IC@dHKP zR}(m(=T_#gm2gPv1*puO&Hnw2CZ>tBKJwKX%I_134+g~H%bNmI-p}8WLXw-(+a42Kk zyx5$ICYjzfn+bt<_vUvk}-V?@%M}ar!gWZ6lXixm~L8oMlM_+{`f*A9v&3} zJg9_uj5usl?eT zrbA3t2p{>(v`DJio|y=dl<{;&=BRD4#etVI>_Tom;B5)c?PkQ?K@%o>sjxvlmSY0b zp54A6uYq16N9pj52x`*A`ff|1gDrv+vf1hu9OhjF>r{11KPX8m|y`9Qf& zu)Q$)J2~n{Xi-i}X0mzN&<8#p{hVhwp&AJ2JtV7t*;HOcgS#wLCP;gDP<$cAx*C(z zS%SF%{(NDMQ4FSqzD(^X3h$-b=fw}cK4FE06GWZSf9au9{ASY5(DusF&YuD}rr!qK z62@^7P8S@#@A_x0ZQPX1!fI(}rbVoKuF4e=>wohWs>MjO=Ht!md?GL#h*D=$<8(3N z_R02V{^A_-*7%2D`%z<(hVv?h;a~7I3!7TVAKe$pt_(y|>Ey za2Q-9p?d_B=HcBLZm|b;84uAni*FqkP%FU95#pn7J|H(pk>SvdAD#M4$km&c!dEOg z`jnwRErzlSN#)wP1#bZQ4#b{lnE;I&a-u&=fR5o)rH4B94~fw0#s2mTNY=IelI6{Z zi3PmNPPqcW+4e&Se-8gO=k;A^_NeciR5?rU31na1C}%(26J-l-D`GG$hZ{-I*z(+? z2iycDt_PyRK-7uu)K#zn&`5kXE_zy%4yjI^HModJk7>tY@3C{BL#oTpU9UZK_HlZt z;M88%3)kbFE0QAHm6`L-Z-8Er3nzeQn!Xe~azU^b{@A5qFS+Yi2N*jAp>$spG5^hZ zG!F%Ltw<`NYbO98Qn@LQ6C=HGOMnRQ)#T~WS?;u;9!1z*u2=E{%6BY-oj(i7a*~tj zR{)ta41UC`iOst{e~68N)upE&b@5E31@WK$&EH3LO9a} z?gSBzqbZM(9O@F7_kw{l@QK#qC1$5_XN$xBL#m#A&7F!}E&9Z|57|LgRo6L}EN{wU z^6b`GP1Bo_d~+DvmaQkVeN3}lq>T5pDDQ5~C>M_p-g$_g7IWNR`JJbxxIq8@Tm$b2 z(`Ad?8mY1AR~N(k*UO=oS51b{i;y%k)gj~sc8*P2d#fhBvc!CTkv%c~6RmULY1HS) z0Iq9^9IMYC%ra~?$ zsy3A=JOlvv5v7?I(LmHjlnsfQv11oy*NxT&j>C%3aD`8DJ|zQB3;#H zN$C*}K-BP+4E9jT*jPl+6=?kRu9=i=IjZv6V^%dD(vA7}SEoJvNLIIa?3Ss#=*Wbw zTjQyNryr}{?(Z}FAaEG}o@r?FQe!>*<2UAbso9ib$vrCgwjwe#IxFQ_60Yd7J3ps& zkZ^5z;L7@@pt?-Yieios{)p_dcr7vgR~#ux7ToO=PKi)ZviD|uO*dWn0Slws=--s~ zB}M%^cbh1q3k$#OuXJa_cL8g}k-4)r_KB0c7>KwN2#2l$wiGTrcbYWuz@pBBab{c~ zomMmzssjs;P`>WsLW^AOHrHxsylzqSU&!=jE!C=IK8>`Va>(R*irg#(?BXyGXqZNo z3dIy!bXJVQcIaT)o55CIX}G}4=Bd{ywfrW)HnstQGGqF z_E$jLUq843jf~}oVSec*0df(*JD6~FK;KrPo({^_4XkjSJ%obSfagwXaVPT=Qx&NC z`@8#ktUHqL2VnW6Sef|%*@q9HY(L0MT%|jS zHE*md{oSK*pY!m$6x}EY+IJ|^_AP40zGO^!vHGu}>nBRCgbMWZKJ9t4sr663MQ7am z{8k0$Zyp+6yJ#R^)9gBO8WgE`8SZK^4Hkkx`#GhoPV9}M-&}vdk9Wp)^ULg?! z6hbU24Dc9m?>bV)xbn+{syLEe{(6Dfumt5p=A-VcX6j>QzG z5!B5>#233K`7iQ;GkEl3Cjhd{c5nHQ$BKv`RV3(B^xuI`fHj|_o=>WYvt^Ve`+SoT zBY{!X^O~4_VjOy!*g@oVFwy-L0K_tTj{G5^G>|RL`wdfq>%-gu$hg?sWceu5K0a_I0$AWChE6zTm_O1C@a`xR$0M=8Ds+-$~lDtZt$ zSZ1anLy}s$zq>J_BeHlc&f?;;NdnMWe@3H8yz+HHXtsH*`s3e1#uoJIA#aktf7;Du zzrNFv=4Jxj-Ukthws0Hg8v3Kb-lKllfoiP%z2`x_yf*#-E{YI~fo>ATe0Dx6!4|9F zY|CGMmY}|1h_R;~&z_J74r@A&Yc%%G?>B0n@DhIJl{=@#Qzt@_{}_yW?sVQ@Tx?nAwfu zwRgaK?kK}C-^cU56D*NXl+q;w;LmyB70ZfR(ZC+XV_e2VH2LcLWJTtHPq&@_GLiz2r?stRMsl&zPuNA+l5!E&P)s{U8li7&O!X zP5fO__(^>pCRYJo2J*6IHh#dr=$gAPe=5}aD?EBrzpGs@?=ZejUy*9kdf*-i4GF)a z_3sRym#{_rZhO)L(z993X<{!CY`Q6<9zWzew$a8;nquCT;_D!T`4n|*1@ni--mIgt z5ebSahDf=T$O~Ua&umxNTb97y6vK?L*5D-s-A(HW#W@0 zMm2Xg=FyBrJTLhf!3PF998Nlr&FzX;SI+Xo8gr9ByWvKoXaZE<&2_H@MG2}CvFB`1 zWXlLJWYi+G%3t5=xN(%Yi{#r}XK6mD+c19Df=vYp6?AH){(8bPYGC?})0as56xbV) zkviUJL^^{5=E>@17b&^`h%nJh!zVua-~2vDeRzO@qb2?yB$*{VrdhwVG+1m;-2u?N zY|WDFCD_;=V2k%tw}HOFE9iWd$zHYt*0a&g#Z+~HqP2eY;t%@Q=fFg4ib5$#`djr$ zIj`tEegis-1foVM45wIdrl+R)CIu52W-x6{R48Kp(C6yB>RD;i%gE_qwD31ii{TSm z|JQ?mmwYs?9=iWjTqf^Gzsc_inq8Rzm-Z~?QSlhFgF^B|pKtOsXKAI_vuFW;#g-!A zE2F+A!92R;erwVg`anq9ebg%nBIXIzcsvbf0>AsOC0O#310ttUfK=O$2R$lNvr-(p zG%1TOV%p8`LZ*V+4o;vinWx|j4T|jRduI+m(InZ%=d#O%7_6$IOj*9XWtkZ6#rx)W z;FtCwH__)o9y<>3Pg!J;ei%nHf^HP_vT@)j6D5mhGBKqpHdiwx=}oP@^q++bBrKGA zVqvF@{A*YdQGA>3hVFH0XDIStg@``b2&eTrW{7bQf!1M8oehu8MZ4S=y}T`L!N)TU zDE~Tu+!e(T{!GgYo{IvE=eQ#xDGRp1)W9j!ucPaKM3)?3ORIAlkn+0*Y41StNcdh=O8_1DV$%6Y!@|q0s`Iv2|5nmbah4-Ee8E@nQCb-b zxc&K>ir5PW*)YjJJV@26%EX7WY~NoQK(!<7%F_3@S$*vC(_|1qLR*brUslNNk^xx+qZ%Q%Naam9bPFENNhkRp`|q+gV&) zn+@P9I?q37%w8V+^~Ot3toDTOBHPTaK}fhUV-@^0cBqyj)wR4{cQAWff`&gx6(g#b z^yNz|=($orQ4KDf)macGXv0win@s>+xf|{Dz73p(4-`ke^!mn-q#PX5lK>c{-5K{k zm#YW4vrt>FGr=KiO5>-i{VN9Po>y*2$DuMF7RFl2BHyPSG0>Vtw-I+YhaiCZ$ER;P zYJoE&jYFY-j@{3zj*xHeJIJ%S+S>>FnGwt@$3$xTYhjSzC#C37)<9uF#7UvHp%+<19I)N=eOG=Ub6r+}sl@BJ1>g=}pq$G;-)quM&4NC`tkIHyc1 z*VYIM8mMWNhy+J1d`NKUrh6150LVKu~dbJrnT#n?&4P)XBdkj2Mw;@&sgs>@QfW- zHIF$;M`tjr6u1PRmU#3s&(yf7tk2DMxt?zVOh_I8%KoAIR)ju1j=!hr4se~>!VhEp9}utb z3I6FnJq?#^Q;mt40;iEGQWhWVE#7=7^xo4HE%JZ9O z_K80HHi;{@2Qk~m49S+nDZBKZg-E0re?^yDV)TZrQs^MQ;ofzyjyiZL zr+W9sYK;y1Mc@C31pu#D9j;aT}VdZ5h1TVk_e}C7VrD-pU}gO0C@EWkMV^uAYvcp>OZg0 zWv2k=1zStd`Px_cZJozwz`)UVIoo@$9!c`kQh-*NE zb~FO$kmH|wuNBIelxw8Wybd?)(Y!i^IZuFhUIkbh$Mq<{u0W&11Xs%`57HrK{~BGT zI+~Ad+Fh|tU|R;D?(Vo{n|uzRaf)>PcL#Sg-()@Dt0FCWXid5J_fvf=*X}H4o6W^C z?NiSnyP3w1JR*4$JY5t;!K{T8G{&NMmp}~he`Idu=fWPS@Kx8M@tWAC$UBJe<@h(K z$)tCD+Fnt0Ch3=Tr=929PG6m&p_nmPm4mGEUfb<&f7L-Ql@+0L6O`RYZC^AG$II^Fi>gi*=As6 zMh|a~^m|9}CuyyU|Vx+_Cz(z#_`Ix*)bsTcH8Yf%^?NAA~EuxwP)VKcNf{AOCV*bae<)D_v2Mu+&d zGSNOT6nO^$OPkpAEhDj}xphS%BzHeKzC#Go+KWpM7p``#Py<#w$e4L@`-<`c>Lty( zKm57wY&g%@&Z}7IL*m+h>r{o4U4J9qojwm|$Ng7ySgvh1nb`-v>WkGRTcQGS-&(B4 zOF9_Bc}zb?=_;n`AF>wIIR|5(StoN^%`_EE>+S;!owm0WDa~88+*y5op&oaC*Ire% z@h#iI)J*Y7kDKUYGAS4^5)76#EX2u;QMO0FmYP1X9gdW6;kgeEPSud>EA`<^PE zGJkmDE`Ot&IhHdGb;*9payxl%yQK7N-?Ef+l}Hr{y*+Q3`rM0OAK-q0*Q&cY5=~F* zT*(GsjHs&$FOIOn?PB}&@-30MnvS0CaO?qRS=YfX0E8ZWhGBjAF~QB*oH&Glri>KE zKj>YvK*OI!VRSr;1@O0x_Or?mLG*!>kRbFa<{v9`^6k9L)qoeC`pMpb@V#sdklvk* zl=PHFiaU0=w6d7UL4#?Mcd}Ni(!{*w9$*&P#Vd)Bv3`0M@mgbHPg%3un9AW4c;T6m z68tS-;q&h=C9r1Sl?_uJ2FEjZotW%>l$^E5#dZQT*-0_)S2CM*s7HYN=|-*91l>4k zQ(^L)mfJGs(@Hk(KPu={Eb`~Gg1XHb|C`F0*3djc)l;Od*s##}pQ*zrM+XSxf@0YD@7BQR-Z-8&i1(oh|2h6$`-+ zZ@=eTFJVar8IkTjMeq1Fwy%U)Y78rCsKNiLqa`xJatxm3ceT;;B@Tz^;5BF=Ewk~jq}_2LxSAwle7 zP{KW|`oQ$*RM=SgZ23ynUQUF8@Zn-SUOuX3JpT99P|hddw49O-X;GP?pR+`WT&x7%bDk$s{k#Z{ zfp}U@cTyg@Z+a1D{ma>lzNl9Nt&E&_`}UskP`bRC7>THIAQ}vB1336k8H(?z$kFsBCg|)ZvPE?uB>*lEVkr z8am`@5-~>-W>j8VQtW{2p0BF5fEbWe8`G@ukEMV3k5cb9(K;kPqUtY4S>A$24T6Y6tl`swHtRm=p#^j(AUbyV=u9oybfw~to|nE z%!Hc8XPv%gbTzC#DvB<<3z+PG2p<1RHk{Igy(?5ly??j9sy_F82CBpqG$h<7;N&ZamWlr;NSTSNs@od zGPSDbUwe=SC_5Gy<5iftW8aCf=CPdK7xh+6oeR6jU5l2>c8qmd;4!6MC2G9yU|&iV zpEW9unagx8E=vpsDi*SuI6iN71660n679s@BO6b2=A|F5*N21&FZulIfB>H`fRmfo z@bvx3SeMJ7vM2Ng3h^u-kDr~Bdl*Rl_3!Ffc@l&6yVwQKX^^JEeJRkj@~>(sqM5tj zt?(jsY#E(v34D4354OIxewrzoLohFX>5tAWP23FkzllO(ERYy(F6aZt#is( zji_A_&JKtClbAiw0|}iOl6gi>+59I;0C{;YxCPN4Mga+S zjX`9?@)qYVExp5&q*m3#t-_?1TvNo#DaNh#jrU-iR7S+*aFP-BI*|sq7{Qjvb%;d3 z*H8=+l&R2fxoBh?_y4TV{0x-WkDaX~j=efWTSF1_j`OtafRh@dSCSkoPcjrbSzfIh2&U*rAXSB2nE5$V1d27Zho?jWSEQqZf2HXZ=J!Vdd< z!pEAa=vJXXBnCwC0cl20?i4@o&(04no=op!S!3_U>i3x)_M2h{codHYhWr$b_vx{M z?FUd3(@Q)opd(O(q!J&_di29L(AM#zll14r5P%^-Z z9vTGY`4Rs;v1*-RT&;3$n%0Km{4tX=w;GR18DZoXkTGPd0VkTja$%5J9#htJeK|$Y zUF}QETOh}PC!|oAq7P8&Jfmg#?&{rMgDhtTx@oK|9q1$h z;hmJ=0ud}m&aez|?m|;`a=uZ?am4TkInkwB?S-f+X;O=jXA$8r8UWB5q^T+>m=K9E zz&3UJg`L)z4xU=q!k)_yo&5TdG~lN&${V&eSlnS)OoaWK0; zpNB`%m!D=$RQ^|iBYRnT-BtAyAC0(|Q-jnS!TdLE!QI=|eJ{<@`Kf7NFPe~;_62C9 zdJ&Y*%2v!Wn4vuPJn5J=vmd*~zVB+@P{<Q8PF2O%og0P90T|9`v6DTmjHC0Mk3WaN|Gco?louzIs0kpilZxiv^@OGs; zQ>(dFdLdUp^5xe~{}6@DXz;#sWeWoN=Sk7kecJ(aipiEC z{DhWy6xn$r`qT_w0h`{nxF}`(HWV6ySe=B1;b9$8`suTro6holW z#k23UDQWy9x}IPju72kKpctwXURTnZH%WbnJ^enf9x?A#lY+ZuGa0mp)%381kOjwR zzg`UBJ3UBR=E)8?O#XRDzmFd6vA}al_*ow_miNx+RS{_pep{~{Apn3-|6NhlieYsA zh5|PZu;M@HBsh8;^#BoHC3=7U0g|3tb0F*KLP9Ne$>h)#$*pEOjO!$zE1eOR0O3GA z#MF3|oqsHAac#W&cX)fNyX?GqEz!4dNBu1$;eMyNx+xR;*tiDtM?Skdy3o;Ltfs8b z#>2g^PGRR|L112Xaf6{j(f~E_2 zwc!Ft&=iOVkq>~5ka__16`vi--1{`$6-6`m z%4t)q_1&|4NYt>LFm~;M!t?--)h9oxKxUp3seHfEzuKB;x)QV|c&sTVp+g1vqW>x! zPwvh%^8F$s8E%~LzwS)#M6Q>oF-NgqTV#(cjEjI$w;Gjvh{H;u@j>jD<3>{kh*PeG z1FxyiUKEV2U4WR&4@L~p6SS1)g==Ct6U5Y=sR6HRW4A%uM~9cISzC_6^4C94=Z8)- zKWKoxlPk+R!Hw&YG^c{8k>}y_B(fMo%3kQ*ZRmGaWy*r+tuS z1$#g^PTM=*z&qB6V9nEtkImvuP5HLQr>vo_3#F@HKxl@&Ojrn^7SouDj~<~?IliNs z$4hy`;h1yS1=@xXKS~+^`qH2tJnpGYd|M z*j^d$L^lyXNyWGJ0FJ$psAPke6MYdVF8bDEI~c=TUdje3Ju%-v2?|B;I-q>c7U}U&?7&@&$(H zv>K1%FoOpANwr{`Z(c8RNo`z`-diqQ$AkMSxRP(&;PQtMQ<@2hLa!<}q>Zt%F~09M z4I2!649V;fy_W~!fEJ3J-ey`nQGVuV4OEt^CT{ITu*cvqW`ua4n22{wuld6iaQyo9 z6#codI4vn)UI(@^6h4I?-_JaoPa;RAspH{qsKhXtjz=daFetUcOdI!<&cTrS9UgzF z7NFHAxsr$59=Tq4XwE_)#3J-wAIBppVM$2$<6Tvz+Ow;00qXA)-%rnn=>;Lw*F-@(Foodx^=2qJSA?qq-6+HFK-TA!1^WnEPH87_=5-3GPGLg=`?H8EG1F!RF{ z;=%~8665QtT5J0w$C6O&hCmYL&PK;Dz%|oTYNp#!D_L)B9oJ|l-?8n!J7nDC!TDG2 z1+Ab^{(;@|oRd`0u8i3IndU8eA@`}J$ejXUpUwpZB$rBSR3r)2uvwgS@mg(T2`^2; zA*#vhk?P7o`g$*xlF2L4vJM%MPws2Dzgq5ax5a~g8JBW}wFK+u0QX^3EH^b9x)i3# zmWUj!6+K;xuw-L0ee*&C-jtI7(i&ylgI~)K)-;)T@bb8aVM=*^MxPkGc-@%uW?k%x zJeHU(dj8+~`YTDk8%e917%s;yCL1qwur8%*EOkL70PGsh8ds9t2*C-5*VN#{u2dYD z2C`r)Y98pQC}^hopOC#v1^@CUw-#>;i{+CEm^vM=>d*4t-y$c> z{akTx4(~QapqP9V+xg6yrUlPJFW`TtV1_F!?PqF1z|*D;uUN84ZZS7(pZUij=)lBe zkVBx`pnP4|k@G({A7{-38SXQoi;`WCJR%f;z*!3;bMdfE7O!;8I)>Ycy(6Jxzox@r zjws5GbWkvft2p6>)wTbFUkOt>V|Q1X<}AG~I_;+rirt5FQ+ZLA6^}E2L`+^fI;0K**oUTH;jiO8G=>`7DW-LRhX^9|rx7)Z}z>(0&q z_a!r!vc+vaiCHrlLK$~7-7DFy424|&8%TMF&;?+ENEREF;%!Wc87zQ#3$7s5byrLW z5rb>r)n}~KHa|kg zcb_~sW>ThvpM^_Kmt==F!o3QUq30G%RT1`5>_7ADUh|nkv8^N8nq|a;&2-D`J_%Lh zP_lNg8H!dDU2)wKG1Fw|JgZx!L7z!`Sd!kPZzjuar=>jtbG@P5iLo~EeYAd6Uhkkkzn+A9Od{7?* z7iKK04W{Z#_bLqvY`VFuV4zdm^fPOBGx<8&PgFDVN<53Qo|9UYGy9Hz-97(>o^e0+ zg;^$8=_61m)6H;(zd-r>cGq6b*^`vc;0IHJJieK6l9;-~l>m@uV+49SDMG)!(w?O>-FMcBaUDGIS^n+NRlXR zOq)VB;SjZ`((%t3Q7WbtTH-s{Iq4h{#@N@`t;tIcZ^1);J8(EUGRw2OSB(rEye=9K z*dpWKorV(mA`J*fIpRN73F{=aOqe@3kAD#Nzd+oHXcnN2=B;4Jf^$rV)C+IWgtFiL z1y&HIvaC+Hn>7#LowlUBMEx-fW{-4-RRCx*IBXUz{=;?AAviX-Ht`wIWI)_Dx+y|2H6~kOGHp1)*b)cJx*ZQ|`qY1pJb+vQyceb^V6mTymLnS$oq)=sc#^rwQmfHSVvm%xA1jg|TA_T*4i;2Oz=>*7) zs$d&B)4LaOOa%>f{-jT@Cg(Mbw)4#@dGCl3sw4>MAO8~o?}>lPcgQGuriE$%Zny9F zzFiTpbtx6f!m=FSYITNBk#M(Awb^i$HkaWi9c*=f=+%T3y6spOP_a-d}^kDv}-&)kU;_t zwPsnZy38kRO}nHQ6LT{~{xF_BXNZ}#Gub>p0Mn$FOF*&8bgs$6+?6zd!d_g#`zcz? z0Lgvz>UZLpUge!U`dD{7m1}P%ISh;8se3EuI$OeE@PK{ zJ@Y^87t?t|4&p~kz4 zT9@)=D%#R<-qfw2!JRRQVNedyPwdqXp7zhtR@)Qvd*+gU2f>7X3uSesBOoebJ6NO& zGGyJKH2(;W^pn$@DE})9(~g+Y^dm#b3@gHh6%ySSqy@T4#xk0@e_r%w6X^W~6X<<# zhYJio)Gk*z@P3;aPaOPfkiH3Ot&)Tn6>77mRG&QA^Ex&xiV!tACNVtCT*~A%tC+SD zZPmX+s*W?HYd*~~`@cI1Oby@(3GC+8s#VQNy!MJ2f-#_oWb;d5@u3LO_u-Drr4&A^ zE*&?ZX0em4V)g{3Ga7riB#FE^vFIztd!kQ@j#8nluV8-fs~G>nvWf5b_m{B;4;a&* zS@>u7LMSWYZy;X8z87Jrbt0Z;rGQvJIxM>VI;Xsd#)7Q6{0ZmRPo_Sp_Lz8KHdg{N zn$KC#C-l(x?|x#@k_{Hnt%#WF{-|&60*Bt^LOX8RjAGmqqi#g(bxmCFMcCE1S?JAP@ z>s8Vv{movD`_C|N-sDIx+o)s-1?y^F-FI1OV|u@FqmzuW{DJI8lt(mOqLD zK`+Oik>)xm$SP&{RlhcWn`cm?eV*ebDXm2JIL&FN^cl%0?kXV2_eXD%1*imZ6sEBc z*?%HVPvG!{m_Ch)y^k|}7Z9H{YGeUh{)eh!!!3?NX)FPS%4_?AU1^YTXcv;1++2?f z>t%?LE#ah%n7sERp~Q7{*nTM|(c(7T#_Qr#RB!^Z7I zKhI{FQ7g3N1CF^hb11SVrFMrI;%YEB%5GhIqfpj2%2rgzovKl*K=?4l{nvC~xxQ-O zbf6n&Od*vQ&%6zajnjKtGaZTaC7tFJhM!PMhVd938IMO{w=MvsPe$wJvn4{BoaYL3 zgm;5};ut4;Hf_y;5>{w$yZCQ}07?rjL>5j{FajiIy=W+juv_wxwb(`bsx+m;Sk7zS zJl|lg=<0$G=BmbUwABny)x|7u39G7q{r2P5kSgPS@BFY_WN zkD2f96g)`W#FjWkU^Tif6jr3vwvsp{l<6msGO}1j4oaY;;1^)2^Q0Y5%k_?N-xGanF`ygQP5On=lpt2fZG@b|poAsUk;WVWHYP z0HQegYhpYs3R1Q0QX`>A2Eh(Gc{_SLlj3-rr36{ycTRoVB02i7Bk4VLRnp!5@T^mq$~WR<7LkghbnT@v zdD}D?**AoyT}zn;%ce}R8Ae*Bs$7_+PI=WTSY|9$sdKxxEXA+0&RTk)HZ2S5x2S8J zi%#T{CO_Qv+1)<%_c=Tei`qWobss6`t*F_i-%4R1lR)7h1W+x)zA@75UpJ)T*ig_m z)lnl}qQo=npnn=bH@}{(@zl%^t$;0>a5OHxj~ZsB+-Ca(E(WU$Yi0GE&;>SF{BmW5 zk21Jw{OWbxABXNdfSTIhnEu?OpdHst{mU6w_eN&WAD_74E~sjp&XqH z@{h?c78kgC>))M9>tHNS5VX^W4YJzwX(ow*B{!^Yz4Em$6NR z5wWn*?L&j&$bIW2mc##`73G=RGN&Su)FG*;%OeVMXKVjd9~Qv`?#$jK?a6{!>r7l0 zujBY-I)pg&i6X`K&8p7QwN9u9k(;zxW&Y_|Kl+q)brLL6=RcSDiFrz?(n7o#TsIQN zg7_fQDzbH$4C>vs9mY1R+)`? z6KLuVJtm1Idb*?Nl1=3B<@k(W)MaeB7sz%fNPIt7pc@9Tdz?98fAo6`ZU5O9dbs~Y zHvjN|(?qo0dK2q^6T8?cnvs!ZaR#0FN6iK-rPsmdwc{^*?}~C6$t)6h-NEX*OaP2 zfXg2$fPDhR>`7r=jTbfag{KzE(vVNQn;5KWn%s7sA6ZJ8IXzI3vKWTA+}(i zMlraaijm#204Z__C=Q>%>AG~MRCWWKBmPQBlz*4rvtIJL;u6{KqK9Hc1+Vhezq_b@ zWT`ko?(`u9+yjoiMIh#xbs*GIMS9+dhC>X z(zzu&)L``GnKOr+4kpYKBBJzc&RA07%ZE_7?w4B6q$+8wiQ47J7OL+2&aAGvkaeF@ zhI2oXGO-d7@V~&L9JK8H%f22OL@eO zXTnsM;!RpwKTmHIgm?r)DH!ZIZq+%) z@c6`lnz7(kV}Pgv&Ycj#hAKpa_x8)(V{L96c_9Vqu7xfx{qLYnJ=ET9rA)YZ3*!&e#=IlD#1wQeQ#I@in;g>A+SZmCP0WoS$zlO zIK{Bg`qNo`kW_|sm4rPHiQ^u2!-YF{-f#5f`_uD<)xzcqY1=046NlU zxSaAYL38b*I=yO<53gZsmpb&IFSq0YCusm9+%J6fB@Gg|+JIWrzMIp~9@f|9<1aW| zr|2`Xit&;N;_~d|v=VkfTT;&o6(4pF$Pb?2V}2cgTQdq=3Mzz%GKc! zEU1^kC;E15V-)0xx+W<`sL|NqWDVs9u!?>teg!Iq|n5dirjHfKMMdhOO8;NYoP=L2~ z!9W3_Fw3?Hne>$8*iYE62i;`%UlO=1m7$`z*R4euF|3cjvo%U{GkP*)57+`yL_ZVag>}M6oYevSN(imxs=WMAyI!e+>}o;N^$! zlW%nB7pc@P4VjODbQSzm&PzQKw3aqUl+nnX>FJ2Z5@<6BXv@xo*>=i`v=@D&|ISj3 zvC8ERh5E%El9tlJX$Kfbt;ag%`09KUTy)((L81ok$kjMv)+cku*zi_sLn4nBn0-SB z9Ufnky#I9%nFoJ8T&85d0{q)TVNT}3#)n}(8;38{#ZRv(Uw-c=N2{?=_)*>}dQj-5 zeTZ$2Z!4U{2bKNuEE*EWA7r996q`fC63G8-1b8kP*5wXkNH79Is8mZagxG4Y+G6jF zXLdi&_Ez!bPy-NZ6zQR41uh)bUHKwV<8UM8b4~3*g4YjFM zqe;u6)Ox)^TS)1V^dIMi<=@h9ahCt5X~mT|oTdDbrtIKo><}W=$XPKqBeE|R=0QGC&j-k9xo@(+FH52Va^(M zd7ewgy+JH$y>RMGI0<)qOz;?|Oa$xapRp7L_{|+uzuF{vKc=2%nYh~(b!-nZ~p+c^p|{5jBg;{07#bTUi#G_?l_TB&8-*Th(o$Ii&9_e zd{NAsrA%i$0jn~bF9mxUaYGSXYxSYX5f@lngCYwxIrJX)Adljw$dXy!wqc$Ee9@Gn zYfNHTp~g3pZJ_1`F{`_XtUKE(}F4w2VRYdP+)8k-O zcl3(e{BuF`{8X!;E5G>!g^xW9rA-JCT0Y$Ar|a#4v%kSs31{Rwvi8BOeE?>C-|zm; zgMu{0gJDnwn@Y`EkbljEb!nPu;^ZV7&wK-B0@{F;=7S_uh9v*ctU;VfVJU<|k4Iov zM90?ToNtenv_@}3)saQGvjs>9!yNl~_2CF+cEm#K{ti9q38K7Ak}?6==&*p=Zd|r2 z&pI-V7>y_V*!4!<*>q{{+fjau_+fvqN09q^1FC=VMrHstOx%4S=~`#KFT1~Ej$(8H zd{*nf2VRAHw?x@jd8F(MZy|kEgCGH--S!ih6wKv6G#SVZo|>x_O?$Q$N*A*kD;YV< zy-#IIJ8qLHj@Hmbu@3(Eol92!9JLGeMn6*W(NPdo;PV#SrXglOYETzV+jq~?6rSA^ z==*|TKlRh>Kk?@1!7FbT?TTD2(#ldX3!a{X2%LJt*aCz?t8Vr$0jHh-%ywHC?Lq|u ztHlie-C!TKuhpG^&4CngI3b_P=9vv?Z;%B0)|a+efX}rUYTO&cbv}64QVpcU=w@E( z7lA!CI%{ROo0iw{DCebH3(UO+>)tAzNP(FSydw89N!bS;*ior2qglmM!ksGYCs?2u zxJFA?1SGqC(H>?lfWi^0#;DDY6oM$;jxa;!P3{YOobx^uU=|eijvXjfj&!sv1-kxY zc`K3p|K$nCZh1>e4yC-JzizrDT%d*(cXVfLSF&8<<=!+Zh1d(NlV(0e%OB%D>0Iv4 z(iN!AQ3apR3{H`%*=_B9XaXJ5Vg;-$HWtV-!x zHwGSU5seR92%-1$BG&~me7n9C@^%m1}@O{t2a9is7m{1k@JZ8C_`p%OpjjnfQxHOU*XBrh84Vij*_N zt9WCpeG319@{qce)QJ2jOq-TyUF3j^hUuS_7RTX^uK=j`E)oC7hl24h!A;3-B46{k z{3`~7)%$JZWO?a+z{5^^$4+E#iEJC${Wtxu6;T3BH_k)sl=Rr!Sud(19({vb8p^Yi-L8bZCD)`tw4sx zqz3!ISZa38oi(y%Bvi@ORMuh_tX*>hThNEmS>_Z^j1tG<#UQ zB|{U-n0Zy55>B(f`j}5?t2@ckb!!x>+xxgP{F6Yj$~IGhAcoIB>KJ0_1p$-E>pO>u z9DGFE@Bj~`n6FrreRk{RQx;sG&~s=v>wey|^SW1dDicfL;~t6l2hvI?5V$|{2?uE; zsrQ`rrv}=sxJbaD7NK3hp&IhZQ%`Lk!O*~FzDI)Pch zLg^hQ_OVsEIwRfF+NiuM2LN*1_e7`NtSd+MJZ{vAk`jE9m~Xj6(lxMgDBFyKNv$Q0 z-ai0VsKK-UdsX#C2*fG)pL$#%EneDndjM)A}(wC}PKk%0Tw_j`rIcBN#hxK1?o0eGHRFmLe zjU4*l8UC8{-MB5++&$Vu1}pzt?C|wls=!JXw7V}OsX2Yr|7<|YejVxd1_9Z$!nYea z4ZO}dEF~mWC96{qg1eNQ)(d#gCXo(gK3*QWX@=tnP8U6&4zt6Lvh3Hxjak zdK&Ixyh8%`5<4mnN+IeKeG-1isHkL_{tJH6#?b}kD9@&rx4=-;6}Z6Ti(LV}$k={=yd-_%~Mve`Jb#`y!n!@$KwKS>-jx`v{12GD7g?dg%r z%3Uh3?-j9CUuA4bVP?xjy|9iS{<-)?3f4qY8fY{_u>{~#(<{M?gZKLIN(8lHH(h&X zbj)-=Bgq;DSdBB@7s9(ZJ{^4=7XsI%O^%Z@)xMQSO!Zwi;3fb(e2LCIqNCh^>q`SoXgEuK{%{$gfb z$Nu&5A1^!7sVk(!uQS~m;|Y^%DLK0`eKQi^xR>_{VQ z-=mMk@sHem%x5qhO94+ON|I84#TMQdb6wI8iF`>(4Pl(cWZ_WYLINA(*>7+vtfjU4 z{G(8U*6i!V4*hvI0p1;6%2|y%_d&MJp!+~g)i|rF?&1>vpbtzSlXCKF$5-aRA8Zh) zB87FtP<_OywQdR1W~;EZztU-ae^a_RG3LzTbT7CM8mkGf{XSaLt`w%woVC-?wHe7w zFay)v6;aX9hHb4q+9gww5x6CZ(RvX#S3H&eUWys@aDsH0Rw`jwXjY)n zVYJ7nM^3xz0YXuL5M&qVV9BRydr7^Wz?YV9X*waTNzQ`XeSYzSOL7uRC{gIuG9Vj5 znX7XM_#Mp!jKpb1PgGVo0y>_xp1z)Xr9b-MEVRtIf|342;h2fe6omX`55|CMFt18z{b=LYRe9W11p$db%!QJ)W)_$G_)YLug zH?+$S02_p%^Q5u{a8lg1U1_0&!|Qk-S}zF`5KAdMNThs@OZIpENEip{n&2k-NJWV#W#CW1wB-4; z%6z*Zy`mJw+o*m&XKA7}cDgBK_n7hTKL!21JR@_D5@Mc`)M%!hm8F@cOjg*81y%`h z#|$3knytt;0*Q_wtD55YTyii6`+0=Hd>W|Oy&~A!Pd=)P8BAy4BI+Lf*S<@dXROQx4lPt@6eM(8y+B!G$nZKUhbuVI07CgolcP8e#G!F~GHeja`A? zgfg|S=R#FotQEdb=aU)~X6<*12^bUT5Wvj`$6~YH)uzRt6#H`&ip!LR2AV$FHPgND5o zb#c0V4u1~nnoLod0^zH`XV`Q}@KHju(w39x{4}fat)~Rog-C2N1(6*HTPsKDqa&zZ zSXGjvlz2GD!c*1yk_&FC1{+>FSYaUHJR%g(fPrCGV|4)qiov>Z3R! zD}R9a1KTLY^oGkeQoFZ1p8~U+^(rnt=nFiU_BmGx5RIwQf%q+75W$LAt{*nf)6FjN za_}kn-BrV|^J`!3mNsp-KM*8LDOhJAr7nH<%Zxaqz}msR5F(h>m4#Cz>GoBNFhM%X zg#v6F9ZM}l^D8a%EEMH>U!h!4RL%Eg=N}viJoL3WO#~%p(7IswrRfif&CqYoENL;@ zD^(*e&!YfSv8?R!Kb;__RwU}=p&FH?vSP5l(B?4k^w+O^0nRx>JA&riH{}78ZMmL` zo5E>Vf|I$=P`dl6w^B7Z`TaV>lahGe4Vf<2ya9NWk@B1uc8*IvLGwP)73n>Fhd{1c zl7yTVe!5-8vx`yPAF8v)pV;%$dvf0r7uHGZ{pu$bTbHC>10c>TsBz?OK>I?Kp7=(e zll!q72hC7goNq^ZDQaO8JKePHNyvOahEj@YBmFw^a&ki~3i9=Kvs_632+YIi4(*5-uU| zM>Pg2rU-T+@vFHUJFqa5;1TZQno8yq>QR&<;wElG4Tx@0Ir-smaS&Olha}z<;qc8wS+iL$uQuY3gXiB zRX`OYJt&=l4m&~Fe+X}unzud=qdqxCIN!a#xsYDT7T@s9SU6trz5fSxpF>)x311F{ zqYc0@?}%py{*aU^a5b2%!qGLO0yxxLQO%S%IcoXIv~R9F!CPBwH#<<}N7&>r={d5_ zyS|#eOC^ND8fFmy1zl4~%qJ3*3^5``sZH-vppZ}%)SWEF3_j~qKSti;W+;?PqqZg`BvOY_)0GCvhd~nPG^5pKlhwxOT#ao! z(%qG4NqJ~>`?{_p8Wv33A9TTar|3%d$iL<6!C21`R~>-}%4o|%@;Qkhg+-%$tk*8b zF+pRQcku1NAYJLE-dP#G?sw$(yw*ng$?{*o)yqCehPLvHgKcwRFJ!*CP1h4KegZ7AA>LP`SNcy@qAB&)RmspAaqRq*_n}yg ze)O0&d0nV+1+|hawbXJCr6$ViUnVvvZS(3i=Z3GA6~IT^h=IZ#{f!N<43vq6iD-*jK`)gU&*^GXTOL zlT9>vssE&+K5dUruCS5jcRgrp?8=!%uN7i!K+41H6=8oVs#QPs#8r=y=Cx;%KY=(q z%k=uwYAa-mIfOg+hx|22WsA+&ajoeGWv+Zd?8RWk#S5kUtPV9|&tKBK~NdO4A$~ zF8XG|IoHC&nhu8HcoN$r=Wc3ZWVIqjnqZWu+SEau$Ry9cq;h60HPMdEJL&%GYl6=D zV7p`+OaLOATy>4zJ#zE-DU%M`KH4l-m3rh9V&DZcI$iLwjR|}Y-3I{oANKhKP{k%&L$=8Dta14Rs2-RGmton!P&fhw+gN@6L;*mRbO$j zlf2;8;x0R)OFYS;hZwdt2uTbB7GK{}oxx`<)npx4sc-L>vVmuZx1|(#l#vKyQZUHK zs5*VAfZBC8%*rv6i!gYF#fOgL2DKJ9;z`#w9sT5X>lnM%xZq&^uQa$T^ zbM!df8tX27=NA6*lW&?E?5VXaLG5@4vTrtD={mAbkpwP#%5CK~f>4z=J*86_^uo_y zzc&A?^V9&mSanT5fi7WqI?QwVGu3K5*lOvmH-8Dw`ZlfS^C;6S9jD#~knFi+y0Lt^ z%6o_i@RUK0Hfa29^<;H!Yl-*Yd@u!3J#eLf2J2m#SWmFIno{4eAxwu|LqViV$Qz@I zS>jnBDNg|1LlnrpVpF-|iug#P8l+a!C-zNOE$MHj)~+Bqcd3)AT%I<@%TVAZ&g8@A z=0|lB&wzY(O@by47Xs%dfPMvX$!^XJ7Pwgiql%^GtFip3z1n{UW~4kWL&Xeld4hXm zE7aT39iI*^O@~n1OMy|pNgIS>|5u%or~lH*(3>X-Q(xXcNlXh@5@}Uy+>J=EU)r6* zW$Tq#LO1G!XfFsgHcIWrj5`mZ_UJ?LQ-1(`Fv<-u@R0-iY#bR%14KzRhqy1C!U-o= z$-t^??AoW!?hELK)rSRkN zPT=LEu;WMxa5*a9LGH78^sIwz0;EvBd*vS4^Z$yrzF9_qw2b@Aa>0{i2dxO3R z`Cl}^vqS~Reb5&NB|feD=P%iHeYCvz)5oDi%qveL>l?yqgMMc8(V|FHCeSbCj?a_G zEsrNgJ_y6qir{(aS^irXr+=Zio#4-R(CJ-zX!<&bcuIoLTwFd~cL%7@`GCa%t87yS zBKIAMR|Njg_J}DPc9bb65yklitEtrNAqteTK@tNTp|P;8vYOq0r5f1n>drsURoiK5 zlt1Z<8KZLCjemc}+-7n|s|x^z?NlmeUnVt*%IvC>XW&HW>-1*DA|dZzDG zxf;LvOTHsg>H$SXr*HO+fl&B%qtjh9ZO~jgc?A#o7&ig_H7gPKUbgP z^921wCMSv;8-I@gkR#>z@UxIZU$wWga&w;IQHkt`AP<#=sEpxEk z!iA=Jbs!be@WIr9SE_mNI18Wg_alBz5iYI9mqLz@iHE@|NMW;_ar`nSoHMzD>b?l8 z`)t?W%Uv{)S za)Uctfv8L;hHpU2XjJDa&YBTrMNkC$-Mi-~icy9Xb!u{_%o&-N#hGVJSLf7`kd<<| z-AyKi*ZR1>&vfYbs)3iCDp9CU&B)*#JhLHGUdfXH2qxah_q`hq8{8;+AX^DD2~%eP z;E=NSvlXyme3vYGa^W@Osd;c=>ELRMF)L}VjuL?}m-~=j-8>vi$X4Qn%zJH=E_Nw9Nf&N0eCiX-i1yc6^O;#~YWmk5x3OR-5N5opwk# z28G${+jVmACyqNTSkBA&alLH`asSN}cc!*7%*yU0#>zWq{4xFx09hW4d zGxMd;G4R1OxVe$6UYu--Dr+#h#3R%_gdThO6c=IgU_}z3@z#f*b;Nd~9zQz4pUR?% z2gO1&{^tA;(Xohs)0h3F_H{sP#(c-+AfqYupXGT${4>&)9n3n5=L9osN%bm@^?b5W zmZD`URH%RhY%ZWnCBe)txe^Hb@m${_OKC;vTeepBDUB;6_Y3r;FeI#4eZ%42@7;d1;rn>0c+w5*VbRN!hvoOyx1M<4_x0*xllBMs}4Q|I0k8^x^dzjI014hT?|@$8{t87!&90nQg$a2Ail%&v6+ z+V<3QIPIs2QTsm!oDx%}ibG8~OHHt~H|&MjwTbVdF!rK9@w{q}%*cO4CBjD^t&mvS zgj^YXew)8#zoB`FZ@G_2F}SQ~E0-IE)^IykICFzhj689XJ;YJTnI|J84rTIeyNm_i zbjkt06ew%Ex?XaLpQuX5e$L+#hR=o<-N6S0mYR7Gl@p+$v&e=PoKgB8e0cVSv$Gk7`slEy;tmkfE-;f33Fr39V#hk-n z*9|hbT+v~LPBt&$)2s4YFd!6pn7&Sm$;oeo-+IJqJ5#~ZMZQ#s67iPQfElMD`%rEs z45F$Sy88Kq!R0A^`9sLxi`uwW_5W6OHz{a-MB*95Reht`&!`h?{(T9)*A*+fu(1zG z&#)B@(|4`uU((>M_&EWH5y0t^LN6-cHkf3dJLc85IZOs;jy3+*zOy!6ogfo+u6q*- zAEk2F@mRW*Ae0>#_gj!2%H^j>A#A}2tQ4)s!LR>tdERUPR(*WfUsmo`{7x6~i>God zn@$mN^JqCN>n!^1{lh~xoS0G<8-#>RiMhs$>EWT`w6^}eh5il5vlP=)_XsmjLHdF^}(Lk;PVOCVlR8fma%VeQv+vhw+cRk zo~tr86C0@({{-+wPLT7EYGXN|5&wL8Kt>`&-4`c`jLlQTdlGluk7m8cYcCB)?xhM< zhc<+9$h*~tuQlW*9dI)jz%V=xX0#WXaece~t;slzXbOc91YX2@|GB0m=w^$;z#&w)~8e=@pstBd8(na zYA96UEoTJg5)oVB0S!^^!x^I~KF2+hUeZ(Hk4F!73T*Ms(sW?b zOvHGkb==(^bm&ddEH(6!kvkJM83n(0L2xMR6d8Ksk-y|ww)vYTOg3x4;>|~L%O=i3 z$F*sVT_AD=S?a3f1C2Q;(pRcFDIo3Fk#`Xcz8)IrAM}+seC5__FboG2#!c-sCEj6M z@Fbq48gC%vKgJ!9s%NH$YA+?0SAfD%LZ_4%`eA}57L7aWIknrt9Ix@5Mw?GXkd;ls z{698dsdB+p5AM- zMGJW@9>m^p41b*{Fbz~HcTWawf*G9}RrA(Hl6&*xQ**hs=cMHQYf-YB(5ul*Vx8~{ zGsy|P(9oy{T4?#sR|{;>v#_jTknp|ZEG&ePqReZCNxstVsMhM{ABptHuhJ(;Fdf#R zEp{O5Lg8$YK?pHhLqOmp$AIfr7)5u}&kl}HuNeXG;aY|)xl_!k$=PF6HlEGYQ6=W8 z+uP`SgYHz1w?FEW$molF)`Y&xW3=(H&w6)>^?3PdO^@>}hE9BBieyX~&hh!3|7z+a zH?scvSjpdge9T`}!@l@r_c^HnNP2TdpwI)RTKDCfB6+O8-&{YF;!l@?%^_qy$|moHD0AFZuW;!CNX%16C(I$yV)%hmg2u3cLriA})~{3qNg_+$SxmQ(thV+^-%uwmch zk;}ix$$bT{8g}==ny0`d?@z7V1<0R86Y3|5?9;miP4^9-eOyP-4CLj%+2L``MX!+y zs_P>LO+6266p$P}ioivw)<1xTv7<`5wR9ol^7&I==Epr8y3}ugc0uxtcXsZhkg{|1 z#Xc>N_E|&<&;cS=#yUzr7StB3Pmt`j6Nw+4ay@N&^h2A<>c8`b+~IyTZ;4yj);+U> zp<&Q|9ND;MStL^Qa+B`OGIGkAckU^7qIw8=*`!10Rh}hAHmgPJDZxpa3{Q64J`1;WyKa<5!hF@>8e))I(w1M?u?#+d% ze?sURfT^9f>|vc#qj}>GPigs5`ybu>qC)!@lcSMrIsX@EY3@81*tVZLnHZ5NLsotD z;?IN4x^tIu2^F6aP5k?3-|5D3AMKof)ausV$K2MTWFN=Agp_gbZTN;giv5b0Sy%`| zrYeRDf~^R$K5Ib9u3P+T-N?+S3q?8=_r8&OVVy6v_17V)$MzQ>C4t7ZWTJdL;1S;? z>HWu|XP0^;Gz?D`KvF0w8&M-4QPpX0;r&=u&8&%^w^&D3bbTaTQS`vsSaEuN@~}MH zdhGG08Tg|bCe;bebDls@Q%)(ZtiQ+nN>jKcaD3dlvXlp^F}7InuDH7$>U4P6WeGlR zob__6i+WP#;_z|LEDYNHzSV!naQ$VQ5=Zf3*B_dMb2`}YyT$EhOHUs<1$NoM$7%P- z&##*k=44$>8R3&1b?Z~#2fPtF#;>q`WFlhe%ChlbqzS;?-r8Ljn_$gpRL76sW5nws z(Msksu0)*488U|cR~kU;7BXI@OakB2+@D@o)CCZ(^fWAiajEoZo30kKjOwqLI{Bjr z$rN>+RgQ^-!ePdkft;)EBLOd-iFans4W?5f7@76Oy_WHna`A?$#{d@U?kftJrk z0LhOV5H9(7@Lnpe^E;Hg^9hWy;X+ju|Bs@p@Q3^V2)^F{V2X$MlBN-8o;)bWF|0@caD!fqUHJKKFUQU$1AjzNvhHvs(VQqM5k>3}-G# zTzX;>YJ2ebkFl7TGjg_f>_x!cY$LAm%w9lgeL;KPUO@xEK{e`j;^>@EH>D2L;K69! z355!%HGda$OP|j-a+b==Q9XTii42zUqkbcV^mRu>EJYg*+MqgWTVZrrF_<=w@89u7G$r5cZ&D5;oBG#MkA-O|GVt9^xikJ*VV zV*=Yc4ffPi?iIg}Ga%qWte-vA%XSP~Ge{h(SydGtIOL{u8ZNDuV|?-!Oz_KMI842& z%VId3Wj?4Sjg)LY{8gG@%&_o0WZoNVk|l)Rmq=2ruGH?n?7xo_i5%~z-T!unzAQfz zk``;?RX_^QJ!7q>YI}n^#K3DfjuJfo%j2wz#i6bD<>+M&Qy|_4c4&z4a^Di4-2B_n z^xL*8@6&x1zf*2orrDFgT!2|?k70b=$qIU&+;sh2HN=r0tx%nGi-;iogv{t{XTnOH zfB3aYe-J<-Ad~axD~zEs^Ah z0ymXF51$scOg`GvSl|xlJ7V)%D^-50C8x6xeBEVFh{+K!pGLww z#!|n`uNU(;td&oy7Kv%w)MYl(7d<~Ab3%sf@4f3M_rZ2__Op{VKn?~jENVigQEb91 z+;9rYfBPfH`wI1bbYk+c3Ln%gGJ9niIrb&`btJ_F6?z1H|RCWF~!o z7tZQ7PX%0|S?YNY*RR7Y0xUbPf=9j9Er_|#au`)DslXU@e>w?CGAdyka??{sKmKe4>^?>3%;T8JWaVH?XJh=JW&#tA6XGZ1Lvy_k|38xi!@CUyUfsz zI!j9FaH4oJa0Me`+{Y`2)TNi^`>Xs%eQc`MriyjSTo#@6EY%EAjF03fr6U&69YsIl zb}8m@(2>?vW#Swq8dG9Qm0S)J1x&ht#2iyVk1}bUV}q&BZBO?oyH0@dGcjPk&_rNxnVHWlatG+wV=K!>5Ts zYThkiXls}wUi{db5?L7Tc&jT*W>s~}qG|*otP$N#NlPNybcsb=s_uc}e+Sxmr`~HXf1EJW+VBlDLuPT~4+b>T!8b#GwUmF@qRqeTGrsq`Qv9x_ zJYTu~XGSuR9V+Gx;yZyEe8uiw`*?wV3*W?2Nc5O1wB||#U4<6zp~9B61Ajt(uV2kE z#?XtldW>Tl8AewS>)Sg#SNYH<7!++@<%m5oOd+AYcrM-jt}WpX;jFV!X5V!4?J%c# z6HiYsS&~G4En$uW9iyD-Pnd~i#NPR8(%pp>*b6_;Hy#Y#E5ofOZGSx#FT8X}y}RVJ zk&MHJhFqX!TG%yuL>%dPu9up`@aXY>wW_{|owt86LWL1Vwo)G#Y1yllWM-b6v zV>lIAl55oc^%$Q-Be20|{6DhF^(d;_5E9+?Ge)(qAspX_u491dMXErIY?rZ!lDj>O zb$E`&R2zYpPYPvVt1BE69?m>Me1tFXUoJ*MWQ`6?dgK|e=+I6WyOfi;EmaXfG^c2!hb zC=8sdBIjXr?-g zB167}e5F3cgBP~vL+(6*IlX+&$@Q4iU)o|dw^a|Xm!qI>90#JuK&C_tiMv6$cVx4v zX1T`;FGoMD((cNg%3E=BNWDohoXcDJukbccQI8=!!^3g+tb{g5=Ut?-3zJZ~-?WVZ zhKAt?tG!Wx4U0Bs+@7iJX+gt3&g``F0HQxia5_IrI|9v~$HKiA{4S$CUn`+!UJVAX zEf24yP2}=Zs{ax3?DT%v%qE?7m?in~YY6ArITOzWmJ!p)2M~4ZoQ}JfNa+pbhCCB} zd)S+l|GH$Iu7e1mM0o|18id*9HI#}>1!F3+B|Q!x=O~XP=tO|bF7c~_1omoP%A4lG z0;!HgE4%lnoT}f$@i0;l(Oalf38hahZY# zW7=+QK4`s(&ZELJ$t8Q;-1p`^HEplnG+Dc3wde>yS-Hhc_luZsa8Y6D2jFWkJR%Ku zuIGo!+nC^uaq6pJ*6JSB`S+=5Fs|=Q$~j;N38+yf_`tCSS0u;TRAKZVC)Lz?FwQ7& z$Sk83R=LL>`EU#hPfayh{lpa=kZaz{Ga!;3>)yB z$P&-vpN{)^?OC~5WG;mwYZ8Ne)91exO>eB?W>E651)*eK2fk{XTeD9VK?Zn6ad&Wp z?oi14O*s>GPXhfwefpFO5OYz39mUP9(R+IG5Qy<9pA=6YPx#U}wQhZWQ_a)v?We8( zNA(!x2R!k4tVimFgx^5h=e|aT4klr`E_SwftqbKRn&aD!7932nMn+_Ceon=UBc{wJ znAp8)>00Ccz+syEM^lxUUt$J_hg|h9nb~qo=TC=gPc zr{e4egfVJH1+SC4#pRJ)AV_<9%1BR)N$(~AfLa2BJVLMs#eAc4Xdha1~jrA3o6A+f%QGyb?gA~Ccp>XjFa_J7Ni{G-g z$6`fPkhrWfZI0L~)Tv_-<)>Q_%uqg_TG!S{`PJreVs^O{%%q<5y2QC_W}n4C=i{w; z04sZm{h6|9)SkYf7XC@9TyhMJly2PUPHcKjo>y#@yFWm8K{ewcRlfnU2da z)CCS0R9JSybERPcL)S$&_aB3ACQn2+d(TB9{tYqEXaCUYOa-*mm(~#zb#IswsTa6c z>~=b=6-W}QH~(R+Q`vsU1xnN?fw0wafwKArX;KlS<#fDaqRvniook(velz2xZ(1dW7M3)ny#$ zLeGBvjb9J=RJv-rhEi)gkGH^g!$P=E%d8w3h z@s6T@@ekdbo&NN{#ZT-sf=TXLd(N4f$i_y@Q1tkJxXHiw1ZB%}9SfB2&8{%vNT z{-L(S}ca6tmo)eD0+WJ1q-s;%T7>YK{n56frX?@{pMD+yyuBNcV>$ z;m1FIia z*Eg|3&&9=vdAZJwebN?6 ziDov)x4&P3kKA`-U=2cSCXS)AT>ht6A#GpyjngQL5@&li#VW<>J-IFsJi!R+-0f=_ zwT$h0{YWh=F&xsAZ^Xy~h3O1sm^#VyEtEMVA9WEg9ra9cvKteoqu}*gjI{5`$S@|= zOg%|l6!Q$J_>5GaAG(O@yuu9R{6)0CT;_gNLO*{R=aaXgoJXA>y79z|xQ?xykd!Yc zoCx_11NoRLvNBD|v@t>_oIEIN^rz zb08xAJ#9?s@9B>ExWV<>?{>NB>laGTw+pp3iBoiz?&8!OTF(sl z4Ip>%>IKS=+$%Q6^a~JfVvkv%2yaCkWrR2R$}dsWEf10I$tpjVJV!}p#?EAf+7ilT zsAS--BbQk?fYCm&8y;NmCuqnnmi(9u&!d}2a;7C}5Ug;x# z<~Avo^dv=Gi?@9aXj-{7uY0$w_oq0Q8$^aw(f&XOyTOEESN~I+dHngw|5JI$ zx0Y#wm&qe6w3YcMTO3j{*o|&9Fkegnb$V`TFbNTUH6(bGPYV!De~x2DONmy&Kp_D& za*joU2|{seV4Xs6QRAUC(0h^{BLdO=z4csRU2=8P5Yx2fI=NkC@9BN*2Q@A4o3Y*a z=(@j;BmPZ?2$>Xx=Sqh)8c@<>rPGN!AV^z_$Fu*TG~xwC1`G4Y$?|4qV$6=VY)mL+ zUGi8MlR`yMJjcy!SV4G~d;)`>Fe)zA4S#=<#9j$W^euTvNaYX%{_zffk?QPgpF^W# zY!o3j`@2)-h{5}LuTvf-qUg5n229ki2VfEPxs~DZqcM#F6G=xJh^AE)c!34K;Jt1t zyFA5ceFFI@nJt1k6+;m^s1EWzQ*d#nNDOIi(4`Sph<~C{ZX1%gElvmf;?xbj%oj4A zZCVs;q9OQT@qb<-lDbVgQ#sbkPuQvkt;dCYiwSO%a_*&xtxHa&HrikD1B7`#)T#ha z_9r#q+Py#G`$UQFL{+x5xvU9Se~AQxG0wPj$(itGE~dC4zXGn~maO}EPr z4cWYgpl~sj{K0lRp3+SxfH$dc?Xr1ki{4o+-Sb=;&L918KFV=TD3#Q6A6EMDy~QUC zaP2B?gHhP!&DWKb6PJ1wD?MI|j1SP14U}4|r^Y=O>aR){wY~DeVDaZ?CYB_CZ+VI~ zofzAI+@Y6Vm~9lyc6k1ySY@&K4+kbJ&fGs{^64orJ-s*{Y$%bn|Ir^nX2^c_9o|yP z5j2sm1P1 zR>au-K_j!k(L$)<(^ekBn|S`Zfy~<&PERlQzm|Nih|naIN&N2wQoRWLiR> zcV;Uo?^G+ht_zgIE_=1+yVJzp(fN_q_4P!RDuUmEsU)spFyjV+o0JB|Wu`7KTApS7 z=xaF3iCW{IybW8GjS*)eQyr1`$fEv^Jjm|e(k}##V%+bx-1E`k2Ewcp1yDT}5?_=N zzYI^b)C=6%=kxlF@ANc{Zmhm~zBa)1`s17wpVKWT1-xMtDaS>{_v;um>UZCxNuD4O z#F;~^Tt-GNgRf=oQuLf{37bI>k3uqTt|L7JQzdn@nfx&MQBUKO));;QXk%pI-L>fb zqzEv{(TFiD)uhLE-Wij55e-WP5`j!q5MkF)tfQAWkg}VKLyE6>+RVTMR|n zrt_bT=DPR=z0nVyYuV5afDx-L+fC*4}|IC3yF1-(I5`OW-mCozG)V8h!CW&+W&xv%ZGp0Yf@$?YX$bdYmRiSOb? z-1YjKg|-4UkO$b@;&5y@b&jqm?@t;J964l|L#zP?w@?}lP7g1<@ZFDlLTF=kVN|b% zqpIrJrE$0g_5NO@rQ#@o!tBB2egS3z5pn?^>d!yjJ%suoeLdPHefq=mTE1EyzImNw z!_T>5Uh&^DOf+$n4En8^wl zTC=jGD|P-kqX3_c1i%>vlWGusE6_1De{R|bAo45{$ksZ*(t~PDkU|nnIv_@Mx3D+i;XNZV0`wDT6b(Q2`thn2P&vD% zWHhDJx7$OQyUy&xrsMsowfW}*C3OHL|N5Xp|CY(&^I#-kHGEdZ$P<((Uk+T-!UZ^g zMAL}loVnVJ9m%5p(0-)qj?a6bxt77pXOYx+42ao)Q|RxqonkydQd5$d3Hr;nzrP-N zQ@JO+Pl3d>uU^{p^ioqlDhhf3ajh;X9c_jW8LVmLq9 za44GiTpthf}7$ zZ?9Z2dxS}?VxEn8FEuPA_cgk=i0yAeny{w6(_guaKMBJHIJMr~{lCSas&-muhFaQ% zcR$o-n{JNmk~?gU#kQ#VTY~G_O5O$HQ@SP0D0oHBkjI88y^2z0q_nNG=2&L!uCH@v z9QMHH8a-m;#u0x4OaTbqZ6&J9@l~Gw(EUJDER_4%(0zcN>prF{K$Ml!kN8nuKCa+B zsFN-j?x@R#-w}c2f7ruiqR}En+xP5EwZrsFsa%~YB#wqyfZ1J@#GIjFqs#v^TuZff z2K{BsU1U0>^o#V9(ib*lI0VotB<1@eY7LhA?|)oy`DF7)FZKh*h?Qaz4{!dKQ}@gx z`Due9x%<8a6(-gyj zAq;n89Fs8-zO>?W29=;2J`_AXiu#2j%kS=j>#+TMrXFNpT`zT*Y4mZyK7~@9K2xltnzYy{Nz^K~%ASlmjNZo?TK896( z>lVKdLh>SdCwt$i{lV9SUY_Hk=wXe@wL%cWzsd%s{U$U%spj{4zm2pNnVpAx3sZgc zajKuJm;s33?fuT%WY$yIuB`R*)pgKOk{l9WPjwEvIDL~;$t0p>knYs#=Oo)9qKHq>7i)}5LA8LIbv zsKbiNME?w)8CxJ@2{Zsm^4q&+Cz!2Qm%S|J2W}oIwoe#t&mfXKgCVX8do^q~!Wxsd z8{Yi(U^?Bz{T2P_sy&K}wj^lmje%wbi^j=Q$}@5vK=lQi>3P6Bpy9Ua-okBk!-0NR zaL+~H+IXmvbo_@7qp%idSN8xx{M3Wg&(qyTG=RKzw#K6@Mpf-L+2Ixu%`BH`}QMbTgV!RXSD?Y-J55MPG7qpyD>^lI_rL7RA`7C zan!x;xo4(n$OJ5~>ij>i9Dt@`$6Ltg#zA610Rx7o$0Jbx+Wt#H=@)p4T~E_ctCcL4sSJs}i{zHk53_n_`X_PQngv7UI7y5Erpm<6ilGD_ zmZQU{+{NTeK^U5}%Y&RPKGxE1?<&XQfC>1mlMYD0qL)f80aA4;jI7=PQ{EkK8OqKd z*4Rg%9>_$J%axHW(M(H;l-;btX*!2um>`{Rf^CZrn9At=hy{z*EeZp!zEv4D6dLv0 z{dAZO%6)ZHE|d15g%-tvrGX2wn4%s)n zs#7!adwhF@&+)oyAc9v&ZQ)H9?vX(HH`F89&Xa=`OC?P1cDZA2}6|B4FA`X%(Ha(hX0pATU;3-O7%!XqKttzsV;<(o1rVm z(p2(RahL>6nqX^PvTGc**DwCk|8F}pIL5`tE{5&2g)g`b z_VIU-eO)E$)dr!pJSB>jr<@Ek<4?yLo+TMH3! z9H^JkB7FGzzw5ye@6|gN-QQJjv%k`IvVflHnCvZS%-5C<#48dgXy#^Eyz?=V60cFj zF}VmwZ4=Ru6~^8onluQYcd9aP7|VvmDJ#tN2qcF2mdbvajPcn^YVfrFdhY3s^Te0Oh$mLnv z(QjQ&fJjWMDZlxh66$>xsvNh!mmTK}C>!64d})zXI`BqQmX{(TR+U;m4vqKVC47J4 zJ!1Kj5BC{7+1LKvnd-uvmSOR8`{oDbhR<)9C#)GdQCvKF^&?`DW{Rg_GLU7xu5(Nw zl{9x9Z>tUlbWZ|<$SMYx9DXfxTB#&@nYv34yGKp!r4^kJ9Wh2-b-A$h;~~bAs$(xh zY4v%k`Zt3{GMKc(lfWU1MF3i7O~9)rU7$uZeL*yZqTvjMqs?430+Z)&k4&lVx!iJ-#>Y!ntNlDBj>HCK-)#3MbZCf zQvP`IU)J&Baq_Xgh8sYG^g4jwFlzS&OpZ@cs24DjtT#>-o&6W~oM& zTCkhandkcHITxRs;ET_PL(S|kR0q%RF;4R+NrzMTH_*Y{Cu{}h<~-y#wyghtbW(XZ zq%Jmi+nt}Vjh>kP-D)O=N)yy5?w*p4{kKl1xzV=}v?SexrGY-wOIBrXWTAYb<3v!O zI8#_&_)>!<^Vv15Zx)~p`+DArT+{UeqlyLd^Pdg8uZj~^|| zD?0wcA9KB`fhJ7yqHlsB;8TU^q0FE7w!6i^PkW0iYj@6_Klb=K*Ka6KcOS(`@$XZ( zO2&R9Gp$z}>m7dg@#z=zn-+B5_N**bdFqLuwc=KPCeh6DfesA4;N(~tKDHfOa@n&S zWA!3`AqPs}K8N##?+L5ie)+_{`S%-er1JA=9`+_Uki$n%`v+nv!c6PA8={Dq!Y`Px zMijVw<|b$!AIYN^wk1iUhm4sK7W|{C9(`G1&dXyW8Oo9x>=Qr1mYP-{Yw3Bbisoa- z8DnJS@x$QRd;dbOPuT1G^s)MH><>UwgaxljcQC(2Pt^s@*VO2`pN^;tY0BHRkJNiv z^^{j%M{F33(j~(U?Z&N3v%da#k7-MNk8GFOJlrNF{*ZPA@09K%rBRCKi5LA*MvxHgox7oPs@>6#}Q0ih3Qa*%WQj$C?bm(CIeq zorK%}P&q`2SznTeU-XLcZhLl7a&yi!1>=<(v>|ltj*@=VhWg>PA8QGPM2}r&>Lf;O zh+{(_rv$-~#>e6;3G)O7bSbFez#nFwe}?Y zK^TiLp~5g@pQb>1K8^BR*_$%?wUmg(zhU#UM1aXQ4h&aQb>T`}jKf zLBQd&r~#F_|CkoR$M-Yu)tgE$`SXggMJ%kkwPzMfvnjAO_I(ByXM_(-FAqWp@u}Lp z#%vd^EJyd3ysTo&)InOPum%JMLyHl|XoRhy|UA68&w80y(!fgd9v zlCzWM{rbXHbJag6OtyHIkC`}16@0>aZ9d-Rf&+uGQx{VWo4%|N{v)y-eLg_@0pRWB zHRxnRIh22iC?T2r17UX5KZRNHf?L&UfQ@z^#+a9ey8#W0rWDFg)q zzdn=KV`H|{&M4wmZsUjZmo1Ku@z|dXj^1;&r^NX*6&m%ZUJ6~%=cx@cBsweq$Jm;% zuVhLI3$Y2ck&lfiJr|#3YKR?_(d{ly*IYOZrx{37@%fjFES1ii>W!f?iGt6j(u@Zu zaCJ>va=#h5qhJ=wlRi}=5D`JSVZpFd&WBvx=x?;f^78Vo?CS}K;g?t{Oe)@E? zKGAAN_vGDJTJ>t&H+q|^=LCWV7fW0=`;X7hcUrFT<%%7ryN0*({lnIZ*<_ED(Ed>n zK_1Pl!nwfy5>Gtz&-Vgn7nh8c_$U+M?QX3z3HhtI8_w}~xHTqC%Z(6x81cVYNh2FLY(rphu zpAu_-7W})yi;0vMl{CDjhgNt^Bw(-6T_uhpbL1>#(j58QqUD`AHH{Iaf08F3>K#d& zKp&pn`UMdo4K)q}$$30SMD%ITb*QB}vYP00%j>@N_=fIrP+2e`{SOu4eBd8a_wHpr zepT=4HT{PkR`+ZY#y#B~kHY6P;w0ImP`#NI;TaqC`>^w?x)&EY$?wQvoSyx70Ylj% zo71Eg-+mY(@$AG{AhoxWZE3m|Lp6bb6!_se=6{pY4_TDb4+p7sS;=4is#EYxtLL3> zKb}*3;v#VOa`UHfFMzsIz;;Zn2vchDMg*{qeseV7@K-ORJ+!{648{c8=`tFdPy(9b z6qjC6OZlXyLP-efph-l;!=Wn8`Q&PEk%mlvK*_8a_Rd)sKb*x9=V;`m%`^-E+MI~T zUn%J@LNbBTtoZ8TjF}Oumg@uQJQz7it9@5@71V8T;2;^!RF3nH!vvlU*agO=56117 z?tc+5UG5VjlpAhq>TiRYOt1p09zUJN%7xHr`-`QO2X$mYZhcMXv@f>WMm(Ku(e3+_ zf6gMj5^&?o1A+gn8LpB3s@!*0w7{pKSe@z;asyEAaVq}z!C3!3#`DomAadWllGjfB zoXKP-zvVFqjq^S)0E{dwa*z}`6?P-SS*IH;R$3SMK6wHH3+w>f)eQiQ70m5V`hR0; z)sXjY$MZ9@d0ob+Uhfn|8OfwkPaZDdYxol71?YtFu1o zVIqS|nnBJ;A6MJ=fhh3+)A=wPg=Bp(2g+zD_i5F8i+juF97>d7vNeh$eb2xk)sl#V zAbis#183oap4$&!^q>dPPwK%!uGnuo8SBc?H5;t~UFImkPy;GOG(A8DbaD4!C zm%^wXjpVk_l)1qer1yAiRLThMvI5Xi%Pv0a{y57Y|0xfHLEej@IL>_U!Y+J@OTHIE zZv#q1bC%G)Gkg+2rFzq?Sl&f<3!radCXW`(5srd>EtURB`6BNs8w=3Aa!)?l7=Pv; zkgV7Lt1mOw*K1JL*9(v5^HW{Y?>0XdEb`R-UKf8pu9BmRYqX6b zwEJrloTt#JY*Y^7TzXIuAyY3ajzlx5sk%}X?I)x@c z8FoUud%7hA+*NpcBxUs{6V}wAN)kEnJj}YvPs~aZkugh zL3~R6^GcU}@HX|%!?j8XcRZ`&%JBmxq|K?)Dp_wiiTW1>W86dSTjDmMr$U$+jhDvu z96WD+gKqzFQP66+az)ff^>~$?<(I5?bSKswjqA%UY#pq-ZK}QF#@Fjw!xqG-9h|uM ze*WxFKUy3Y>BEsp`>pziBKs7T^ANgfvH=r$c(hte(p|qfQ5Z#TqB=<%KuoG9w#DYW zD=qIRn#QDlS~$iuc%wS@@uCWwQ7d_&Kno5yb5-3@6yb6hy@>A}J=gkeA=hfQ=w z#Sr11>iV{?1IbkV%XEaXL@^)#1?dol*#O&rk3pWt)uY}G4H=jDwsc)j%F^5quJt~b z?2|%Kx9S;?31WCMz!M{>_z98h4I3n-OI}=Yy~<+2ah7$dm=nv$oOk76Mv7rqc-|O5 zp>5ufh!vxVO8np0f`CwI0Yufy>O&*6g5?};!wf!aFJOG&6!170XUOKP0SLc#`zf!< zRRTU)1vyK@<9{1iaT9x2Ob4H-`8aTprltS7f;oE(kp%pGT_ZHkzcetgIgBYBJSb&8 zqrU&TMPpXy>)on@6uNx@#cRw9{ep>K0BIoor3}LJGLr?(Qg#^KjGmcHno|?7;L@9s z(Nh}-b)x^`bqfA?EBux*IhugO)d|jm;q8z!SA)R_-Tck+NASZ#f{Lgg?3F9r8rF*u zam}z}>BdHTZ~CsR-NRIDnPfKTv-;vKS>%fX65V-{R!z+6FvxY*s+|~)bYJTFd8d;H z;F7xOQ_ed-xsyKO;|Y$ujH)(ihUxL5cSCV9^h81&|3fRZ5fc`Z|9f@D)1=y#A1#Xk zs!Fz*F0~}u{)!)ef)DvkKl1+9kc|~hq5T&hDYY@t722BhEwm{Oi>3=n>5 zqXh$7G^V3|6)RbFcER3DRBNGvedUSfqiju>gX?O(%RPN9O^xFeR0|ivvzXPP_qxjW zAx`?>I;?%_FmGh`Wk?KHCpXVhrE67Tt}8Yys3d>;v&088Oe4D(yvyO$@hKh(3)XoK z9o|v2)7UdxK0e7zet(6+)*r0yyc7bNan=FQ{Ii=206SQ#TSA9wEALyP!9;9MHi z(zFaYzg0SA$~;Ii)WV40uZX15e?py9@fm(aNDq|QhN>{IyWy~F}%dYQ982O z;VzuTysgzB{+;ohdw-XEhMx5c3G$lt{j54cwtLfd$1na} z)r#XIO(8Tdi}C1Sz|U%OLW62B`Zk9P!Sx2LCa+oTJCS-D07hTz+Dr5D(=ZP=`@oTu zo)o+B)}0x_1Jh4oO`Hr`Mo8r##SqT-Tw23k3WZbtk%*%6&ULb+s<-8Q_X5?l($K7u9ol-VpbE!s3a07J-7!Cyh1xr+3*Ik@e*F#NM94Kg zP3~7cve5upU&R5f2JC0@)FlWk@0GjUOx*O}TR^GVY)3Ln!6R>{cd@P)gzc2$#gvy?Xs{d^wf8-6ZWW;Sv40v&TJ(|0O&V>n86?9g|Dd5ZIr{(OneBO zC6`$7+eweE7@q7AayzkYL$8{0fcYoJDFIQ*sp1;hqUrg%)%xl`sJ@4Ck7WhvRc|5J z82$d~x za_bt^$GTJ6>2p%4Oq_pVJ`6Y+BQx~e7K$c(fRBrnvvsPnUp`{M-&YxOS4La>e?RlU zf+|ssDWh~X7v|CQPDZmRO6Lskxe#Iny^=cKf}BZrD`4mTo}idLpjfTAdtAGXtDdV{ zH>=n!R5ll9JylJF@=Pm3zQwA~dflE(tWV`4nMDX?FPOEC71WNXaSE zRw}$7;u1Z>5WXybJc9xA+sVU#4M|vWVV;?`aC~N8X^o&B{@&0W!+OxF_f$8)_eIzR z3!oif#bRnRMG<0gjkVb|!i^tyFT#j|F{^>`E<3rQ0GA86FNFawBlIy;by=Q z>wag1IYR*y%FP?D%x|ryjPUKhAw0h<1B=Yq4*#sG>mXVYhe_yiFtrd@E~78TRydK8 zATT4RxYCj4jK`5@>4&c}L_^F%I4L-H+(;GCYsEt>sT2iPjTNPYEFvgikxD$zw;h^M zFIkibTX@do4XrtBjA{YzKk1}gTmioA*zAY_XI9>d`d+#BBPLkLiAQH1JA*GY42mSN z`y^4N?$)^C|ERbS4ak@memfecnv<7c&*y@fX*A`k2%vlMpKO#M(83oOhCx7oB`^sy zs1`_BeG?~hE2x~*Rs+lncugtX!aZ~OIr;=WGr$PIYi{*=0YJiE!7VuT4>P?61bt-` z_I8Z8%1XnG4E8*+i}HQvN16$c*@ZJByDKIFt*e@{^z28B0RWC4RuHVo_VFNptN zpniNIXIsc4e1v#K9#}W?RA!&Fvp$4->OV)hBman4?dE^W{C_G6h8u{pd1s=A?+KO> zeL_^S1z`NDJ8Hews9haZ=e0RC)>`}{CjN|YvIKaIXwbKJALo9uY|7@U4!6Ya%-j}4 zz>ME?g<~VRuq&2XQB~Wfy`_`X`GXzU5RV!gwP}hGER#U6s)DjmN7R=k9>o#Rhe=hx zvSg7*7O6L}$>ynHLnD4YY@XE>;68k4qZFHIEd*op|>A!hSmu~mgQpBt2tgBa{5thaaESCT?PKDaa zFLOR#PjDb@rjq%2gL zQ4BR;pbF$@drz}BB~qZD_?GqFJO=_Ds86ywPB=NH9G7Y z;S@4%DlK##Ko;t_=cpmhPM7;Ck8jGJ4Ln!PnKiWE?voCe*%9oRVZTTxOegsL$4ZoD4F!_ zDR?pGIiJgw-kK!269^~1GX{hTMAEo>)o}ZL$*VNQl2a}n?!I&bv|jlJy|ui$JAqNL zYJpxf36XU?RH=FF-9Nn&-Z@6cztQ zc`i^!+VCmYvJxd#N>-kYPu~YK&Vnf6*L%{bfkkIMXG>6 zAoS1#0g3bu0R;sV1?j$2MOuJFnluefK)TYa(xplhM36gv-+S+mn}7Q`IdkUBnP<<; z-fOL`W^negv+SlX6JDIp1jlI?c>N^+X?ZcBFGG_S*>Y~VEwk^TCSz@D^?r4#+>WW1 ziR7G4dq)<%8xQ$9zusGG%_%u4-#D?T=RgLDb0M~o{V*S!tbmZa5W*4-BW46SQ9-1r z;JmWYcS*b|yRJu}vzlx*g?tSiem6ZHhYbltBQ+tJYg3=t%lT05!cVBh)>-W8uIt-S zaUfv8+EW5P zIWypy75(g`U{T)vr$DZa{)tzIwqc~_g|opI8l2N2crD3D95ZSj^l+U`b%n9Wj2sm< zk#t;S$Nu}tRMEPT`p}7+HgSo9BX2wJg98ce3%8+96fjODHsaGJex~#^4`{hqNR=}dM9$w-2*_zQT)S47Obh}jogV8Dfn)S1+L(hd!MV(boDfZ|{ zpo%&EwYJ;mj;~NU{!ZvguvBzc@gzLJ;D=k$k_T^-xhOWEIA+n@P6TeUoH)LiVK7;G zl`ZrAem1~DJeg{+z}J9MjkyecYR6{-57{=|PeM6S69o#@?7Hy z5ev+NdD6y0SM{x?c<`xP8BzgUq`%s%j^yzsT2JJ}xZ#JEx))`&s|1Y_2rWytHy_bB z7A@fuXd568!%vhl(sDB1ckOIzm5IZk8`}fcoB*oOmE08D5RF)s);6Sm)!#<*?B^wU z`Le)r4ykV+Tjq-*dMx;dO+!3qm^o1wXz=&#?jQQ z{5^VNzD1I)4ryUAAulw+!tumSdQySu|##Zhiu{8PJet=bgH^yu0N_Rv&P&zc30Uq3mFT>hE-DPDZIaSf*Lq>`5U%K^ZKL*sXhd0*=q z7bab>Fdw}bQ)-V&o{n?rlXRVhtG{Bn@$qc<8Wo|*GFXYtELS;`%E)KLcPpahz3tVF z=M5($J?RsjUiI!1#gBepR*$x~?N6JfUMXxB@em!(85Kt68U*iPWz|3VQkm=t_ATrV z+IkFWv&O%9_UGo2laxgEczlL?jViiSKlHhah^Xk+3aMwYd*pcdC%)b-~ z&U4&*Cv}L@QYImB;(l{EKmi#UQ4GImX@=FI9BZK*1NEcLmuXBT&jy1RxTVOf>9^o* zQ~Ke;&okWLBi?+jQAC%<>}nzusE>ZgMc1nJtS3RV8>mt&s+SVbFozXmeWzb7@4NDy zl?pShP!J0p#3PEraN-XVR2v`KvWcGNhafndD3)f|-*QdJKXY4=;B@1NA3v{6>LkHK5i09BrxPC+fG-^V``P-$SgnVPojGJJsfj=APjC9pf;?ZzFz}5tYrC1Cz7`M2#6ZbM0mS9w)uT8-J~+EwtPs7VEKdeKIMI4zT-cag)A&M`?>YL|Ol~L& zAu=sQZcWAJ*~lG2A5^9KgSE3?$@}aNibXmoQ$}EmCz1I9KS@~=qCt?Qqu~>=aWFb| z5zS6;8Rk|wvndY!{c+w_>r9!n=gBJFcagd3ei8%OknC;GkIz0ayb*)o&U(h+rP6Ok zHjEABHO%9`n#Z7x_`E7O8#^V zc|KzGgyjz^E$DJ~6;i09?PkS#l(U4euIvTEEl%f(>{ zr(#z^fMUajJ9{OeHZaWDRcz^y{`QFhI$2LSU;|~1g!F1CJE!i>AbPGdUB#)7xWEgL zU{*7T+TGn$em}_h3uYO<)XJ~CchexOP}yN6OZDlRs#4-Ri`zt%tN8k$+ZP+AbO->Qh>P!?$nMeTl@CnpG?EmHi1p?z%d2Z>PPN zmz!rc4SddY74Fdz!E%UF6UrBNm{Yc6hi$d* zB|veoJ<~DRxqg3+Ch#xqMh;D%@wVBguPuu&b%)rwDZ_O z;Eu?g1Th6C3icDss0oUW!zH??$J@!UXIqhk;R#q|#&KB;cEosQLylAwNxyK(r)t|7 zt%q;x#vxl}DDWc)Ar@;ExeG7CQdK`6uAOd0jT~|K7Z`P!)L-v*vV^Sig;Jlj3{@LY zrqhWYl6t25Ul=Zuar+Uba_Dz-Gl*H+tGw4iWx4w4>u%MKbG08t)1PCXIDMnYX-$ac zd_psGE{EOMO}!2XI{CA)sob5@AV$@!>5X>WvftDXUVc#+MHVDQTjAt_?jd?mqc0yp zk96N9ytwn@*sT{sUHNd;Z|x7mDjN)>u~XB>B6gVJ{pvX}sT3W!Q@@}17#U$9kI0^G zPc7Sfz4}?6hqP8fEzco|H@Mb}zHzu-n)*m$dz1+9XG~u^weEo-;zaSk-U^pOHXiM( z{K^qiY2289+8BS^u4;et+tuTqEeH-v#e+KAb^s7NvCHn=R2wuFdMAYLu8iNtG-b*; zoH+ua=i6De_Y9#qYE$iAk4Ib?{BLo;I{5CXx(g;%m9{0_&V-SATJ#~7gf^n?#~h~< zPdH!ho*wJ7%^}@st`oaff3wJ}?w?`F|Jj?S$E4AqOkC>ex^w^@7IFN zx(%yrdA*EQKQ`KADN432Z_pW0j*&xg2j`l3V!CdPkGNER#=i}n)!MC28V}AIhW{D& z`To9_*r-hOP&83Ql5dzK+zJB>-*WcR4372B8z%rwX&{M~+o{n=CFvmo$mSpxSteGC zYc(0)Y_0k{cu_k+b4#3&%sS`KilE#rR&qPG9RT0gLzgNkmDr``@AXaT@AzS3*_-m) zqnWI3TY9$BbWV?5_6w|_x0&G8|0haGo1_p zwT1*~yL3V!`MNa9iMWyvo~zcElWIkR-*D&njrU6l^vSj-yXF}(9>&@@F^<>=&eMFY zz7Wx4I+n11-LOg;&ufB?|2?h4wQYS3!)P4Jzw+j_8MXC?VO2g6rR(_@32XAQMkn(Y z;zvBF;|PEh5WojMho|^HyP|Mr5u}5cuvYy2dwDyAX0h1`YMRM$5xL$|I4sIIKYz5) zU)bBMRmzy~77%2*iR)ss8`7cAPD^uwPl8?qx6#I{l$||Y_@3#V5i*efzHse?W46gp z{BwXqykNX%t*>!(Y!a=z7SKR1kc$UpF@WBtl~%#kL{VQspI1jdH?~LRA#e6hm^DFl zc!bhT&gLh6vD$26jahZqNzuTaTt=sH4M_>;uck~^(?&4(1#hxssg#kkx705*=6&m= zJ?}F1LZ5CjHLmD>pNdNI22aEmi8S~OPKXK&ml)hvxnk;6}+eXIm9LW2-?HSdma-b z*kaaZeDAl$JEU5dNWrMmawVBTEejM?!I0HC7T0fCj-nWJ(fK?^0ED(aWjEy+qM!xD zu<|9x`dl7%^jzgE@|u8fldHE=6N{zvGn`nTU=X|T?tq2x+!c}$$C$b@a~(xSTe!E?OQYAlM%Z}u>fMa)2Es3rB+$BI`eQtas@Sjgy+n_8BD1E!BfY2RdxHK; zu5q)+KFZ(c>P;K25;gktU9DI#)?Wrof9BHP%M=Q+>42VNb=K82KKJd#PDZK$)JFbpgRP+0L%L?z>&wE4>ebk<{V9$A z>&1a%k-&AM5=Oa|nAB6|d4k?grl~1H*h3?z5_nIm$JiPWJHo#~-6ZYQ???cL}l zJXxm0Ht(?DtQrRMH_zx@ujzW z`-%&-3mUn5hpjK1GZMN}=rlLn{@YVoi0E4vlz%*xaN9O47Wi|JyS!etIH#snK0y2u z+3lj{%w30jo16L0%5S&q(u3W$>7!vQ2b=o7G~v=T!efa z&f=1+4dX<;?S?0cf|vdOh86g>|99nI<1OfdHn{&kSN_)kEhmcpKLbu~@b@wQz4EUC iq+!6{{xz0)yU)orZq-o9ZsKi7z)w%xNUKr<9rHi$j=}f< literal 0 HcmV?d00001 diff --git a/windows/MSRHoloLensSpatialMapping/Assets/Square44x44Logo.scale-200.png b/windows/MSRHoloLensSpatialMapping/Assets/Square44x44Logo.scale-200.png new file mode 100644 index 0000000000000000000000000000000000000000..a6bbd8439398f6729939bc4f4f4ef65ecd692230 GIT binary patch literal 13981 zcma)j1z20l)@XuDk>U=8A_am3cbDQW#Ua5ZSaB=Gy*R}REneJO++B*h6e|wJ{pFl< z&$;*i-hGlUJA3xbl36;lXC@J9DsosDWEcPd0PD59vDJuzDI61JHL7dE?Y@QAskDJ1@Ow7NXX9Lg{$sI`r}w+mF$TSd#l+s;A&LMtXpBkU;%C*S~eGo$fz zuy=G7^c11}ldd4V{6{rAEzO@GZgwKH5`QqH(Nk8Vk#cf@((tlzfGjvTcxm_q*f@E) z`FOZkX}}y{PIeA3J0}l_lT(lfEXc`4^REvroSO^8Qcy!$_Fufk`jHYXP=c1{5Sfj?+~!5}yU$kofy&CCgwd~VgZGN)BPJ+<}IA_zhwCTK$dw6b#(g&9j^NSJM!OrAQu0?!Q5T!|5Ovif*ooP zb%4`zh0DbGk3cYMCpRZoYp4GM>3^F4RKy<);Mx*Yb+LgvjhVf)lZE>qBwtI5(862T zAT|&|J~K-`xLtWbUi{N(cz>%g72y%l?h~+R@d`%+Uh+H*Xs_ZwNOBmzg;yH;9Ly-wXui z<2DEJ!`%bK1%aCJnQ?P-S?~z_i7zPS0yT4Ua?x^fvj5vt)&AB5jg%DJGda0wm~?F% zAx<8yul@rEDsAQl6`}pZb3q*3AWj}FPF_Lymx~v~!6(SU@fWDF6U4^S>wkiRxwSaC z1i3f`xq1EvC_HQ+W^QKxPhg0Jprw*m2D5Sfr$haPWMOUQXa$95UG_i4Wd9>S{UsOsUsn0I$p6;b-%%q0 z_x?W=;`%Q&NSaywqY%-*!%>!xi<^&=iw_=7(tm`LfCLyGO_H(_TmrJ(ToO{kfAX}q zfn)wz`iltr|DD^PkpGca|3-!<>pzPBj1usNf5sW8BV0@u_$YEE+G7gIwEATE=1vG z?!X4fb{GqEkR=Fwc+sWtv>iS4ZG-%K@BCFg7D0q+FEoATJdP`ZGCSveX}Y&P+FgAw8!;u zQY)S5D5d(`jB&xOshZbQ-*kXo?hMAun-eFmsW|Dgc{-!w!XE&hCJP!>paJ8u$ZTyJ z#XO@kkCx($101?e_QA89w3Und_D zev<0OyoouQHvq05XK|bzxnt6-yhYDxgc(#z)m;boAV80V=@9-OLXE$;2t11?sMO)k`wW5Q2+e_&d>VCR_FF*wY z=d+alN=_Tu_>=dY;5KZR3@e;nTwz+W=DX3>^DpMmsq^CcN5sgTo2#}xG9FiD(?^vm z`i@cW?W(cOPtn?l=8D2HFFo&GzmNY?L+zAwLKK);iT8U70kXb>4gNGbyEY+P5}pt+ z_O-_%mW*)+2Vi~uaQf;EL6E{IYfp#7CF2Z!zY1s~BZy5LgaUEzUHqxrJlfOzN-{@4 z)3b11%lJ9xyjOv4j)A49AA68T;jw}bldXgn35o&3J81-ysY}jYVF03$NoZIb#7sPINNzz3C&?mjAA+P?b=m2pLf}F^tpZkK(4>)Xo>B(*T z15FbKHVrIaBHBujiFO24;r?zWH|{G>Q7W4xGOb5!r(VH7&2#u%Zs4=Hh90KWBAN;~ zN%}bILL-hZq)AcA8kJU!G`Nl@eql^*_uX1zE#Cb8o*sM|)?>DjCtS1KGYaVgvIds_ zs41`ylU>QEU5h{x=M0E8lO08Fx3C+kO(}&+j+BDe)2Y?F{ncf{6Z9IC3fk70Ys4PV zQ1c>(fpaJj7f~fy72Qr@%PZ-IzsU;XZU zU0LlOqC^EghIowjGU5TCM;lRz&q}SJ3w8-5)r@>AukgwBx>&EJK=+=g5M)EB@Cp<0 zo>|?n?JVMl1LX9@Lytiwk|l#)ZNwt&DBw{-&d>eB(I~Hc>zDu^f$5sUT1<-UdeNDC zuE5fzg$xq>brP_`Fb;*e!@k%Ft-pzl_PMdmp+s{o5x{=XXiTd*3FE zo_KU0UxMEbElPgVsib#`mQ4xjue*9mPO5Zjn(zGh`U;QvSZE999bZ>|ZRPSxK=7~{ zqy-2Y%$pEY+N{kSn|)$8xIJ&Idf|A~iP--JV2BzA;yXK%?K&M=AgQsT(sz{9-J{Qo zj1#RIhy2)xlq8AVB)*6@kN7?1JHqsmXTlLP)S5e9ESD;}hd=#X@>%tDy(~FaQ83*} zvk|y19cMU9rGWRcl1o5;m4ml=m^7isOKzd!zjh}|@jLz9U#xOB znX0`UvU&`-UQDDQW5uBQmfVi8<^pMb_4$om-}sM;^*UQ|MogmS`>0o)Fwvuk_bKji z1YI!=;}t!L@0GlG@JxvZYFJ_h0W>x72@F$*;-G3VZCcbqN}s{D=TM%phQt~Hz8BSsj%wH|q%q!~)ptlx z;@wRchUU*1g@RhKmVFkNnid@j$2nKjC~JsN;xf6!V6Z*bxL7nBS_!VA>k;qc zO{o0314CMxsgWHSfcCE@-=s-KW=%)x#zbAuD_eT_ssf83dI1?YSf&@Q)SxCWKqH>Q zj&SgfNlLoYT^3tCaqG85dCX&pHmWzocJ)MxqKNwBXdXn^F^iT$MS%~??t-pW0zY&p zWK!-(croJ2+|Aw359R?W=kZl+z4kPQi%Jl0As6<~`qMq1Ha_<#du?-GT{7g+TFl0P|7^qDa1E>G%F z5Xp^4cVQ;%;YGWr9KdeOddgG0?tXp!5QT{lMpou`XIvLp-5%s}*1rJQ;_M4W1++J` z590Ehs*ziIwtPdVeP8Llc}(){ffWM!D2n$GG8N?3s09Gawv=487*v-;j1Q*u$_)Y9{xb6WRWkG4EZaCGUZNT4m~4Arj1 znCRUdB|vvx8GJU)`%X(A~eb}%#0?HT^Wx;!;(u{x39+)LVu| z;XomRTfMj)4Vlb$87Dw`r5<2ZaOX7@>Ke~Ub^Asx8dnu)-dLLY3U{FJ-Sp#1K1#|> zLRehsiWcs%&7yEt$^h3WU`1;~lNm|yTcoUtiY^v}ene}riWz+8R~+C1z>|q>|OrW?}Vdx5p)g)4_c%d#v#_x99po*lYA`9@~Ie}3X;QEmP@CQ0(G1E)wz0U z4KU4wX9830-eDv85CJNXBbUbFJzZor&nfmGd**3L2!Yv(JeHJ8KyBpm45CUsrvE#a=TG+zJ33ZKhJ|GOnpic^D3ffLvA{jlYFZ=j{fM~ z@BuPrbQ$G(MA>C)~0)rFdx9Cn9 z7&uty)fiWQx?k4JIm9+l+WefC$@}GAps-$!ltqWLt$rVU;GYXH9mS!l?U2d8>yXcU z2;P1OMk#;aslAb*$~7gV4(9#rJ_@~4r2dsq zfsquX%oPp>Hj)b_Q?r7948P@tQSpqS` z_;eSgzPQ#Jzw7;4_j&!S9{ez(-`_3{`8n2xXtZlwnMg(v_UPVywh|wzS{E%U`XyP( zzgWrHyLfl!cc=I1Q2G`v>(FyDLIzr!Pj9?)fj$rlF21Rm0P(fKqFr^sx7~@80S+R~ z-HGE~4j&{?n#T|-Q2>Q)ls(T-PxC)D}vhuQJ+oL0t;a<*P8-C!{1+3(jP&T`*8=jxDlSA)KZV{?pm<8?S0@DhZ zG>rTEFI7HSh{U%DHr6T2an15#^sg4T_x#pT*r@bRUP~hY7WnB9@sI9NhUKnTF~L50 zuGld}SBP^302Lkh`f7%h<(pt?{U66yHoGZ!T^By1hKx*sRIhBuI@;-D5 z3?d#>q((9zyLY9LT8mAAM_Mo1qA@+|H5wshz>B+zj8UC))1><%#Qq+1#jUOo3Tu#Ho>6oD#=>Zb(WW)vUvJkd^ zMxEPc=BL4ize+2p>S zsN~M$N5(5trDvcZ0Sq&eBzdyo9VHasz;n9 z>yL?jkJE96B>5WT$@U# zVaiYQ_n0!NKdGz@;$gQ^SNsUZTuP^tGCqD8& zX3iT^$a9BL7@ROyPsi!oZO!foURUFAg{@WUx8hgZMX3{3rm5=#+AZNGK{!AR+XakM zvF`8pYwY5Qz7A`1C>lXBC>E`-{P>COM0iBj?yQq39v`r&3ZI~A8&%XCpgcYROY;QI z?S=5;M)8_OdCG@%rBf-Ij>UDD&!^Rx6}1FZm{t zy-UlUX2W}J!`V)W)agZOtGl06OyMsKZEJzX3wENpp-!gBET#0>H?8U^7e8Ja_6h~9 zZIHuE+>;AHzk2GSp!A1z`Sc0?-?19<Yk^Km8}G2ew2NFaOZ zqGglDb0VJGShVW@n?`{6M8F zzVUnguHNvVjlP2tY~8gJ?4+?RaY=Y{nY zoUQRC>IA$Z5I^jYiP+)RUAESK;mM`4boPW|izX^|YiS-YWzpVAhW7KP(mu1wm-%7i zR&v8-1g*A}VO=iJ(|E6WeQdf*P_fx06}hC)l-W}GVGYW!X8n!Vhgo-wMd zKXX5S%7Z8#xLJ8DAE>+f-ugM9p!Y_Q&lc$ylr0UjUApVajDRgGw#0O#m8lO11T8T$ z4PGrqKLaGjAez_l&Kz9S{yrI$Nd=?XQoezv;eFv?^Yv3mGGW2XG&u_v+Sq^Y3vn;@Q7Y-CMS@2wqy0`F4yLDx1dPX`q7Z~2X zX%UGwFiPZR{!$7J_+tIpb~=))u>J{}DU+15MC*c)d3vUzuGOgaS+=G4iL=1`p!k*t z;3KoF>Zo<8Sgc!AHD1{j^-fM!y!kHQ8X3M6M`S|{_8!|KnM^TA%wn#H z&bHtrcQf6dj_IOL?I<9SHSv!x}ZHV^thNhU_qn3^8-;7&i@$2K#ONtQBYmY=53k7x?1j zw9W?S3qp((?1XOahGT#3EcpX!+fWLExJLZA16j63v=Srzen$i#@#n6snaHZGzgR~c z`6j#|y=?N_LNwrK)saiUd7z)h>VzRf%NjEMI!N>5@B>f9lj{qC((b&<2<&Tw7cgVL z%1tuKh4+X>bk`FXI(=!+JTOQpLvpM%=9RCVMuDdVqy z7~*O{7G(OfM?9M`0VSgj-X-D6vfASDh-V%we0^+Wz_$@;WjX+>@ui>J{s`aKGf&n4wSag{mLAFSq1x2swQb_S#!r$6C|1d>{q(BB_q2 z+Oi9#&}Y-O_OOgmS27qmk>=i=z00nda}+kHmCJwWe zn^z-Z#>~m4;7~_o9)`fTzvAtTf*OFx5|zwcCcsPm=w3WZLUeF(l?x$p3z^ zi`4EKxeuR!{K;RCzi8oxm`i&7o3%4bVJW|+DT}#+pY&3Mss9f|)Qj?mb|31GC3(~N zdAP|P+F3f{8y@|mt0$t$FV+h4*H}9a4GtoMYDOyWO+-=-3l@U)%9jXrgq|be%)dd` zQYQq6k!w{p5w({@A^u(}DN27j>0dcv24A}e&S8{(#`={jl6{9AIZM+N81yZ-n4^q| zt1P<}ARN4kn)7Ow$J;X1Xh5ZeQ+2?Dy`AaJH$vaVFKtS;*5kvPbvaPkk6!?d<+79k zK#snUqu7%?DFrLZqi}}-Y(vYgM#EF!#oFXfGu9F9j&F6p)H>RT8}1#~GBA`3P~5-| zu_q8UrGs>1v$+S}kQa5@xaJvQX&rhiO7=O;fWLq21{=SXKfV>*!Gn!w%WXHkxx3Vl zF>l1;y<)0fob9b}LId-nxUi-h90SGxm>YWwi&rqiVFLMg( zYxFkp_X!oH3WEl-QdHUk0_Te^hn7_g=E>!5iBfdgFeakP>a+XH?=g!bQ~4MLnD@UU zD%x3eHWO8r1l0qBX+6c!Ui$idQyooVrocGu!$VmWb%O6pkYmy*vpyqRM~%HeQf-YG zzRw=B*#7AGHiebnQdYD)mwY2V15k6Ndwn+vH(Yzz3p$*&-144|>P{dT&YNA#R);vk z3-DL&O=BNl)RtFRO5>H*jh!CXM!ZZnR?YzcyPA;&2gflYaNYd6Q17d{o9Ft%pVAkO zzEcMd$TVrDxb+Z!k0=wU5?t6Me0x2gcro~vI34$B>cgfeuiD&cAF*wSBwpa$(6i|x zvy+hg^nKe?uLIu>4c@BDeGjRPO{xasuxQsl;>%uFV^p;Pz&by+0!Ac+!@q(2{+qc> zckQ>*JZ0Gp|2TKS8XRE19g{59Y4%u&K3ae6G?OnyYF@IX8J(J&RlFnj^Zgqyar)JE zVWq+ZQ=LglQU3M^9{diK+zgK+A>3N^ylR0@ql5%41J%PCMY{!0Sf=&I0AnA>q(?m4 z&f70+jvah*3?(?dG40l#PC5oU<{1c%pYp9m!r1Y#Xx6KTQ>#2VG}XUcA92fmKY@V-AAx(t9d{7^$T=l*;FjY+-%w@2$i3`xxxG zP*-m|)q5j+ec|%F{zD>(nD0A7rVjhAHmXnNfmDg%SQ+vAj!nX2H@T(iqO}&94;U>_YpxJuiU@S!QRC#8 zM56_6`KbjC>R_2-@+c2<_OUHy%n9siAj9`l<|*wkGWZ8;qT*?`nCyem^D=HbT&Y>w zZ5h04-;SCXuc|^O&Wg$SW<_vP`O-90T4)453<9b1c*fX+Po6HtZzJoMg0@~gc?4s& zRS0Svv}sHvfIWZa%%r`2MCy5k7O01(q&Dn8M@d4TvEY9bGm1qjOvsHJa^;t5)iU{v z!)F$O6`@(gCTOCewif9J;X+E}yY}ju-WM&({l73YC19{h%Xc|#TR!<5<#N1yYZ7Y` z`Ja8jfH-jWr^v--<1uj~e)x({gEsH}s&T0(w+O#y18L;oE8j+H;Tk^QUIyM*>yClJ zm{*ZSKP_x;<3WN(#TA2_hy5JZWB!18E^x1n*Cw~B?}PaDV6W5FExWM%3L z!0)nY?TCa(TE3#JuF5j!P%U4J_s!V)F(BgmH;0>;+trkHOn_?FuD1(}VABU6|eZJ<|+titBM1OUHukN^) zYzMKEBf#uY9cn zyL`vj8F0$YH_7ViTSO?@Bb#MYtGKvASX$;!<%_qfnu#YpcH9oLNAu@~-Q+RjY=*7> zj$;!1963vgjiQ@Kb*(2eei$Sx+N0s|j(0@dtV)jI%WpgcCPzA;XSm<^xM_dUp)fjf zTnPI!DylUiyB~4By9ss1S%ur^-fQ)O!1YmtvG^+m4>cAGnJMo3=1hP#YWoG?L{Sgu zBrb^!sR?z7({NBO+cj`xf;l>$^?c_ST2HA|E1Mj_-`}wB_)$B*#56=|*fVIo>!*wbgH&v98)Q108iRVRpKn&t8%S{Ig2#q3hUhjR_iFa-XI2d{SCeNUm&}WyFbfmV z<^D_E+xld3$?w_jQ4~$HJofL0_QKU?n7lRLGK|_$q}eimNJI%&3^n_i+F7+Grh<0S znYwY~`OxhI*pltwch0vC!>0ce3wc15(C> z<bhW#8N@dPQ4AVlOMDoI7(#9!EIY=+6%C%7J(2N#^9+0Di25iJkQC=m$@7z&bJvE9)Z6K>B&xe@~?sqtq!@#o}bp?(6)IHL2{ zkOc4%hJ3xwUAcg^qSTcNZlJnp06BJ%FSP=BlhDJ1_j2nQ8eH#u{mQ%;Pu>#Q0WeHi z8?XHi4KcH?EQb;D9D^^YqMV3*3SIfyInw@m*7u$v`ooPVUSgA_r=X+Er`uOBR{-11+moI#+?h zcrOMW;731R6-ZVLYCF)k8M~S%q5$yw5Er|b#qHhZhJ)?px)EMt3UWcEJ8mY^>;7zPHRn8S`(mZRzmh!w^VFeL=W1a<)PTtg(Bir~tihS)PjB zOG4|}reEIW`s~=-Mh>&+lk)g2B@9php!^AaIxkXX23-unPad=d;E`10uqZ@mXK;me-zTE-b-=u1RaE0@Zd>?Lni zTzhwHBtXfUg8~P_D60{%ov2-`9I-L$C?j;4wEbcKh2+TGbJL@d2h#QzGIx&vHge(TeK-+P>7^y@JE$Gv_7=~B zS9r2*YSfX1OdkPhei5)b@~<*T&(QCNhhYR`9ZLu<&q%W>#r*V@%fpTK6zCPF(odIo zX3AU6J_E3SSnfwMx~Ms4Or1`Jl!y%-U{6l1>Im-y0m}iTs3#MSUmHt?xbE#x5IN#} zI+dNlugq<(KR>J)ve&a&XkQH*j7(@a(wEfyc+i@SiTMD@g2gC!4?{rzG1%{-JSgh8dxXL($p=blkn-&MP$ld2qARRwtKH zvQ8W38s+P#M|z@?yiE#T|15|0++VetX47MSMzktMLv8q5vl!j!`#rQJ*Ju?I1sIta zJh+GD)<{zm3loKX+T?Bism|?hx__>n7-EzpaO59ap5*=(c_Ipoib;RNT~Ms#MK7r? z>yq#LYeDr${#zJO@6;vyl7AY5=iB!wY{0fs`*Iay2!71=TPEA3f{Ks6VEH5yb^^xo z?IM0J9^D{{HAa?xd$(>Z6IkVNse6A6(Lqb|V>-?=7&7#I-u2;)YhbYh*QoTWs{&I%?5hj4{7*<1xMe5H z67(IeAy!hHWwD&jTIBg^bj{^b9F9-Im&_{L976%mOzU~34^1z*z5BaSZZLj*-kF4) zCh05?no%Q|(y^}+w>OU^ip5G6P>#ImntVKd|G_D}bWY4zJ{3ivK7{S4$lLd!jVVbC z#hrgFeXgv2?@1GYGrK~kYc%^cbl7uDWv|4KJ(1ibSsTOWK=%l0|BOsT>psuI zBUW`+KKBJeS$o8dAEz=Q;QMZ@{$&_5OTHzn^jGV<#Q4%YOBT)F)TnwRkJuAr0s=-R z$;Bh}1MlC=|L$IDnEp^0+(dOQewqq6%ZL>YdY`(veI$e2Pbd+EWqMo1#XA-tj`vyL z;nG#0wR?H(4$E=G)x@zh!~I$nQFz=_J7s0z-pPCD>a@xE_u!|Dg)eT{Vrusl0M~U(DxTw$l^xgjgWVyN# literal 0 HcmV?d00001 diff --git a/windows/MSRHoloLensSpatialMapping/Assets/Square44x44Logo.targetsize-24_altform-unplated.png b/windows/MSRHoloLensSpatialMapping/Assets/Square44x44Logo.targetsize-24_altform-unplated.png new file mode 100644 index 0000000000000000000000000000000000000000..a18fcdf8a7af2fe9e3d46747cd4ef585a9e86d43 GIT binary patch literal 3405 zcma)92~-o;8cqNKV<{*IiYzhKf=fsydm>vFB1l<^Q~?p3OePRWG9d{hBD9EA6r^CK zQdEjiQvr7cgo2{h<>7`}v5J5jRY65Sst6W3Vbh-H>uXMC=FYv}_y6}_@0m@(fr~A0 z_Bad%W8vp32tl7S441hndcUXj=tm!umA>I>3}%Y8;lg6J??e%%Tcn|3ny`S+I1nOt z1I364cGJm~C>n!t_tGgrC?3|}MR1H%;X!y&TTj4C#U6y^^Z;^zk`Kp9eUnx2(&WHU zC^;TtiwRzycy}EK6(EN-AYLbzDbyUD2Vq1m2OS%xNd)`|L=*2p;2IR-!vccwd_)D~ z8E#}EL?$!vOtu@qpfTyxg?I{?0+7fQ5?H%Qbd6_NCZVl zqQ--O?sU`yxiTPNLa;(T<|x! z1;HqM&O5SC5~_L3hJQi!NrDxc2|DWfeG&Qco5JPH?dUAVS*AS8do}zBBp>u z21EmiYzak71So)r0zfP}nZ+EJ^C3Rfhs^}2bU;X^_yB+pjZLF+eRvEqjZUUhnL^q) z*H59=fC>m6*DW2@&89qZ zo~gm(p1||@Xl4R5yz6qQLX2qD^WNjY0#E~c5Db}1B-4lhJrrPY&_9(yBr`c=@+dR_ z5lbbj{|=?lLIEm=O6Sn1e}kfBBL+3#{{@R7js#K3K{SJ;axexaDHSmU{6v5_d_;z* zP{ru(sPE7F@%h0jL?V@;3+j-?JiMO|p8>EL3?ju1FcisXOa-t?ngol5DnyPS$#RbL z10IH%FqZ2Eby_ScEaY_`U2H?Goq=8l`tzX3-!v z#GaotS6iyf$$)u=8w6r)N zWT(C|?^3qaw!x{(&ft!qkXFqXktkHwG<;|IR52#f|!Y zLXDE3SWpoIqg|IYVkXJZpGNH>jYj32$?v>2UNu}a`wb3JkGX*d#!NWGbG#gdOezhn zCnj1>f{}9KQUn5kC*)GuLbS5@?jt&7Qj|F|8WlqNXKf?M_xkEM8Ew{v;lwF{zD%4m zumUwxg`Ohe##=kl!%5^P;D-8IRGx}ghAzjNbr09P-nmBmqU~7#qoGT(^;?r^=18V~ zJ!QX*<08Fi@#3>(rHO(w(&tY~9cREPDdiD2u7o-|toXeDYJO7OOnudysyV``ODux< z%_hD0+m|JGYqc*Px;u1M6sAWH4o=nEwE5fEb)BMbGaZl^+}hQnFEi`YBM+gYFWfgpyPN67Cg)oO!2zhDCfLtW8s}1>_vN> z>z}=YD?47k{LW&>e0L5(e8}k}DIl)!yCo0eY%XW%?B-&djW!NA&3GPD zTAT1A%>9tiR=4inY`oaoe9)NSQ6F@;%QocF!DpK@cW?^z(er=4{jj+E*r(6CzDar5 zyOQ*cr)S(@Ti3|qZrjXr?7HkHX{9Y@9Yto@&yBL>+~9#3Ej{|;Z4UnDZWgXA2=9@( zcJ>E#MbBC!TA6e6ZST!6DUA#CyF-nTYpXOyLYGxPVQ+5xy8D8;M9ZTM zo7CT$WLxiitOm%KX)t_nYJFn z71eg@jGd6QbaI_v7KZz3ij`AF(^m`Xo}K4jA`NE0abDlnQbzvr&!8WizDiwP8D34A z`qcA=(?y4f(#B6cx|TIV9aKeF{n1Cu-M+uk_nCb`-jWA6++I7Rgb{oNzP7V%GW9;5 z7oFbpdbaiN2cx69ZHK$FbsWj2oL9}yUw1}Sct)`X?Xu49NesB#D%D!%x4!w_C1LA= zEoH7Tq`a?9C)-yqt>#U$g)aYQrdiO#%+c2d4y>zeYt|3W0}c%S=yisFJTZL3n~cX# zEBDKnl@mdIGPfYuJJ6tzd{Z_cq_14 z*06l5OXJSmr#TK678NON;$Orye6(B#K1};P=JBlcmT_N)R`(SpmK5B*ly^7GpFWUB zko@Ri`eW^#EA`~GdSo4Q*d%O)_4SMs@MDYE4T`vO_nuoDPCT#23m+T{l5`BkzHH%a z*k#WYd2BD=lEBws!}s|?E4*ja`Rx-IhW{c(|oVVGg~cM z=kYqM^SEa^>s}qD7xIJ7mJXfXv;;SgvwY#9(sPr7I!(Te7M-;V3aXF2wdLa`Q4%9Q za{s=I-3n5lOF*kr`neQSqqBOmn?0DYUek>iUZ3(`Q6ZBLtU989+<1J`DL%DnrmpVr zymm#4sAuaoFgj}6&qIny^k2-SjNP}FUFR%2;|D@sm%UCjyQUmlH{UtJhU#uwY;)2d zQ@m%Dq>78sW6R-dQ?qWLZ#lHqN4~E8ZA*7j_7f=7#fu>|fogtj%`d-=?Af2Et)(Xy z3f+Mi4nrcRcrm3hM-{_B5B+Ch7@ zQ(p10oxR$1&6H!VXJ7kV>T4uk$T`uNfc?(j`;+8iixm6vX$iq^f8eXb&O~81uUOlb zdh!N8jfr*DSD05?!HnL@g2EHAQJNCRUw8@qB{eneS6(m^pDqAw7jmy<(#9-oa87QQXLs*0@Ak*s63jv4OyiEm zwQ+)spQLb^$;RuxCm5+$DG!3~NS?k_1h31TU473=kd}6Dr8#CUW^NQ#-LojDpN}HA@dw?s+JH4i(p1#-8&T@-ogW-e6&nHlDfVV3BFCoZ2Hvj+t literal 0 HcmV?d00001 diff --git a/windows/MSRHoloLensSpatialMapping/Assets/StoreLogo.png b/windows/MSRHoloLensSpatialMapping/Assets/StoreLogo.png new file mode 100644 index 0000000000000000000000000000000000000000..13d17a525a8e0644e831a6d8b600e990cad0e060 GIT binary patch literal 6374 zcma)B2|SeR+a6JtqOwOaNJwKg+f2rivG4m9nhj$c#$d?4hiu^xS(06nkgb$ZWXT@M z5;-AT5ej{yPM!1redk-|H}CsC@AF>QeLwg5%yP|8UxSr}j|Bh#uxe?djcHfd!NGKd zc0QvNbDwr$_RzHQ0sxM392|6jo7uboz>#F4sU^iyPZxgGX10{{w2 zR1XZ!g+Kvf364Z}l<;a(i!hLgM+sZV=t1;6R0&Q*O@A`M#9!YO=kJ0;;DwbGfeKV4 zO@JGLf&o(9T;08pRFv=!xk%dhU>Yn8`~ji3poCQp6ap>v41ua7G65(n1p(n85Luuc zLJBG?EhhuN0E9tcP%s1rhRT4TP^1hD355gydI{6Ck?{^lW3>8Tx@dPOVJ8a30|^HE z`ua-w!lg)LM=%tDKpe<`!9X+w$ji^2f}w)ky+nRVKoh)hWTFR!NOA`rNW@@C-V~HD zZKXd=aP!d9`z_er>n}&qTn46MJit&X2-wZ-z^)%?FN!hY?`8Ze+RN0>g8()rc#*ux zI06kW@;6z{ho<>28~z_;H6MaI578)f?dm@D=;*oL~2RT|? zWk4`I33&=?8XGn72fzP>!lX^1a3owBDgB>NTG`++6wLn##^aC< zB(fWZmO(@}j3WW;;qE95{2d^qD#?{ZrYWYa4*t)1Emc)RGRcAHN_*gCtZ@mbrKTzi zMaas6U{cV7BKa9pG=WU?A>h@?BsbuXEJqUm#lr+S0s`Uyhl1oB=c4yv4HCWdCo!7>ge|ILj5 zU!wfv`#KS5B7X(^U!wRE=0$R#_+rQe6-Qb@{P&!K!KC2-OsJnEoD;^~kwELZ;2&m! z5Bk$jyTCuA^0&!5GpV< z8hS}xg;rtGa1~XBA39x$H0F=dPa)v{UE2@jKl$E* zO!+qUU$3iqHBen=s67aB8$=OrND~L{=nd8^sM}~;ah*t`L;0^a^=%#P6^BbuQCr;z zubo+x7X3y*-)dm)`@KWZjt^7$9~6_mDX-A)uquBIUwL#yIA&9x!{uv8#){rcm!(5k zfu)#Qkf=jOb57>uExU>7^=<9@1zB-zio+(=4BruB)A)1bGuD76gt^$T~+fnEV<>WOfdEfli9x$iNdtZ@+?YRL`jyJhh8}P}oNWkm~pSnaQ zab(-3C{uQH(eCkU5y4w;OZi9^#W|1sea9}FZQ;-ap3ivQ@U{&(dL2_Xb4nKuOC#F7?K1_NLf(Gh^^rY;lg$lU z^c3+~n9j}oYDMot&5JuF*tu`F8BYwJ5uZ1&E|YC`o=xCgNFOeVcokc_yjlD*XXIAt zx#md|E5?B(pRGktjTvuXdSV(A<3o&XRxY+^hmV|$R=C-l zIWl0hgDeKDS4alE=T~KOZbir`dUERRc_vP{IiL#z@!76f^nV&Us1Biqfy$Rx?24iK zfp)tgb-H`ITt(EHC>aC3=g3hGmxr|{9xE~6bE`AV3>C^nA7&Yoz0X?$t<35>d5hO} zbewPXeQqj~MN@e|l}zQ9JSoP1qJ)&IFEv>#Y}!BH=%=9heGCW!nz?O;V za@On_0{cTYz5cY4*>BiQ7F1pfuUJQ2q!5n`DsF%Vn*$W?ZFtWoE2Zt2xhK8|yR@9# zlu}H^h$>IS+#6f(c=~l(=*+vrw$$8;6;OWHmkVVd>mOFLMMx$N^CcGVo)j#`=w7T2 z^$Mwd?U6J6;CS(aMn~t2V=YHcHxn}0D+as2Y)aT&um(-mU2F&%6=cb}A+EQqG(JKV;P>RxQ!Q-AhGSfevxVwx}b>V4?7geBb5XgB_F9gAh167L+- z{-A81(T}f>)?#@}Pv5((_IM@ov;HFEokY9sqQu4)X~R(-Jzvn0a;0{~s7!a?XzhpA z?!&s;qlWRriJZ`9cRDZmTJx|kjbE8b3_`E-jBDjfeBEFS?=rVwNFTqc`f}7wjmOFU zmK;~sfKyA?=t#@lpm9qI;gp28;*I`7;UuN}`c2?_UiJ?R$keyeR4YcZV!MB!M3^vQ z4ElaHn81ol$2H5s-@kgGyARxkMnK=+c-y^}&+lR@n;`SZeA_m0%4u}qx=J~$19H0F zI;d>=>0+;Iyak|r)V288xM4F=&qFf%o4}m!Ma>ql)yzz@#e&xK^(S;}&Q;ZHa~t}S zho|bPoFbe4DD@X&Twe5(QwwD zaoS`ef8TH@{rl9jz6EX8jYc*^ zlle#x)-nNV79$u5`c_)9`9ziawP05?H!8}aG7)7cxUt(=#L(K;t<${5hvZqduf81H zd)k$+Hx}B2SJ8 zYHO$aO;LH|()b2oP;s!U+eGlg%9xH>@%zNEkCIQ)#;2>z9(_yAftxJtit7l9P?%>t z%c7}4EE6bfOV@V;fT=f{e?Q0vryww@HrQE&ez&?>F*W~DA)QiDhbhApXA++}Qs3ns zia<{v>2u58h}EcsyyZR4JIhh==FF_@Rh~gMrI(K<_L6RkhOwK@%vnR8*N8g8=<{|t z3y-TjI>EO$^QtK#>>l1fmZxM-J6#a4Q1J2%92zEdmUvP3=04eYgL7Y%^-$YV!lwwj zj?m*AiBCQlkBy1H6!(mT^_&a%!dxyW#f@YzoEk-W?Pz2e1TU@+; zOu{BDUEG(IKKW6?vj)EarO=J53`UBL<4=!FR`UROqEiF8=WLoc%r$qMjXcI2iHd4E z1&jW1odKnE`^KM-69ir;&k02KHzu|Eec~KiJZ+K~PGO;7wf(zSl}3S|vUZmmW7d3y zcA!PUVzHgkbxgQ6LG&IImx*G3SQ~#^{9rDjxGFqbC!&mXbjs;wy(Rv&Mgq1;VKi(^ z>7$u{^B?^ugzyC^BdX2(9P2wFq)y{=;(R{rQVrP~Y0J-nofqdX#fomb4k#9G;S*c^ zSl3ReEPr|NRzhV(tBEU!v-lVv15+Y@OT`&6Ma3M;RL%+8kC$)9HfS5y8#%Qj4dTa>oiYoy>URAcAK1V~YV1%3WuKStpo+yR9g5(E zLzB63mKxX~qyE>TUsQZlr!Y~;?cHlD!Xu5_%tgWFA*Y_-8LEpIz!c7&DCl+fu~~jo zcs&gqaLdH)hO3x$5bBPrH`W|?tgxJ(xnSMhvfW>B8=Ye^8J`k>>zWfb`6|CQ(>eLl zZOC6mBqZXr0b1|`{K?(u&0<3on`?2a z^agh1#J8lC{>dxjBLK7|oe?O_$tBHK+ivA05C!|n+&-O}v0HYTHD64sSA93VB(iz6 z*MeLA{pa2H#Ug8HlhnyR+~cjLxxST6@$6tOFZ(m*k9`6wC~?!Tv!6gzQ+(!uv2Aym z?^PYAHy9B<)ptzXM(mTgo%vLG06erdKt3V!K6l1Bp^St`KK)wVSii{jrV6@Fw;o}m zCC?eNi5vsbTUau_CR0uu|0MnIY%BNV9ZPHqC0q@tD!- zyU801U5zYb3F8$5BeO4G*u=#47{Z$(t%}QfIU?3EHv0PeY?oh0)eD86w~aE%RdKY2 zV!g$$1$V~Iu0@?~J`Q+w4FIESejUy<6_NYL`iac4PlXJHf+5s_9`le7PcU!#nP=lI zGQNs}(jSsCi8;4`m*(G(glYm419Vh%U&rV}x>pCWA+zloVLE417EIgXO57R-d6}}0 z3^*Y2MYPCUKnj8T7)cz@^(~4+^fnvOmmL{t^y&7-SLKiApbUvsDvU@-is)tQoe%34 z`@ZaH`wv5>OCN&gfO+YV8N1{AK}YAli@DzRJ2Z2bP6GWzwQ01Gs~gkMqxG!NR=8}j ztHY%4T)PDH+R5E%`g=G$`!mVqSp;B(E2;bJX(_8=n+>Wt?sU7hK;AdNA^o+Cr@0jF zbjgxIK~HK!G!^4mG341Hq*pa9bUMNe2!b08_TQ>ae}T9A!c@**r0iR1b(mf9t#i|Q zTlB{aDd!57+0^4XYwHp&FY|6zDp0yeVWiIL>^$S9L*2WKNiUfIv9YB-+q`H&`zedC zXYZKH_ZE`I<8IGA<`nV@zEC$3c)6xqf~vX_rjwxNGKfvh=PYE(PvWy@N%k{|P>8{D z?sJN4otzXqAMl~$UPyP<#FbA+*&Y}Au4i)$B0N~nn0EV8nyKr3VHsun|`JzVc{8&y`Sl2K~ z_|l*0{pN+!r@Y7W!;~`O;RQZ9H`v zu)d0Rlgb2}UG7YkOZ|p*4$_|aX7LjZhecX>k|UZw1$NA5PDU&=z;7rAg(ZpJ^; z#<`<>Tg+?`UZFaYjAZBN!|1_pfb|^#WpiuB z6w-vouGVU$=N-;89)VX3#tA~}eix7$`g~uSC04m`3yC~T)`zb>Uh`J+4#WT{Dod%3 z1xGRk=R0`fP8n3b)t8I^oF^@qUt}}%T)v%r)Jyh@N)f*sdRv!6s&ywHapJKb%flU= z3%#h25=!lBvP)-Ncmog6uj3JKz9q7RwJ4lh?G)c-2VVxePj-aop66u*^XWIA?w;2G z&?g1dq$b&%`tCc?FbKhVvP@kJ(XEYVYTlR z^Z6|xb`~#V0?Y4*$m!O^-;@C^lqn zZg1=n6AJ<_aihk*n-#Ae)>}=J<#o6TVIKn3T@ur#>+pu#kLJzgx1uiu#^1fO%+xxok5NPUH?ckA^kbRMhcu3S z4yMCrM)L1EvK6fhNR8pfB8N1_#uzkxCIq-H$|q60PjE_TiJvi{ew43Z4g>)4(=U1z zJ@P*ri+De|@CLjXWVUC4j9`V-_SK!QC}bSmD7Xgg|hDYw+N1!QI^<1b6Sn-rwHm z+^0|9zCZg%L-A0xYRVd84ta;HFy(jBFVJ40!N9=0kd={8g@J*yg@J)(L_q?sK&g)= zfq$ruGCD3WFzC3?f3PsgsYEa^NT03LwOzFp75GdX?3j&A9gNMGA$E?yXc!m)VThxV ziH(^n$k@!n%3hG-sIip-WMwKyp~a=hs^}1?Lv`A*%$)5e6?ltNetBmm(9 z7O*pOH3C8GZ0%k6Ac7Qst;+|zf4|M{T+c5^m0=TnuC`p;g#CqW8J zS64?q78ZARcV>4EW(Q{r7B*g9-sd&g*_nV5OfDYwu0{|hdl$-oR**1rF>$tXbhUD@ z2R*N7WbE+KRgeO>)4xfub5vCPcVT;%|1b(*84JY7k%f(!mBr5PnXbP^ySS>F{nu^$ zkE31GJsizgRLxu*K02G20mCW(YqF#pu=9Ut_&=B|>1Jl{`tNjr_5b_H|LkLG^6xmu zkIuG#vB}hg#mv^s4p`3xpo#5Yf*dU!Tpe629sVDd{`c#@81cLTz%4!{XDdKxjBF(w zOg=s@DJvmJ0er)3YGuj?HZlhT=gP&zZpv=N#BIW9#KddPZpy^Q&SuQcX2Qe8$^-sq zo&RY*FDr)_Cz}MT6f3(p8=E9254R+%I47%^q$pU5ot0DcpSiO3F0MxQCT9QaZ3XPj z&S}bJX3A~EWXi$L%fxBQY0hM1&dbik3I?-rn6R62ahVzaHJ?x1+04k*!CBqG!S)|X zRsM$)AaQX(GTAsmbXr#SrVj2d^#5&+nS_z6nIOfpC7d}?j zzlSP1m|B^8{I5gVIn~)X_&7ND*m?e!p@7<$8o3(%zYaDv;WKw|wle}G$jZ*h!i>ey z-hu-3?*Z|NJJ>on0~-T($MN5<%ZiIDJ3E+L*#cjn$!0b%i+?*Ut#_T*sOk7|SQw|zIoBlWH_}fYVSAbLcuUqEjU^h46HsWD2XJrQiCcuo7$(R?+$z;mQZena| z#%pe3#!bQU?=8w$xd3P8@gK{eX6E#tceYl*j(}?M8JRq5IY6cnK*{rMJYW2u$oM}K zl)vY@Tbcn&{&V2}!zunf%*Dan)!oS1Ow%ipK+UnKt**Z$EOQ9$~i8RGIEHi#Kn{L2ubf7DS5%)to=KNwIaiDz}< z6=j!@U=x!P<=~a#K_+l@L{j!2W4R_RF=g7)uO+zt-gu9&({cu}55hx>)9 zOXB#5#!^TYiisddl&jz&R)EI6js$aN4ty-!Zc}+51P&g3-(%1>2KgObRZ?AjyeSIb z;E4uaE~lqXB)!kCch*AB7dCi?WrzN{K+?-wc=Okw4IWx9vcIqGQf@U&m26o<|Cp4=v|4<7CWE`Hc=@2X>TBl8mfS1F=m`%&Pc zuFUrL6LGqX7jf{4usAH^oBxfCqmuD`G1hn?c640Rm-Qk_9055LBqOwCiz?hTsOYR*ecLkQJ_d) z_v}p1?H7E)fB71hTJMwG#v~sH<43|>77Pxx73o~oU&>CAZ9ya@M-)ed+Dolrdp*zw z*)PW0c|@0N3$scFP$G%)WT)HRVD-~Lx_+NAY8$e!4IcMr33gG%!Nxic5B-725&n&R z{VLWF=Y$r=*FQUmpMBk^D|Km?N$BnHddQR)`p)_IFrBq{WQeG;o$~&mKb=P_&wh%d zJO7Nkix8bR6X(rQ=r`VH4Pt-RAX@kn5%1VP#=5maX^=};(^98V_IcF3p`2BB*5#Lv zt4uP-_~jYm_r&;QN<{p1)em1ehTxT=#}DgJ3f_hqcKN*}hzJ!`hZSepix#ygA)aEs zQarxn6>croCAw{s`1sHo@s0R-x0lbmwOSg3Y!tCan$x$rMnL=c^-*wWGFU-q9YkY` zd!aW>SxG+U2FJ{@+hxs8_NQpVrGldzLKJY;Y(3cDJ}}f+EnNl7;*Rv_Y3%Wea2jfj?=~+4ZFY0$!_aVZxgcZXjdJzBA;~ZFmLq?+&ir8#)YT9)X)^r5bFIv&RcZ&x#lP3J!YQi?F3V3WPbD#|p3NyEiM!n1 zy^`ZZ|GqTcrx+GQCTIpZkoJ<@kiAQEYx;=`9!6~@d2e3kX&(Rar_y=p(*RFIIm*{e z3>^gZdPRoA=`Z;ATBeceaG)`H+7<+h2!fZ+^OWx0}~`2Z;|OD7$0J^>HKX4_J&Aq$7!kE zLCl`|y(t2Hq_6FS_6pbgJm2#*o`Vl@Sm7i^M?R0g{T0dHFS!54T;Zn6MNYCutHnWB zLEoibTG6#t5-v-0CC#D>0MyMf9wr^4ouc8%UBBW#e|d)pJ-mv5ZnfS;Q2LsbE&;A> z81))(gZHf<*w7slFRbj3XT_m;q!{$lg(9O@WjAR0)OX|t6j<7mSk$jUC+)#($&{uMoE=4e5=1F@pl6`8>s zWVHpT(j5VY1*u% zj48cwbGAO1Iap8h4dyM0DXScozJ}YN7b8azn$+OeJmFc8dcQYSFZ{gMN$lCEW_*yM^&0wWJZdyC--pLX?d#<2okyN694b2eGRx!l?`31h%@+U?EA*$!M zQ3`)i1sEOtsG0AVaO-;^V<}CMC0zbAB-DP0O~w)a@=sBYn`La~WXX;(1&FO=MTvo^ zCtUuAn6cRF;u^L{9S1=R#P&N*ky4o|hy}5SWYRFO=E6e-$VvqwpU5i$jvSuwTXCVS zN&V}!uWN@7%4i9xW$gl4gro%66=A+(C$w;>rbBGFgs(4J?j4;AT0%Z3QzW|4@7(p- zHdu1KCn@{UJPoeLy6y4RDQ!Gfh4scAm0!SJS-6{Xf3iNgBGtess?y{Dj`P`w9LjlP z`v&cA{q!4;`yh_%)RJ4y>yGDVGg69Uydyv2eT#=& zzV9pFU9!S-U#7GJLtH33`g$O}Uyz^3-Un7{5MoevSD@`i?cSdUjM5ZR%%ztEtbTB4 zD4BjR9c<6!dyr(W8l7MmzTUEVO=;o#!{t>-oaCt#io!3Puqf1r#dC<+!^&podgDgP z45ori{AD?S2S!^hC#s|eihmsCrA@0^d~%-c%^Dmk`OSY})?MDfqqB16nXNG6B1 z+vSJw^+BTGZai(%hbh2bZag2UbWh0PVF*Ab{?Za*_Ol54m%R5oyrFtOEDZ}Av_TIN z;eo!n`Dj1`zNAOX*OzoBvxK7){%pQ_A?_~hdL`C?vBvrhyUPzPlO&h^I* zbRP6*+C$~mAL}?z3O@$sx3X3BT@2N|Ggm7y=kz+;Y=YA~h_EktY8CHI>dP$%D# z*W=57gR#X@h8C^!lGNP8hi>Z4jk0G&6n9P|}#hF&=-*CA3yVTY7#wEo9g`&_{#{&x%&&3Irt=B|v9igAM-J znvyfAveF~6m%I&AqznGqO!-wq3j^pTKFzgTmI|if_CQ}Gb7wsLKJch`+^%|@(T=ZLo4S& zE;P)(Ue>rIz4Z+#b@@a?Vrw+j?hYH*jwWhEBAuJP3KLZqJ zUMi)dRmPoqP?yU+gbYB|1a1`XD$))h5ByUrR$}$MEePEEy~f|qc_T|PfP_44#JKO=z~Y=*2qkYJc^kdfEw|Nnf>?k%a!sReTYh_R)4M! zc<49Ldz^!eE2dS4FZ7lSh;9a61m^n|C2{`Z6!-7DwNK!ya$To^@BX}}`orPpvK|RH z1ztxB*)2^S?{F4+cD2j*`~7MRDPA=Ra~x#VNb=<^-TPg z(u41jj*&%8+D=W@6X%>J=+Ht%j3&Ub*!M=E7Jdlp;+X`jnFPv@S9rgG<7~$h;W%W2 z6=?hU-3g!b2i)4X9u1Hm+?amekkzCv@xpvD@3+)<0?l2w-#M)MUurBAPdB2EBF-=TJOi`Sbn6J@!@l?m^{+Z|rG6kuW00F-X<4>##t4+9dMv5w8DGb?!ChJ0u zGi%XfMMH7nr$?%Ygh&Wp;Hhm5>v_gR)I*G7Wr2Xs!VT%j8M5`#4fv?c&Z4@yGUW_? zsDXJsEF`q>)o1cz0*!8`)H`MX@<-3K_g zmEDUqlv(PwfV|Nbd>|YQqBJ}OA*sW{#+%?_N3$)ygIObjMT|tQ=Q2dgBo-!IgLE7q z*jMH|J~SCuhWdMdRzO&R;coW6T30NyJGYKuGd@-bHSV*OTSfemkEwSY-DGf|*gdSE z<~K;Qc@L+FkIk6yeH;x1uGWBLNg@2;B#*13Dc2g;gOh95+wg60WLba+d?S1?fThV_Aq!(a|+J&qJbI|kc zeoA||6K2Q;ns}d#l|4qviHOjJ93_g2(o4RKH7v1Vn;Xo4N^(F{ zJHluaS|y%x!KNt3;}c%2Dr>AxduWWs;OODa`$yBFmb>7vD2A33Sn?Xw^l!Fx0*{}? zlszX5ozADbXo8^roKfV+p@yY;h1M(zcDGT++V(H-04FZOZ`I;{_N(5@A*tom#c3LS ze<@fPbAX}Nt7pNtpu&B_*z5KNB@a*2qNmsw}T55SSW1ftxKNJ3&&})4o1x9(CF)x*@&a9;J_CP!r|A~7+pkT<7cxAu{8#}y( z(De%=rp?kEm@9j0MbGw)=M-e60sML+c+0!>2kC4)V>PB;vU%7}m=eo@fMG+$l?`ue zb!+0!84GS=k*}!+-*mvPJqe8R^q=qrSVVBSKWEkmzS~5=wR{vx_BKT+7kMW^etelNCBG*;Hzhl zwdMw3EE5D)5R!5<8wjb(@f$406aR12B(~-G?&*7m1pc#DyQu^pTt|sKVkxRu%t}oT z7i~SYaL9lvlHv7nc3Sou6>q-}S)PvkojYj0?CfxYL&80i>@8`$arU+3m5hDSvR>+Z zBV^xZlT||GD^ zeGk?uRKNz;KHFe2DiC?7aOgq0XhT!j@U#)%0&d6G#=a=;K+`pxP_bzeDjT6-$QtvnqlwHlgs$Lq#sN|Mu;dM_v9QEe|4G9KpvIO zvTYX-#}pH5GUb+g4mGq-=sR%THL=0U&Uc1>$By4)!PrRhbJI4caCaIoNob6C2=Mcx zC3TuF9p=KiPk0-OqmHjZw^L+5La%tAVsYPZyU|v>;AE2K(D9J{Rig|`VHGPu({cLx z!G4d1DZvZ&jTKg#w=} zGKc&-P;$%XoAySp4CDSC!v`v6F`0@)n7MZ2mL_p#;7`3{RJWmJjS%SHY0rS z=aCm*HJftrG+S4~Qt0||q!4VFhV);IAfS*YDN0{5*?Q>H+LsM;u4RRVv=kF*KH6S& zD2`c~5We_huz33jf03qi+?9_P?;an}|9YL#I>2!1SUFtW^&^5`4i{_E@u3p1kGr@PnLOVVtQy-B_&4J(o2=`r94AHO^g(9YZwo=+? zu=+Vi_T^hn!jAaGlfxng;o^$$FyhALDpJX(U_a@cWB&PGz9zrf(~5G5qyT+oBU1kw zO&_-5F4L2KbH-0gGj8j^)#4~-%?%BOHqXyr{l$zM?X}pQdY)ZUswp0Ica|wP^$tEJ zMncc>ya5rEB{q+HjXNOL6t!lUWMIi7@`P7xs-+OO_EEWOHKkl*_`;W>LdA5-xT`oy zbH;nU?R1!yh_ZTPTL<9(LYsk$HhqaI27{ILhIpxd;ACFBiw~!#JY90c_;7@I^4-dM z7_AhB6Tz4k(QSLrXP2jU*ceDa9suyMhg*1EA%{PD$D3}B#tI@~8L=@2u`zv+zT6=l z=v93SP`Vl92&KtT;PfEoKEoEd?hAVQ?AdkpI&24QJcxcAQu`9)5#{sIDwbXh!a{6L zNM34e&u9bbIL$S6f&M)~R^a~Lp%NGOcy0XbXk%(*h)Y#MwRF)4{)OB=9W-l6vcFNPS2? z_uOh2nY}?B6r&igQz&_iJ<8ImBeY#NH@;Z^HDrwoh|LPF5?I%(vMLkAqne2}*px}g ztM+c94%Y_=bwkq4yFkV=c5*_DigrW-XWjmU%-?}R&oB;=_HRw?|=7`UY1#{+QS zd1nV!-nfp^6k?RRRIG?V+(5MPXcSeV!JWR>~C;0R+*KS0xy6H;EQ^%r% zLr6MDCxC5veBOVEg>I`z%YwW68#WN3QUVT+H@#<(fo^px__B0_T7NMV8DQ6K@urp_ z{Fe;c_uFo8$^KDMbLaR@SUIC$P4%N!xDo-_-KFy5Iak0(gXqfTa%+Ns^%O^F=P~gF zukeVmS9Ehk?fPphO49JS*-d}+1M#xrD*`h6uGO#@I4c6RzN;gHrPh;}$ZLaY0QCSF z3qYbsSdusOMKL7Ckmlc~2f&~~wgNE(FM~PDGJ0wJoW+s@ZvATETc4sfXIj5Nw#R0# z`&@qtN0v;4z;r0l`XL5&z7$Wuh+~uS9+E^EU51llkE>@kX5{W4TTT~;fn^8n+Njna z-wFTuv7VwyG-~|KH6fi>Z{?wqYTphs3X7sZmpw%VFd!BMP3tUx+1oGnB6R33+WO%v z`gs)nq-zHSXAMPC1y7@!1Nt3j>d`T;;wiVe8jRysvpV$cQ!sfVGv_WvqS-{zh|rLy7Cx>&(-PX`Qkie5z?pIc zU=YJIoF|NSDg%+9U+T#J;$% zCg*^5Z0>~0)<)2pSB@wBdKJrG*itreN7kGnlt5+6jW`Dqo50%vB&4iCGvL0_vevw` zmHXy>!ryp`&WEmc3;O_Sr3D38h^aFr#J2?v*dV?0>J_m%*Be->&z+=M{E8#aVz-gv zXKWOzKfd+@L9{ECV@BZmlc)R134uIs$>A;o#?zjm)8Jv5-Cc@#nOnbz(|N;5%Z2an zl=43*ZBkb52F@ST-~W}({uiX&2&rbu2Y{)m@bebOrPdPRyjvv!}eBP{CNtqf$P zPXFTttSCm#06`p*=tuC))JlrckOfu`1E#mbkGYw>VIlVlj=L;Q`JO09C=q)Kh$0!Q zKVyN@`OpAzt#zXxsxjb%AjT5HCb?b`lC}6bboF)XV&p4d)&-txi_)AH3Qi+FUHu!f z?5(d_)!EaJs@g_5O_huCd@LXM9d7|3_qhMvpv@dLB8}KtKV5%*ZuVWWFW*YCX9Au6 zYA}frm*iL1OrG0%Aa|zseR{ckGKsp1UXuw+UR#T z2S7;sPU%rHMOf>|iW_(TtoH`su=4Ky@h=$=%p#Z!xOQptqAz*U;`Bn%xdQJUJZX$? zTLVdMn1l9HECCD_Q0w8#``@%ES}hqJh5RDH#y|SI&Q1*x`$P{S61LrS&w@kT-D(>? z%)OUqC=?WkCeUwOO!6(q!5X=ylQYLX6}37_epFkTmP@HWX@{nV#6GG0?} z%z)@|7Jw~O5p+mq5oKkoFeJ=UgqQEdVl@pR?jeUT|IvLfXVFe6w!UT*oh}k zU$V&hA^CcsqQ5_;M@PaMSDi_dDY#s$o>hizMLJt6`!%=^IoE$~`*CNo0p0gy{#XGU zQhR3dXKOj?nWqQ;^ew0hc|Dv$D^97)zF$#Rcb15sy4mWQfZ;qT-`vn@W->q z)?W#%(_%FebAN(OXhDT5h*WE~#LsI=ql}~8JqWNxHsp~Kg&Rf4f#F^wT1&6Uq|baq zb&dD+Oi0rG=qA*IV(fk+ly+o|8_tqK;*Kn4lZ86jqXns*Hs0{e*=whGzd1KQ^ra`w zYUpGhq{rrbC*;ZLVU*Z+B`QU&C_zE(wO>E1v@%uak0ccxJ%qd)7m%K^|7ELt+0@2Z zZEn1R0E9yp7HlQn=H)!M)Hq3<0DCZ>*#n#5g{<^>6)9+?9cFCPny-;L{|R=XuOYT3 zvkD$tgeM&quM*P|t^R8!L6@KTy(?OB0L_e=z=LN;n0s8>sbd3whHT}zp)Jb@4xFU} zVinmYxn?(Qa3O%Fh5TettvDbFkK-$e~DF%io3PL<#e*g?W9Y3d+boCZT*)n6TM z4GAaE!dw08AdMjctU5jp>pJ|~p#mtBvdG6Y%b{}t2pzdZJ^_Z-<1a(&EYzyr6qNBANZ=ZMUa zWJhS^+1!48x04u-fUPLLV}4vTx`4_JzYsW1jI(vNEbD$`B9rn!l<71vL0_UTyRw>s zeWuuzLwA*mk~zA7zBPm$De6x9jYNj@mk34yBHO)0vcK^8O8kf-kY#|i%@1nhrxTV+JHekdGgwMZjJkX57=nmG1$q=)0T&92Aq&!Yo^QD^4ed#UU zzXe)hmMww)l5?f0t0vP5j)!&q@xmY|IVpYAlQ{jKyZx5?QHAE(UrT+69;Z+ojR8A> zlRWMi{o@@ivg`Q}d83b4@Z17ZSoimZE3-FjdHZ+2kR`oYs3tIgnBgK}Z9E(cf#yE$ zD7fluNIWWX@b)D_@CPeMInU*<;OXzeHr*GB-xGT|V5^4U9dv&WE`R8|@L{0-H^FUT z0xb*$6vrubqW@W0xH@h6;C% zh`~jVV{pROU`LBPu*8b;ASC;llSp%v3;z18Tz_nG4Uc8?h(6K_KOTvUG4w{jXOoz$ z!3`?R%coFFNWXO}lKBQ~CH*2<PQyGIdclf}G3Zp2e4>cw>cugaeCFt6~TcT+aock`ZZH z>29?z?>1=QTU4ZqQSA3}fz%(BR(gP8<>UM;^;6wsx_-LtAJpj==?Op=TTq@KEe#Vw zZlKev)~C3dnCruYx#B02Jg3$1)I?f2udn+wtq)o4FrY)*>|zF}artrs(L)hWL@`k5 zK4idXtpbv9(W!|URmtD!+@&>6B742>uv@O_YH>kwUb0-m$AyKrhraUw5GxNbSVt+Q zFPPQv$%huC?)$=*o3wCAHrHP7lrEnJmJC75;`cL3wvo$|*){b$ALlW}gj>(nxv+fK zv}%2>T?(V5;e<^K1}%8Gtl%BF75{XIDCYbNMv?2*b)tVPvg zSIq;yFG+map%fY4&AvRSi5;X`MhMKM9hc|F3s_%$oWGoLTfhA-rud-~Bd&em^+R64d?@M_CVgod@lbSou_iIqlX& zB-0BNO0|*d2u-xN=lXKE6-WKBnD=WprhcWG#BugY%+>7P^BXIPM4&}oj;vf^ql?N z1YCY|AS$^Istv|{Lza5rdU=q z{27>I2-7K;?I$uFRDuYP1?vlA3rB-twZs_;hZOsx^7!+v^4fQ*T=oOYmCl4l^i~d_ z9DenAysLNny_!<8!yC_iAf}ex`mjO`WHReYt7g1Krd|O^XDX)jQ21jZ@f7%0|9SyF zxZ>%!Yb2`#==L;@l&1dE$w8V)LXP52O+m!w=STr}UdcRlziQyVF`a*h);SYQV_L@} zDnvJV#cbEDyZ?UZ_@Vr8?c;hiP?G&!{C3MRb6RnJN&F04HJM~_u`2aySvBQVQ5FTt z=O{F86}+u3Je>9-I5Z$9c=g<@dVk6R+ZBP8|CoJcH1YP630`a}b-^F<(xc8J4k8E2 zz7A`kCy1>hj5u1>n!*38#6(QTrfO3umjV===lbHO7uQcOO5;lkC@v}<+ai-8a+j{TKlqex;g;Hv)v%2}Wa;4pwlkQO zO)e|kyfwhF7;6}$*&*6c8NzDuZfbZGN4DXAq?F@NG%G#d+saHM@*x3&0WY!2z<;6evYMt)}#m#n`lRaccqB*qGi~VjiiX>FZYA zuw4^%I4;IUC+yLCf8jvDR$T4Qs<}I$J3J&tBX>2?npZfc z$XSa5NmRzJ-_j$%+6ZL@0p&R~C4ELrN?#3L0fAS#;cdnfX^JKrNjBWt^-%l>l)wGg z&bPZRif%<^zK=}u240LbS4896g{Em-v+q7Hp!DKK<6uU3k6R)T!7@|Mzfk?Xn&<|a zn91^d@zVu;{it^nD=T3GH55w+zLL+?jfg<#46gDWKD;)lb!|cY5S+G;M>kK>nR}vy z-!VQh@3a9s5#mp0z#Ujq6>6r=C6&p3rJKMQ|o+<<768zYu9dmY>ThUC!R&y!ZdykaC}Y?)<&_pmjd52@`>V4nz2Oz#I@Y{jJOK7 z5(5J^jZV;6@?BOj1fnZMpzAK`%pRmVJ0R_773D@UwxcZXW#N}fW#px$@JGS97{jeYTn~IFW<+tt~y{cFEun2gi_Rx z<21jOki@Xp_2QE}Lxr_$B}#kt7f$+}+v6^Am1u0(6?97}`D%*WDU{RjQyh!l9WdwuXh^c0^976F@f4P?EBJ4(O2hDcMn zCX`4-CHQrIi!^_c+Td4F5seD#3TvF_w4C5yDeaT%ToCN}WxDJ`h*Gy>B%J8Q+knRv zX|FTOK~$@_?|b^JUVWwaG&&m&^r=4+u1DcVH$Qh(T~XRZ8EwEIB4EE$0Gca%-1@bL zY3x%KEoN|kDc--@s#*>^0IDQ!s9>VxOw;5o^`8V9yhsD{Kq5%zdZ(!2DXnnC8edfR z6(;0N-n|jJ8&Vl>wrug))dJkya!Xd_;Y_JHnXS~oNNDAu*ByGNQsl%g0B516A8dX{ z5texVVyGR|fADkGZiY&l4JC#f5f>-$t8{Y+g+wXqE1-XSrpGpy^P}Bgj<}hNeFb+TI&~+gnO^V))|eP8nzq7b5Gs?-47Dlwq)yh zeMb{oL|Jq1JHW8d<;A1ta_Y%AK`UO|U+y0GGLC)kUH^)S z9r=zTojP4d^6d8GEFK2X>2}Ic%W?lpi(Gbm;3ahQ*TiuAJN4ePro+PQou(X)DS>9( z+IPhtcb=ScI8WyF=LK2%vO+i;M>QIh$@gvaq(9L_PiK-~`DVIgqHc^+O7D$A& z{G1g!F9to9P6*$osQx&DwxC*r6@0GNoaXr#K_nMNAItlKS zh%DWf7OJ${p8sVXjuW$=-=gRXCBg~(t4zE4%*SM{Gx>JB)ALJ%emh2G!7GMyy+WMi^zm3pDlzC}2UOS?^upEaCP}U&U>4 zk&yerASt)O1y6y;+~=xJiWewtZbSt~RIO12BiWW4+$LwW`d-++pQ~NN2QbV-t)}`@ zX=>urn4`yfa8=Yp#zEJR){i#=c18u9mw$9Ej7oKva6A!Jqv{!O0*kt@#PU+Sl57;& zb#((nMS&XJjTORLG@fKoXO8kdQj;(`6NtEJ;tBcQqZ>84}iG`G{O9PhkBQNp(*fGT{dfe1n*1hNj> zKO&Fq&5}vX#VlNY9tZ{^BCJ|#`cGTUh^_ZaJo{7jTmTp=L-4mfxU|50(k!t8}WbLhfxoi1P^a!*1#?Yem=WYd{;ii}W!hvTmNx=1I z{Osi)*l6W8mP?t$pQB5d$tNapfsc1i{96_lqWH0-FKv4_Yt{IkGIkGjWGh{H*9GG( ze;eE0xmMbTEugq7!S;PT2^VZ=B#rbvsflHN6*X!amONkc{4_!Ipn35nvz?dd?iS&x z{^JXqkaxan3`GW-M}sS^K))hbU+?Z(s@nA-{C9FO91B$yF)e`MvKxO5-=y%^th1l0 zZu-h&vkxH=E>w*OYA@WJ+Rq=dT<6*wI9+Fa3g37d4SVf{bpP4^X8Zfdj8_EE6+GGd zq{5;5c%#maSIlmA)$CvHs02@Fd{bB zFWjXCpKv;#UQi(6ka}nS-1r!^JT5K@w7D3}7!b8&5orp2v6AzJ2FbOwZm$W_*7VJ{ zp$icvJ7(fD3A zGzB{bg1n-Lfau5lua?^G3EsUVlF%8%6c|!COOm)6aRp4E`>ct=^v&*J;39%ydwhF5 zsFu{TQA7=!j0%Ra7eyFXQREA+f)%FkF+b#MD^0DZV6s3^&I!tTpZq8UQRfdO3GnL& zGk>;w=mYAzw@_Sx�Yc!kB5Oq1{rDVL5QTos~QyD=k@`4o{Hf${xYct94$TG&mT* z+6!;ty0b_@uCV6)Jjzn;V8xGKDyxZQyY4#>8bYhTB4%?-4frPEy}Sdt;gKsTAh{qo z=KlLV;lhMVk|K@(nrKpLADi|ECzqnVAumFEpUDp{zr)?e>mobhgsFyJV!IxU?j0RR zT{Y-h9CiR$MG9;sBrs*$Y^@2m7TSG@5pl5Bh3n9Q9p9=qeD#ozb0&$C4Oo`4=NRdP zptVg_2`3en?fs;q*#&cB!C#Sbx0C%V8uR!jq?bOgj8?z zJO^1?oY`B*1-eplxLQ#fGao*io)BULXhg&)<WymcaIHvj%{7crb55&{xq z*^9l3Ko{S__f0=LTS;+v*IWe%)KC_0pr{1Q8h3|^|CDXkSg~L!o6C^HCH|);JF}0S zuOlH}o_PW^<`18|nsGc;77^i55cz6?*R)PiujV!}Clml%sqkw)rsGm55Y5%yQJr-# zjJ_8o6HqY?WyFI3A`y{#__cI35m6>fXKb~5)-4y|$V;iQEE;_X-PmTg=>bqo zlJ?Mknvv&!Xx;!hnd^lB?4x)eGyd&Q*6_+Bb?K7&0iyu*Bc)Uvk&SU0x3GbifR(K;QZ# zLj4TSUu8YSzV99BIW?gGPX6TOrWTM0d~TNthypZ=DwXoXgB{hCW_ZfG@3lKxyKg*E zW$obL>EabSI?oo8DzAjAozAna-XlmVb3x+7vENB(gjIza17%o&VgKAWL??Cpz++n* z5(w>J*tDD*2K1q32kY~MVJ&}S<(uX0G4!%uH#cQm*?j)yiy8(--=IO15`$vAGfzA3 zEq**I#Jef_8bMAfKgRqZ=x}!2YGFwO*m<4bave&fj{h|>HKT0n;Z!lW+}S6)wyqeT zsh4s~Bd{QSCej*fH!n@2Dk&fb^_q^!FEPX@aB0g4K}u z9Xl9^f*`*70)~FGM>s6wPTW>q%&&w^;vwY7WVd3ZW3z1I=@mMf=?j!k{y@_@6b;CA z;=HtnT@t$~IT~xY_>v>Pfg+uTKX~@-Wa?<-EB8@JzFyl-C~GUh>#2H%;)K);lcmwU z5;CDcw@Hx-Ak=8*5K2dN4vWf|4YwAjZ12Z{jgZ2SMiI-KOWqn@ls8X7&cLN!@)n|F z#>A6;;yyn;I*)2Cq03xMGVa=_u86=1TDYdUZqm2|s||QLr%1EZ*?$*&xU{MDaS_2r zZ6e78db^IDtG<&x?f~f@tlI4Dshdm*ust?}JbMe3Pxgxje7qkyp}6047t@U zZQBt6`++|it-jmg@+)a`ct9lb=C4}R)@Bw^RUsIsJ}$=o5ws|WBHg027a610`j`aq zgVEV1u{OA4)IV7Y!ZkqpNtqW00g;04?}M@@#io$}@hfnS1b$=YFx8p;PwRnRq{FhL zo0!@&;cz5qZk=7l9PnIXkDWw3j?J88`hxb5G9%^JsghTW#$4HR#ZDA0sFs%r-y9VC z6?~pDruZXRY%dcY=nnKbwMp-?HOrQVJUp;TYk}s=l;p8-od9WHqfMK@?lJHu=p+A9 zPE?UIMNxPWbrouWjRbFrKAX0# zlNx;q=AWdeej9L<-gWo)(=M(l+t>?ni}6Tnpxf;dT}yb=<1T_>9!z?B7$L?IgVX8i zb9ChJO6W+uP|^C?9z6>e3)V^7Ci%W7=Zk~)hTTWz7(&}qT{VCw;z!292I+hQt+B{# z8z}B?`#`$)KOgI^zAA5ItM`yF#)b;PB?st=v~RZU!!s5jqKcS^)W83UoCmYUbN!$^ zdu-LQCQPHFJ@Ry%6_|LrqX|P_TLlp%LljoZ%Cx2rGLw4C07!t-d?$y{b8c$Gqq*8e zmt{}EKBMs`ht9&qpqTcJ#O{v0-mXF`1bE21(4LUt!t~^#X8E4%JnmgAmR!x+dcQkH zqGnTe;!l1c#V(6SeeM$P^6;n34*vgQ>MDb>ZlXQi(h}0BGy+o6A=2Ib5K1@F-5nAl zozmT164DKdG(2>7bC>tdow?uSg9Eew-LvQXYSj)Ud-96iMc9k=G|`GR>+-m02=Om5 zUaGf>R6%MjrqUop`n$u={JMVipA7G91M_{YtTws>0&(e*%L^#q#=Ww`#C%AH^H%o@ ztnjI&n~ZBF7s64izM-TvHs^t)_0kYvmA(f%?*{rBsVAfq`KRN@{AHmqh#NytVkS+> zd?--c)ay_lWMHPro6b$0_~WZA1?&>YK8pXg5xzeN?La@l^`-$rdsRTPw@CrJd^)oM z8tKpPc*VLfO`I!gltmwH4q#6UtlnyC#vs!f)To?DgqzK;Vh)PC8ac(;IxA$SzD?ut zrtfpj<60FH!%&(us^UB&;ikCl5@N2+Z+E->)2lFMb$eKJyQFb3Ig7`Qk?tg{Mxn7c zD%3&3%_3~jTD{3=JX2R;+kZg8K%h3XIAGPMXzu^*^n>|#2Mr^PY{+%U&E<5(^t|I1 zwAJXny4IPWboo<-yZMztO~W;8$)*3MRoPVZtF6rdYEZ&L>eu@;ULFiLcwzQsrX@n8PHpd zbMC^ru@VBLW$svt2T2P&9r_Ij(|is#zK7!ud|oqj(LN;XqN6zdkqKH&(%stpaSd`ry)sOxj~!03PiKQ^k=?pRjK zUeM1DIv^+$sigO=EtCU$r(fH@Aa`5H> zJ^>%RRYoL7amMnFtkl}zQ}1k@y-}C?5j~l>-n93g1X2XF#c171$s=z@j5-}8iYciB z^)bQJPZy5!aRsWV280SX&#GkyJa{hRFE@9#1x^RHj)CBKA_2d@_p^WC*Zax?H2XX1 zwWbJzF~^frf!1AptD}DiGcm8b8brV`CBP2F61nk2(FjNarV`*gSW$Br_Av@vB6anJ z>)L(~A7hh?+CLH4_V`7U9?xu$%q>G#cGcJQZ;7(}*@dwpayV^)H zj0DcZdQUFtdF;=W8<%Cx+zjuT&{}2t{fbEm0eqfTcVFVxp^(=(K%>^2!%g8-nRQGn zs0N!Ozt63NNxY+DU22GCk^zTvqRCGS9U0rB=(6@83+OUB6i1 zL0Om4k9%m((a#CRQSSMr2&RB$|N=8DdK87 zZ%3BR0El=d>${>faOG2holx_0lt}`#G&U<+?nQDk7l+-sUM$;z`qw?fCi_~=7e=p< zM55{??9C86QBm5ATkH+6ml0Da4%jUN z;Z1mtC#(}?6LOpP~a@TSs9v+Rt^&F@3zr3E#p!vBFUP(*-)D(hR^o8;RH$syy!W`mH?MSHiBagt|# zyNxPzwh^R*7fo=k{Nq@|G~lNU?2SUw?ni%FTf-8)NM;Z88=*MV!LrO=H`xP!`nY{8 z=V$>MyBexK{rPHbB=S2gHcq6g?+RGl{{$C*e?UIq3AXo#9YIv?K`?e%4)E-0z-I z-ZN}Vu$8pKO~R}m0zRdVMdXH>$dh!~=W}dRi~t2}pmD2F>e}X5tP|`|Si&#dbuYX? zBm`J|L{(2vgIx%INxKwsJTgVdVXsCr5m>U@Ov!1#;pz$vsUtv$B#N%I zP^ts4KC9lcf*@U%#Q^fB*`&T7MMt@5dmW!vljG~smj^hS?3UNcIy5ZDxFQUpElQJm zV6Q(;4V!pxZ&?C?%j25-WPAQf(jQ=WI?JsUc;(6y$CR&4bU$n6HdD?Kp_Jgf09W_9 zJ{YDQRk8*U0p4!U#kKWwG~`1(9`C;lsrj-sSOU7V(-+|dPw%*F{2U_T2H6NW5Wfng z9MEz*M=C^mog$^^=ZvsFXz;Lv;J`kw?SB^+zmG43?u2qL za^mk93fNwv5ra1xD_9Mc%)l4cq?2O*<5Rr3zn{6)jzkZ;B5w`KiFs{<0L;HT&gyIB zYN%i|wtOcXQV+bEFc7)|g>Ss?QZ{;M0So2)6|R3*3|L+|k>wf5@ij47Sa**=Jr+0m zC`O2XKO35BQ)pL6TgZY%L{uZ*>xJgp9v2I?8{wV47w=Oi_h)|lQ~Otz*aM?gP}iE~ z(L&f=$GwM#po??b@%cO2&|wJ?(E*e!W)lo0ivAEEGx?CttX|d%5qFoK)C5R4%McAWp;faKKq?uieKFCsO zy?U#4`+8%gW}xB`v#F1^%k$M|Gz4tym|yY*PJ8I)OUKA&Ou!;G?lRDU7wMh&m3Z1A z($~*=2#12NF;#7*j!3wN5|H(wL}Cb^*w)HoYRuaA32g+OHqw%8Gutj9uiAdnZuqYy z0>Oqpo7TUF?B3b)8f3IwKCbADtF1dgHV9=y{;=t$WDzAu)%-9~{n+ynNNUEKyVx}k znaB5Mu!Vul8)`~LO{$(@PI{gD5TWyw7hl^4&oX?A{tJX?AumB?{^%YKx4Q%7yT>o+ ziB8{ON#@I+i`pwte|KBM zc;B1n+4;yHzeOmG@p+NWYTq%{&K3R9AaDl`Zk6Z{rWryC92{Lgk#M5~$7t-Mt;+nl zb>$Id$K}bJI#X=2Mie=(Xl$E;@5Tr{FoL0A+ys{%QIsfe3%Q8P)$8MkFx|KIM|0f^yS3g#6iQNKze)4C_t(GY;+<4}!>rONIdi>$q#muk20S^A7)Fttx5wT- zr>!=(>#fJB$PV**qSKSw5tA;L*7Ae@&1Lpn*}?L8-o)TwhfrnfIuuahw!9ud+JJ=i zIuq!0HsOUne;_q2V*i-i5Nag6GQCq_WHuY2LzU_TZ6ziNLxr3fBc@hK%dG zANN#N2t?7RfjUY5Jnh?MIG00kqF+<{M#=)OifThAVoAag>@ES>%lcS0&A#D~mE6X7=jLV_lq_9<)sgXWmVI=ltB$=Q(j=*DC zh!0hiIGIqGL{i0Kmk<}v3tI1Y6OM9WdA=Xb8BsrYy;keuR>tlz4-|abYA;|*wja}y zmH{FMIqP|9#i>CCTbKTS@3oBQ+FQo_8jcPH`v@X)=U&NXAk44%NFFJe$fp!!Mo^9U zgEZ7{fynj2fDi`iJZR4WU&prQm9a*j+26Nil-rLZCzSE|R&?6m&eQ@H-3SI2?l?U5 zT>xD0KhzL<3DgD^VZXI}TP4A>7@Q+@4rqU5WzClxak&#jjD9?}(BB_vlU&+W^y5lG1uDMzK5;(kn%#O0*Z1puijM>n&Q2R?VczFtr2WaO3_i4xcMLAEJm%> z&YtBwH{D9Nd z&;k>)MHGERfN{P-!j8ojqayM@BnUO>Jc38Q7@NO!vXGgDhIpOV(?;?frnu7nE#5`M?!U7lP{A%X4b^6f}6_gQzV5$}^S7 zA9dTakrdp}E(cR_eowsMvylP9cl8C3_|Nu`m7qMXK0KeXpc0Bpe}I3p^qGro2bpO$ zIjsL~8ne0legx8262@GnxZ3g}au&n^0|ycV@e0@$Ye&Xp#IW-w!*qP!&-^{h(Vr*A zc<_9$t#z@~3h^}N6k`3i&+ON)B<^`C;#+JaR*d}J#mlvc{YiNF8o^sKO+oQL^`L<|=N z>vzvPj==%X<_itvSgrijx+Za4LP5oCPdqD_xU|$CJIig12i&U^1ls?o)HI(8Wa|l% z7aufAQRh`#@iQae)F9~F3}8vrf77{;yKl#e<81Kv%_sd5*qZ?*iNgIyc==xS)vv6D zZ>Ids_LgU!9=ptEBSo~KMEvV`rZ~?YsKoAFM^Pc40Gxmsj1uDTx98}Y^uar(U|>l5 zw2-{w2FtfqE`g0^7?i2867<=Eg14#lt}eatMo|%5PIDE7<#%VInvV+(rWvyAHpbTC zK5l`^z~#^zI%j#gJ5_hdL`{CsDCJ}S16@NP!ANnY1k3Z{Z$ufecf&=VD5`;}E0yx1 z?bzV$T*n*gZFptT*qVXF}p0ce%h|`QzsI5V7ZPF4@C%0JpID9;<}GVq`7IQ>GxPz{z!0z;%bw z7b4qo92zQ``YuU6hsCSDE+vSa>4F!HgplTz+B>CG> zd+-y;L$`X(E7p>;*tC;f$IRR=gn+w00cf}YVPunQ)@rkTt^rD??xftmy;1TG3SiUv zvOKBY?y)_UgB|Qm{%OD}+|*y(r~L`9?>ckfCaA0+2J(I{V(#J%27qbU7ov9wFX9d< zW?Ld+&IKrz(KQc8gv`g*%D6!n1IZx(8t?yI-=U~8^lUV0N-D~gE3d#!&JGF7JE*I# z^PT2nAM!CnOs?nQg;{k(X&XuP#~)b%Be-v1Fs^=pV8(w)DhR1C#NguRp_1$B^I!|| zp=ntAsCwjrI%1hA#s45y?TiS^Pg!pNw4ZA=q&IwVf`HETcGQRqi+{zM8JH9;uqfB; zX^n~s$RRqXWq&q`ySKfN9s*V7fO`b{FtSd+KZ?t{R1Oo46mRr z3jBaUOKHO=?kHE_Ge|TSe=F2!V2Bv*&wzq|KbbM5p?e>qH2W~~5~}8NyttTI#8h8^ z`T!@+uPi4#0mNg38dz4I){Hi~4b`^rX9x6ac`_#a{8Ap~1l%84I=Huz+Q)&dD#S}h zC-bE{4_tgaV7Bik%-o{ zKsy&DODXw{JB5vGWLGAG$-c ziPYO?%{hnXT)gjt#4&EN0*k@zsI2&xS6S=gyM_002V>LY{a44QOcFN8kHYefK8rrj zJ?sorlm~z=si57>gIdRO*b}AZST-OLte-)*S61w_MNv`gV+vB*MhAMqr5GRL8aqpA zDWZ*x5KdC@`FK^qcxUg3*0Ssq3@m~ox_M2w9n!=LQv=^iu46P*){l3$Jgmql8i#Kz zk3O}Q8F(Y)BX=(zk zNE{zK$|x-N$qu~%kr(|aR|#q|xxmUB?jRBF@F&ZF{O>mNVY029Ks~m)P1?53Ro5cW z`akIIjVJq|VmYtRR*cmZ=+AA>zQgzPTf25qKQHsPW;yhvtsxFSji-~|h62wHl2Rnw zg1FyfH*0U@*I!@HI%h_fCch-h@i38Bl;0I30`=rxvca6N;dINF%@7|pmE|kA*GmCh z80jZ>KP#J=j0WjK2AjO&I82srCL6-uEf?MfV1w_`K|b>Vp=wk+cQA>no2M05y-JJLk9Bew9WuC35NB#O%k zWw-Stm4Qm}9|>|+wR~aK@0Jxpj;UzIBco;dmfJ#K#$@Id{z9aiK@oZ zhRax7QE6AL>bf0lBg%*LYBKr6y_NojS-?Px7)b)SEuO8CcT=vhIEc%Vi~$K_49yhA8=I1UTbpU1+>q?>NNU|k=GtcIFXO^tJ}1` zF^1hG1H3pw-+UP;eUY2gK!}kB(mxPJXJXK@^1^=(i-ucfXV?W-u7eOCpGH*3ds6YS z1J4I-f=KZ_oFJjlkMxMS_qq%!?*)|6(NGL}a+ma6=RGZVUntEB%y0`*7HZ>v$!T8A z4XV8F?i?D?v~1%0FD*1KZax9WsigV}_`munL+C*9g0mdB z;Pb0uVw)MOHU}C6p!uiyeP&x+oLjVjI^96Lp~Acf@joxX6|*CyyV zmRa8m{*&h0rz&I$-|u=(*&#kpb(c#8%S$Gk@+<>+F5264bPQRP3~IvRK!;DMCY+Mv zOHH{3Padj}0v8v!L=||>%bqOg=)rS!?s&Om`2cx$M(uYlD(QK5H%%+fRDw%5q-;4F zH}Lt;5$=8RFtg&J7aS4m4ONOp`}f(pF-kpR!$d$L_0tPc-3Qvq@^@soKE|L*k9E0p z$b2}J+Fv0Y|B4!@QvgygCs^}pSdS$;h3#qo2x7w`*50XE2x<0lhBS&S75^^jV7!A1bwI#eo$GUh5njT#Q6L<|8ZAP4$!sO7ObzTQP1)9S7!d+iU! zDCe32Q+0@op%X!>x_|S_h|p~_^HY_do=HSV#+8XhAq$X&0x|hUG+%K!FE>G%eNa${^X?7a#on_UNr1@bfZ- zyB8(*8<|s1jekyc))}s@uNZg2!(F@ej8bD%4K~1A2x$i(kgjVQk#~;n!K1@F z{y~N>4hD?bBT{t&S2DkP!-7Or9}9ZkdNsxd4+rG7+8nI;6M-qP)kH{>{BVdLmw^#?Y+4rsSYko^C>-tV*I_ z_ih=dW$AjUw`56k0ITh)+ySP!1XobtT;W-p!+&8=ZVkD9lsrDDl z*F*@|(MmQ39+CI+kcrgxv|FrEYEq$$!&S$Lr2t7C9DuXj3l+sO9a3s}zNkMA*_hul zyc7JCaL2Wz+Qi%r-^3Za3|9}g%6g422{(UtMn}2ODQaV!nnl5ZxOXFZfg#)T^csPS zfw{pH!ckZKlqkO_X+UkWF{2bY7&3cd>t+c2O8!laUCcNLI8+z(0YOTb%#aW^?D^0h zn$XURh@{ol+|*k8C8}idruo@qayjGKc4wjGfGo#&n0I^bt(7Rf& znfI35RVJ@GkSe8E=qq4(lF$eR>M8}VEn6reQ>z79mmqQ`NTJx$r|pu@c7Lc!wf8K7fp|1Y zHhb(U;z(;<1fu$0Ds%$EAZX<2)1N0BG`@GVMemd#fd(+$A}F-s=a_QTtI5}w@n%O} z9PNC8FmPWB`jQ{6mz4x}xV5h0Vy2eRccg;`&9Q#g?G2op_`o;3A7%hXHKIAMf8bQxMNJ``Q;Se>&IUmcvkp`SxZOZQ3(Y zNhy*jO(8n7{J>|*!E}{A3xQ@uyhwpg9C~y}Ds&ekwx2j!uz>qI_>a>LjWrxeTn(Za z2)Ou`LsW(D_;RobRv23yHOp6bL0TP?)18szibek-eB>8xd-hC8=A@Li>8Ahvkhrv^ zzJQ9*wU5z3xfJKmc`fP-Dbus@(Tc;24y)?;+Gs56b3~hu2GnT^^iYP{btG{NKhyz4 zM8K5W{c%FIlBVC4!1n$g8ryuG%5WRyyx{)k!{#fA`p_yXqCfIPV$&@{I_b^AGb-V? z&Qa>KUSG3V#oJWAWb?GSJx$IipveXn8%34b67#NlUXWKr%hEV59 ze7+e{fQpk7d2Y}arCl<8Z~xQlB8(S(l7-1(zP>K7A%02uD>J9km~SzFCENbytTTit ztDzc+?~dhM;5ex;ja_c<6si7*-ywc0K6OE!|E?u(s6(#Rl~l0)KQZUEv+&h8yfC@& z)yfbZ`4gi5X$P*@^2f+6Qz?WI3V(#GFvFeuq_uc#cslG$G8)o0f&2!0L?16u#FX_t#S1s;h4arTbT8GMmkO{n z@sV6JR;LeF3HjzrH@wREmf|~1fFmk=FK~#ESc*=zTbQCk#EVNwz=V8#$LrgYu7#nJM`x_ zE*uQ%V7~4WkQ*eaH!OPqlXwq965?F#ZP#DGbSZN8z1;h+)x!!z7SqaOQtZn^$<}Vj zlT8uNT|F>ad$+_<+zaRGcug$zGA@4qhPS+CKZTblM+oh{hsCxT4E-5j8#?taJBrn) z$fbl-e<_L*rCUKo_2rgIngVQqio|}iDjzyVA`L69;&5U_QA8DP?Ct06+oqvqM}w2y zIX7;JzYs6=JyW*1kys7eyBlU6z3^e%4SXhf zjuYF^hgZMJV~M_@P78(ZYWTz~o#$dB!s4SK6B4^EEK_VFc-ot%oCr$x@P97iysHPd zL?I{atftKd2ja}`fF;Gfh4C*RX}#im44eoR3GRcHX~P~n4HP&O>h9vld+c1O69$3! za_w{mk7bj<)%Z={x2tjr{=+$)rukfw#rgH5)EZl2hUh25wE8it-Y7>Ck`Q>2N41&U z;(Mk7dJS2xkcrbby_K?~n;$B_zObLC!f;q1Mhd`@;VTnzI+|3oHM_9j14uAYnv9(w z*(IGi6LoB}{;K4~?PJ#((I~A#Mmd?QsX@15&$t|)6`25ZIfjJq%zv8pzLn132&g(u z6SGhSL!Mv|LQP%P_zDb8mxWst`7zyV?zu0r%+cI&>OFB1*`K0aH@UY-U3uI7 zvX9$@se!&g*w%t?v1ra12rN4-)nhwXNxsBg!hCq9+>peHK_Ym$Mev-yYC}S?6V$2Hi*93~K?&3r7x@-@6#RojI=hl6|X@vbFR?K~Ycou=K+07l= zS+eyiBr~-!1Hb#!^DX!B+)v%7pN#20=cakjV%}}tVwDzI-JUsk8x$?+9lqlzaAB@9 zS!$ik@Co8Hleq!E(iTPb~#XC4F6n07VaqPPTw zcBN2O_t{v|j<7dN?fFHyUnm_kJ_a!Vq7_&UwTBN{jcC9~Kfm>g(D2S$((`ur@!kj_ zL2_v|U!GK>2-UlCi7>peRmtRMVWsj5{IJ#ZP2)@D2YHB1=yWep)dHD#WSL8nk4L%v z1`9}OMW&8Sq!pUeAi60LH{DqS2QxL;dDh2u`@Ta*$aO(N+7LQrh&>T$iDi3Xk$L!L zM1q)2v#O_Df{KZ3k=J1|LToreBcyn%+yOUR6aTG55^4kT4>6;F z!Sl-przMu@qbX7j8yzXu1l>v(0oAsxy~_O1Dqj|6k1$8im-P3)%!Q{SE2s81?@sLb zKe*s4B4FiV%C(Dmk0ga6Mbi>_AdHk`h`2ljXnlb}49vt9hDCJ9odaBPU&(y0k3a`I z(!AGc`_Bj4Lz=R6cs!WyDAmNC3(bEW&}E51OZ`Jn-ZDA>c^Bq^9f zu>AfZw{CCQZFk-=v%cQ;jNN$761Wiy_{`BO$X`Omi!(r7^17jFPJno@TY!ugGZA5u8`$D zAfz;ZNeZG_`MF;sVT|)3r0-?Bpg34|eb45u!-EpxNNNxWi;(>YEczVE(!jm?-IQpL zVq@q4)m`~>2T$^6tuW72$e|9ELBfYP$ABP`2w4 z5q-taIFfFU5VqhJQL#$gz>&kjqi0BBE^_Z50`O>psHA}YHt@^J_nXLr3WqmW)0yfD zc7Dp;p8YCMo_@3g#WKQpZqd94SJHP1AA7Lrk>vskJdIf4bM@|w3-75oKPmRcDmt@+ z8^%}V*XKLSgt)ydSN^Zj*c%~KONiN`^T7rJk~nXWLB!#62R?`Je8L=G96Ie{vEE;E zv)_gJAR!}}>ECL`-8@k?td5C*@ab>ZvgEsjq8zY>Pq}8g_jF9pfqx)_maHCT_iqxW z9i^Y|j|}(DiPPY;i?0K#9Qm()NhAdmGo%lTdStv%>Yl9~d6jPV;xhdq?5Qvlk2?k8 zt&%zIg87#yBDQ!nma)l^mg2lRe!o4&r`#KEXz}vnt1@`oG8Y1J6YEf%AvqqW!mA;Y zkQkqX`U#aKArK`slf8?hq}|3_rvGA<2ww6kAN7Myj3?&kkSjLPc1 zUz;)RG3YVqT~RxsLz*IC!hob<$v{qb+pFt+hM+$S{c!?9sW>K7_ua=Doey*30Wi_d zvHT%C=e~6MCk8?P&d`h1X?u+@B3#1E@k7o>BhZ0-Er>Rnc5(H3s&7E#x@9$E!EkWB zDCC9HdE+dwySN*$^-5x?c2di;Hk1kgO}G^CSmAde5qL*rOi?~|KLwUgcbn*GsSK1b zUhD zSnbGbO|6`R-)!O~Q)*#hF(|1uaj*k8gB1hQTp0*3>s$6Mw}@FX2K!RRDWHOS%o)eI z!G8!3iz!_7*Vb^<#$1>4(Q7?#`&l%(R;?@_gX%U{x!;uYk^TwIOlbKRBDj zL-CX}g|GIu+HGD6uOg!pVS(T^63(v|)IoS^4Mv3Zb4A~~r8#qH<5kvI@5KKsJk9@hI&b;?-&vmEPi%F?BlEW}ZXMur zXD;tEnK?`|lCGB&4d8_Bma2+7DmU>!X2KGwhqF`KYo(7l1h5$7i1p{~AAgV|&i#s2 zJk*C>r3(!*KzIX(D&pX47YP##8i%w0zKGu{VK*&(q6$Rny-t?Xfn%p1OgWpcW$Ta6 zCt6~bKB2$oB)`9dA%Kbb;hWcty6lZx#`x%4tJ4QVUfDzd#aoill%L>V*5u+yQ)JD^ zSVs~y5RLqEGW|CGps{MgytzE79zG!Zua3D>{3UDvpDyM>?YBbviEcrfI~wBABrIr9 z2e!~Xswzb5VEF0OJ|Nz<#r<;f1mGo$GEu)eUK>@?Y~|7{ig;rib7g%kO27NG>$(2hfoBfH@vpS5kK*AH*4UVl=t#)Z$hSPB6rF*g zL^ffZu-qS@ou_pbI%cv0JTnPKs!PjBB%Wu%T?Z68He*fGw4tEDD)P@Fo%0?*T1*Zl zeE#m2rVA-8c5^3C?p7`x8H;o03i4~%=ar5o zmidcG21zV0o%;xx{FMI{eR%btK_wR@>jZcr&`yrg#*-bt9skF1jzg^S-aEXM z<6;2A@O!koolp194mUUTO<-M4UZVP;-e?s|uX#kO%|6_Xo;d0QU{XR=AWTNnN4t*6e+-ne4weM65qEUX?%>_nScBlHW(Zue$(~E zraP3mw3bkxb?(Fc)(ZT00r)Y70$MTV~C8#ITnDKDfaUMUmWLd@i! z{;EE7)*v{{B9uz2od|B8i3ai5NA&vUg!=i&$ z;lw!Q8T%*suSK}8)Y{yV@)I`=bGJ>_HcfsJ@GqHkVN}}Vo3>?wx^5I!{Tbm#is}78 z1^yMLRhYUkPoJG^^CZ^!Yu}O+V>r4j-w|%&yS6zM-baBvc29G*wNvro6lLPqeSis^ zGTlXf0?6N}d@AZJ(ni2qEw0`NW$hLr4kZO&cU`h_m!yV>!BHS*%$?rLJvBUmhDCG$ zD%)Lw#T@cp|F7`cT5TLj>*qp_3GTXT+qRcOW2d{Cb>?PU%bWh)mgpi?d>TT58X$*^ zI#`X`A18t`XLl}uKP$bSeCc3V=!29;su2ZNv3n#DLI5WfxAH})vand(WA||k61wrz z-~BRA`_gLridzo-9VTjO(%c2TSxsK42+*Ww?*g!`)jdr?>*XJ_#f+dKp~IQXI-i~0 z+Lv?k{9dQ4EQ-@%L}DAI7N)B#B#Y2~KBojn_&F?szNJ|7(@YHO4LH2mTOu_HGe^y; z2~o#gb0A2Wt6RI>>m4Gr$NmkD@0&V_cHep=iUlpOaF?Ai{wJ(&DthC1!< zu80nhGH{9(T>d*n$qJ(08Tem{lB)k$RQ=KI!x#9%%$}*LC5_HhYiUZV$8-IyoIjhr&YRz6^eafD9=a{MCbY@QgU|8n-urU3mKQF@eTzV>Lh@z&J)Q_e@)cDY`l8Y#KY3wvFsR%wpEpz}APM`=Fako?e-=G9E z-Er4H#y0_)u%FWQW4(VYXGte#UW-!7hv{!wkYBtd5)ubNCB3L z1E&NxDHh#f=wol#mH0&Gav2%ZT+Y`q!D5Z}sKztoKf6b9I(N2zjsqm2MjX!{)aSoG z4^`~OO*ug^@Hde|A1<0E|F^orBOoqWzEkq_R31R+L4zDw?IcJjxDN#1b64avTz}Br z`^q0LSxt~B$~xUitAfz9_~Tv!=T0pvsttT3 zm?>V-mpxoNcw8E+84D|&YnWOf3*}z7YK-}k+#Jrg%XR2poVEDs1@u&P@92S!t3ex2P%QFh{pR+Y7YTCA7U-!xd%^|W#_qrPkj{rr7i{=Ao3YM-#BZv>l1Fv}Xl zD1D83jO2VdVMAGYD&ddF0K9l_mt#9+3W$p`(+z*>Uq9={DxAK{TlYtG6gv}m&v;1i z2-%JFWvAO>$XyrNOyV(=^GJ#788j#!xjZj?6)TM}ps4+)>^sh21v z)naX%@zuf?3Sdf#ha<_}Wi#W|BKLNpAN0YOqvW=yH)r=Pq_DnPp$)LhrhR7R~K>4-VSzm1q@A(8j%UJq|%Mvj+3 zMGB|SI3}Pi$I@*{z2Y>kP}L-LWqEe*Oze*vZ3%vz_G7UedCyHGdc{<1AO{10L94B{ z#`NqMReq+!rn&wpPuuin!Z>l@=#nrvV`6s(i{@SLD`NcBNO9Af1$A8?#kIJ2<7K@) zU4LMC=uPnjJzoHLU-+#iIa8FkWnS&2(D#3i%OI;T2K>hoKrSZd&;cwj;^h#7+NYVR zBnqR(>hF65@3JR~s;5&-vUz?j1u>rNf;z*dCxn8g6bqgPB5LIY?n*-mzyrFk^#lZa zKjdxwmNpe^+TV8ZzF9ftw3XE3C7#dXW~;n_Ff?_!0Q?bau33i27-WA;$^CO(H|vj* z7~#Ndw{PO~D94H5qzdnE3KZ4k)uW*p8I}Xli9S!JP)C&Png~F&wZDof8f$oZUNIP^2W?ItjZR;7a63tPZ}t4O zeevd2vaBI5)Uez>aD0RHPZ)G|!S)^CX$gPC8YAHRvU(UFx()v|r&FcDdxHXZA04hv8yV^#dV8`x)c`&j>KL@^<{5vF@i{~GA5&jgve@5qS>)0o3jSnu5pn- z#1*C@D4F)VlDd%^5(d(zPIcM`GF3XESTW`0QY-Q zEn|=Y#O-DMSRGUGm0&c?id-$GpI!g&@n}!)(N{slgnvI#?}m$pE5E~6r|0BNySF*! zt6#PiBsoX$i7R+a0R_O6#;E5}%~FAvzvsx!#?WFOJ5I~!l#cxa27VJP_j@CA+Nhc} z@hirr%IlYw`yDP*m(A`j(7BYhM0OQIpU*?T=@lH8yez6XA6AOyAFrYkW*=;*AXZUV zWgU%4&gH2^2R=G=ZO5uxQ*1H6!Vz&Is}=})*W3EToo*`ce?8uh&qblOzgHxBRLWI3 zD71s`Em{9w$Z%6B`Bq4behv$ztyYeHc}&_`sIHHy6aloCVoJbu_6+mBCMX~mL9xbs zP4EeaEflSxCzQ(mWK-ZQ$!DVE2oPnb#eUt}pAPgN(pYpKsKl7Qjj*exWTn=JJ6;5g zjr{dwtiE9>a#!pn8uDD@jHM49_VpbQg;RwC!X2=`muW*~(enVR!GZpPWN8qj2(M`U2t9zCh@J z-&-OvjfccTN-qxA$FN7tB&TRSG8tK-35W1s`D~HKR;Q<=B!40*INWenesZQYj{*eo zuh~BkV&)33(Qk>fi1Le{y9ln!RGwl>@;kPj)86uQHkN5g>NYO+6l|%W zbr+kY$9Azu$l*SNmqR%gr8+~z22xY0jVgULD6+7BU}Hz}UNY<7oRZ}hJWe&~ct5-( z)V-?6{8M9hlW7BfabosliVWWg6$Cub@(%5EOz|Q+bk(%TU0JS5GbhWgmPP2Rl3DK9 zM(*ic>2KZ7j?>L6ZLcp-M+*YEs5x-LaSO;CMEtaElidr@=++ZoB;>r;CmSuud)HSY zfqh7SQyGdAQEb$6Il_(EabssW25&Uyadzu>z_Qff3JtML|0#rwa!f*qt-?XjL(iJNuMyECo=D<=Pw~3 z4tB|)0(jIm9L`_FZs~%V%XDc@Dz(E{uCsWW7M%0@?IKHx(*nO2xN6vJq_6Ke5Up#> zxEy-~BR}!Ln=8Nr8~kp(bx4VazD1-|3GG0{E3b=dv6R2qB^X0+0b0KE{4H< z3MSext7)Qlr8n{h{wzpb_m{42Q!_OqAANJs=%!oLkWP(DDgH!re(&l1aAYTFSi~6+ zx=I8kf^NxSD^sY9z5wEobes9s%6To5xW3QjqQjX~9E@ zfOL0vi_#q;-5}j5-AH#gcxX89;{M+Mm+KgJ+;QD|owe7R^QpPNu2J?-I(xI)`^u^PhHer0K!Z|8(sMQ@a@jZnd7nc zF7x|0YzRfEzcAw^;Un=`_z$BYmhLdLpcMR32rEL3J}P05QZ_YB_7Wn`Gx@%j?xKwP zg>*gscjYi0P?ct&80`1S5Psr6?;O}l0aF8tH>Uwy=_br(h=XgDw02qyWNI0aP%bjY zveiLYv{&zB{{xts1~X?THld3&HNmPord~Y}wU5T84574T58bydZ%EN76FD#fCq(F{=-dnDLi8{y!z&4u8{)BQ zbG4iTnAoAo{w2a*Gv^;Q2!1P^5^Mma6(aw;5}A`*lQ7+=t`_GW;3gcc3)D>w%R!!KLH_?*F=aG4_&W{g zr4-e#!zufsYAK>9d&}KRQ;A;oY=)=7b`fztP9Mm1Er#zZaSgJq*Mrk&7iZ@XiqVS# z%Q*uXYsIJ5Pd6;G$WX40k3UVy=$L=Vkk%LViqF=naDkx;kmZzHZfs!8Jhu?AKJJK9 zT4;2bTK|oi<`P*$iPSxYfu&LA?#5ntKn{8?zMXA=K|8DOV!fc#+B~s%CHTsmSxU2% z4u)RTAcH~uQbgL*PZO2iIUt0x8W$=sjSQ)PF#Fk1b)g(>`_0AAdhXM-i=ZbfZ zYoIBu2DQk)=~etzK-2vCPX22e3X)>Hc4B-Zue6u)w1`WK8LV&gS(sCWlpz_Q4$uF= z9c_L|H1f$p5nc%xgH=ht%)-HGY$2oVE~JNZn?pBE%>LrT<+B2Rxfuc5EOr=^iK5`y zVoBXm4-;{V>)lmS>vU*JLPB=`_}H9ad@{$s%^)qII;6=QA1>dTp2CogNC>rIM93do zBwYND`2QHfa8q~;MZ5c+hb;(yL+e9=iuX?=Bc=T`E7hxed(4%K&to46t)YNq)Inv$ zMb#Zkmilp|&EVtezU(4cYWy-B8FiD4P_-KUF6je467BjHrS`%bobp0wsuBjqP{DE< z$={pJLvRn46W2nWrv|YfTIQ0yw_J=nOG~Kf1U$iN1c<5ui`~DHv{G^p*XG(g)ZuzT zbLOH{X9zBjZtB&E%W{viP({=aMP6!BOKlS|qYAEI!UWu>a|Js(}tN^cJbN z@kTs@)@;eCYcH%%7n>;n;gr$p16rOkww|{$yl21f?bDINM$uDH!qP_psrrD7oHWFSbB*4GDRvpY^@oCKpga>C<|>lJs}kf z`dRN@0QEv~;rE+I-!iTUf(V=8liabAY~dP#U;trv>5D&U50PN|$znjGz0r%TCh!ay z&!(=y{bZ*fmf8rLnSJjue*1NCvkFu(u;RFjJ8Gqr_m`Fx`(CFujw7n^DI8_iT{S<7 z0kn0pr~DqYjZ@%IwB|GvB>vlW``7;XgL11p?}amF=`|H#BT|PSOjg{$KvexFk#g0g zUX;zdy&o2CuvWY&X&<3<-A52GgWm{|D6Ly4<>Tz_8GQ&2X6XJ~wbZ%|AOcN)m3RWG zjS^gTmjs*ql*+$*I7yugL?ZdW2^BHreb~2xZ(o*mm^B#H3&115({do;+p0nZBrUA> z`~H-n%R6}STV>LN%UxP`j;Kh!rF7e!4hTyGxj89?C|!>2P!mc$M;d%f;98gi+x!{w zD6|WU2UBG6H=lLp>-9x<;rL4o+K$gt+u4 z`GW?uq5$Gh@DKG4#xgQBZDX31UQiJQq~Nim>04katHqJy`(HAI9^)qBpb$g@?S&|g zm}!UAK?AJf>_+R<1@>?JH#t+;{W)~J={0#gpa&EAT4qa{?Xup%ERYfLD;ZA(MDeF? z0J`h3u(Nyom2PPFt2>tZCZVKJ`F$fgYP#Ij%E*Mkl`J1Bc>qv>)cJ}wR43i^qe^Rf z#ohg?H98Xlf~~uSM~E(ii8>xS?k3Z$<@c3w80cfYbC{%9S6Ch z%S*k#Kle`&iPNE_C(`xUVInR;-=#hDKdif6kSx2|vl?G|R6Z}no-^dcIVL<$pcR}@ z;L8N5zS*GEfRf(V8x&WRC?NITpWB&Vu!nsVxk5+SIM|K5Coga=B(x;rdx#DW!$(bN zzUkcBllmPUKLbW~?gKRa1D%-ygndC82lV)0;MvOoQc5(&yF?25XN44gg}v8+p5Q_l z&U1kw({@4pLtI7~6D1jzXP5)Jb0ur}2%pwZ&pnjD6c-Y8EEHKmVX14oH1%cgws5{j zah47(e8@~zC2%tD-2Arop%Y*Z=cQ?lS2c@uHSFaG6fQ6q80O2K7LIpyhpegz9*bsS zh1)Id{=aZy1*PCftzuSpuGQFg=%))rn7wE`HluUr#9eaO?OYG9bZ+>&m>&@{+sC_p zyC>NPEK@dsOqQSFJ@eB9Q6`@njW>Rp1kujD$Ro81r(muntn+%XL&Ud36(53HGCzBU z88QG)YYp~j9y3c3^-iM7y{zlK4V;^=C$&QR%sf!*!ZoEBWoZE<8EZ{Z?QtH zdWTeSSARu72#o6moE2H<4Oc*DviGE& zDEyp3ku)n(YqPmCL?YmCa@#BPwMm*tHZ9;R8S@;@*JB@A z#=)I@@Ioc2?Be$_V0AZ5vat<*YhaoWQ+RH4e=r0Qw+ioH>#bXqw_&_F|FB zAJ{sVXWQ!LVwrVMq@H?gTaeH98v-ULgU+@KXT^WkcbV)?#`RpioWML}6h@rmfmCTbZK&l#`ZDvtpZ+!ylLO+4xk?{ty5Kj;2FIRKuCWd>=} zt`#mCwz2fn{*9_)WKB26g_j88n1o~vKF|fxh*d1K@707s+*Fk+N@IURR;NRJa3`FW zVr~eigGM*#188Vbf2)KszAg<$)UcQc+0A^`F@z>+D)zBCSrw*E{jzHt>&UUdZjK9-VU{z#8c@PAvNKJbdQ@%d*^e96-`9WFF2#=5_{(>oaCt`--)C0ZC?# zntPB_7@PBqVgaF)l;^veDvpI9{coa0#vVw7mX%}{KF>@Z3wMEY%ZnM)Zmv`%EekTB z{~Aty7((s=*y;SV0$+|H=6}dJfi`J;%jzOA>?@BFgnW}g-M6<`%Lqg&f~nioUZv65eZAo0gXm+A`5ACz)VV_BHx zv6PaQ99mmI=Ek&zY;@0w8-+G8R6=3?^Roi(44FV&V;8XoG@QjB)SKL*RGQq7S4|kg z5Z~$O=ko?>O0D4+KSz@n<~Mt9Rq+m%ENQ)|Oa0QEiXixs{kq)2lZNN&LP4w-uESK| z%x8-sQ4d!hC9t^Wz!ca+t#*b}4w>tTHjD?aLJ&C7wXToI#|3VbWp$S2S#Ai19|4N= z#{wm~lJ@g&ud6?rB=<)`3?H%Nfyz2eCAY!o;NSMhBo;J(ubvu_7+4Q*XG7Wo7I6JS z!|Pja4DFLYx>tCgp9~9Gbw}QF)F6%Qzb>&gN3@ddQU(lR`Fe65t(nKHoqJH}{%8hq zc7jvE@9kGb^4~G+1}CxKSET&Lh#9g~4a?qJw6Pt!qyu>d{HM(rbImuZO^npJptD>VLu4p-VbJwd;!#$hPeVt%~b)92ToC{l8i34go=8qQa!)gi!w4Cjpr|V zlB`K+zkRdwdZOMP)_v{ZS*7VdWoW+jZaD9{Euh#g8AqA`JHA&)P!|F(`U}JQDJY^| zzx)A}mPf(h)|?^DflO|@Ido|-r``7nBHE~c%iGgQI%)psU)ASBi3=d)-2{3b=ONdSC-@u4-f`oYte8h-LYrek;#Gi}bh88wq{o~SG zJ}-z{JwuLLcrrBnj1kyNd^x}oM13ZL0G8}S1|VJ~PWNO$Z#6O!O<{;;DNZ9KO@XlK zL5>ut63=fBF+bTumnWb#JFdNC*1gzMT;Od_d}5BMCIF4oRc>;yg!k|~Cy*4HIha1( zyUu9$@6nfC&U08O8@u$`t~xtRn9%tff&ju%D8PPwz}O-6WD{%s=axMNN2URXg6re8 zMrP0j0yD6atjVtRp!elml*4&i_|rUC_Yly^gOx1hepj5FIgsON=@6p zuW|%2NBo)=C?HidLrrC3LCl}_(H)p%`;OQKy>~j0^xU*wzr=meF}0U3Iq?3FdLcNS zK<@EF+N~Z4dG))31ZF(Xd~?m0mSpDe{}a|liE1T%6e_Qz#afY;d-``x2>@) z{#F<|b2X@g=@vww(N)K$2WhlYD#9uNjL;}xgbG~JiYUjb4|fmNe3@l)dG8rWx%M*> zF^mdL5?M_t-JHbj5Nr@0TtsuKw)H98#Bu>$h^G=IV=JNYT#=N@L$3-pkuw7+{L=L9 zg`1R~#QC1d8a^9{={Z{ck#yTdN1t{^DSxC8qWv1I7sKOvSz$aLAgKcLyk`dLix%D4 zd$>E6!~&bq+*rqVKQ9@Iz@wu1LBesxOsNU}0wZBjgce?g%}*x*U-a4c4v5Y{TnP0P z@a8t%g9M$b?f7h2Z~cyBw2%ryOoAZRuNPmpwb1KgC?M?2oO$VLhl3gXS|qn3rrAYP zjV)qBIVL>rOeVR46^~kwP&r<+p#t)LlBLNDuls-|Nf z0V_cbxP6v~r5;W3n&rzU_)EMQu~RTu9+RNQMsQQ|ack#pUfi7nu2~N^Z;`9#DcaLA z20w5UwKM>^n;vZZqLx587Jll1SvbRfQoamE42Dm7UrD+JN14Pud3utDSVP_taF>j_ z=G64P{OY+!3OEIOAM4Ua01otdm|y(dCuD&y7lha97^x79PJ_F`8%#jEwDm_o*E06^ zAy-u<5Z8K<9HJhED7)rX-M}Rtz~31n(hOx+hBOz>X}@=zS;&nhV~q0Ru68~9t#!y6 zF+9m9r-g5$O6B(=T$86^l=p_%9@g1PiPi%V2L_~T?Jz1T!1%&S>Y`Mm_nFI`A1dj1 z6DogMPqsoNGAm}(RR>AyE1gWl?NufkB24$d;C!86npz3Bo=jyoJvz>3WOrvj72!Lgz!1|knUWO0zSfmaDMI=gF~dbhP! zSL4BCXUgW8(Q{; zGdi75hySD)K-69=u+XC4+s-W2zsO7#+DdSd%@LUq>1!p}&^pHA_PtBK6JLQtCSR^( zcRgzQLWrF_E(JdhrU%r#peCW<&A?0i<{l0p=iZ`qx`4I~UfsoREmwh@X2-75U<&$v zCHx4;BytWA?~e!eOop#ja{xJ?x*{o}RX*FrY-DF|t8oRFbKoUbO+P$?VAB5r3qKN$ z>$#n(bePREp2CNOfQ-||b(8OPtMEE}8z&Nuf(Ly(&J`X%tuG%GPL|f2jnrA_GwBPI zP5^*g4s0zh`!rIm*R49ub23>&>r+4K0stv;^D^&@>RA@^i-0idR$T{Gly^Uw?XrfaOmd~b=Zrb(CF89{!GusYTt-$;G_QulV3>v5B4V(por5~-!lTGJ3pwk9~Ho5Smua8fCi(NEz+bW zf61`@R7IU=k>=*?K7d=Pq)OV`fS@d0hYAhR;rn!%Ldk)rQFEhRPzb1?$&~gC!&H_Z z0FFdFpt6ado6nkNt%!t>L~M%KzT&O2U`KiFSeENLbbeZb_-NNypVOn}aemglt|!5J zWBrJM=)45&h}DT z#)!8clIt8gS1zKV{LZ^_SS-hGpV$j^>&8DFyfQl7V>eV*Z{ia!@3C_S7k-p_j}~T7 zSKdbF2M$}?ChOBZJ-!dk4@uqm3)(_;_xHAQa;geAQKx&j6+qq>Ug)Q#@h+pXKg?Kt z_+=johz)3Bl*9zG^yFqfxuI8QBB6$AJt3Rlsh3w&_|rRnSE$w>^wokJ63|u=T7YQN zLdS`DGf{Kz-7uN%nywiMW>7Q2&?PP0*GJLGfqG!6Vmy7hj9!s6DI<%)v_aZnA_I(o z5VfBHW?8}K2*~BaP1U~tI--3AQaWyGsm7=t_uXSHF$AQc`dyh+pi2cO$a6XkJ`DH* zFhK@$i=Mu2>5Z!3SazJgk!l)t1*6opftBuil`G&s4sqGRXY4QHvpa`yW)O}C$ z{57%r;nWK+ae);i5dd{PYKLul01|OBM?}OWkeE{KztmGJ&uyLKtX{{c8Gc(RyXBOR zG{rjZJ#6fd_Yg5X#oF$Sh|K20H_-14m9*}B^)KTVYsCYsq7ph_O`XGVIsQfwlkdQd{T$(H6a!Grr+w0jPS@)6vqWw2?>7HMx~u? zH-2Hg{ui?;z}BBXFzk}61;s)=~6 z=;Ek_udg7yhDWeD46ci%w5El0ch8!}6P;`-Uvz}-Yh-FCGaxy+*O658xXjuVkP8LT zq=TfnKJxfcO{ov|EwUzXogK1wk?M#cqT8dLp@h>FKMo&ZoJV8p5u4FL+XwR_|Hz|$ zKo(W@7nsy>p02`>=Ao<2_J!&Eaw^5h8y4w}qP~*ONt3-ML(|yaczuL9Ei*%tm++yW z_H{uasJ6@I>gFeJ=liudYik;XB zV*JZ#rFkH&o-UZyP<;=dvEDcOc|wogUi0rdjQ^cz_4@&CCZXUCBA5Tw>`LJ!1# zp`=tn88m1`lKtlFhP%0>1ku?G^I%oludi?cd_FVf&J>LY?qjtVdFU}iq}nsJo5zx2 z_;9>NXwLK}QI)sOKlr}s2iYom;b~WT({0nh#uu=HA3*G>_->V`Vx2xr?AQ?S8EBf)#px zpsS^?&Uy$mc84kc-J#oWxbwa)poHN`3x7UeP@fI}Lc7M7EUvaywP)rU9lgXG*Lh{` zU8+t)dUq|eTdUhjQy2Fdl!cgS8eTi$(*VG_HPl*abYAV}DRUqkUIL`1$6%skaq>MIV3c@HTJl^yS>v??AeO@kKOe>IUVn}fojv;d8v0)5bC z5y*o*{y5*d>rGw&J#ONADnw-{vPz8)^ zirzxr!?#dv_@U~w;KnXc94avNf5J^BaZNFavzvjS-`I%=ewu0BObd>8PMcJiPl=ze z%1AXMyP9~DL)V<&%KNs)9G4pXx zeDQ=&^Gw~wM;BMWTxy(5U0m8>xzETNpCgnIIl}NoU*=YZ+-rT#p#$nZC23uck91Z7 zKY={xgXM@(B$#@)YU9Y`M_C;c#Lf4SIkxp3c>CGWjTVx?Kqpo+{H%rVZ2`c$Enh}L z@yrgHcH;<-J%BqHcYx6xQIz-Gvao~bK!9# zCXm1@rFLSgW>VAZ$f0(>{5Y^JP=yAmCP+-VJqj>#H zF|d@#5Ydq9HGl~pagfhoV9eveLZa1jVL3Iu5H9|j0C^kV&fv5X#Pv+5J4UamfL<*? z{Smn3l$Zn+S9cLAkmv`zj(kNQVe1UR*R`K(2!3b>N9Ul!(pp_0M&BEDARw6^Tow5NM4*zz{l zTE^cur!f!f&=Ellgi#!9k}v#GfMJzVS@>#(x4J3C_m0gu_K|q1@^+mG-_k7gv^~&u z+nwaG&u67$8GeP{0h*b+)lGpch(B(p?mgQue{qc#dcM;Z;0pm`h@%mThUjuEtpBrm z%g;mEZ9>@K3N`I#V0Q5tT1BuHN;FOw-uLlyhG-H@+xh@0EOJ`%-!_47XM*0bSi6ei zQJwOt8@@2)0)~Ze^!bcQVB=~2r~d~&R-vVk=g)(>dc{Q^R%~q7-qmN?SRS}B^O$JI zzf%*~)I}*v|LUIp)x_5`9MEe~>Q#|qqr8KW1jhNiBJ?1>ZH8Vl0t>_}jm$l~IiI>% zSe|Jdpo8+ep9c3b?$d%)n3E1swe)vD`TZgi3bVD3%+V7xKJ-ujh#40B$zsTgW%Gu$ z0uLvTeRN$iYz;u|3w=eM*RlNK0qQe@y5bDWN~YApb=1Y^(x2?kMD1^;fXz$w#cNK4 zA*&ZS5olCT)uY*;;)?jRAtU#!se>kzRvaf)NxG>M68=JL%}6;HCmuUmW4guYcE=1} zX>wEv1%f>q%IpG^pr73hRN^B21)Gc}&%341bxc{LlxNXTFDdqXn0>kAG0Rr7x|mS?2O6MsgS;v0pbrP~cx&Ac#kG?e|i>$2k}rYV-nNNQa`Pmkj+0dD@JjQ{$+ z9@$X@N*Fqje>mQ3bY^hP@VeD&_A*L{#2JCj=?CI8Bg$pf5jG`36qQ9feP7OAJ(D;l z?C5P;b@!_u*zg-zxTc5Qa)-M0!LKx%tas;%)K2aM8+t7UHoaM(FLnk(U!_J6PAxPk zH;+xsT9zS!qAXnB8?xdls*h+GYZNd~7eLF%`j})mntJoYX*?BEzK=bO3!#uKy1hUG zU0GON8CJNr`E(;fzw7nz?MI67!+}elPKxEd*F)W1Fuwg;?iwWg1Jv_BZ9$p^q6g0_ zo>p`9zB-as#E#d}*)f_JeLDKWbPz$um*6$Bx-#}xVdi`Tb^2#NGt+}3|B1cD7()8C zj9iM6t8&39fDy^K=^^}aaMevc%pl@v=f6Qrxpp=w&!`_avImiY=|qNH|C(@$aNH>= zDKscm_ECI93@p z0|eWo)SHfKXZ`>KbqT?8GQfo5DBTVD-Eb?}*&F~wV1Xzcf0<>BX!{ekV?AO3hcfBel{TvlvO z25m6h)c2fLij^9d^`eJbDAp1$c7M+H)-kk{A=Gff#a;K2+HkJQv5+~Zdn}UY+b6hxlHDOfCpDD=3pbgihl22RlXnFZxOXFP`m?5ZLJ_gu;lD8`^}IWd^yh zMH(U^_g;6is8}Ij|2>+Kk&;B$qGTZqJs{aDG@TPUxAZfVC2>@#_$MVS1(K8C9FJ?7 zBBN_fQ5kpj_C$Ap}IOxp-D zd%-0H~s3Xu*~M;(={SvWVT;ECGXKexm~|kD_;6Qb{}qUW$38`rez}LV`lC?OX!-Z z{Dx(_W!h!C%R{-`L15CZL9yKy@NG-vxe(#kc4D@d?^mAV_z|5@;wl7bA(NPQa7z>W zz1O0MXh$B^@iBekfvG}niv1I%x~-Pd)c;hUYDX9K&ogl&uvWMKNn1F&^X+D%Dkk9O zLv8Wrc;p}sz*%Y!A0#lnVkx6>M0bt_=XQIM35aquO!K9J>HA3?aZ>RG&)TG|5^q1|v+k4LG24 zac8{D0pF-TROj@C0%00CpRwX%XW;qa?f~|k0zvEpkLVzrI+-Of?uS=GCVcGb%B&hp zf-$rFW@U*#$t`m`%E6vXWB})y<|z|}y*<+@?Lcm19~*yn@%6-!UJ&amBE7!w8~RIx zr{#BvM9N5Cg$43`?EIgo2|ss1L7w#a?_VLjP!808Vu7LzuHk!~$C@_Dk~*)+A)nW_ z?;6?PMw3By&+vCdYDZ7jI#8l9I)~t9O>67J$GIXjxv3B*YLGVksRGMA#@jbP!RKV= zb#BhZ+?8}LPx43$KD7!tvO_(s58Hn60Exm;gVi{CkeoRS)RaU*

=RW~XbXdm(=B z{cPMLw8RH5sF`M3A7gsd$^@T*#&{_&W*r;2g z-!^!={bhI~LZP1@96U&3e&5)ZpiZQDu^DFCSIa6VqPo8sOEw?XCvT}mg`o<64T;1} zF{EmHf@lcxCRe?K(8js-eIBhGaDqo9?N>8h5P$)c6t^V3nf4 z0#Uur2c)9?mbkcx_;DJ1;Uh_fhwiSdyB3wSKq;?CxI)& zhqA2x+WEzAn-|wZ$5cEIINvw*I`gnQrfPpoODSW6pTC+r#D=7~fR6HM!!2ndimnG_ zIaP8(d+zqj$qiKedtZdn6Azd9psbEZt91APnpzY{`5{it-Z z8>kIK-%#g$yGaDthDIpF>N5?=J8&j?!iLASvmy)4nNpyC^&rlWvLHKl!znie(3h~B_x4(XI^imeS@JQF?Fm1XJ+00UuHMTF(al7*yHW51*@>AtZ zTT)0H#1x7cIUwRkyE^)!?xx$+z=Y7CuourTzt&@%!Mo;k9*YVw${C_ni!>PHjmRy?^wY-a4v zjqi3?hxl?(EoK7k(vOBj_wR*3LjY*mj#*-_q)4&eDl2`a#h(&;_yn7PdznT~+1d-% zYX%jNK-tG<@<7$CD!ia&d=H1tw_aOo@`cYlYL4#iT-%VyCJ~aBkHH zQENlbDoefh>4L(H$_gD{HW!-2oip&r0!F+yE#@Ym;><0g0*Lh6ZCsxZ=Rqo7vmg+F z##NHJ`KP^GPUBtjSNGLgaUc>dmi3e+*hmOILxNWu=-)OLqZ5MUC~#DG6X=pYB~N>M zm&jvx|If?;OOOa-vIV9UHV+Nl&>OlBz-lOv93DY5H~hvWsIqaL1oJMPxjDpQI_V z^YSs&5)n__Sq>YJft=PR=jH`?vC_+{ z=5WpC)*qZR0N{+%jLrsgqxFaw6`OKX$*-c$v8dy3g|PoV?Tq$BKZl=6xSgj|JUhJi zmgM{`YIRmtucvZ?j@-$1p{Dil7Pz1v_k8^0p05oQiR$W=pSnQoAdRUb%gIH5CK8%E z%{egi?rB&KbIq@Jx{K#Kn->SDO*cTF;AsSu=En(kNCQj!pj5?D2jZTvbMQxX6IMH0 zFQt{znp^SVd_{`{Uh}xgY{t;MvoEw#Fr|7-kI?;=@rpU3rI`TcO+WVY z&_h-q=?G4Mql}98skhH4V`O0)j-<(Cq$};bb%^YVB7Y@`bEN4(Xh&>t6}#`9B>x`PE$_XNK`~5;R&wtxv;H0L8dip4c*KM3LD=Dy z=tA42I$DQ@`1qCbJf8fG%;mt|@9qa&Eo=Bd^mn}quyx%(&yV=+@2S(dmfttbyY~vT zU&n^F43P+VVJ-3h_gtV(KI`8-hRfw>F20&YECjjYnt!lcoSNQWr>DMo4Hd||8(D3S zZ?6%-?<+w?Z@ch}UAwVOzFi7x7e>T@pFX=8+3k&oW18A{XOo3c@}TD^`OaaBkb(^|NK^MX0px(nJP+td(ZawKX>-d$GcD&CT(R9Dl4^R{C+wS7*qM3qcCU*TOp6%zoIfCF_mE*9i+nL zcmOrQskwEw=pK9^T`9rN4`y^$Y1^E}afN=MiwVi3zs{G>(cIiiI!5Ry0e1}gI(FA> z05xo1d%iZ1n#nz}h}2VzsZ@xG4HqExa^414@QB!%mT}jF2z6Qp2~XbRD|ooyar+Mb zvOF&tJB-!a7X?$f^{yQ`a76Xp`nB|l!jUzIUxZv4OY4jZJo)hWtNxc8c=$m*l}{8u zo4zoLzduAmMGZ*!01!YG)YZKjjpe;b4q^?{Ns?2S-`cHZsGo_!nG^u2l(~m)84w}? zbaKGRX|LJ?`I-i9YvTxrMj&@Ds1hR}ICA<_R4Kjn|2Bu}ZniZo`l6sR%t75^{uP|>+2LvB=my71q%Ii~sKF+Kc>aa6l zon}tv`5SjXNY4aN+$4s&tGR!z+jTVIF9Pp95D?RR61*ky5FL00# zrcviBnO%GprybEU697m{%pVmrCbjwVvP4S~uUBX(!AdTA?`AG%6jdWW5`Yl4eo`8= z9xXmw{B70$|F9O)HO*IvNprrfu)SxJh^e$%Mwfu{e5eOsXy$Cm_j+`7Wz;~JH6_mi zwPnlmWegmvZvo)Da?GC>UG|4Y{dMKsd=L}C$H73t_TMb?wf5%&D?Fn2KW4yBQ`%!N zjV_<>G5IAHKo8+)UpP|WV&3C%vIMyhae{;L&f^gy)Y+Iaq7ja;QK~QmB1UiP z!r#ZF!!+Yyg!mxfi0{~?vjJWo0ZFz^11>NPL>#Zdf_04o!w6toeFCh)?1tJ_BS&>s zM{C&p8CF>G0jj|v1=b)C0tE(z6%~@1BSt{1fQ7Zd?d`MQcdZcjeyVWzso+|-BShHe zXcaZ{)P%vxovR!FA@Y{k(Z~0}KC2w*qoyBNH~2hRs<1h9=91Lg8?Xdb3-`m#oy;p~ zuYwGSDPC$5L<$6pn|)NxsYw6f@|833E2m_jsQ-%}qB!Q}cz7xCXz^-F7D{Gww12w` z%|;tIDFQ@D^j`+enjEzV48X79-rzg@UY!Ox8f-=y;mVki8wR87Q(p%NznPXv*J9A_ zqgSTv?<~zr>9iQlH%fub{g;jHVmICJU?SF`nSy0X|KRNTrH}U7&31=+hgu!1^+j(el%>S zUP+WB@wJ95o-wG;VI6{0!xdZ5wOG*Y1|O?80siPMJ)NOFAJt!e7&D(9ly1$%oD&Mf z-b~v%f6@7Yj9K+$_>vbzGV|sBMjGuI32R%Wb@`Ek_2(OJ&*bj38N4S*@5?x@yXSZ3 zAM9>e>R(}ul+U@Ku2B@bGcmu%GJA@Nt8IXb`z};lKNlH;lRrG+kjVSrGG};T#lzgn z5yteV2aY6lr+T{hqU5PR%$+iIRiAT-qkc5Kc9khF_HwyMQi^0HdkFoiu^pf|YcP>~ z4xhSsuDN`1@b3pCsL@{Z%PTq#MH}Z0_!><>zf}60K%_$-yv3@4jQ1hqyy!*I#-H*xPKK2QfQs+L&|XH@7?|_=P40 z2}gJ;k;GtQ&JDLlxz6+-M9u=-v*l6#$bF|v?b7RJ8$_%r4$=-lEuV65HKZw%}_ipMa3!h{r9-`Y{y`wMv+#XpCXb;e#TLnhZ3GByHK* zx~kbmy=1)6=3y?Om35%940|%DpqtMGX8p5_Pr7-0K>FD2=~wfRtgv+tp>{-xy>A~v zwUJXdL$W%uW*5nc^my;aAcYXgbUSV=%j>zVm~f$Q&dK3NQN_r?lV4S}Z&ilf1}5Ym z5|lm+mQX)I023dR?v69`Px_e(B9=nB{auFlVluUSe3{y*28A$<@!7;byHZiveGjb{ zOMP}J-u$-hCQBh=gnZ*~hu1W=1<^a+=G&Ito~!-JZ*QPn7u3h@hpyh27`X|rl~#rW z_w__%X;vbhTX)(nq#gGTN~iO_uSy8Kz+7RL`VvDIEp#_=OY7{#jG>M8lKz9DQtt7X z{S4HunNDc$wPG|<)E!Mz0Po4W>4%a}g92wd%t!TMnBcds4_=l%Oby?i_ri}GW34RY z{Yi4e8f<}6X|O{gAs$ahMMcMsk;=%ij?9sRXI?{Hb?bH5cfeuIiE;faCfs{>VN6aa zA;I!H-Gi?7naOuLsC4zSNROzbEoAnhl_TcBq*Y$t#8*e?)ZY?HW&~UhR+YMor&F|l z%99pqk1WBEjAl?fj>hrY-(pg0QE06MLL|$D%cX@|SVyvenf>Oz_fOD~p>40yItthi zccZxuv_~d8T&*(38;Z>4mB~N3|D~b|%ss8Z|O`F@9K=K&NfH< zD{cIG*|mPzrA#`+Or7foVVn^1SW>#X+ls+>sFp?PMs&;$J!z=R8efG+SAb{6(ZBjg|0N5? zOl9XrMOA57scc|(+V|#1c(2u4|2H}F-tKiR7e8EQ5mP5#h{e@Ub7CLE-yUX5yreoB z{!mA!XhY)M%N7=E?Rj%$)H>g{U8`2fcSQ4NV&U4H)pPmR>Uqn?5i-X6kte;(c8rLU zRFte;?cv}1`|@@gci8#xTNTgSUO@EU_h!`}!{ohI5eiMN8Xlsdz?& z2lXK6?Yf%tV$VYDvVts*&y(utsIl}q;sdUKR=38*mE^42q$Eu~?V4hqOoLuX@1?}! zSswQ!hoZ#GLU|Ul`--$)vIeFY3x$z}+ZkBv!PCpwM*cjepl9cYW@K}4)n62JHpYLy<+@spsCrgCrybuq8UYGu~)ooq-i z->@3LlyWaZA|D*^`2Fwu+qhULxU>*@Fzos&`#kK!f-k%Soo1;pVmAAjdra~&8tfk@ zbjcRmisl`#jW@13b7NVwLqeuH@?kF_@Y2htsVw(YG+)%QU->?E{1SoTV9 zFA@?vu6Gt*XDjmaucZ`+JQ$cB1x<>IL$$=k_u-U67?AdBNY2x??!n{2^9?US9s-OK2TvGuq}{sbPn>qZ9JY%+PY%xDGoz8 z%OZxPRVx^kD;sW$#^u+Fv@%G_C}oGu6u zD!WQ>uq1ATZqOVJXV^aY88m%k4j<&~eJ9wO(Q<>c#T>f+nbK})$N0VNKT5u|)Q5B~ z5@Ml~U*N#B!j4C&ig>%JRyl{CBE{0=RcEpo)1I#KL3T1?8=@L%t1*7#tFRIZ{?l(0 z8}GVeP+v9NM5@g!c6H>Czpim-r+5Mt-)cRl?B81cywcBKkam8n?;ybHgO=ls>c$$> zqbO}DzVR6scbAA={8!34N%~^A_7msSTw4<7Jb9Fr&+##YCFE&ZydKd>&y!wB?2W4K zF2j>ctgmKgw>Hwp<-R9)M4yw;Y3b9@u(p$Gmm(K%NE`>k6P2%@4GECvdH!RR28$Fa zP?qVrasIFM&c4ex+F+K$K_J);Vb2KX>*!o?NGb^X`$UNmv%AF`Y;tM%k}YE51#`|= zQme=E{p^vcheSqj`4 z<;LJIY8+6ripml_6Hn?NZt$(ZzEFSK@|S_Xk8ulKn&Y!SJYaRkEA%>8Nd9(|n77>p zYGTJ^e||YOQy;Yy{y=FHTe=<6rw7g#)&f)TCdmK2iB{C$+p}!02KTj7_W?C1sn`p; z)$}@xbuRLBOQn10F8VdXDvj3Wz8X(c+{3`~a7PZ$1Yh-YB+QeAME4C#eX)O^uAKUN zIH@WbCB!#q@I`yn*8jIgZS69kLdK*+2udX7b_NxA_j*zFi)nsA1 zPipc!_1t`-#P;n#{%3VRluG6H1>W@q^p{VhG(P&p@)SgSCiky+8(%0{{p7e-5cej_0W*Ma274e9F7rr zBfpOa?Ss58+NmVg=_%Dt3}eRee}qd}3vfHH1bsa~h)|sUvOXHmYN2g^%1V;BxR`3L zfXi(3o2%X7oHxlBoB~aWPu(SBI0pG~81-`a&feUx+%QMx!EsAG%YxprosTx|ET*aw z-%4bPi)%!Ngf!**p%A6Heo4kpd_`BspVuJ+dCJ>PWk2M9EWlQ^tyzhKkfZv0x8UOb zl!h33jeS;G<0FRliVk@IE#6l2i!Y(v88Yvgq0LFQ828B&{~3=M-YeB=?1%T)8(f?j zo~&_PZ`@cLU(w^ns8fQCldSJ6+0rI&kH}$E|2Dju55wBa>860+-}p%gk3vx)UH1*+;-TRwZm8mk)8<$3)cyv<9tCq z1sRCf{@mbtFqhU#UO$i4+5T3RwV->+KOx<72o~vaw7Wq=wX(8FpuKF8pYA9GtH}85 z)%*YUdu9H<){DOT85gp03cidJ6s#1K*kOEoj#31}V-aApY_r1#2Zak-(znZd-|sNj zzx6t4#e_W%EQ6o(%>TYFD(wHSCV%Bm|36H6enybJe)_!J?~~=LZF`rWQ{#JgR9NZK zUSNCn7%R6-v;{D20qc#>cYeCxF6lj+k?Ch}#dz1#17FttzU7*nt$M{HPQckz{_X7w z;dlQRe-SD_UMO?i_F>+hDR+e5^*!F9{$%MR2c{aq?*B8d$sN{eP*%FD4eY`7B(?}x zSZ$x*c~m)N8so8*Uh`I@lz!TDw4}J^?2$(ktJ9<&hleN2es>8J%l!RowSCdoXRqI# zKCKqHV#1%KrqqVwceCCm?0Le}C}6a$H}06Q`@Yr^#_qmQ26vZT;Vv%cBsL$IxHElb zmW+BE*YeW_ek)qC?&l;wGJkg4c>U^QRu4p09tKwE_1h9(-0=@f?iDaPz{p%~up+H= zS0i&;f|!8d#HGL}l1xYuvoP8}f928S6va(8Zajw88wy^0`}ysSwN|9)@sr(R;%oOm z`d+2Yyg#a{9aw{OKDWI8_<_aU!v+2w9Vafix}+SPDGBTv8Qrz;JF`mSbRtW$t#E(+ zkC`Xm-<#3eBW#sA`{KS{{+MkaXMKM^yK2+Jc|e=xeFOy~182Gd-TG#JU6;fvo$w7k zM{C}_e=k-4W?EL*VV!_wa}NGG@jvc*{kPwDYSk*8TwLl3fR?dJ&NX^&-M;T&NwJLb zhL|+BxNYlr#eOxh0_{0CZ=(9~HvJzv_hiT(`5||hW7$^ zK5PK&M79F0c9nE9y;kVIhJ|_41Y5fR>7Ny=FYn6SVE4%(zVyRvP1Q|VDM=p<6j^4? zt^DTq=D^%{X${tfE>0&3WCR6&t_GH$D)zruMMw69=l(Q2*I>`^k0Da>dEFe*jW3nw qq?~;X3=vO35O|q2N)1#H{AZ6fUM_Xr_sC)fAn + +using namespace HoloLensNavigation; + +using namespace DirectX; +using namespace Microsoft::WRL; +using namespace Windows::Foundation::Numerics; +using namespace Windows::Graphics::DirectX::Direct3D11; +using namespace Windows::Graphics::Holographic; +using namespace Windows::Perception::Spatial; + +DX::CameraResources::CameraResources(HolographicCamera^ camera) : + m_holographicCamera(camera), + m_isStereo(camera->IsStereo), + m_d3dRenderTargetSize(camera->RenderTargetSize) +{ + m_d3dViewport = CD3D11_VIEWPORT( + 0.f, 0.f, + m_d3dRenderTargetSize.Width, + m_d3dRenderTargetSize.Height + ); +}; + +// Updates resources associated with a holographic camera's swap chain. +// The app does not access the swap chain directly, but it does create +// resource views for the back buffer. +void DX::CameraResources::CreateResourcesForBackBuffer( + DX::DeviceResources* pDeviceResources, + HolographicCameraRenderingParameters^ cameraParameters + ) +{ + const auto device = pDeviceResources->GetD3DDevice(); + + // Get the WinRT object representing the holographic camera's back buffer. + IDirect3DSurface^ surface = cameraParameters->Direct3D11BackBuffer; + + // Get a DXGI interface for the holographic camera's back buffer. + // Holographic cameras do not provide the DXGI swap chain, which is owned + // by the system. The Direct3D back buffer resource is provided using WinRT + // interop APIs. + ComPtr resource; + ThrowIfFailed( + GetDXGIInterfaceFromObject(surface, IID_PPV_ARGS(&resource)) + ); + + // Get a Direct3D interface for the holographic camera's back buffer. + ComPtr cameraBackBuffer; + ThrowIfFailed( + resource.As(&cameraBackBuffer) + ); + + // Determine if the back buffer has changed. If so, ensure that the render target view + // is for the current back buffer. + if (m_d3dBackBuffer.Get() != cameraBackBuffer.Get()) + { + // This can change every frame as the system moves to the next buffer in the + // swap chain. This mode of operation will occur when certain rendering modes + // are activated. + m_d3dBackBuffer = cameraBackBuffer; + + // Create a render target view of the back buffer. + // Creating this resource is inexpensive, and is better than keeping track of + // the back buffers in order to pre-allocate render target views for each one. + DX::ThrowIfFailed( + device->CreateRenderTargetView( + m_d3dBackBuffer.Get(), + nullptr, + &m_d3dRenderTargetView + ) + ); + + // Get the DXGI format for the back buffer. + // This information can be accessed by the app using CameraResources::GetBackBufferDXGIFormat(). + D3D11_TEXTURE2D_DESC backBufferDesc; + m_d3dBackBuffer->GetDesc(&backBufferDesc); + m_dxgiFormat = backBufferDesc.Format; + + // Check for render target size changes. + Windows::Foundation::Size currentSize = m_holographicCamera->RenderTargetSize; + if (m_d3dRenderTargetSize != currentSize) + { + // Set render target size. + m_d3dRenderTargetSize = currentSize; + + // A new depth stencil view is also needed. + m_d3dDepthStencilView.Reset(); + } + } + + // Refresh depth stencil resources, if needed. + if (m_d3dDepthStencilView == nullptr) + { + // Create a depth stencil view for use with 3D rendering if needed. + CD3D11_TEXTURE2D_DESC depthStencilDesc( + DXGI_FORMAT_R16_TYPELESS, + static_cast(m_d3dRenderTargetSize.Width), + static_cast(m_d3dRenderTargetSize.Height), + m_isStereo ? 2 : 1, // Create two textures when rendering in stereo. + 1, // Use a single mipmap level. + D3D11_BIND_DEPTH_STENCIL | D3D11_BIND_SHADER_RESOURCE + ); + + DX::ThrowIfFailed( + device->CreateTexture2D( + &depthStencilDesc, + nullptr, + &m_d3dDepthStencil + ) + ); + + CD3D11_DEPTH_STENCIL_VIEW_DESC depthStencilViewDesc( + m_isStereo ? D3D11_DSV_DIMENSION_TEXTURE2DARRAY : D3D11_DSV_DIMENSION_TEXTURE2D, + DXGI_FORMAT_D16_UNORM + ); + DX::ThrowIfFailed( + device->CreateDepthStencilView( + m_d3dDepthStencil.Get(), + &depthStencilViewDesc, + &m_d3dDepthStencilView + ) + ); + } + + // Create the constant buffer, if needed. + if (m_viewProjectionConstantBuffer == nullptr) + { + // Create a constant buffer to store view and projection matrices for the camera. + CD3D11_BUFFER_DESC constantBufferDesc(sizeof(ViewProjectionConstantBuffer), D3D11_BIND_CONSTANT_BUFFER); + DX::ThrowIfFailed( + device->CreateBuffer( + &constantBufferDesc, + nullptr, + &m_viewProjectionConstantBuffer + ) + ); + } +} + +// Releases resources associated with a back buffer. +void DX::CameraResources::ReleaseResourcesForBackBuffer(DX::DeviceResources* pDeviceResources) +{ + const auto context = pDeviceResources->GetD3DDeviceContext(); + + // Release camera-specific resources. + m_d3dBackBuffer.Reset(); + m_d3dDepthStencil.Reset(); + m_d3dRenderTargetView.Reset(); + m_d3dDepthStencilView.Reset(); + m_viewProjectionConstantBuffer.Reset(); + + // Ensure system references to the back buffer are released by clearing the render + // target from the graphics pipeline state, and then flushing the Direct3D context. + ID3D11RenderTargetView* nullViews[D3D11_SIMULTANEOUS_RENDER_TARGET_COUNT] = { nullptr }; + context->OMSetRenderTargets(ARRAYSIZE(nullViews), nullViews, nullptr); + context->Flush(); +} + +// Updates the view/projection constant buffer for a holographic camera. +void DX::CameraResources::UpdateViewProjectionBuffer( + std::shared_ptr deviceResources, + HolographicCameraPose^ cameraPose, + SpatialCoordinateSystem^ coordinateSystem + ) +{ + // The system changes the viewport on a per-frame basis for system optimizations. + m_d3dViewport = CD3D11_VIEWPORT( + cameraPose->Viewport.Left, + cameraPose->Viewport.Top, + cameraPose->Viewport.Width, + cameraPose->Viewport.Height + ); + + // The projection transform for each frame is provided by the HolographicCameraPose. + HolographicStereoTransform cameraProjectionTransform = cameraPose->ProjectionTransform; + + // Get a container object with the view and projection matrices for the given + // pose in the given coordinate system. + Platform::IBox^ viewTransformContainer = cameraPose->TryGetViewTransform(coordinateSystem); + + // If TryGetViewTransform returns a null pointer, that means the pose and coordinate + // system cannot be understood relative to one another; content cannot be rendered + // in this coordinate system for the duration of the current frame. + // This usually means that positional tracking is not active for the current frame, in + // which case it is possible to use a SpatialLocatorAttachedFrameOfReference to render + // content that is not world-locked instead. + ViewProjectionConstantBuffer viewProjectionConstantBufferData; + bool viewTransformAcquired = viewTransformContainer != nullptr; + if (viewTransformAcquired) + { + // Otherwise, the set of view transforms can be retrieved. + HolographicStereoTransform viewCoordinateSystemTransform = viewTransformContainer->Value; + + // Update the view matrices. Holographic cameras (such as Microsoft HoloLens) are + // constantly moving relative to the world. The view matrices need to be updated + // every frame. + XMStoreFloat4x4( + &viewProjectionConstantBufferData.viewProjection[0], + XMMatrixTranspose(XMLoadFloat4x4(&viewCoordinateSystemTransform.Left) * XMLoadFloat4x4(&cameraProjectionTransform.Left)) + ); + XMStoreFloat4x4( + &viewProjectionConstantBufferData.viewProjection[1], + XMMatrixTranspose(XMLoadFloat4x4(&viewCoordinateSystemTransform.Right) * XMLoadFloat4x4(&cameraProjectionTransform.Right)) + ); + + float4x4 viewInverse; + bool invertible = Windows::Foundation::Numerics::invert(viewCoordinateSystemTransform.Left, &viewInverse); + if (invertible) + { + // For the purposes of this sample, use the camera position as a light source. + float4 cameraPosition = float4(viewInverse.m41, viewInverse.m42, viewInverse.m43, 0.f); + float4 lightPosition = cameraPosition + float4(0.f, 0.25f, 0.f, 0.f); + + XMStoreFloat4(&viewProjectionConstantBufferData.cameraPosition, DirectX::XMLoadFloat4(&cameraPosition)); + XMStoreFloat4(&viewProjectionConstantBufferData.lightPosition, DirectX::XMLoadFloat4(&lightPosition)); + } + } + + // Use the D3D device context to update Direct3D device-based resources. + const auto context = deviceResources->GetD3DDeviceContext(); + + // Loading is asynchronous. Resources must be created before they can be updated. + if (context == nullptr || m_viewProjectionConstantBuffer == nullptr || !viewTransformAcquired) + { + m_framePending = false; + } + else + { + // Update the view and projection matrices. + context->UpdateSubresource( + m_viewProjectionConstantBuffer.Get(), + 0, + nullptr, + &viewProjectionConstantBufferData, + 0, + 0 + ); + + m_framePending = true; + } +} + +// Gets the view-projection constant buffer for the HolographicCamera and attaches it +// to the shader pipeline. +bool DX::CameraResources::AttachViewProjectionBuffer( + std::shared_ptr deviceResources + ) +{ + // This method uses Direct3D device-based resources. + const auto context = deviceResources->GetD3DDeviceContext(); + + // Loading is asynchronous. Resources must be created before they can be updated. + // Cameras can also be added asynchronously, in which case they must be initialized + // before they can be used. + if (context == nullptr || m_viewProjectionConstantBuffer == nullptr || m_framePending == false) + { + return false; + } + + // Set the viewport for this camera. + context->RSSetViewports(1, &m_d3dViewport); + + // Send the constant buffer to the vertex shader. + context->VSSetConstantBuffers( + 1, + 1, + m_viewProjectionConstantBuffer.GetAddressOf() + ); + + // Send the constant buffer to the pixel shader. + context->PSSetConstantBuffers( + 1, + 1, + m_viewProjectionConstantBuffer.GetAddressOf() + ); + + m_framePending = false; + + return true; +} diff --git a/windows/MSRHoloLensSpatialMapping/Common/CameraResources.h b/windows/MSRHoloLensSpatialMapping/Common/CameraResources.h new file mode 100644 index 0000000..d9f9659 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Common/CameraResources.h @@ -0,0 +1,82 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#pragma once + +#include "Content\ShaderStructures.h" + +namespace DX +{ + class DeviceResources; + + // Manages DirectX device resources that are specific to a holographic camera, such as the + // back buffer, ViewProjection constant buffer, and viewport. + class CameraResources + { + public: + CameraResources(Windows::Graphics::Holographic::HolographicCamera^ holographicCamera); + + void CreateResourcesForBackBuffer( + DX::DeviceResources* pDeviceResources, + Windows::Graphics::Holographic::HolographicCameraRenderingParameters^ cameraParameters + ); + void ReleaseResourcesForBackBuffer( + DX::DeviceResources* pDeviceResources + ); + + void UpdateViewProjectionBuffer( + std::shared_ptr deviceResources, + Windows::Graphics::Holographic::HolographicCameraPose^ cameraPose, + Windows::Perception::Spatial::SpatialCoordinateSystem^ coordinateSystem); + + bool AttachViewProjectionBuffer( + std::shared_ptr deviceResources); + + // Direct3D device resources. + ID3D11RenderTargetView* GetBackBufferRenderTargetView() const { return m_d3dRenderTargetView.Get(); } + ID3D11DepthStencilView* GetDepthStencilView() const { return m_d3dDepthStencilView.Get(); } + ID3D11Texture2D* GetBackBufferTexture2D() const { return m_d3dBackBuffer.Get(); } + ID3D11Texture2D* GetDepthStencilTexture2D() const { return m_d3dDepthStencil.Get(); } + D3D11_VIEWPORT GetViewport() const { return m_d3dViewport; } + DXGI_FORMAT GetBackBufferDXGIFormat() const { return m_dxgiFormat; } + + // Render target properties. + Windows::Foundation::Size GetRenderTargetSize() const { return m_d3dRenderTargetSize; } + bool IsRenderingStereoscopic() const { return m_isStereo; } + + // The holographic camera these resources are for. + Windows::Graphics::Holographic::HolographicCamera^ GetHolographicCamera() const { return m_holographicCamera; } + + private: + // Direct3D rendering objects. Required for 3D. + Microsoft::WRL::ComPtr m_d3dRenderTargetView; + Microsoft::WRL::ComPtr m_d3dDepthStencilView; + Microsoft::WRL::ComPtr m_d3dBackBuffer; + Microsoft::WRL::ComPtr m_d3dDepthStencil; + + // Device resource to store view and projection matrices. + Microsoft::WRL::ComPtr m_viewProjectionConstantBuffer; + + // Direct3D rendering properties. + DXGI_FORMAT m_dxgiFormat; + Windows::Foundation::Size m_d3dRenderTargetSize; + D3D11_VIEWPORT m_d3dViewport; + + // Indicates whether the camera supports stereoscopic rendering. + bool m_isStereo = false; + + // Indicates whether this camera has a pending frame. + bool m_framePending = false; + + // Pointer to the holographic camera these resources are for. + Windows::Graphics::Holographic::HolographicCamera^ m_holographicCamera = nullptr; + }; +} diff --git a/windows/MSRHoloLensSpatialMapping/Common/DeviceResources.cpp b/windows/MSRHoloLensSpatialMapping/Common/DeviceResources.cpp new file mode 100644 index 0000000..e34345f --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Common/DeviceResources.cpp @@ -0,0 +1,361 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "pch.h" +#include "DeviceResources.h" +#include "DirectXHelper.h" + +#include +#include + +using namespace D2D1; +using namespace Microsoft::WRL; +using namespace Windows::Graphics::DirectX::Direct3D11; +using namespace Windows::Graphics::Display; +using namespace Windows::Graphics::Holographic; + +// Constructor for DeviceResources. +DX::DeviceResources::DeviceResources() +{ + CreateDeviceIndependentResources(); +} + +// Configures resources that don't depend on the Direct3D device. +void DX::DeviceResources::CreateDeviceIndependentResources() +{ + // Initialize Direct2D resources. + D2D1_FACTORY_OPTIONS options {}; + +#if defined(_DEBUG) + // If the project is in a debug build, enable Direct2D debugging via SDK Layers. + options.debugLevel = D2D1_DEBUG_LEVEL_INFORMATION; +#endif + + // Initialize the Direct2D Factory. + DX::ThrowIfFailed( + D2D1CreateFactory( + D2D1_FACTORY_TYPE_SINGLE_THREADED, + __uuidof(ID2D1Factory2), + &options, + &m_d2dFactory + ) + ); + + // Initialize the DirectWrite Factory. + DX::ThrowIfFailed( + DWriteCreateFactory( + DWRITE_FACTORY_TYPE_SHARED, + __uuidof(IDWriteFactory2), + &m_dwriteFactory + ) + ); + + // Initialize the Windows Imaging Component (WIC) Factory. + DX::ThrowIfFailed( + CoCreateInstance( + CLSID_WICImagingFactory2, + nullptr, + CLSCTX_INPROC_SERVER, + IID_PPV_ARGS(&m_wicFactory) + ) + ); +} + +void DX::DeviceResources::SetHolographicSpace(HolographicSpace^ holographicSpace) +{ + // Cache the holographic space. Used to re-initalize during device-lost scenarios. + m_holographicSpace = holographicSpace; + + InitializeUsingHolographicSpace(); +} + +void DX::DeviceResources::InitializeUsingHolographicSpace() +{ + // The holographic space might need to determine which adapter supports + // holograms, in which case it will specify a non-zero PrimaryAdapterId. + LUID id = + { + m_holographicSpace->PrimaryAdapterId.LowPart, + m_holographicSpace->PrimaryAdapterId.HighPart + }; + + // When a primary adapter ID is given to the app, the app should find + // the corresponding DXGI adapter and use it to create Direct3D devices + // and device contexts. Otherwise, there is no restriction on the DXGI + // adapter the app can use. + if ((id.HighPart != 0) && (id.LowPart != 0)) + { + UINT createFlags = 0; +#ifdef DEBUG + if (DX::SdkLayersAvailable()) + { + createFlags |= DXGI_CREATE_FACTORY_DEBUG; + } +#endif + // Create the DXGI factory. + ComPtr dxgiFactory; + DX::ThrowIfFailed( + CreateDXGIFactory2( + createFlags, + IID_PPV_ARGS(&dxgiFactory) + ) + ); + ComPtr dxgiFactory4; + DX::ThrowIfFailed(dxgiFactory.As(&dxgiFactory4)); + + // Retrieve the adapter specified by the holographic space. + DX::ThrowIfFailed( + dxgiFactory4->EnumAdapterByLuid( + id, + IID_PPV_ARGS(&m_dxgiAdapter) + ) + ); + } + else + { + m_dxgiAdapter.Reset(); + } + + CreateDeviceResources(); + + m_holographicSpace->SetDirect3D11Device(m_d3dInteropDevice); +} + +// Configures the Direct3D device, and stores handles to it and the device context. +void DX::DeviceResources::CreateDeviceResources() +{ + // This flag adds support for surfaces with a different color channel ordering + // than the API default. It is required for compatibility with Direct2D. + UINT creationFlags = D3D11_CREATE_DEVICE_BGRA_SUPPORT; + +#if defined(_DEBUG) + if (DX::SdkLayersAvailable()) + { + // If the project is in a debug build, enable debugging via SDK Layers with this flag. + creationFlags |= D3D11_CREATE_DEVICE_DEBUG; + } +#endif + + // This array defines the set of DirectX hardware feature levels this app will support. + // Note the ordering should be preserved. + // Note that HoloLens supports feature level 11.1. The HoloLens emulator is also capable + // of running on graphics cards starting with feature level 10.0. + D3D_FEATURE_LEVEL featureLevels [] = + { + D3D_FEATURE_LEVEL_12_1, + D3D_FEATURE_LEVEL_12_0, + D3D_FEATURE_LEVEL_11_1, + D3D_FEATURE_LEVEL_11_0, + D3D_FEATURE_LEVEL_10_1, + D3D_FEATURE_LEVEL_10_0 + }; + + // Create the Direct3D 11 API device object and a corresponding context. + ComPtr device; + ComPtr context; + + const HRESULT hr = D3D11CreateDevice( + m_dxgiAdapter.Get(), // Either nullptr, or the primary adapter determined by Windows Holographic. + D3D_DRIVER_TYPE_HARDWARE, // Create a device using the hardware graphics driver. + 0, // Should be 0 unless the driver is D3D_DRIVER_TYPE_SOFTWARE. + creationFlags, // Set debug and Direct2D compatibility flags. + featureLevels, // List of feature levels this app can support. + ARRAYSIZE(featureLevels), // Size of the list above. + D3D11_SDK_VERSION, // Always set this to D3D11_SDK_VERSION for Windows Runtime apps. + &device, // Returns the Direct3D device created. + &m_d3dFeatureLevel, // Returns feature level of device created. + &context // Returns the device immediate context. + ); + + if (FAILED(hr)) + { + // If the initialization fails, fall back to the WARP device. + // For more information on WARP, see: + // http://go.microsoft.com/fwlink/?LinkId=286690 + DX::ThrowIfFailed( + D3D11CreateDevice( + nullptr, // Use the default DXGI adapter for WARP. + D3D_DRIVER_TYPE_WARP, // Create a WARP device instead of a hardware device. + 0, + creationFlags, + featureLevels, + ARRAYSIZE(featureLevels), + D3D11_SDK_VERSION, + &device, + &m_d3dFeatureLevel, + &context + ) + ); + } + + // Store pointers to the Direct3D device and immediate context. + DX::ThrowIfFailed( + device.As(&m_d3dDevice) + ); + + DX::ThrowIfFailed( + context.As(&m_d3dContext) + ); + + // Acquire the DXGI interface for the Direct3D device. + ComPtr dxgiDevice; + DX::ThrowIfFailed( + m_d3dDevice.As(&dxgiDevice) + ); + + // Wrap the native device using a WinRT interop object. + m_d3dInteropDevice = CreateDirect3DDevice(dxgiDevice.Get()); + + // Cache the DXGI adapter. + // This is for the case of no preferred DXGI adapter, or fallback to WARP. + ComPtr dxgiAdapter; + DX::ThrowIfFailed( + dxgiDevice->GetAdapter(&dxgiAdapter) + ); + DX::ThrowIfFailed( + dxgiAdapter.As(&m_dxgiAdapter) + ); + + // Check for device support for the optional feature that allows setting the render target array index from the vertex shader stage. + D3D11_FEATURE_DATA_D3D11_OPTIONS3 options; + m_d3dDevice->CheckFeatureSupport(D3D11_FEATURE_D3D11_OPTIONS3, &options, sizeof(options)); + if (options.VPAndRTArrayIndexFromAnyShaderFeedingRasterizer) + { + m_supportsVprt = true; + } +} + +// Validates the back buffer for each HolographicCamera and recreates +// resources for back buffers that have changed. +// Locks the set of holographic camera resources until the function exits. +void DX::DeviceResources::EnsureCameraResources( + HolographicFrame^ frame, + HolographicFramePrediction^ prediction) +{ + UseHolographicCameraResources([this, frame, prediction](std::map>& cameraResourceMap) + { + for (const auto& pose : prediction->CameraPoses) + { + HolographicCameraRenderingParameters^ renderingParameters = frame->GetRenderingParameters(pose); + CameraResources* pCameraResources = cameraResourceMap[pose->HolographicCamera->Id].get(); + + pCameraResources->CreateResourcesForBackBuffer(this, renderingParameters); + } + }); +} + +// Prepares to allocate resources and adds resource views for a camera. +// Locks the set of holographic camera resources until the function exits. +void DX::DeviceResources::AddHolographicCamera(HolographicCamera^ camera) +{ + UseHolographicCameraResources([this, camera](std::map>& cameraResourceMap) + { + cameraResourceMap[camera->Id] = std::make_unique(camera); + }); +} + +// Deallocates resources for a camera and removes the camera from the set. +// Locks the set of holographic camera resources until the function exits. +void DX::DeviceResources::RemoveHolographicCamera(HolographicCamera^ camera) +{ + UseHolographicCameraResources([this, camera](std::map>& cameraResourceMap) + { + CameraResources* pCameraResources = cameraResourceMap[camera->Id].get(); + + if (pCameraResources != nullptr) + { + pCameraResources->ReleaseResourcesForBackBuffer(this); + cameraResourceMap.erase(camera->Id); + } + }); +} + +// Recreate all device resources and set them back to the current state. +// Locks the set of holographic camera resources until the function exits. +void DX::DeviceResources::HandleDeviceLost() +{ + if (m_deviceNotify != nullptr) + { + m_deviceNotify->OnDeviceLost(); + } + + UseHolographicCameraResources([this](std::map>& cameraResourceMap) + { + for (auto& pair : cameraResourceMap) + { + CameraResources* pCameraResources = pair.second.get(); + pCameraResources->ReleaseResourcesForBackBuffer(this); + } + }); + + InitializeUsingHolographicSpace(); + + if (m_deviceNotify != nullptr) + { + m_deviceNotify->OnDeviceRestored(); + } +} + +// Register our DeviceNotify to be informed on device lost and creation. +void DX::DeviceResources::RegisterDeviceNotify(DX::IDeviceNotify* deviceNotify) +{ + m_deviceNotify = deviceNotify; +} + +// Call this method when the app suspends. It provides a hint to the driver that the app +// is entering an idle state and that temporary buffers can be reclaimed for use by other apps. +void DX::DeviceResources::Trim() +{ + m_d3dContext->ClearState(); + + ComPtr dxgiDevice; + DX::ThrowIfFailed(m_d3dDevice.As(&dxgiDevice)); + dxgiDevice->Trim(); +} + +// Present the contents of the swap chain to the screen. +// Locks the set of holographic camera resources until the function exits. +void DX::DeviceResources::Present(HolographicFrame^ frame) +{ + // By default, this API waits for the frame to finish before it returns. + // Holographic apps should wait for the previous frame to finish before + // starting work on a new frame. This allows for better results from + // holographic frame predictions. + HolographicFramePresentResult presentResult = frame->PresentUsingCurrentPrediction(); + + HolographicFramePrediction^ prediction = frame->CurrentPrediction; + UseHolographicCameraResources([this, prediction](std::map>& cameraResourceMap) + { + for (auto cameraPose : prediction->CameraPoses) + { + // This represents the device-based resources for a HolographicCamera. + DX::CameraResources* pCameraResources = cameraResourceMap[cameraPose->HolographicCamera->Id].get(); + + // Discard the contents of the render target. + // This is a valid operation only when the existing contents will be + // entirely overwritten. If dirty or scroll rects are used, this call + // should be removed. + m_d3dContext->DiscardView(pCameraResources->GetBackBufferRenderTargetView()); + + // Discard the contents of the depth stencil. + m_d3dContext->DiscardView(pCameraResources->GetDepthStencilView()); + } + }); + + // The PresentUsingCurrentPrediction API will detect when the graphics device + // changes or becomes invalid. When this happens, it is considered a Direct3D + // device lost scenario. + if (presentResult == HolographicFramePresentResult::DeviceRemoved) + { + // The Direct3D device, context, and resources should be recreated. + HandleDeviceLost(); + } +} diff --git a/windows/MSRHoloLensSpatialMapping/Common/DeviceResources.h b/windows/MSRHoloLensSpatialMapping/Common/DeviceResources.h new file mode 100644 index 0000000..8fbb3db --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Common/DeviceResources.h @@ -0,0 +1,117 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#pragma once + +#include "CameraResources.h" + +namespace DX +{ + // Provides an interface for an application that owns DeviceResources to be notified of the device being lost or created. + interface IDeviceNotify + { + virtual void OnDeviceLost() = 0; + virtual void OnDeviceRestored() = 0; + }; + + // Creates and manages a Direct3D device and immediate context, Direct2D device and context (for debug), and the holographic swap chain. + class DeviceResources + { + public: + DeviceResources(); + + // Public methods related to Direct3D devices. + void HandleDeviceLost(); + void RegisterDeviceNotify(IDeviceNotify* deviceNotify); + void Trim(); + void Present(Windows::Graphics::Holographic::HolographicFrame^ frame); + + // Public methods related to holographic devices. + void SetHolographicSpace(Windows::Graphics::Holographic::HolographicSpace^ space); + void EnsureCameraResources( + Windows::Graphics::Holographic::HolographicFrame^ frame, + Windows::Graphics::Holographic::HolographicFramePrediction^ prediction); + + void AddHolographicCamera(Windows::Graphics::Holographic::HolographicCamera^ camera); + void RemoveHolographicCamera(Windows::Graphics::Holographic::HolographicCamera^ camera); + + // Holographic accessors. + template + RetType UseHolographicCameraResources(const LCallback& callback); + + Windows::Graphics::DirectX::Direct3D11::IDirect3DDevice^ + GetD3DInteropDevice() const { return m_d3dInteropDevice; } + + // D3D accessors. + ID3D11Device4* GetD3DDevice() const { return m_d3dDevice.Get(); } + ID3D11DeviceContext3* GetD3DDeviceContext() const { return m_d3dContext.Get(); } + D3D_FEATURE_LEVEL GetDeviceFeatureLevel() const { return m_d3dFeatureLevel; } + bool GetDeviceSupportsVprt() const { return m_supportsVprt; } + + // DXGI acessors. + IDXGIAdapter3* GetDXGIAdapter() const { return m_dxgiAdapter.Get(); } + + // D2D accessors. + ID2D1Factory2* GetD2DFactory() const { return m_d2dFactory.Get(); } + IDWriteFactory2* GetDWriteFactory() const { return m_dwriteFactory.Get(); } + IWICImagingFactory2* GetWicImagingFactory() const { return m_wicFactory.Get(); } + + private: + // Private methods related to the Direct3D device, and resources based on that device. + void CreateDeviceIndependentResources(); + void InitializeUsingHolographicSpace(); + void CreateDeviceResources(); + + // Direct3D objects. + Microsoft::WRL::ComPtr m_d3dDevice; + Microsoft::WRL::ComPtr m_d3dContext; + Microsoft::WRL::ComPtr m_dxgiAdapter; + + // Direct3D interop objects. + Windows::Graphics::DirectX::Direct3D11::IDirect3DDevice^ m_d3dInteropDevice; + + // Direct2D factories. + Microsoft::WRL::ComPtr m_d2dFactory; + Microsoft::WRL::ComPtr m_dwriteFactory; + Microsoft::WRL::ComPtr m_wicFactory; + + // The holographic space provides a preferred DXGI adapter ID. + Windows::Graphics::Holographic::HolographicSpace^ m_holographicSpace = nullptr; + + // Properties of the Direct3D device currently in use. + D3D_FEATURE_LEVEL m_d3dFeatureLevel = D3D_FEATURE_LEVEL_10_0; + + // The IDeviceNotify can be held directly as it owns the DeviceResources. + IDeviceNotify* m_deviceNotify = nullptr; + + // Whether or not the current Direct3D device supports the optional feature + // for setting the render target array index from the vertex shader stage. + bool m_supportsVprt = false; + + // Back buffer resources, etc. for attached holographic cameras. + std::map> m_cameraResources; + std::mutex m_cameraResourcesLock; + }; +} + +// Device-based resources for holographic cameras are stored in a std::map. Access this list by providing a +// callback to this function, and the std::map will be guarded from add and remove +// events until the callback returns. The callback is processed immediately and must +// not contain any nested calls to UseHolographicCameraResources. +// The callback takes a parameter of type std::map>& +// through which the list of cameras will be accessed. +template +RetType DX::DeviceResources::UseHolographicCameraResources(const LCallback& callback) +{ + std::lock_guard guard(m_cameraResourcesLock); + return callback(m_cameraResources); +} + diff --git a/windows/MSRHoloLensSpatialMapping/Common/DirectXHelper.h b/windows/MSRHoloLensSpatialMapping/Common/DirectXHelper.h new file mode 100644 index 0000000..073e36d --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Common/DirectXHelper.h @@ -0,0 +1,70 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#pragma once + +#include // For create_task + +namespace DX +{ + inline void ThrowIfFailed(HRESULT hr) + { + if (FAILED(hr)) + { + // Set a breakpoint on this line to catch Win32 API errors. + throw Platform::Exception::CreateException(hr); + } + } + + // Function that reads from a binary file asynchronously. + inline Concurrency::task> ReadDataAsync(const std::wstring& filename) + { + using namespace Windows::Storage; + using namespace Concurrency; + + return create_task(PathIO::ReadBufferAsync(Platform::StringReference(filename.c_str()))).then( + [] (Streams::IBuffer^ fileBuffer) -> std::vector + { + std::vector returnBuffer; + returnBuffer.resize(fileBuffer->Length); + Streams::DataReader::FromBuffer(fileBuffer)->ReadBytes(Platform::ArrayReference(returnBuffer.data(), (unsigned int)returnBuffer.size())); + return returnBuffer; + }); + } + + // Converts a length in device-independent pixels (DIPs) to a length in physical pixels. + inline float ConvertDipsToPixels(float dips, float dpi) + { + static const float dipsPerInch = 96.0f; + return floorf(dips * dpi / dipsPerInch + 0.5f); // Round to nearest integer. + } + +#if defined(_DEBUG) + // Check for SDK Layer support. + inline bool SdkLayersAvailable() + { + HRESULT hr = D3D11CreateDevice( + nullptr, + D3D_DRIVER_TYPE_NULL, // There is no need to create a real hardware device. + 0, + D3D11_CREATE_DEVICE_DEBUG, // Check for the SDK layers. + nullptr, // Any feature level will do. + 0, + D3D11_SDK_VERSION, // Always set this to D3D11_SDK_VERSION for Windows Runtime apps. + nullptr, // No need to keep the D3D device reference. + nullptr, // No need to know the feature level. + nullptr // No need to keep the D3D device context reference. + ); + + return SUCCEEDED(hr); + } +#endif +} diff --git a/windows/MSRHoloLensSpatialMapping/Common/StepTimer.h b/windows/MSRHoloLensSpatialMapping/Common/StepTimer.h new file mode 100644 index 0000000..6b983e3 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Common/StepTimer.h @@ -0,0 +1,200 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#pragma once + +namespace DX +{ + // Helper class for animation and simulation timing. + class StepTimer + { + public: + StepTimer() : + m_elapsedTicks(0), + m_totalTicks(0), + m_leftOverTicks(0), + m_frameCount(0), + m_framesPerSecond(0), + m_framesThisSecond(0), + m_qpcSecondCounter(0), + m_isFixedTimeStep(false), + m_targetElapsedTicks(TicksPerSecond / 60) + { + m_qpcFrequency = GetPerformanceFrequency(); + + // Initialize max delta to 1/10 of a second. + m_qpcMaxDelta = m_qpcFrequency / 10; + } + + // Get elapsed time since the previous Update call. + uint64 GetElapsedTicks() const { return m_elapsedTicks; } + double GetElapsedSeconds() const { return TicksToSeconds(m_elapsedTicks); } + + // Get total time since the start of the program. + uint64 GetTotalTicks() const { return m_totalTicks; } + double GetTotalSeconds() const { return TicksToSeconds(m_totalTicks); } + + // Get total number of updates since start of the program. + uint32 GetFrameCount() const { return m_frameCount; } + + // Get the current framerate. + uint32 GetFramesPerSecond() const { return m_framesPerSecond; } + + // Set whether to use fixed or variable timestep mode. + void SetFixedTimeStep(bool isFixedTimestep) { m_isFixedTimeStep = isFixedTimestep; } + + // Set how often to call Update when in fixed timestep mode. + void SetTargetElapsedTicks(uint64 targetElapsed) { m_targetElapsedTicks = targetElapsed; } + void SetTargetElapsedSeconds(double targetElapsed) { m_targetElapsedTicks = SecondsToTicks(targetElapsed); } + + // Integer format represents time using 10,000,000 ticks per second. + static const uint64 TicksPerSecond = 10'000'000; + + static double TicksToSeconds(uint64 ticks) { return static_cast(ticks) / TicksPerSecond; } + static uint64 SecondsToTicks(double seconds) { return static_cast(seconds * TicksPerSecond); } + + // Convenient wrapper for QueryPerformanceFrequency. Throws an exception if + // the call to QueryPerformanceFrequency fails. + static inline uint64 GetPerformanceFrequency() + { + LARGE_INTEGER freq; + if (!QueryPerformanceFrequency(&freq)) + { + throw ref new Platform::FailureException(); + } + return freq.QuadPart; + } + + // Gets the current number of ticks from QueryPerformanceCounter. Throws an + // exception if the call to QueryPerformanceCounter fails. + static inline int64 GetTicks() + { + LARGE_INTEGER ticks; + if (!QueryPerformanceCounter(&ticks)) + { + throw ref new Platform::FailureException(); + } + return ticks.QuadPart; + } + + // After an intentional timing discontinuity (for instance a blocking IO operation) + // call this to avoid having the fixed timestep logic attempt a set of catch-up + // Update calls. + + void ResetElapsedTime() + { + m_qpcLastTime = GetTicks(); + + m_leftOverTicks = 0; + m_framesPerSecond = 0; + m_framesThisSecond = 0; + m_qpcSecondCounter = 0; + } + + // Update timer state, calling the specified Update function the appropriate number of times. + template + void Tick(const TUpdate& update) + { + // Query the current time. + uint64 currentTime = GetTicks(); + uint64 timeDelta = currentTime - m_qpcLastTime; + + m_qpcLastTime = currentTime; + m_qpcSecondCounter += timeDelta; + + // Clamp excessively large time deltas (e.g. after paused in the debugger). + if (timeDelta > m_qpcMaxDelta) + { + timeDelta = m_qpcMaxDelta; + } + + // Convert QPC units into a canonical tick format. This cannot overflow due to the previous clamp. + timeDelta *= TicksPerSecond; + timeDelta /= m_qpcFrequency; + + uint32 lastFrameCount = m_frameCount; + + if (m_isFixedTimeStep) + { + // Fixed timestep update logic + + // If the app is running very close to the target elapsed time (within 1/4 of a millisecond) just clamp + // the clock to exactly match the target value. This prevents tiny and irrelevant errors + // from accumulating over time. Without this clamping, a game that requested a 60 fps + // fixed update, running with vsync enabled on a 59.94 NTSC display, would eventually + // accumulate enough tiny errors that it would drop a frame. It is better to just round + // small deviations down to zero to leave things running smoothly. + + if (abs(static_cast(timeDelta - m_targetElapsedTicks)) < TicksPerSecond / 4000) + { + timeDelta = m_targetElapsedTicks; + } + + m_leftOverTicks += timeDelta; + + while (m_leftOverTicks >= m_targetElapsedTicks) + { + m_elapsedTicks = m_targetElapsedTicks; + m_totalTicks += m_targetElapsedTicks; + m_leftOverTicks -= m_targetElapsedTicks; + m_frameCount++; + + update(); + } + } + else + { + // Variable timestep update logic. + m_elapsedTicks = timeDelta; + m_totalTicks += timeDelta; + m_leftOverTicks = 0; + m_frameCount++; + + update(); + } + + // Track the current framerate. + if (m_frameCount != lastFrameCount) + { + m_framesThisSecond++; + } + + if (m_qpcSecondCounter >= static_cast(m_qpcFrequency)) + { + m_framesPerSecond = m_framesThisSecond; + m_framesThisSecond = 0; + m_qpcSecondCounter %= m_qpcFrequency; + } + } + + private: + + // Source timing data uses QPC units. + uint64 m_qpcFrequency; + uint64 m_qpcLastTime; + uint64 m_qpcMaxDelta; + + // Derived timing data uses a canonical tick format. + uint64 m_elapsedTicks; + uint64 m_totalTicks; + uint64 m_leftOverTicks; + + // Members for tracking the framerate. + uint32 m_frameCount; + uint32 m_framesPerSecond; + uint32 m_framesThisSecond; + uint64 m_qpcSecondCounter; + + // Members for configuring fixed timestep mode. + bool m_isFixedTimeStep; + uint64 m_targetElapsedTicks; + }; +} diff --git a/windows/MSRHoloLensSpatialMapping/Content/GetDataFromIBuffer.h b/windows/MSRHoloLensSpatialMapping/Content/GetDataFromIBuffer.h new file mode 100644 index 0000000..bda5daa --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Content/GetDataFromIBuffer.h @@ -0,0 +1,57 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#pragma once + +#include +#include +#include + +using namespace Microsoft::WRL; +using namespace Windows::Storage::Streams; + +namespace HoloLensNavigation +{ + template + t* GetDataFromIBuffer(Windows::Storage::Streams::IBuffer^ container) + { + if (container == nullptr) + { + return nullptr; + } + + unsigned int bufferLength = container->Length; + + if (!(bufferLength > 0)) + { + return nullptr; + } + + HRESULT hr = S_OK; + + ComPtr pUnknown = reinterpret_cast(container); + ComPtr spByteAccess; + hr = pUnknown.As(&spByteAccess); + if (FAILED(hr)) + { + return nullptr; + } + + byte* pRawData = nullptr; + hr = spByteAccess->Buffer(&pRawData); + if (FAILED(hr)) + { + return nullptr; + } + + return reinterpret_cast(pRawData); + } +} // namespace HoloLensNavigation diff --git a/windows/MSRHoloLensSpatialMapping/Content/RealTimeSurfaceMeshRenderer.cpp b/windows/MSRHoloLensSpatialMapping/Content/RealTimeSurfaceMeshRenderer.cpp new file mode 100644 index 0000000..09afb26 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Content/RealTimeSurfaceMeshRenderer.cpp @@ -0,0 +1,410 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "pch.h" + +#include "Common\DirectXHelper.h" +#include "RealtimeSurfaceMeshRenderer.h" + +using namespace HoloLensNavigation; + +using namespace Concurrency; +using namespace DX; +using namespace Windows::Foundation::Collections; +using namespace Windows::Foundation::Numerics; +using namespace Windows::Perception::Spatial; +using namespace Windows::Perception::Spatial::Surfaces; + +using namespace Platform; + +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +RealtimeSurfaceMeshRenderer::RealtimeSurfaceMeshRenderer(const std::shared_ptr& deviceResources) : + m_deviceResources(deviceResources), + m_loadingComplete(false) +{ + m_meshCollection.clear(); + CreateDeviceDependentResources(); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void RealtimeSurfaceMeshRenderer::Update(DX::StepTimer const & timer, SpatialCoordinateSystem ^ coordinateSystem) +{ + // + // Called once per frame, maintains and updates the mesh collection. + + std::lock_guard guard(m_meshCollectionLock); + + const float timeElapsed = static_cast(timer.GetTotalSeconds()); + + // Update meshes as needed, based on the current coordinate system. + // Also remove meshes that are inactive for too long. + for (auto iter = m_meshCollection.begin(); iter != m_meshCollection.end(); ) + { + auto& pair = *iter; + auto& surfaceMesh = pair.second; + + // Update the surface mesh. + surfaceMesh.UpdateTransform(m_deviceResources->GetD3DDevice(), m_deviceResources->GetD3DDeviceContext(), timer, coordinateSystem); + + // Check to see if the mesh has expired. + float lastActiveTime = surfaceMesh.GetLastActiveTime(); + float inactiveDuration = timeElapsed - lastActiveTime; + if (inactiveDuration > c_maxInactiveMeshTime) + { + // Surface mesh is expired. + m_meshCollection.erase(iter++); + } + else + { + ++iter; + } + }; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void RealtimeSurfaceMeshRenderer::AddSurface(Guid id, SpatialSurfaceInfo^ newSurface) +{ + auto fadeInMeshTask = AddOrUpdateSurfaceAsync(id, newSurface).then([this, id] () + { + if (HasSurface(id)) + { + std::lock_guard guard(m_meshCollectionLock); + + // In this example, new surfaces are treated differently by highlighting them in a different + // color. This allows you to observe changes in the spatial map that are due to new meshes, + // as opposed to mesh updates. + auto& surfaceMesh = m_meshCollection[id]; + surfaceMesh.SetColorFadeTimer(c_surfaceMeshFadeInTime); + } + }); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void RealtimeSurfaceMeshRenderer::UpdateSurface(Guid id, SpatialSurfaceInfo^ newSurface) +{ + AddOrUpdateSurfaceAsync(id, newSurface); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +Concurrency::task RealtimeSurfaceMeshRenderer::AddOrUpdateSurfaceAsync(Guid id, SpatialSurfaceInfo^ newSurface) +{ + auto options = ref new SpatialSurfaceMeshOptions(); + options->IncludeVertexNormals = true; + + // The level of detail setting is used to limit mesh complexity, by limiting the number + // of triangles per cubic meter. + auto createMeshTask = create_task(newSurface->TryComputeLatestMeshAsync(m_maxTrianglesPerCubicMeter, options)); + auto processMeshTask = createMeshTask.then([this, id](SpatialSurfaceMesh^ mesh) + { + if (mesh != nullptr) + { + std::lock_guard guard(m_meshCollectionLock); + + auto& surfaceMesh = m_meshCollection[id]; + surfaceMesh.UpdateSurface(mesh); + surfaceMesh.SetIsActive(true); + } + }, task_continuation_context::use_current()); + + return processMeshTask; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void RealtimeSurfaceMeshRenderer::RemoveSurface(Guid id) +{ + std::lock_guard guard(m_meshCollectionLock); + m_meshCollection.erase(id); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void RealtimeSurfaceMeshRenderer::ClearSurfaces() +{ + std::lock_guard guard(m_meshCollectionLock); + m_meshCollection.clear(); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void RealtimeSurfaceMeshRenderer::HideInactiveMeshes(IMapView^ const& surfaceCollection) +{ + std::lock_guard guard(m_meshCollectionLock); + + // Hide surfaces that aren't actively listed in the surface collection. + for (auto& pair : m_meshCollection) + { + const auto& id = pair.first; + auto& surfaceMesh = pair.second; + + surfaceMesh.SetIsActive(surfaceCollection->HasKey(id) ? true : false); + }; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void RealtimeSurfaceMeshRenderer::Render(bool isStereo, bool useWireframe) +{ + // + // Renders one frame using the vertex, geometry, and pixel shaders. + + // Loading is asynchronous. Only draw geometry after it's loaded. + if (!m_loadingComplete) + { + return; + } + + auto context = m_deviceResources->GetD3DDeviceContext(); + + context->IASetPrimitiveTopology(D3D11_PRIMITIVE_TOPOLOGY_TRIANGLELIST); + context->IASetInputLayout(m_inputLayout.Get()); + + // Attach our vertex shader. + context->VSSetShader(m_vertexShader.Get(), nullptr, 0); + + // The constant buffer is per-mesh, and will be set for each one individually. + if (!m_usingVprtShaders) + { + // Attach the passthrough geometry shader. + context->GSSetShader(m_geometryShader.Get(), nullptr, 0); + } + + if (useWireframe) + { + // Use a wireframe rasterizer state. + m_deviceResources->GetD3DDeviceContext()->RSSetState(m_wireframeRasterizerState.Get()); + + // Attach a pixel shader to render a solid color wireframe. + context->PSSetShader(m_colorPixelShader.Get(), nullptr, 0); + } + else + { + // Use the default rasterizer state. + m_deviceResources->GetD3DDeviceContext()->RSSetState(m_defaultRasterizerState.Get()); + + // Attach a pixel shader that can do lighting. + context->PSSetShader(m_lightingPixelShader.Get(), nullptr, 0); + } + + { + std::lock_guard guard(m_meshCollectionLock); + + // Draw the meshes. + auto device = m_deviceResources->GetD3DDevice(); + for (auto& pair : m_meshCollection) + { + auto & id = pair.first; + auto & surfaceMesh = pair.second; + + surfaceMesh.Draw(device, context, m_usingVprtShaders, isStereo); + } + } +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void RealtimeSurfaceMeshRenderer::CreateDeviceDependentResources() +{ + m_usingVprtShaders = m_deviceResources->GetDeviceSupportsVprt(); + + // On devices that do support the D3D11_FEATURE_D3D11_OPTIONS3:: + // VPAndRTArrayIndexFromAnyShaderFeedingRasterizer optional feature + // we can avoid using a pass-through geometry shader to set the render + // target array index, thus avoiding any overhead that would be + // incurred by setting the geometry shader stage. + std::wstring vertexShaderFileName = m_usingVprtShaders ? L"ms-appx:///SurfaceVprtVertexShader.cso" : L"ms-appx:///SurfaceVertexShader.cso"; + + // Load shaders asynchronously. + task> loadVSTask = DX::ReadDataAsync(vertexShaderFileName); + task> loadLightingPSTask = DX::ReadDataAsync(L"ms-appx:///SimpleLightingPixelShader.cso"); + task> loadWireframePSTask = DX::ReadDataAsync(L"ms-appx:///SolidColorPixelShader.cso"); + + task> loadGSTask; + + if (!m_usingVprtShaders) + { + // Load the pass-through geometry shader. + loadGSTask = DX::ReadDataAsync(L"ms-appx:///SurfaceGeometryShader.cso"); + } + + // After the vertex shader file is loaded, create the shader and input layout. + auto createVSTask = loadVSTask.then([this](const std::vector& fileData) { + DX::ThrowIfFailed( + m_deviceResources->GetD3DDevice()->CreateVertexShader(&fileData[0], fileData.size(), nullptr, &m_vertexShader) + ); + + static const D3D11_INPUT_ELEMENT_DESC vertexDesc[] = + { + { "POSITION", 0, DXGI_FORMAT_R16G16B16A16_SNORM, 0, D3D11_APPEND_ALIGNED_ELEMENT, D3D11_INPUT_PER_VERTEX_DATA, 0 }, + { "NORMAL", 0, DXGI_FORMAT_R8G8B8A8_SNORM, 1, D3D11_APPEND_ALIGNED_ELEMENT, D3D11_INPUT_PER_VERTEX_DATA, 0 }, + }; + + DX::ThrowIfFailed( + m_deviceResources->GetD3DDevice()->CreateInputLayout(vertexDesc, ARRAYSIZE(vertexDesc), &fileData[0], fileData.size(), &m_inputLayout) + ); + }); + + // After the pixel shader file is loaded, create the shader and constant buffer. + auto createLightingPSTask = loadLightingPSTask.then([this](const std::vector& fileData) { + DX::ThrowIfFailed( + m_deviceResources->GetD3DDevice()->CreatePixelShader(&fileData[0], fileData.size(), nullptr, &m_lightingPixelShader) + ); + }); + + // After the pixel shader file is loaded, create the shader and constant buffer. + auto createWireframePSTask = loadWireframePSTask.then([this](const std::vector& fileData) { + DX::ThrowIfFailed( + m_deviceResources->GetD3DDevice()->CreatePixelShader(&fileData[0], fileData.size(), nullptr, &m_colorPixelShader) + ); + }); + + task createGSTask; + if (!m_usingVprtShaders) + { + // After the pass-through geometry shader file is loaded, create the shader. + createGSTask = loadGSTask.then([this](const std::vector& fileData) + { + DX::ThrowIfFailed( + m_deviceResources->GetD3DDevice()->CreateGeometryShader(&fileData[0], fileData.size(), nullptr, &m_geometryShader) + ); + }); + } + + // Once all shaders are loaded, create the mesh. + task shaderTaskGroup = m_usingVprtShaders ? + (createLightingPSTask && createWireframePSTask && createVSTask) : + (createLightingPSTask && createWireframePSTask && createVSTask && createGSTask); + + // Once the cube is loaded, the object is ready to be rendered. + auto finishLoadingTask = shaderTaskGroup.then([this]() { + + // Recreate device-based surface mesh resources. + std::lock_guard guard(m_meshCollectionLock); + for (auto& iter : m_meshCollection) + { + iter.second.ReleaseDeviceDependentResources(); + iter.second.CreateDeviceDependentResources(m_deviceResources->GetD3DDevice()); + } + + // Create a default rasterizer state descriptor. + D3D11_RASTERIZER_DESC rasterizerDesc = CD3D11_RASTERIZER_DESC(D3D11_DEFAULT); + + // Create the default rasterizer state. + m_deviceResources->GetD3DDevice()->CreateRasterizerState(&rasterizerDesc, m_defaultRasterizerState.GetAddressOf()); + + // Change settings for wireframe rasterization. + rasterizerDesc.AntialiasedLineEnable = false; + rasterizerDesc.CullMode = D3D11_CULL_NONE; + rasterizerDesc.FillMode = D3D11_FILL_WIREFRAME; + + // Create a wireframe rasterizer state. + m_deviceResources->GetD3DDevice()->CreateRasterizerState(&rasterizerDesc, m_wireframeRasterizerState.GetAddressOf()); + + m_loadingComplete = true; + }); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void RealtimeSurfaceMeshRenderer::ReleaseDeviceDependentResources() +{ + m_loadingComplete = false; + + m_vertexShader.Reset(); + m_inputLayout.Reset(); + m_geometryShader.Reset(); + m_lightingPixelShader.Reset(); + m_colorPixelShader.Reset(); + + m_defaultRasterizerState.Reset(); + m_wireframeRasterizerState.Reset(); + + std::lock_guard guard(m_meshCollectionLock); + for (auto& iter : m_meshCollection) + { + iter.second.ReleaseDeviceDependentResources(); + } +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +bool RealtimeSurfaceMeshRenderer::HasSurface(Platform::Guid id) +{ + std::lock_guard guard(m_meshCollectionLock); + return m_meshCollection.find(id) != m_meshCollection.end(); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +Windows::Foundation::DateTime RealtimeSurfaceMeshRenderer::GetLastUpdateTime(Platform::Guid id) +{ + std::lock_guard guard(m_meshCollectionLock); + auto& meshIter = m_meshCollection.find(id); + if (meshIter != m_meshCollection.end()) + { + auto const& mesh = meshIter->second; + return mesh.GetLastUpdateTime(); + } + else + { + static const Windows::Foundation::DateTime zero; + return zero; + } +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void RealtimeSurfaceMeshRenderer::CollectVertexData() +{ + std::lock_guard guard(m_meshCollectionLock); + + unsigned int uTotalBufferSize = 0; + + m_memVertexDataCollection.LockRWAccess(); + + // + // collect vertex buffers of all surface meshes into one data block + for (auto& pair : m_meshCollection) + { + auto& surfaceMesh = pair.second; + + StaticMemoryBuffer& memBuffer = surfaceMesh.GetVertexMemoryBuffer(); + + memBuffer.LockRWAccess(); + + unsigned char * pSrc = (unsigned char*)memBuffer.getPointer(); + unsigned int uSrcBufferSize = memBuffer.getBufferSize(); + + if (pSrc && uSrcBufferSize) { + unsigned char * pDst = (unsigned char*)m_memVertexDataCollection.realloc(uTotalBufferSize + uSrcBufferSize); + if (!pDst) { + memBuffer.UnlockRWAccess(); + break; + } + + memcpy(pDst + uTotalBufferSize, pSrc, uSrcBufferSize); + + uTotalBufferSize += uSrcBufferSize; + } + + memBuffer.UnlockRWAccess(); + } + + m_memVertexDataCollection.UnlockRWAccess(); + + // DebugMsgW(L"total buffer size: %u", uTotalBufferSize); +} diff --git a/windows/MSRHoloLensSpatialMapping/Content/RealTimeSurfaceMeshRenderer.h b/windows/MSRHoloLensSpatialMapping/Content/RealTimeSurfaceMeshRenderer.h new file mode 100644 index 0000000..8b8a7bb --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Content/RealTimeSurfaceMeshRenderer.h @@ -0,0 +1,102 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#pragma once + +#include "Common\DeviceResources.h" +#include "Common\StepTimer.h" +#include "Content\SurfaceMesh.h" +#include "Content\ShaderStructures.h" + +#include +#include +#include + +namespace HoloLensNavigation +{ + class RealtimeSurfaceMeshRenderer + { + public: + RealtimeSurfaceMeshRenderer(const std::shared_ptr& deviceResources); + void CreateDeviceDependentResources(); + void ReleaseDeviceDependentResources(); + void Update( + DX::StepTimer const& timer, + Windows::Perception::Spatial::SpatialCoordinateSystem^ coordinateSystem + ); + void Render(bool isStereo, bool useWireframe); + + bool HasSurface(Platform::Guid id); + void AddSurface(Platform::Guid id, Windows::Perception::Spatial::Surfaces::SpatialSurfaceInfo^ newSurface); + void UpdateSurface(Platform::Guid id, Windows::Perception::Spatial::Surfaces::SpatialSurfaceInfo^ newSurface); + void RemoveSurface(Platform::Guid id); + void ClearSurfaces(); + + Windows::Foundation::DateTime GetLastUpdateTime(Platform::Guid id); + + void HideInactiveMeshes( + Windows::Foundation::Collections::IMapView^ const& surfaceCollection); + + public: + void CollectVertexData(); + _inline StaticMemoryBuffer& GetVertexDataCollectionBuffer(void) { return m_memVertexDataCollection; } + + private: + Concurrency::task AddOrUpdateSurfaceAsync(Platform::Guid id, Windows::Perception::Spatial::Surfaces::SpatialSurfaceInfo^ newSurface); + + // Cached pointer to device resources. + std::shared_ptr m_deviceResources; + + // Direct3D resources for SR mesh rendering pipeline. + Microsoft::WRL::ComPtr m_inputLayout; + Microsoft::WRL::ComPtr m_vertexShader; + Microsoft::WRL::ComPtr m_geometryShader; + Microsoft::WRL::ComPtr m_lightingPixelShader; + Microsoft::WRL::ComPtr m_colorPixelShader; + + // The set of surfaces in the collection. + std::map m_meshCollection; + + // A way to lock map access. + std::mutex m_meshCollectionLock; + + // Total number of surface meshes. + unsigned int m_surfaceMeshCount; + + // Level of detail setting. The number of triangles that the system is allowed to provide per cubic meter. + double m_maxTrianglesPerCubicMeter = 1000.0; + + // If the current D3D Device supports VPRT, we can avoid using a geometry + // shader just to set the render target array index. + bool m_usingVprtShaders = false; + + // Rasterizer states, for different rendering modes. + Microsoft::WRL::ComPtr m_defaultRasterizerState; + Microsoft::WRL::ComPtr m_wireframeRasterizerState; + + // The duration of time, in seconds, a mesh is allowed to remain inactive before deletion. + const float c_maxInactiveMeshTime = 120.f; + + // The duration of time, in seconds, taken for a new surface mesh to fade in on-screen. + const float c_surfaceMeshFadeInTime = 2.0f; + + bool m_loadingComplete; + + private: + // + // we'll use a memory buffer which only grows in size as needed. Because we collect + // vertex data over and over, re-using previously allocated memory will drastically + // improve performance. + StaticMemoryBuffer m_memVertexDataCollection; + }; + +} // namespace HoloLensNavigation diff --git a/windows/MSRHoloLensSpatialMapping/Content/ShaderStructures.h b/windows/MSRHoloLensSpatialMapping/Content/ShaderStructures.h new file mode 100644 index 0000000..12fa532 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Content/ShaderStructures.h @@ -0,0 +1,66 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#pragma once + +namespace HoloLensNavigation +{ + // Constant buffer used to send hologram position transform to the shader pipeline. + struct ModelConstantBuffer + { + DirectX::XMFLOAT4X4 modelToWorld; + }; + + // Assert that the constant buffer remains 16-byte aligned (best practice). + // If shader structure members are not aligned to a 4-float boundary, data may + // not show up where it is expected by the time it is read by the shader. + static_assert((sizeof(ModelConstantBuffer) % (sizeof(float) * 4)) == 0, "Model constant buffer size must be 16-byte aligned (16 bytes is the length of four floats)."); + + // Constant buffer used to send hologram position and normal transforms to the shader pipeline. + struct ModelNormalConstantBuffer + { + DirectX::XMFLOAT4X4 modelToWorld; + DirectX::XMFLOAT4X4 normalToWorld; + DirectX::XMFLOAT4 colorFadeFactor; + }; + + // Assert that the constant buffer remains 16-byte aligned (best practice). + // If shader structure members are not aligned to a 4-float boundary, data may + // not show up where it is expected by the time it is read by the shader. + static_assert((sizeof(ModelNormalConstantBuffer) % (sizeof(float) * 4)) == 0, "Model/normal constant buffer size must be 16-byte aligned (16 bytes is the length of four floats)."); + + // Constant buffer used to send the view-projection matrices to the shader pipeline. + struct ViewProjectionConstantBuffer + { + DirectX::XMFLOAT4 cameraPosition; + DirectX::XMFLOAT4 lightPosition; + DirectX::XMFLOAT4X4 viewProjection[2]; + }; + + // Assert that the constant buffer remains 16-byte aligned (best practice). + static_assert((sizeof(ViewProjectionConstantBuffer) % (sizeof(float) * 4)) == 0, "View/projection constant buffer size must be 16-byte aligned (16 bytes is the length of four floats)."); + + // Used to send per-vertex data to the vertex shader. + struct VertexPositionColor + { + DirectX::XMFLOAT3 pos; + DirectX::XMFLOAT3 color; + }; + + // Used to send per-vertex data to the vertex shader, including a normal. + struct VertexPositionNormalColor + { + DirectX::XMFLOAT3 pos; + DirectX::XMFLOAT3 normal; + DirectX::XMFLOAT3 color; + }; + +} // namespace HoloLensNavigation diff --git a/windows/MSRHoloLensSpatialMapping/Content/SimpleLightingPixelShader.hlsl b/windows/MSRHoloLensSpatialMapping/Content/SimpleLightingPixelShader.hlsl new file mode 100644 index 0000000..8532578 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Content/SimpleLightingPixelShader.hlsl @@ -0,0 +1,86 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +// A constant buffer that stores per-mesh data. +cbuffer ModelConstantBuffer : register(b0) +{ + float4x4 modelToWorld; + min16float4x4 normalToWorld; + min16float3 colorFadeFactor; +}; + +// A constant buffer that stores each set of view and projection matrices in column-major format. +cbuffer ViewProjectionConstantBuffer : register(b1) +{ + float4 cameraPosition; + float4 lightPosition; + float4x4 viewProjection[2]; +}; + +// Per-pixel data. +struct PixelShaderInput +{ + min16float4 screenPos : SV_POSITION; + min16float3 worldPos : POSITION0; + min16float3 worldNorm : NORMAL0; + min16float3 color : COLOR0; + uint idx : TEXCOORD0; +}; + +//-------------------------------------------------------------------------------------- +// The pixel shader applies simplified Blinn-Phong BRDF lighting. +min16float4 main(PixelShaderInput input) : SV_TARGET +{ + min16float3 lightDiffuseColorValue = min16float3(1.f, 1.f, 1.f); + min16float3 objectBaseColorValue = min16float3(input.color); + + // N is the surface normal, which points directly away from the surface. + min16float3 N = normalize(input.worldNorm); + + // L is the light incident vector, which is a normal that points from the surface to the light. + min16float3 lightIncidentVectorNotNormalized = min16float3(lightPosition.xyz - input.worldPos); + min16float distanceFromSurfaceToLight = length(lightIncidentVectorNotNormalized); + min16float oneOverDistanceFromSurfaceToLight = min16float(1.f) / distanceFromSurfaceToLight; + min16float3 L = normalize(lightIncidentVectorNotNormalized); + + // V is the camera incident vector, which is a normal that points from the surface to the camera. + min16float3 V = normalize(min16float3(cameraPosition.xyz - input.worldPos)); + + // H is a normalized vector that is halfway between L and V. + min16float3 H = normalize(L + V); + + // We take the dot products of N with L and H. + min16float nDotL = dot(N, L); + min16float nDotH = dot(N, H); + + // The dot products should be clamped to 0 as a lower bound. + min16float clampedNDotL = max(min16float(0.f), nDotL); + min16float clampedNDotH = max(min16float(0.f), nDotH); + + // We can then use dot(N, L) to determine the diffuse lighting contribution. + min16float3 diffuseColor = lightDiffuseColorValue * objectBaseColorValue * clampedNDotL; + + // The specular contribution is based on dot(N, H). + const min16float specularExponent = min16float(4.f); + const min16float3 specularColorValue = min16float3(1.f, 1.f, 0.9f); + const min16float3 specularColor = specularColorValue * pow(clampedNDotH, specularExponent) * oneOverDistanceFromSurfaceToLight; + + // Now, we can sum the ambient, diffuse, and specular contributions to determine the lighting value for the pixel. + const min16float3 surfaceLitColor = objectBaseColorValue * min16float(0.2f) + diffuseColor * min16float(0.6f) + specularColor * min16float(0.2f); + + // In this example, new surfaces are treated differently by highlighting them in a different + // color. This allows you to observe changes in the spatial map that are due to new meshes, + // as opposed to mesh updates. + const min16float3 oneMinusColorFadeFactor = min16float3(1.f, 1.f, 1.f) - (min16float3)colorFadeFactor; + const min16float3 fadedColor = (surfaceLitColor * oneMinusColorFadeFactor) + (min16float3(0.1f, 0.1f, 0.75f) * (min16float3)colorFadeFactor); + + return min16float4(fadedColor, 1.f); +} diff --git a/windows/MSRHoloLensSpatialMapping/Content/SolidColorPixelShader.hlsl b/windows/MSRHoloLensSpatialMapping/Content/SolidColorPixelShader.hlsl new file mode 100644 index 0000000..06ed300 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Content/SolidColorPixelShader.hlsl @@ -0,0 +1,40 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +// A constant buffer that stores per-mesh data. +cbuffer ModelConstantBuffer : register(b0) +{ + float4x4 modelToWorld; + min16float4x4 normalToWorld; + min16float4 colorFadeFactor; +}; + +// Per-pixel data. +struct PixelShaderInput +{ + min16float4 screenPos : SV_POSITION; + min16float3 worldPos : POSITION0; + min16float3 worldNorm : NORMAL0; + min16float3 color : COLOR0; + uint idx : TEXCOORD0; +}; + +// The pixel shader returns a solid color (red). +min16float4 main(PixelShaderInput input) : SV_TARGET +{ + // In this example, new surfaces are treated differently by highlighting them in a different + // color. This allows you to observe changes in the spatial map that are due to new meshes, + // as opposed to mesh updates. + const min16float3 oneMinusColorFadeFactor = min16float3(1.f, 1.f, 1.f) - (min16float3)colorFadeFactor; + const min16float3 fadedColor = (input.color * oneMinusColorFadeFactor) + (min16float3(0.1f, 0.1f, 0.75f) * (min16float3)colorFadeFactor); + + return min16float4(fadedColor, 1.f); +} diff --git a/windows/MSRHoloLensSpatialMapping/Content/SpatialInputHandler.cpp b/windows/MSRHoloLensSpatialMapping/Content/SpatialInputHandler.cpp new file mode 100644 index 0000000..a287f6c --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Content/SpatialInputHandler.cpp @@ -0,0 +1,56 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "pch.h" +#include "SpatialInputHandler.h" +#include + +using namespace HoloLensNavigation; + +using namespace Windows::Foundation; +using namespace Windows::UI::Input::Spatial; +using namespace std::placeholders; + +// Creates and initializes a GestureRecognizer that listens to a Person. +SpatialInputHandler::SpatialInputHandler() +{ + // The interaction manager provides an event that informs the app when + // spatial interactions are detected. + m_interactionManager = SpatialInteractionManager::GetForCurrentView(); + + // Bind a handler to the SourcePressed event. + m_sourcePressedEventToken = + m_interactionManager->SourcePressed += + ref new TypedEventHandler( + bind(&SpatialInputHandler::OnSourcePressed, this, _1, _2) + ); +} + +SpatialInputHandler::~SpatialInputHandler() +{ + // Unregister our handler for the OnSourcePressed event. + m_interactionManager->SourcePressed -= m_sourcePressedEventToken; +} + +// Checks if the user performed an input gesture since the last call to this method. +// Allows the main update loop to check for asynchronous changes to the user +// input state. +SpatialInteractionSourceState^ SpatialInputHandler::CheckForInput() +{ + SpatialInteractionSourceState^ sourceState = m_sourceState; + m_sourceState = nullptr; + return sourceState; +} + +void SpatialInputHandler::OnSourcePressed(SpatialInteractionManager^ sender, SpatialInteractionSourceEventArgs^ args) +{ + m_sourceState = args->State; +} diff --git a/windows/MSRHoloLensSpatialMapping/Content/SpatialInputHandler.h b/windows/MSRHoloLensSpatialMapping/Content/SpatialInputHandler.h new file mode 100644 index 0000000..b1c65de --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Content/SpatialInputHandler.h @@ -0,0 +1,42 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#pragma once + +namespace HoloLensNavigation +{ + // Sample gesture handler. + // Hooks up events to recognize a tap gesture, and keeps track of input using a boolean value. + class SpatialInputHandler + { + public: + SpatialInputHandler(); + ~SpatialInputHandler(); + + Windows::UI::Input::Spatial::SpatialInteractionSourceState^ CheckForInput(); + + private: + // Interaction event handler. + void OnSourcePressed( + Windows::UI::Input::Spatial::SpatialInteractionManager^ sender, + Windows::UI::Input::Spatial::SpatialInteractionSourceEventArgs^ args); + + // API objects used to process gesture input, and generate gesture events. + Windows::UI::Input::Spatial::SpatialInteractionManager^ m_interactionManager; + + // Event registration token. + Windows::Foundation::EventRegistrationToken m_sourcePressedEventToken; + + // Used to indicate that a Pressed input event was received this frame. + Windows::UI::Input::Spatial::SpatialInteractionSourceState^ m_sourceState = nullptr; + }; + +} // namespace HoloLensNavigation diff --git a/windows/MSRHoloLensSpatialMapping/Content/SurfaceGeometryShader.hlsl b/windows/MSRHoloLensSpatialMapping/Content/SurfaceGeometryShader.hlsl new file mode 100644 index 0000000..ff8ced1 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Content/SurfaceGeometryShader.hlsl @@ -0,0 +1,50 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +// Per-vertex data from the vertex shader. +struct GeometryShaderInput +{ + min16float4 screenPos : SV_POSITION; + min16float3 worldPos : POSITION0; + min16float3 worldNorm : NORMAL0; + min16float3 color : COLOR0; + uint instId : TEXCOORD0; +}; + +// Per-vertex data passed to the rasterizer. +struct GeometryShaderOutput +{ + min16float4 screenPos : SV_POSITION; + min16float3 worldPos : POSITION0; + min16float3 worldNorm : NORMAL0; + min16float3 color : COLOR0; + uint idx : TEXCOORD0; + uint rtvId : SV_RenderTargetArrayIndex; +}; + +// This geometry shader is a pass-through that leaves the geometry unmodified +// and sets the render target array index. +[maxvertexcount(3)] +void main(triangle GeometryShaderInput input[3], inout TriangleStream outStream) +{ + GeometryShaderOutput output; + [unroll(3)] + for (int i = 0; i < 3; ++i) + { + output.screenPos = input[i].screenPos; + output.worldPos = input[i].worldPos; + output.worldNorm = input[i].worldNorm; + output.color = input[i].color; + output.idx = input[i].instId; + output.rtvId = input[i].instId; + outStream.Append(output); + } +} diff --git a/windows/MSRHoloLensSpatialMapping/Content/SurfaceMesh.cpp b/windows/MSRHoloLensSpatialMapping/Content/SurfaceMesh.cpp new file mode 100644 index 0000000..4def245 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Content/SurfaceMesh.cpp @@ -0,0 +1,532 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "pch.h" + +#include + +#include "Common\DirectXHelper.h" +#include "Common\StepTimer.h" +#include "GetDataFromIBuffer.h" +#include "SurfaceMesh.h" + +using namespace HoloLensNavigation; +using namespace DirectX; +using namespace Windows::Perception::Spatial; +using namespace Windows::Perception::Spatial::Surfaces; +using namespace Windows::Foundation::Numerics; + +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +SurfaceMesh::SurfaceMesh() +{ + InitializeCriticalSection(&m_csMeshResources); + InitializeCriticalSection(&m_csUpdateVertexResources); + + CSLock lock(&m_csMeshResources); + + ReleaseDeviceDependentResources(); + m_lastUpdateTime.UniversalTime = 0; + m_fClosing = false; + + m_lastActiveTime = static_cast(_pGlobalTimer->GetTotalSeconds()); + + m_smud.surfaceMesh = nullptr; + m_smud.pd3dDevice = nullptr; + + CreateUpdateVertexResourcesWorkerThread(); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +SurfaceMesh::~SurfaceMesh() +{ + ExitUpdateVertexResourcesWorkerThread(); + + { + CSLock lock(&m_csMeshResources); + + ReleaseDeviceDependentResources(); + } + + { + CSLock lock(&m_csUpdateVertexResources); + + m_fClosing = true; + } + + DeleteCriticalSection(&m_csUpdateVertexResources); + DeleteCriticalSection(&m_csMeshResources); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void SurfaceMesh::UpdateSurface(SpatialSurfaceMesh ^ surfaceMesh) +{ + m_pendingSurfaceMesh = surfaceMesh; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void SurfaceMesh::UpdateTransform(ID3D11Device * device, ID3D11DeviceContext * context, DX::StepTimer const & timer, SpatialCoordinateSystem ^ baseCoordinateSystem) +{ + // + // Spatial Mapping surface meshes each have a transform. This transform is updated every frame. + + UpdateVertexResources(device); + + { + CSLock csLock(&m_csMeshResources); + + m_baseCoordinateSystem = baseCoordinateSystem; + + if (m_updateReady) + { + // Surface mesh resources are created off-thread so that they don't affect rendering latency. + // When a new update is ready, we should begin using the updated vertex position, normal, and + // index buffers. + SwapVertexBuffers(); + m_updateReady = false; + } + } + + XMMATRIX transform; + if (m_isActive) + { + // In this example, new surfaces are treated differently by highlighting them in a different + // color. This allows you to observe changes in the spatial map that are due to new meshes, + // as opposed to mesh updates. + if (m_colorFadeTimeout > 0.f) + { + m_colorFadeTimer += static_cast(timer.GetElapsedSeconds()); + if (m_colorFadeTimer < m_colorFadeTimeout) + { + float colorFadeFactor = min(1.f, m_colorFadeTimeout - m_colorFadeTimer); + m_constantBufferData.colorFadeFactor = XMFLOAT4(colorFadeFactor, colorFadeFactor, colorFadeFactor, 1.f); + } + else + { + m_constantBufferData.colorFadeFactor = XMFLOAT4(0.f, 0.f, 0.f, 0.f); + m_colorFadeTimer = m_colorFadeTimeout = -1.f; + } + } + + // The transform is updated relative to a SpatialCoordinateSystem. In the SurfaceMesh class, we + // expect to be given the same SpatialCoordinateSystem that will be used to generate view + // matrices, because this class uses the surface mesh for rendering. + // Other applications could potentially involve using a SpatialCoordinateSystem from a stationary + // reference frame that is being used for physics simulation, etc. + auto tryTransform = m_meshProperties.coordinateSystem ? m_meshProperties.coordinateSystem->TryGetTransformTo(baseCoordinateSystem) : nullptr; + if (tryTransform != nullptr) + { + // If the transform can be acquired, this spatial mesh is valid right now and + // we have the information we need to draw it this frame. + transform = XMLoadFloat4x4(&tryTransform->Value); + m_lastActiveTime = static_cast(timer.GetTotalSeconds()); + } + else + { + // If the transform cannot be acquired, the spatial mesh is not valid right now + // because its location cannot be correlated to the current space. + m_isActive = false; + } + } + + if (!m_isActive) + { + // If for any reason the surface mesh is not active this frame - whether because + // it was not included in the observer's collection, or because its transform was + // not located - we don't have the information we need to update it. + return; + } + + // Set up a transform from surface mesh space, to world space. + XMMATRIX scaleTransform = XMMatrixScalingFromVector(XMLoadFloat3(&m_meshProperties.vertexPositionScale)); + + XMStoreFloat4x4(&m_constantBufferData.modelToWorld, XMMatrixTranspose(scaleTransform * transform)); + + // Surface meshes come with normals, which are also transformed from surface mesh space, to world space. + XMMATRIX normalTransform = transform; + + // Normals are not translated, so we remove the translation component here. + normalTransform.r[3] = XMVectorSet(0.f, 0.f, 0.f, XMVectorGetW(normalTransform.r[3])); + XMStoreFloat4x4(&m_constantBufferData.normalToWorld, XMMatrixTranspose(normalTransform)); + + if (!m_constantBufferCreated) + { + // If loading is not yet complete, we cannot actually update the graphics resources. + // This return is intentionally placed after the surface mesh updates so that this + // code may be copied and re-used for CPU-based processing of surface data. + CreateDeviceDependentResources(device); + return; + } + + context->UpdateSubresource(m_modelTransformBuffer.Get(), 0, NULL, &m_constantBufferData, 0, 0); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void SurfaceMesh::Draw(ID3D11Device* device, ID3D11DeviceContext* context, bool usingVprtShaders, bool isStereo) +{ + // + // Does an indexed, instanced draw call after setting the IA stage to use the mesh's geometry, and + // after setting up the constant buffer for the surface mesh. + // The caller is responsible for the rest of the shader pipeline. + + if (!m_constantBufferCreated || !m_loadingComplete) + { + // Resources are still being initialized. + return; + } + + if (!m_isActive) + { + // Mesh is not active this frame, and should not be drawn. + return; + } + + // The vertices are provided in {vertex, normal} format + + UINT strides [] = { m_meshProperties.vertexStride, m_meshProperties.normalStride }; + UINT offsets [] = { 0, 0 }; + ID3D11Buffer* buffers [] = { m_vertexPositions.Get(), m_vertexNormals.Get() }; + + context->IASetVertexBuffers(0, ARRAYSIZE(buffers), buffers, strides, offsets); + context->IASetIndexBuffer(m_triangleIndices.Get(), m_meshProperties.indexFormat, 0); + context->VSSetConstantBuffers(0, 1, m_modelTransformBuffer.GetAddressOf()); + + if (!usingVprtShaders) + { + context->GSSetConstantBuffers(0, 1, m_modelTransformBuffer.GetAddressOf()); + } + + context->PSSetConstantBuffers(0, 1, m_modelTransformBuffer.GetAddressOf()); + + context->DrawIndexedInstanced( + m_meshProperties.indexCount, // Index count per instance. + isStereo ? 2 : 1, // Instance count. + 0, // Start index location. + 0, // Base vertex location. + 0 // Start instance location. + ); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void SurfaceMesh::CreateDirectXBuffer(ID3D11Device * device, D3D11_BIND_FLAG binding, IBuffer ^ buffer, ID3D11Buffer ** target) +{ + auto length = buffer->Length; + + CD3D11_BUFFER_DESC bufferDescription(buffer->Length, binding); + D3D11_SUBRESOURCE_DATA bufferBytes = { GetDataFromIBuffer(buffer), 0, 0 }; + device->CreateBuffer(&bufferDescription, &bufferBytes, target); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void SurfaceMesh::CreateUpdateVertexResourcesWorkerThread() +{ + HRESULT hr; + + m_hEventExitUpdateVertexResourcesWorkerThread = CreateEventW(NULL, TRUE, FALSE, NULL); + if (!m_hEventExitUpdateVertexResourcesWorkerThread) { + hr = HRESULT_FROM_WIN32(GetLastError()); + } + + m_hThread = CreateThread(NULL, 0, _ThreadProc, this, 0, &m_dwThreadID); + if (!m_hThread) { + hr = HRESULT_FROM_WIN32(GetLastError()); + } +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void SurfaceMesh::ExitUpdateVertexResourcesWorkerThread() +{ + HRESULT hr = S_OK; + DWORD dwTimeout = INFINITE; + DWORD rc; + + if ((!m_hEventExitUpdateVertexResourcesWorkerThread) || (!m_hThread)) + return; + + rc = SignalObjectAndWait(m_hEventExitUpdateVertexResourcesWorkerThread, m_hThread, dwTimeout, FALSE); + switch (rc) { + case WAIT_OBJECT_0: + hr = S_OK; + break; + + case WAIT_ABANDONED: + case WAIT_IO_COMPLETION: + case WAIT_TIMEOUT: + hr = E_FAIL; + break; + + case WAIT_FAILED: + hr = HRESULT_FROM_WIN32(GetLastError()); + break; + } + + CloseHandle(m_hThread); + m_hThread = nullptr; + + CloseHandle(m_hEventExitUpdateVertexResourcesWorkerThread); + m_hEventExitUpdateVertexResourcesWorkerThread = nullptr; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +DWORD SurfaceMesh::UpdateVertexResourcesWorkerThread(void) +{ + const DWORD dwSleep = 0; + + for (;;) { + if (WaitForSingleObject(m_hEventExitUpdateVertexResourcesWorkerThread, dwSleep) == WAIT_OBJECT_0) { + break; + } + + SpatialSurfaceMesh^ surfaceMesh = nullptr; + ID3D11Device* device = nullptr; + + EnterCriticalSection(&m_csMeshResources); + if (m_smud.surfaceMesh != nullptr) { + surfaceMesh = std::move(m_smud.surfaceMesh); + device = m_smud.pd3dDevice; + + m_smud.surfaceMesh = nullptr; + m_smud.pd3dDevice = nullptr; + } + LeaveCriticalSection(&m_csMeshResources); + + if (surfaceMesh && device) { + UpdateVertexResourcesTask(device, surfaceMesh); + surfaceMesh = nullptr; + } + + Sleep(1); + } + + return 0; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +inline byte* GetPointerToBufferData(IBuffer^ buffer) +{ + ComPtr insp(reinterpret_cast(buffer)); + + // Query the IBufferByteAccess interface. + ComPtr bufferByteAccess; + insp.As(&bufferByteAccess); + + byte* pixels = nullptr; + bufferByteAccess->Buffer(&pixels); + return pixels; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void SurfaceMesh::UpdateVertexResourcesTask(ID3D11Device* device, Windows::Perception::Spatial::Surfaces::SpatialSurfaceMesh^ surfaceMesh) +{ + // Before updating the meshes, check to ensure that there wasn't a more recent update. + auto meshUpdateTime = surfaceMesh->SurfaceInfo->UpdateTime; + + if (meshUpdateTime.UniversalTime <= m_lastUpdateTime.UniversalTime) + return; + + // Create new Direct3D device resources for the updated buffers. These will be set aside + // for now, and then swapped into the active slot next time the render loop is ready to draw. + + // First, we acquire the raw data buffers. + Windows::Storage::Streams::IBuffer^ positions = surfaceMesh->VertexPositions->Data; + Windows::Storage::Streams::IBuffer^ normals = surfaceMesh->VertexNormals->Data; + Windows::Storage::Streams::IBuffer^ indices = surfaceMesh->TriangleIndices->Data; + + // Then, we create Direct3D device buffers with the mesh data provided by HoloLens. + Microsoft::WRL::ComPtr updatedVertexPositions; + Microsoft::WRL::ComPtr updatedVertexNormals; + Microsoft::WRL::ComPtr updatedTriangleIndices; + + CreateDirectXBuffer(device, D3D11_BIND_VERTEX_BUFFER, positions, updatedVertexPositions.GetAddressOf()); + CreateDirectXBuffer(device, D3D11_BIND_VERTEX_BUFFER, normals, updatedVertexNormals.GetAddressOf()); + CreateDirectXBuffer(device, D3D11_BIND_INDEX_BUFFER, indices, updatedTriangleIndices.GetAddressOf()); + + { + CSLock lock(&m_csMeshResources); + + // Prepare to swap in the new meshes. + // Here, we use ComPtr.Swap() to avoid unnecessary overhead from ref counting. + m_updatedVertexPositions.Swap(updatedVertexPositions); + m_updatedVertexNormals.Swap(updatedVertexNormals); + m_updatedTriangleIndices.Swap(updatedTriangleIndices); + + // Cache properties for the buffers we will now use. + m_updatedMeshProperties.coordinateSystem = surfaceMesh->CoordinateSystem; + m_updatedMeshProperties.vertexPositionScale = surfaceMesh->VertexPositionScale; + m_updatedMeshProperties.vertexStride = surfaceMesh->VertexPositions->Stride; + m_updatedMeshProperties.normalStride = surfaceMesh->VertexNormals->Stride; + m_updatedMeshProperties.indexCount = surfaceMesh->TriangleIndices->ElementCount; + m_updatedMeshProperties.indexFormat = static_cast(surfaceMesh->TriangleIndices->Format); + + // Send a signal to the render loop indicating that new resources are available to use. + m_updateReady = true; + m_lastUpdateTime = meshUpdateTime; + m_loadingComplete = true; + + // + // retrieving and saving vertex data from the GPU is expensive. When debugging and + // to ease CPU and GPU impact, disable the below block if not part of investigation. +#ifndef DISABLE_SAVE_VERTEX_DATA + // + // save vertex data information + bool fSuccess = false; // pessimistic + auto bound = surfaceMesh->SurfaceInfo->TryGetBounds(m_baseCoordinateSystem); + if (bound != nullptr) { + // + // get the raw vertex information + unsigned int uVertexBufferSize = positions->Length; + unsigned int uNormalBufferSize = normals->Length; + unsigned int uIndexBufferSize = indices->Length; + + unsigned int uBufferSize = sizeof(SurfaceMeshStreamHeader) + uVertexBufferSize; + + // + // TODO: add normals and indices as needed + // uBufferSize += (uNormalBufferSize + uIndexBufferSize); + + m_memBuffer.LockRWAccess(); + + unsigned char* ptr = (unsigned char*)m_memBuffer.realloc(uBufferSize); + + if (ptr) { + SurfaceMeshStreamHeader* hdr = (SurfaceMeshStreamHeader*)ptr; + + memcpy(hdr->signature, (void*)SMSH_SIGNATURE, sizeof(hdr->signature)); + + hdr->scale = 1.26f / 504.0f; + hdr->center_x = bound->Value.Center.x; + hdr->center_y = bound->Value.Center.y; + hdr->center_z = bound->Value.Center.z; + hdr->orientation_x = bound->Value.Orientation.x; + hdr->orientation_y = bound->Value.Orientation.y; + hdr->orientation_z = bound->Value.Orientation.z; + hdr->orientation_w = bound->Value.Orientation.w; + + // + // copy vertices + hdr->uVertexBufferSize = uVertexBufferSize; + hdr->uNumVertices = (uVertexBufferSize / sizeof(short)) / 4; // one vertex equals to 4 positions of type short + memcpy(ptr + sizeof(SurfaceMeshStreamHeader), GetPointerToBufferData(positions), uVertexBufferSize); + + // + // TODO: copy normals and indices as needed + //hdr->uNormalBufferSize = uNormalBufferSize; + //hdr->uNumNormals = (uNormalBufferSize / sizeof(char)); + // memcpy(ptr + sizeof(SurfaceMeshStreamHeader) + uVertexBufferSize, GetPointerToBufferData(normals), uNormalBufferSize); + + //hdr->uIndexBufferSize = uIndexBufferSize; + //hdr->uNumIndices = (uIndexBufferSize / sizeof(short)); + // memcpy(ptr + sizeof(SurfaceMeshStreamHeader) + uVertexBufferSize, GetPointerToBufferData(indices), uIndexBufferSize); + + fSuccess = true; + } + + m_memBuffer.UnlockRWAccess(); + } +#else // #ifndef DISABLE_SAVE_VERTEX_DATA + #pragma message("====================== saving vertex data disabled ======================") +#endif // #ifndef DISABLE_SAVE_VERTEX_DATA + } +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void SurfaceMesh::UpdateVertexResources(ID3D11Device * device) +{ + SpatialSurfaceMesh^ surfaceMesh = std::move(m_pendingSurfaceMesh); + + if (!surfaceMesh || surfaceMesh->TriangleIndices->ElementCount < 3) + { + // Not enough indices to draw a triangle. + return; + } + + CSLock lock(&m_csMeshResources); + + // + // update data block for worker thread to pick up + m_smud.surfaceMesh = surfaceMesh; // std::move(surfaceMesh); + m_smud.pd3dDevice = device; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void SurfaceMesh::CreateDeviceDependentResources(ID3D11Device * device) +{ + UpdateVertexResources(device); + + // Create a constant buffer to control mesh position. + CD3D11_BUFFER_DESC constantBufferDesc(sizeof(ModelNormalConstantBuffer), D3D11_BIND_CONSTANT_BUFFER); + DX::ThrowIfFailed( + device->CreateBuffer(&constantBufferDesc, nullptr, &m_modelTransformBuffer + ) + ); + + m_constantBufferCreated = true; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void SurfaceMesh::ReleaseVertexResources() +{ + m_pendingSurfaceMesh = nullptr; + + m_meshProperties = {}; + m_vertexPositions.Reset(); + m_vertexNormals.Reset(); + m_triangleIndices.Reset(); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void SurfaceMesh::SwapVertexBuffers() +{ + // Swap out the previous vertex position, normal, and index buffers, and replace + // them with up-to-date buffers. + m_vertexPositions = m_updatedVertexPositions; + m_vertexNormals = m_updatedVertexNormals; + m_triangleIndices = m_updatedTriangleIndices; + + // Swap out the metadata: index count, index format, . + m_meshProperties = m_updatedMeshProperties; + + m_updatedMeshProperties = {}; + m_updatedVertexPositions.Reset(); + m_updatedVertexNormals.Reset(); + m_updatedTriangleIndices.Reset(); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void SurfaceMesh::ReleaseDeviceDependentResources() +{ + // Clear out any pending resources. + SwapVertexBuffers(); + + // Clear out active resources. + ReleaseVertexResources(); + + m_modelTransformBuffer.Reset(); + + m_constantBufferCreated = false; + m_loadingComplete = false; +} diff --git a/windows/MSRHoloLensSpatialMapping/Content/SurfaceMesh.h b/windows/MSRHoloLensSpatialMapping/Content/SurfaceMesh.h new file mode 100644 index 0000000..91c3002 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Content/SurfaceMesh.h @@ -0,0 +1,150 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#pragma once + +#include "Common\DeviceResources.h" +#include "ShaderStructures.h" +#include + +using namespace Windows::Storage::Streams; + +namespace HoloLensNavigation +{ + #define SMSH_SIGNATURE "SMSHSIG_" + + struct SurfaceMeshStreamHeader + { + unsigned char signature[8]; + float scale; + float center_x; + float center_y; + float center_z; + float orientation_x; + float orientation_y; + float orientation_z; + float orientation_w; + unsigned int uVertexBufferSize; + unsigned int uNumVertices; + }; + + struct SurfaceMeshProperties + { + Windows::Perception::Spatial::SpatialCoordinateSystem^ coordinateSystem = nullptr; + Windows::Foundation::Numerics::float3 vertexPositionScale = Windows::Foundation::Numerics::float3::one(); + unsigned int vertexStride = 0; + unsigned int normalStride = 0; + unsigned int indexCount = 0; + DXGI_FORMAT indexFormat = DXGI_FORMAT_UNKNOWN; + }; + + struct SurfaceMeshUpdateData + { + Windows::Perception::Spatial::Surfaces::SpatialSurfaceMesh^ surfaceMesh; + ID3D11Device* pd3dDevice; + }; + + + class SurfaceMesh final + { + public: + SurfaceMesh(); + ~SurfaceMesh(); + + void UpdateSurface(Windows::Perception::Spatial::Surfaces::SpatialSurfaceMesh^ surface); + void UpdateTransform( + ID3D11Device* device, + ID3D11DeviceContext* context, + DX::StepTimer const& timer, + Windows::Perception::Spatial::SpatialCoordinateSystem^ baseCoordinateSystem + ); + + void Draw(ID3D11Device* device, ID3D11DeviceContext* context, bool usingVprtShaders, bool isStereo); + + void UpdateVertexResources(ID3D11Device* device); + void CreateDeviceDependentResources(ID3D11Device* device); + void ReleaseVertexResources(); + void ReleaseDeviceDependentResources(); + + const bool& GetIsActive() const { return m_isActive; } + const float& GetLastActiveTime() const { return m_lastActiveTime; } + const Windows::Foundation::DateTime& GetLastUpdateTime() const { return m_lastUpdateTime; } + + void SetIsActive(const bool& isActive) { m_isActive = isActive; } + void SetColorFadeTimer(const float& duration) { m_colorFadeTimeout = duration; m_colorFadeTimer = 0.f; } + + public: + _inline StaticMemoryBuffer& GetVertexMemoryBuffer(void) { return m_memBuffer; } + + private: + void SwapVertexBuffers(); + void CreateDirectXBuffer( + ID3D11Device* device, + D3D11_BIND_FLAG binding, + Windows::Storage::Streams::IBuffer^ buffer, + ID3D11Buffer** target + ); + + Windows::Perception::Spatial::Surfaces::SpatialSurfaceMesh^ m_pendingSurfaceMesh = nullptr; + + Microsoft::WRL::ComPtr m_vertexPositions; + Microsoft::WRL::ComPtr m_vertexNormals; + Microsoft::WRL::ComPtr m_triangleIndices; + Microsoft::WRL::ComPtr m_updatedVertexPositions; + Microsoft::WRL::ComPtr m_updatedVertexNormals; + Microsoft::WRL::ComPtr m_updatedTriangleIndices; + Microsoft::WRL::ComPtr m_modelTransformBuffer; + + Windows::Foundation::DateTime m_lastUpdateTime; + + SurfaceMeshProperties m_meshProperties; + SurfaceMeshProperties m_updatedMeshProperties; + + ModelNormalConstantBuffer m_constantBufferData; + + bool m_constantBufferCreated = false; + bool m_loadingComplete = false; + bool m_updateReady = false; + bool m_isActive = false; + float m_lastActiveTime = -1.f; + float m_colorFadeTimer = -1.f; + float m_colorFadeTimeout = -1.f; + + private: + Windows::Perception::Spatial::SpatialCoordinateSystem^ m_baseCoordinateSystem = nullptr; + + // + // we'll use a memory buffer which only grows in size as needed. Because we collect + // vertex data over and over, re-using previously allocated memory will improve + // performance. + StaticMemoryBuffer m_memBuffer; + SurfaceMeshStreamHeader m_emptySMSH; + + // + // To increase overall performance, use a worker thread to update new vertex, normal and index buffers. + static DWORD WINAPI _ThreadProc(LPVOID lpParameter) { return ((SurfaceMesh*)lpParameter)->UpdateVertexResourcesWorkerThread(); } + DWORD UpdateVertexResourcesWorkerThread(void); + void CreateUpdateVertexResourcesWorkerThread(); + void ExitUpdateVertexResourcesWorkerThread(); + void UpdateVertexResourcesTask(ID3D11Device* device, Windows::Perception::Spatial::Surfaces::SpatialSurfaceMesh^ surfaceMesh); + + HANDLE m_hThread; + DWORD m_dwThreadID; + HANDLE m_hEventExitUpdateVertexResourcesWorkerThread; + + CRITICAL_SECTION m_csMeshResources; + CRITICAL_SECTION m_csUpdateVertexResources; + bool m_fClosing; + + SurfaceMeshUpdateData m_smud; + }; + +} // namespace HoloLensNavigation diff --git a/windows/MSRHoloLensSpatialMapping/Content/SurfaceVPRTVertexShader.hlsl b/windows/MSRHoloLensSpatialMapping/Content/SurfaceVPRTVertexShader.hlsl new file mode 100644 index 0000000..ac960d7 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Content/SurfaceVPRTVertexShader.hlsl @@ -0,0 +1,82 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +// A constant buffer that stores per-mesh data. +cbuffer ModelConstantBuffer : register(b0) +{ + float4x4 modelToWorld; + min16float4x4 normalToWorld; + min16float4 colorFadeFactor; +}; + +// A constant buffer that stores each set of view and projection matrices in column-major format. +cbuffer ViewProjectionConstantBuffer : register(b1) +{ + float4 cameraPosition; + float4 lightPosition; + float4x4 viewProjection[2]; +}; + +// Per-vertex data used as input to the vertex shader. +struct VertexShaderInput +{ + min16float3 pos : POSITION; + min16float3 norm : NORMAL0; + uint instId : SV_InstanceID; +}; + +// Per-vertex data passed to the geometry shader. +// Note that the render target array index is set here in the vertex shader. +struct VertexShaderOutput +{ + min16float4 screenPos : SV_POSITION; + min16float3 worldPos : POSITION0; + min16float3 worldNorm : NORMAL0; + min16float3 color : COLOR0; + uint idx : TEXCOORD0; + uint rtvId : SV_RenderTargetArrayIndex; // SV_InstanceID % 2 +}; + +// Simple shader to do vertex processing on the GPU. +VertexShaderOutput main(VertexShaderInput input) +{ + VertexShaderOutput output; + float4 pos = float4(input.pos, 1.0f); + + // Note which view this vertex has been sent to. Used for matrix lookup. + // Taking the modulo of the instance ID allows geometry instancing to be used + // along with stereo instanced drawing; in that case, two copies of each + // instance would be drawn, one for left and one for right. + int idx = input.instId % 2; + + // Transform the vertex position into world space. + pos = mul(pos, modelToWorld); + + // Store the world position. + output.worldPos = (min16float3)pos; + + // Correct for perspective and project the vertex position onto the screen. + pos = mul(pos, viewProjection[idx]); + output.screenPos = (min16float4)pos; + + // Pass a color. + output.color = min16float3(1.f, 1.f, 1.f); + + // Set the render target array index. + output.rtvId = idx; + output.idx = idx; + + // Compute the normal. + min16float4 normalVector = min16float4(input.norm, min16float(0.f)); + output.worldNorm = normalize((min16float3)mul(normalVector, normalToWorld)); + + return output; +} diff --git a/windows/MSRHoloLensSpatialMapping/Content/SurfaceVertexShader.hlsl b/windows/MSRHoloLensSpatialMapping/Content/SurfaceVertexShader.hlsl new file mode 100644 index 0000000..b384ae2 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Content/SurfaceVertexShader.hlsl @@ -0,0 +1,82 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +// A constant buffer that stores per-mesh data. +cbuffer ModelConstantBuffer : register(b0) +{ + float4x4 modelToWorld; + min16float4x4 normalToWorld; + min16float4 colorFadeFactor; +}; + +// A constant buffer that stores each set of view and projection matrices in column-major format. +cbuffer ViewProjectionConstantBuffer : register(b1) +{ + float4 cameraPosition; + float4 lightPosition; + float4x4 viewProjection[2]; +}; + +// Per-vertex data used as input to the vertex shader. +struct VertexShaderInput +{ + min16float3 pos : POSITION; + min16float3 norm : NORMAL0; + uint instId : SV_InstanceID; +}; + +// Per-vertex data passed to the geometry shader. +// Note that the render target array index will be set by the geometry shader +// using the value of viewId. +struct VertexShaderOutput +{ + min16float4 screenPos : SV_POSITION; + min16float3 worldPos : POSITION0; + min16float3 worldNorm : NORMAL0; + min16float3 color : COLOR0; + uint viewId : TEXCOORD0; // SV_InstanceID % 2 +}; + +// Simple shader to do vertex processing on the GPU. +VertexShaderOutput main(VertexShaderInput input) +{ + VertexShaderOutput output; + float4 pos = float4(input.pos, 1.0f); + + // Note which view this vertex has been sent to. Used for matrix lookup. + // Taking the modulo of the instance ID allows geometry instancing to be used + // along with stereo instanced drawing; in that case, two copies of each + // instance would be drawn, one for left and one for right. + int idx = input.instId % 2; + + // Transform the vertex position into world space. + pos = mul(pos, modelToWorld); + + // Store the world position. + output.worldPos = (min16float3)pos; + + // Correct for perspective and project the vertex position onto the screen. + pos = mul(pos, viewProjection[idx]); + output.screenPos = (min16float4)pos; + + // Pass a color. + output.color = min16float3(1.f, 1.f, 1.f); + + // Set the instance ID. The pass-through geometry shader will set the + // render target array index to whatever value is set here. + output.viewId = idx; + + // Compute the normal. + min16float4 normalVector = min16float4(input.norm, min16float(0.f)); + output.worldNorm = normalize((min16float3)mul(normalVector, normalToWorld)); + + return output; +} diff --git a/windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMapping.cpp b/windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMapping.cpp new file mode 100644 index 0000000..be43df5 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMapping.cpp @@ -0,0 +1,641 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "pch.h" +#include "MSRHololensSpatialMappingMain.h" +#include "Common\DirectXHelper.h" + +#include +#include + +using namespace HoloLensNavigation; + +using namespace concurrency; +using namespace Microsoft::WRL; +using namespace Platform; +using namespace Windows::Foundation::Collections; +using namespace Windows::Foundation::Numerics; +using namespace Windows::Graphics::Holographic; +using namespace Windows::Networking; +using namespace Windows::Perception::Spatial; +using namespace Windows::System::Threading; + +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +Windows::Networking::Sockets::StreamSocketListener^ HoloLensNavigationMain::StartListener(ListenerContext::OnConnectionEvent^ onConnectionEvent, Platform::String^ port) +{ + Sockets::StreamSocketListener^ listener = ref new Sockets::StreamSocketListener(); + listener->ConnectionReceived += ref new Windows::Foundation::TypedEventHandler(onConnectionEvent); + listener->Control->KeepAlive = false; + + create_task(listener->BindServiceNameAsync(port)).then([this](task previousTask) + { + try + { + // Try getting an exception. + previousTask.get(); + } + catch (COMException^ exception) + { + // HRESULT:0x80072740 Only one usage of each socket address (protocol/network address/port) is normally permitted. + if (exception->HResult == 0x80072740) + { + throw; + } + } + catch (Exception^ exception) + { + } + }); + + return listener; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void ListenerContext::OnConnection(Windows::Networking::Sockets::StreamSocketListener^ listener, Windows::Networking::Sockets::StreamSocketListenerConnectionReceivedEventArgs^ object) +{ + DebugMsgW(L"Socket connected"); + + m_writer = ref new Windows::Storage::Streams::DataWriter(object->Socket->OutputStream); + m_reader = ref new Windows::Storage::Streams::DataReader(object->Socket->InputStream); + m_socket = object->Socket; + + m_mappingmain->m_internalState = InternalStatus::READY_TO_RECEIVE; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +bool HoloLensNavigationMain::InternalUpdate(HolographicFrame^ holographicFrame) +{ + HolographicFramePrediction^ prediction = holographicFrame->CurrentPrediction; + SpatialCoordinateSystem^ stationaryCoordinateSystem = m_stationaryReferenceFrame->CoordinateSystem; + SpatialCoordinateSystem^ currentCoordinateSystem = m_referenceFrame->GetStationaryCoordinateSystemAtTimestamp(prediction->Timestamp); + + if ((m_internalState != PROCESSING) && (m_internalState != UNCONNECTED)) { + return false; + } + + // create new anchor + EnumAskedState tempState = EnumAskedState::Default_Ask_Pose; + if (m_askedState != EnumAskedState::Default_Ask_Pose) { + // for async processing of data receiving + // should be checked the connection timing + m_replyedState = EnumRepliedState::Reply_Anchor_Pose_Map; + tempState = m_askedState; + m_askedState = EnumAskedState::Default_Ask_Pose; + } + + // HoloLens pose update + auto cameraPose = prediction->CameraPoses->GetAt(0); + Platform::IBox^ viewTransformContainerStatic = cameraPose->TryGetViewTransform(stationaryCoordinateSystem); + bool viewTransformAcquired = viewTransformContainerStatic != nullptr; + + if (viewTransformAcquired) //get Camera pose in m_baseAnchor coordinate system, + { + HolographicStereoTransform viewCoordinateSystemTransform = viewTransformContainerStatic->Value; + float4x4 camPosition = viewCoordinateSystemTransform.Left; + + if (m_baseAnchor != nullptr) { + float4x4 anchorSpaceToCurrentCoordinateSystem; + SpatialCoordinateSystem^ anchorSpace = m_baseAnchor->CoordinateSystem; + const auto tryTransform = anchorSpace->TryGetTransformTo(stationaryCoordinateSystem); + + if (tryTransform != nullptr) + { + anchorSpaceToCurrentCoordinateSystem = tryTransform->Value; + camPosition = anchorSpaceToCurrentCoordinateSystem * camPosition;//->camPotition: base coordinates(spatial anchor coordinates)2camera coordinates + } + } + + bool invertible = Windows::Foundation::Numerics::invert(camPosition, &m_curPositionFromAnchor); + + // distance from anchor to camera check. + // base anchor is newly created or changed another one created before + if (invertible) + { + float xp = m_curPositionFromAnchor.m41, yp = m_curPositionFromAnchor.m42, zp = m_curPositionFromAnchor.m43; + float thres = 4.0 * 4.0; + + if (m_baseAnchor != nullptr && (xp * xp + yp * yp + zp * zp > thres)) { + // get anchor map + auto anchorMap = m_spatialAnchorHelper->GetAnchorMap(); + double minimumerr = -1; + IKeyValuePair^ bestPair; + + for each (auto & pair in anchorMap) { + SpatialAnchor^ candidateAnchor = pair->Value; + float4x4 anchorSpaceToCurrentCoordinateSystem; + SpatialCoordinateSystem^ anchorSpace = candidateAnchor->CoordinateSystem; + const auto tryTransform = anchorSpace->TryGetTransformTo(stationaryCoordinateSystem); + float4x4 camPos_inAnchor; + + if (tryTransform != nullptr) + { + anchorSpaceToCurrentCoordinateSystem = tryTransform->Value; + camPos_inAnchor = anchorSpaceToCurrentCoordinateSystem * viewCoordinateSystemTransform.Left;//->camPotition: base coordinates(spatial anchor coordinates)2camera coordinates + float4x4 camPosInv; + bool invertible_ = Windows::Foundation::Numerics::invert(camPos_inAnchor, &camPosInv); + + if (invertible_) { + float xp = camPosInv.m41, yp = camPosInv.m42, zp = camPosInv.m43; + double err = xp * xp + yp * yp + zp * zp; + + if (err < minimumerr || minimumerr < 0) { + bestPair = pair; + minimumerr = err; + } + } + } + } + + if (minimumerr > 0 && minimumerr < thres) { + // update anchor position pre-created + m_baseAnchor = bestPair->Value; + m_AnchorKey = bestPair->Key; + m_replyedState = EnumRepliedState::Reply_Anchor_Pose; + } + else { + // create new anchor and rendering map + m_replyedState = EnumRepliedState::Reply_Anchor_Pose_Map; + } + } + } + + // new anchor create + if (m_replyedState == EnumRepliedState::Reply_Anchor_Pose_Map) { + Platform::IBox^ viewTransformContainer = cameraPose->TryGetViewTransform(currentCoordinateSystem); + bool viewTransformAcquired = viewTransformContainer != nullptr; + + if (viewTransformAcquired) + { + HolographicStereoTransform viewCoordinateSystemTransform = viewTransformContainer->Value; + float4x4 camPosition2 = viewCoordinateSystemTransform.Left; + float4x4 viewInverse; + bool invertible = Windows::Foundation::Numerics::invert(camPosition2, &viewInverse); + + if (invertible) + { + const float3 campos(viewInverse.m41, viewInverse.m42, viewInverse.m43); + float rad = sqrt(viewInverse.m31 * viewInverse.m31 + viewInverse.m33 * viewInverse.m33); + float theta = acos(viewInverse.m33 / rad); + theta = viewInverse.m31 < 0 ? -theta : theta; + const float3 camdirection(viewInverse.m31 / rad, 0, viewInverse.m33 / rad); + const quaternion q(0, sin(theta / 2), 0, cos(theta / 2)); + SpatialAnchor^ anchor = SpatialAnchor::TryCreateRelativeTo(currentCoordinateSystem, campos, q); + + if ((anchor != nullptr) && (m_spatialAnchorHelper != nullptr)) + { + if (tempState == EnumAskedState::Refresh_Anchor_And_Render_Map) + { + m_spatialAnchorHelper->ClearAnchorStore(); + m_spatialId = 0; + } + else { + m_spatialId++; + } + + auto anchorMap = m_spatialAnchorHelper->GetAnchorMap(); + + // Create an identifier for the anchor. + std::wstringstream ss; + ss << "anchor_" << m_spatialId; + std::wstring w_char = ss.str(); + + m_AnchorKey = ref new String(w_char.c_str()); + + if (m_fVerbose) { + OutputDebugStringA((std::string("State: ") + std::to_string(m_internalState) + "\n").c_str()); + OutputDebugStringA((std::string("Anchor: ") + std::to_string(m_spatialId) + "\n").c_str()); + } + + SaveAppState(); + + { + if (m_baseAnchor == nullptr) { + m_baseAnchor = anchor; + } + const auto tryTransform = anchor->CoordinateSystem->TryGetTransformTo(m_baseAnchor->CoordinateSystem); + m_initNewAnchorPositionFromPrevAnchor = tryTransform->Value; + m_baseAnchor = anchor; + currentCoordinateSystem = m_baseAnchor->CoordinateSystem; + anchorMap->Insert(m_AnchorKey->ToString(), anchor); + m_replyedState = EnumRepliedState::Reply_Anchor_Pose_Map; + } + } + } + + } + } + + Windows::Foundation::Numerics::invert(camPosition, &m_curPositionFromAnchor); + } + + return true; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::CollectSpatialMappinginformation() +{ + { + m_meshRenderer->CollectVertexData(); + + StaticMemoryBuffer& memBuffer = m_meshRenderer->GetVertexDataCollectionBuffer(); + + memBuffer.LockRWAccess(); + + unsigned int uBufferSize = memBuffer.getBufferSize(); + unsigned char * ptr = (unsigned char* )memBuffer.getPointer(); + + if ((uBufferSize > 0) && (ptr != nullptr)) { + double holoHeight; + Eigen::Vector3d holo2floor; + + // + // FloorDetection() is very CPU intensive. When debugging and to ease CPU impact, disable the + // call and assign temporary fixed values. +#ifndef DISABLE_FLOORDETECTION + FloorDetection(ptr, uBufferSize, holoHeight, holo2floor); +#else // #ifndef DISABLE_FLOORDETECTION + #pragma message("====================== FloorDetection() disabled ======================") + holoHeight = -1.31; + holo2floor << -0.163, 0.345, 1.251; +#endif // #ifndef DISABLE_FLOORDETECTION + + if (m_fVerbose) { + OutputDebugStringA((std::string("Height and floor: ") + std::to_string(holoHeight) + "," + + std::to_string(holo2floor(0)) + "," + + std::to_string(holo2floor(1)) + "," + + std::to_string(holo2floor(2)) + "," + + "\n").c_str()); + } + + m_floorAndHeight[0] = (float)holo2floor(0); + m_floorAndHeight[1] = (float)holo2floor(1); + m_floorAndHeight[2] = (float)holo2floor(2); + m_floorAndHeight[3] = (float)holoHeight; + } + + memBuffer.UnlockRWAccess(); + } + + if (m_internalState == PROCESSING) { + m_internalState = READY_TO_SEND; + } +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::LoadAnchorStore() +{ + m_spatialAnchorHelper = create_task(SpatialAnchorManager::RequestStoreAsync()) + .then([](task previousTask) + { + std::shared_ptr newHelper = nullptr; + + + try + { + SpatialAnchorStore^ anchorStore = previousTask.get(); + newHelper = std::shared_ptr(new SpatialAnchorHelper(anchorStore)); + newHelper->LoadFromAnchorStore(); + + } + catch (Exception^ exception) + { + OutputDebugStringA((std::string(__FUNCTION__) + " " + std::to_string(__LINE__) + "\n").c_str()); + OutputDebugStringW(exception->Message->Data()); + OutputDebugStringA("\n"); + } + + // Return the initialized class instance. + return newHelper; + }).get(); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::StateReceiver() +{ + if (m_internalState != READY_TO_RECEIVE) + return; + + // receive data first, then send data + m_internalState = InternalStatus::RECEIVING; + + DataReader^ reader = m_listenercontext->m_reader; + Windows::Networking::Sockets::StreamSocket^ socket = m_listenercontext->m_socket; + + create_task(reader->LoadAsync(sizeof(UINT32))).then([this, reader, socket](unsigned int size) + { + if (size < sizeof(UINT32)) + { + // The underlying socket was closed before we were able to read the whole data. + cancel_current_task(); + } + + std::lock_guard guard(m_listenercontext->m_sockLock); + int receivedValue = -1; + + try + { + receivedValue = m_listenercontext->m_reader->ReadInt32(); + } + catch (Platform::COMException^ exception) + { + DebugMsgW(L"exception reading socket buffer!"); + return; + } + + this->m_askedState = EnumAskedState(receivedValue); + this->m_internalState = InternalStatus::PROCESSING; + + }).then([this](task readTask) + { + try + { + // Try getting an exception. + readTask.get(); + } + catch (Platform::COMException^ exception) + { + this->m_listenercontext->m_reader = nullptr; + this->m_listenercontext->m_writer = nullptr; + this->m_listenercontext->m_socket = nullptr; + } + catch (task_canceled&) + { + // this will usually happen because user closed the client socket. + + // Explicitly close the socket. + delete this->m_listenercontext->m_socket; + + this->m_listenercontext->m_reader = nullptr; + this->m_listenercontext->m_writer = nullptr; + this->m_listenercontext->m_socket = nullptr; + } + }); + + return; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::StateSender() +{ + if (m_internalState != READY_TO_SEND) + return; + + m_listenercontext->m_writer->WriteInt32(m_replyedState); + + switch (m_replyedState) { + case EnumRepliedState::Reply_Pose: + SendPose(); + break; + + case EnumRepliedState::Reply_Anchor_Pose: + SendAnchorID(); + SendPose(); + break; + + case EnumRepliedState::Reply_Anchor_Pose_Map: + SendInitAnchorPose(); + SendPointCloud(); + SendAnchorID(); + SendPose(); + break; + + default: + return; + } + + this->m_internalState = InternalStatus::SENDING; + + create_task(m_listenercontext->m_writer->StoreAsync()).then([this](task writeTask) + { + std::lock_guard guard(m_listenercontext->m_sockLock); + try + { + writeTask.get(); + this->m_internalState = InternalStatus::READY_TO_RECEIVE; + } + catch (Platform::COMException^ exception) + { + OutputDebugStringA((std::string(__FUNCTION__) + " " + std::to_string(__LINE__) + "\n").c_str()); + OutputDebugStringW(exception->Message->Data()); + OutputDebugStringA("\n"); + m_listenercontext->m_reader = nullptr; + m_listenercontext->m_writer = nullptr; + m_listenercontext->m_socket = nullptr; + } + }); + + m_replyedState = Reply_Pose; + + return; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::SendPose() +{ + Platform::Array^ buffer = ref new Platform::Array(sizeof(float) * 20); + float datamat[20] = + { m_curPositionFromAnchor.m11, m_curPositionFromAnchor.m12, m_curPositionFromAnchor.m13, m_curPositionFromAnchor.m14, + m_curPositionFromAnchor.m21, m_curPositionFromAnchor.m22, m_curPositionFromAnchor.m23, m_curPositionFromAnchor.m24, + m_curPositionFromAnchor.m31, m_curPositionFromAnchor.m32, m_curPositionFromAnchor.m33, m_curPositionFromAnchor.m34, + m_curPositionFromAnchor.m41, m_curPositionFromAnchor.m42, m_curPositionFromAnchor.m43, m_curPositionFromAnchor.m44, + m_floorAndHeight[0], m_floorAndHeight[1], m_floorAndHeight[2], m_floorAndHeight[3] }; + void* p = datamat; + + memcpy(buffer->Data, p, sizeof(float) * 20); + + m_listenercontext->m_writer->WriteBytes(buffer); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::SendInitAnchorPose() +{ + Platform::Array^ buffer = ref new Platform::Array(sizeof(float) * 16); + float datamat[16] = + { m_initNewAnchorPositionFromPrevAnchor.m11, m_initNewAnchorPositionFromPrevAnchor.m12, m_initNewAnchorPositionFromPrevAnchor.m13, m_initNewAnchorPositionFromPrevAnchor.m14, + m_initNewAnchorPositionFromPrevAnchor.m21, m_initNewAnchorPositionFromPrevAnchor.m22, m_initNewAnchorPositionFromPrevAnchor.m23, m_initNewAnchorPositionFromPrevAnchor.m24, + m_initNewAnchorPositionFromPrevAnchor.m31, m_initNewAnchorPositionFromPrevAnchor.m32, m_initNewAnchorPositionFromPrevAnchor.m33, m_initNewAnchorPositionFromPrevAnchor.m34, + m_initNewAnchorPositionFromPrevAnchor.m41, m_initNewAnchorPositionFromPrevAnchor.m42, m_initNewAnchorPositionFromPrevAnchor.m43, m_initNewAnchorPositionFromPrevAnchor.m44, }; + void* p = datamat; + + memcpy(buffer->Data, p, sizeof(float) * 16); + + m_listenercontext->m_writer->WriteBytes(buffer); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::SendAnchorID() +{ + m_listenercontext->m_writer->WriteInt32(m_listenercontext->m_writer->MeasureString(m_AnchorKey)); + + m_listenercontext->m_writer->WriteString(m_AnchorKey); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::SendPointCloud() +{ + StaticMemoryBuffer& memBuffer = m_meshRenderer->GetVertexDataCollectionBuffer(); + + memBuffer.LockRWAccess(); + + unsigned int uBufferSize = memBuffer.getBufferSize(); + unsigned char* ptr = (unsigned char*)memBuffer.getPointer(); + + m_listenercontext->m_writer->WriteInt32(uBufferSize); + m_listenercontext->m_writer->WriteBytes(Platform::ArrayReference(ptr, uBufferSize)); + + // DebugMsgW(L"======================= sent total buffer size: %u", uBufferSize); + + memBuffer.UnlockRWAccess(); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::FloorDetection(unsigned char* buffer, unsigned int uBufferSize, double& HoloHeight, Eigen::Vector3d& floorpt) +{ + //// get plane and Height + //// around 1m x 1m + + //// ransac + int ransac_max = 100; + std::vector points; + std::vector indices; + Eigen::Vector3d bestn, bestp; + unsigned int cnt = 0; + int maxcnt = -1; + unsigned int uBufferPosition = 0; + + bestn << 1, 1, 1; + + while (true) + { + SurfaceMeshStreamHeader* hdr = (SurfaceMeshStreamHeader*)(buffer); + + if (memcmp(hdr->signature, (void*)SMSH_SIGNATURE, sizeof(hdr->signature)) != 0) { + DebugMsgW(L"FloorDetection() buffer misalignment at offset %u!\r\n", uBufferPosition); + break; + } + + Eigen::Vector3d center; + Eigen::Quaterniond orientation = Eigen::Quaterniond(hdr->orientation_w, hdr->orientation_x, hdr->orientation_y, hdr->orientation_z); + unsigned int uNumVertices = hdr->uNumVertices; + + center << hdr->center_x, hdr->center_y, hdr->center_z; + + if (false) { + OutputDebugStringA((std::to_string(uNumVertices) + "\n").c_str()); + } + + buffer += sizeof(SurfaceMeshStreamHeader); + + short * vertexBuffer = (short *)buffer; + for (unsigned int i = 0; i < uNumVertices; i++) + { + Eigen::Vector3d p; + p << vertexBuffer[i * 4] * 0.0025f, vertexBuffer[i * 4 + 1] * 0.0025f, vertexBuffer[i * 4 + 2] * 0.0025f; + p = orientation * p + center; + + if ((p(0) < 1.0) && (p(0) > -1.0) && (p(1) < 1.0) && (p(1) > -1.0) && (p(2) < 0)) { + points.push_back(p); + indices.push_back(cnt); + cnt++; + } + } + + buffer += hdr->uVertexBufferSize;; + uBufferPosition += sizeof(SurfaceMeshStreamHeader) + hdr->uVertexBufferSize; + if (uBufferPosition >= uBufferSize) + break; + } + + if (points.size() < 50) + return; + + std::vector bestlist; + for (int ransac_t = 0; ransac_t < ransac_max; ransac_t++) { + random_shuffle(indices.begin(), indices.end()); + + std::vector candlist; + Eigen::Vector3d v01, v02, nfloor, cand_p; + int numInliers = 0; + + cand_p = points.at(indices.at(0)); + v01 = points.at(indices.at(1)) - cand_p; + v02 = points.at(indices.at(2)) - cand_p; + nfloor = v01.cross(v02); + nfloor = nfloor.normalized(); + + for (int idx = 3; idx < (int)indices.size(); idx++) { + Eigen::Vector3d targp = points.at(indices.at(idx)) - cand_p; + double err = abs(targp.dot(nfloor)); + + if (err < 0.005) { + //inlier + candlist.push_back(indices.at(idx)); + numInliers++; + } + } + + if (maxcnt < numInliers) { + maxcnt = numInliers; + bestn = nfloor; + bestp = cand_p; + bestlist = std::vector(candlist); + } + } + + // plane fitting + // solve least square problem + // ax+by+z+d=0: ax+by+d=-z + Eigen::MatrixXd A(bestlist.size(), 3); + Eigen::VectorXd B(bestlist.size()); + + for (int idx = 0; idx < (int)bestlist.size(); idx++) { + Eigen::Vector3d targp = points.at(indices.at(idx)); + + A(idx, 0) = targp(0); // x + A(idx, 1) = targp(1); // y + A(idx, 2) = 1; // 1 + B(idx) = -targp(2); // -z + } + + Eigen::Vector3d ansX = A.jacobiSvd(Eigen::ComputeThinU | Eigen::ComputeThinV).solve(B); + + // rendering: 1.0m upper from hololens - 2.0m lower from hololens (3.0m range) + // hololens point (scale*(dwidth/2),scale*(dwidth/2),1.0) + // ax+by+z+d=0: n< + + + + + + + + + + + {b65d7ef6-4502-4ff4-9c74-942a42e2db5e} + HolographicApp + MSRHoloLensSpatialMapping + en-US + 14.0 + true + Windows Store + 10.0 + 10.0.19041.0 + 10.0 + true + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + Debug + ARM + + + Release + ARM + + + Debug + ARM64 + + + Release + ARM64 + + + + Application + true + + + Application + true + + + Application + true + + + Application + true + + + Application + false + true + + + Application + false + true + + + Application + false + true + + + Application + false + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + MSRHoloLensSpatialMapping_TemporaryKey.pfx + + + $(SolutionDir)bin\$(Platform)\$(Configuration)\ + $(SolutionDir)build\$(Platform)\$(Configuration)\ + + + $(SolutionDir)bin\$(Platform)\$(Configuration)\ + $(SolutionDir)build\$(Platform)\$(Configuration)\ + + + $(SolutionDir)bin\$(Platform)\$(Configuration)\ + $(SolutionDir)build\$(Platform)\$(Configuration)\ + + + $(SolutionDir)bin\$(Platform)\$(Configuration)\ + $(SolutionDir)build\$(Platform)\$(Configuration)\ + + + $(SolutionDir)bin\$(Platform)\$(Configuration)\ + $(SolutionDir)build\$(Platform)\$(Configuration)\ + + + $(SolutionDir)bin\$(Platform)\$(Configuration)\ + $(SolutionDir)build\$(Platform)\$(Configuration)\ + + + $(SolutionDir)bin\$(Platform)\$(Configuration)\ + $(SolutionDir)build\$(Platform)\$(Configuration)\ + + + $(SolutionDir)bin\$(Platform)\$(Configuration)\ + $(SolutionDir)build\$(Platform)\$(Configuration)\ + + + + d2d1.lib; d3d11.lib; dxgi.lib; dwrite.lib; windowscodecs.lib; %(AdditionalDependencies); + %(AdditionalLibraryDirectories); $(VCInstallDir)\lib\store; $(VCInstallDir)\lib + mincore.lib;kernel32.lib;ole32.lib;%(IgnoreSpecificDefaultLibraries) + $(OutDir)$(TargetName)$(TargetExt) + + + pch.h + $(IntDir)pch.pch + $(ProjectDir);$(IntermediateOutputPath);%(AdditionalIncludeDirectories) + /bigobj %(AdditionalOptions) + 4453;28204 + _DEBUG;%(PreprocessorDefinitions) + + + + + d2d1.lib; d3d11.lib; dxgi.lib; dwrite.lib; windowscodecs.lib; %(AdditionalDependencies); + %(AdditionalLibraryDirectories); $(VCInstallDir)\lib\store; $(VCInstallDir)\lib + mincore.lib;kernel32.lib;ole32.lib;%(IgnoreSpecificDefaultLibraries) + $(OutDir)$(TargetName)$(TargetExt) + + + pch.h + $(IntDir)pch.pch + $(ProjectDir);$(IntermediateOutputPath);%(AdditionalIncludeDirectories) + /bigobj %(AdditionalOptions) + 4453;28204 + _DEBUG;%(PreprocessorDefinitions) + + + + + d2d1.lib; d3d11.lib; dxgi.lib; dwrite.lib; windowscodecs.lib; %(AdditionalDependencies); + %(AdditionalLibraryDirectories); $(VCInstallDir)\lib\store; $(VCInstallDir)\lib + mincore.lib;kernel32.lib;ole32.lib;%(IgnoreSpecificDefaultLibraries) + $(OutDir)$(TargetName)$(TargetExt) + + + pch.h + $(IntDir)pch.pch + $(ProjectDir);$(IntermediateOutputPath);%(AdditionalIncludeDirectories) + /bigobj %(AdditionalOptions) + 4453;28204 + _DEBUG;%(PreprocessorDefinitions) + + + + + d2d1.lib; d3d11.lib; dxgi.lib; dwrite.lib; windowscodecs.lib; %(AdditionalDependencies); + %(AdditionalLibraryDirectories); $(VCInstallDir)\lib\store; $(VCInstallDir)\lib + mincore.lib;kernel32.lib;ole32.lib;%(IgnoreSpecificDefaultLibraries) + $(OutDir)$(TargetName)$(TargetExt) + + + pch.h + $(IntDir)pch.pch + $(ProjectDir);$(IntermediateOutputPath);%(AdditionalIncludeDirectories) + /bigobj %(AdditionalOptions) + 4453;28204 + _DEBUG;%(PreprocessorDefinitions) + + + + + d2d1.lib; d3d11.lib; dxgi.lib; dwrite.lib; windowscodecs.lib; %(AdditionalDependencies); + %(AdditionalLibraryDirectories); $(VCInstallDir)\lib\store; $(VCInstallDir)\lib + mincore.lib;kernel32.lib;ole32.lib;%(IgnoreSpecificDefaultLibraries) + $(OutDir)$(TargetName)$(TargetExt) + + + pch.h + $(IntDir)pch.pch + $(ProjectDir);$(IntermediateOutputPath);%(AdditionalIncludeDirectories) + /bigobj %(AdditionalOptions) + 4453;28204 + NDEBUG;%(PreprocessorDefinitions) + + + + + d2d1.lib; d3d11.lib; dxgi.lib; dwrite.lib; windowscodecs.lib; %(AdditionalDependencies); + %(AdditionalLibraryDirectories); $(VCInstallDir)\lib\store; $(VCInstallDir)\lib + mincore.lib;kernel32.lib;ole32.lib;%(IgnoreSpecificDefaultLibraries) + $(OutDir)$(TargetName)$(TargetExt) + + + pch.h + $(IntDir)pch.pch + $(ProjectDir);$(IntermediateOutputPath);%(AdditionalIncludeDirectories) + /bigobj %(AdditionalOptions) + 4453;28204 + NDEBUG;%(PreprocessorDefinitions) + + + + + d2d1.lib; d3d11.lib; dxgi.lib; dwrite.lib; windowscodecs.lib; %(AdditionalDependencies); + %(AdditionalLibraryDirectories); $(VCInstallDir)\lib\store; $(VCInstallDir)\lib + mincore.lib;kernel32.lib;ole32.lib;%(IgnoreSpecificDefaultLibraries) + $(OutDir)$(TargetName)$(TargetExt) + + + pch.h + $(IntDir)pch.pch + $(ProjectDir);$(IntermediateOutputPath);%(AdditionalIncludeDirectories) + /bigobj %(AdditionalOptions) + 4453;28204 + NDEBUG;%(PreprocessorDefinitions) + + + + + d2d1.lib; d3d11.lib; dxgi.lib; dwrite.lib; windowscodecs.lib; %(AdditionalDependencies); + %(AdditionalLibraryDirectories); $(VCInstallDir)\lib\store; $(VCInstallDir)\lib + mincore.lib;kernel32.lib;ole32.lib;%(IgnoreSpecificDefaultLibraries) + $(OutDir)$(TargetName)$(TargetExt) + + + pch.h + $(IntDir)pch.pch + $(ProjectDir);$(IntermediateOutputPath);%(AdditionalIncludeDirectories) + /bigobj %(AdditionalOptions) + 4453;28204 + NDEBUG;%(PreprocessorDefinitions) + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Create + + + + + Designer + + + + + + + Pixel + 5.0 + Pixel + 5.0 + Pixel + 5.0 + Pixel + 5.0 + Pixel + 5.0 + Pixel + 5.0 + Pixel + 5.0 + Pixel + 5.0 + + + Pixel + 5.0 + Pixel + 5.0 + Pixel + 5.0 + Pixel + 5.0 + Pixel + 5.0 + Pixel + 5.0 + Pixel + 5.0 + Pixel + 5.0 + + + Geometry + 5.0 + Geometry + 5.0 + Geometry + 5.0 + Geometry + 5.0 + Geometry + 5.0 + Geometry + 5.0 + Geometry + 5.0 + Geometry + 5.0 + + + Vertex + 5.0 + Vertex + 5.0 + Vertex + 5.0 + Vertex + 5.0 + Vertex + 5.0 + Vertex + 5.0 + Vertex + 5.0 + Vertex + 5.0 + + + Vertex + 5.0 + Vertex + 5.0 + Vertex + 5.0 + Vertex + 5.0 + Vertex + 5.0 + Vertex + 5.0 + Vertex + 5.0 + Vertex + 5.0 + + + + + + + + + + + + This project references NuGet package(s) that are missing on this computer. Use NuGet Package Restore to download them. For more information, see http://go.microsoft.com/fwlink/?LinkID=322105. The missing file is {0}. + + + + \ No newline at end of file diff --git a/windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMapping.vcxproj.filters b/windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMapping.vcxproj.filters new file mode 100644 index 0000000..dbc640a --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMapping.vcxproj.filters @@ -0,0 +1,150 @@ + + + + + b65d7ef6-4502-4ff4-9c74-942a42e2db5f + + + a4e35f6e-771e-4e96-ae2a-6415fba206a4 + bmp;fbx;gif;jpg;jpeg;tga;tiff;tif;png + + + 2582b612-6d01-40f6-a199-be84879182e9 + + + Common + + + Common + + + Common + + + Common + + + Assets + + + Assets + + + Assets + + + Assets + + + Assets + + + Assets + + + {6104e536-a330-48ae-9fd5-8ac4d82ee784} + + + {381a19a1-a703-45a0-9212-41e34ce97352} + + + {301af131-be93-4f67-87af-cea676aa90c0} + + + + + Common + + + Source Files + + + Source Files + + + Source Files + + + Source Files + + + Content + + + Content + + + Content + + + Source Files + + + Source Files + + + + + Common + + + Header Files + + + Header Files + + + Header Files + + + Header Files + + + Content + + + Content + + + Content + + + Content + + + Content + + + Header Files + + + + + Assets + + + + + + + + + + + + Content\Shaders + + + Content\Shaders + + + Content\Shaders + + + Content\Shaders + + + Content\Shaders + + + \ No newline at end of file diff --git a/windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMapping.vcxproj.user b/windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMapping.vcxproj.user new file mode 100644 index 0000000..c3839ba --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMapping.vcxproj.user @@ -0,0 +1,27 @@ + + + + 10.1.1.206 + UWPRemoteDebugger + + + 10.1.1.206 + WindowsDeviceDebugger + + + 10.1.1.206 + UWPRemoteDebugger + + + 10.1.1.206 + UWPRemoteDebugger + + + UWPRemoteDebugger + 10.1.1.199 + + + 10.1.1.199 + UWPRemoteDebugger + + \ No newline at end of file diff --git a/windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMappingMain.cpp b/windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMappingMain.cpp new file mode 100644 index 0000000..ca57fde --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMappingMain.cpp @@ -0,0 +1,576 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "pch.h" +#include "MSRHololensSpatialMappingMain.h" +#include "Common\DirectXHelper.h" + +#include +#include + +using namespace HoloLensNavigation; + +using namespace concurrency; +using namespace Microsoft::WRL; +using namespace Platform; +using namespace Windows::Foundation; +using namespace Windows::Foundation::Collections; +using namespace Windows::Foundation::Numerics; +using namespace Windows::Graphics::DirectX; +using namespace Windows::Graphics::DirectX::Direct3D11; +using namespace Windows::Graphics::Holographic; +using namespace Windows::Perception::Spatial; +using namespace Windows::Perception::Spatial::Surfaces; +using namespace Windows::UI::Input::Spatial; +using namespace std::placeholders; + +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +HoloLensNavigationMain::HoloLensNavigationMain(const std::shared_ptr& deviceResources) : + m_deviceResources(deviceResources) +{ + // + // Loads and initializes application assets when the application is loaded. + + _pGlobalTimer = &m_timer; + + m_fVerbose = false; + + m_deviceResources->RegisterDeviceNotify(this); + + // + // initialize vertices array + // m_vert = ref new Platform::Array(1); + + // + // set up socket listener + m_listenercontext = ref new ListenerContext(this); + + m_listener = StartListener(ref new ListenerContext::OnConnectionEvent(m_listenercontext, &ListenerContext::OnConnection), PORT); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +HoloLensNavigationMain::~HoloLensNavigationMain() +{ + // Deregister device notification. + m_deviceResources->RegisterDeviceNotify(nullptr); + + UnregisterHolographicEventHandlers(); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::SetHolographicSpace(HolographicSpace^ holographicSpace) +{ + UnregisterHolographicEventHandlers(); + + m_holographicSpace = holographicSpace; + + m_meshRenderer = std::make_unique(m_deviceResources); + + m_spatialInputHandler = std::make_unique(); + + // Use the default SpatialLocator to track the motion of the device. + m_locator = SpatialLocator::GetDefault(); + + m_locatabilityChangedToken = m_locator->LocatabilityChanged += + ref new Windows::Foundation::TypedEventHandler( + std::bind(&HoloLensNavigationMain::OnLocatabilityChanged, this, _1, _2) + ); + + // respond to changes in the positional tracking state by cancelling deactivation + // of positional tracking. + m_positionalTrackingDeactivatingToken = m_locator->PositionalTrackingDeactivating += + ref new Windows::Foundation::TypedEventHandler( + std::bind(&HoloLensNavigationMain::OnPositionalTrackingDeactivating, this, _1, _2)); + + // Respond to camera added events by creating any resources that are specific + // to that camera, such as the back buffer render target view. + // When we add an event handler for CameraAdded, the API layer will avoid putting + // the new camera in new HolographicFrames until we complete the deferral we created + // for that handler, or return from the handler without creating a deferral. This + // allows the app to take more than one frame to finish creating resources and + // loading assets for the new holographic camera. + // This function should be registered before the app creates any HolographicFrames. + m_cameraAddedToken = m_holographicSpace->CameraAdded += + ref new Windows::Foundation::TypedEventHandler( + std::bind(&HoloLensNavigationMain::OnCameraAdded, this, _1, _2)); + + // Respond to camera removed events by releasing resources that were created for that + // camera. + // When the app receives a CameraRemoved event, it releases all references to the back + // buffer right away. This includes render target views, Direct2D target bitmaps, and so on. + // The app must also ensure that the back buffer is not attached as a render target, as + // shown in DeviceResources::ReleaseResourcesForBackBuffer. + m_cameraRemovedToken = m_holographicSpace->CameraRemoved += + ref new Windows::Foundation::TypedEventHandler( + std::bind(&HoloLensNavigationMain::OnCameraRemoved, this, _1, _2)); + + // This code sample uses a DeviceAttachedFrameOfReference to have the Spatial Mapping surface observer + // follow along with the device's location. + m_referenceFrame = m_locator->CreateAttachedFrameOfReferenceAtCurrentHeading(); + + // Notes on spatial tracking APIs: + // * Stationary reference frames are designed to provide a best-fit position relative to the + // overall space. Individual positions within that reference frame are allowed to drift slightly + // as the device learns more about the environment. + // * When precise placement of individual holograms is required, a SpatialAnchor should be used to + // anchor the individual hologram to a position in the real world - for example, a point the user + // indicates to be of special interest. Anchor positions do not drift, but can be corrected; the + // anchor will use the corrected position starting in the next frame after the correction has + // occurred. + + // Create a frame of reference that remains stationary relative to the user's surroundings, + // with its initial origin at the SpatialLocator's current location. + m_stationaryReferenceFrame = m_locator->CreateStationaryFrameOfReferenceAtCurrentLocation(); + + // Create a spatial anchor helper + m_spatialAnchorHelper = std::shared_ptr(new SpatialAnchorHelper(nullptr)); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::UnregisterHolographicEventHandlers() +{ + if (m_holographicSpace != nullptr) + { + // Clear previous event registrations. + + if (m_cameraAddedToken.Value != 0) + { + m_holographicSpace->CameraAdded -= m_cameraAddedToken; + m_cameraAddedToken.Value = 0; + } + + if (m_cameraRemovedToken.Value != 0) + { + m_holographicSpace->CameraRemoved -= m_cameraRemovedToken; + m_cameraRemovedToken.Value = 0; + } + } + + if (m_locator != nullptr) + { + m_locator->LocatabilityChanged -= m_locatabilityChangedToken; + m_locator->PositionalTrackingDeactivating -= m_positionalTrackingDeactivatingToken; + } + + if (m_surfaceObserver != nullptr) + { + m_surfaceObserver->ObservedSurfacesChanged -= m_surfacesChangedToken; + } +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::OnSurfacesChanged(SpatialSurfaceObserver^ sender, Object^ args) +{ + IMapView^ const& surfaceCollection = sender->GetObservedSurfaces(); + + // Process surface adds and updates. + for (const auto& pair : surfaceCollection) + { + auto id = pair->Key; + auto surfaceInfo = pair->Value; + + // Choose whether to add, or update the surface. + // In this example, new surfaces are treated differently by highlighting them in a different + // color. This allows you to observe changes in the spatial map that are due to new meshes, + // as opposed to mesh updates. + // In your app, you might choose to process added surfaces differently than updated + // surfaces. For example, you might prioritize processing of added surfaces, and + // defer processing of updates to existing surfaces. + if (m_meshRenderer->HasSurface(id)) + { + if (m_meshRenderer->GetLastUpdateTime(id).UniversalTime < surfaceInfo->UpdateTime.UniversalTime) + { + // Update existing surface. + m_meshRenderer->UpdateSurface(id, surfaceInfo); + } + } + else + { + // New surface. + m_meshRenderer->AddSurface(id, surfaceInfo); + } + } + + // Sometimes, a mesh will fall outside the area that is currently visible to + // the surface observer. In this code sample, we "sleep" any meshes that are + // not included in the surface collection to avoid rendering them. + // The system can including them in the collection again later, in which case + // they will no longer be hidden. + m_meshRenderer->HideInactiveMeshes(surfaceCollection); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +HolographicFrame^ HoloLensNavigationMain::Update() +{ + // + // Updates the application state once per frame. + + // Before doing the timer update, there is some work to do per-frame + // to maintain holographic rendering. First, we will get information + // about the current frame. + + // The HolographicFrame has information that the app needs in order + // to update and render the current frame. The app begins each new + // frame by calling CreateNextFrame. + HolographicFrame^ holographicFrame = m_holographicSpace->CreateNextFrame(); + + // Get a prediction of where holographic cameras will be when this frame + // is presented. + HolographicFramePrediction^ prediction = holographicFrame->CurrentPrediction; + + // Back buffers can change from frame to frame. Validate each buffer, and recreate + // resource views and depth buffers as needed. + m_deviceResources->EnsureCameraResources(holographicFrame, prediction); + + // Next, we get a coordinate system from the attached frame of reference that is + // associated with the current frame. Later, this coordinate system is used for + // for creating the stereo view matrices when rendering the sample content. + SpatialCoordinateSystem^ currentCoordinateSystem = m_referenceFrame->GetStationaryCoordinateSystemAtTimestamp(prediction->Timestamp); + + if (!InternalUpdate(holographicFrame)) + return holographicFrame; + + // Only create a surface observer when you need to - do not create a new one each frame. + if (m_surfaceObserver == nullptr) + { + // Initialize the Surface Observer using a valid coordinate system. + if (!m_spatialPerceptionAccessRequested) + { + // The spatial mapping API reads information about the user's environment. The user must + // grant permission to the app to use this capability of the Windows Holographic device. + auto initSurfaceObserverTask = create_task(SpatialSurfaceObserver::RequestAccessAsync()); + initSurfaceObserverTask.then([this, currentCoordinateSystem](Windows::Perception::Spatial::SpatialPerceptionAccessStatus status) + { + switch (status) + { + case SpatialPerceptionAccessStatus::Allowed: + m_surfaceAccessAllowed = true; + break; + default: + // Access was denied. This usually happens because your AppX manifest file does not declare the + // spatialPerception capability. + // For info on what else can cause this, see: http://msdn.microsoft.com/library/windows/apps/mt621422.aspx + m_surfaceAccessAllowed = false; + break; + } + }); + + m_spatialPerceptionAccessRequested = true; + } + } + + if (m_surfaceAccessAllowed) + { + SpatialBoundingBox axisAlignedBoundingBox = + { + { 0.f, 0.f, 0.f }, + { 20.f, 20.f, 5.f }, + }; + SpatialBoundingVolume^ bounds = SpatialBoundingVolume::FromBox(currentCoordinateSystem, axisAlignedBoundingBox); + + // If status is Allowed, we can create the surface observer. + if (m_surfaceObserver == nullptr) + { + // First, we'll set up the surface observer to use our preferred data formats. + // In this example, a "preferred" format is chosen that is compatible with our precompiled shader pipeline. + m_surfaceMeshOptions = ref new SpatialSurfaceMeshOptions(); + IVectorView^ supportedVertexPositionFormats = m_surfaceMeshOptions->SupportedVertexPositionFormats; + unsigned int formatIndex = 0; + if (supportedVertexPositionFormats->IndexOf(DirectXPixelFormat::R16G16B16A16IntNormalized, &formatIndex)) + { + m_surfaceMeshOptions->VertexPositionFormat = DirectXPixelFormat::R16G16B16A16IntNormalized; + } + IVectorView^ supportedVertexNormalFormats = m_surfaceMeshOptions->SupportedVertexNormalFormats; + if (supportedVertexNormalFormats->IndexOf(DirectXPixelFormat::R8G8B8A8IntNormalized, &formatIndex)) + { + m_surfaceMeshOptions->VertexNormalFormat = DirectXPixelFormat::R8G8B8A8IntNormalized; + } + + // If you are using a very high detail setting with spatial mapping, it can be beneficial + // to use a 32-bit unsigned integer format for indices instead of the default 16-bit. + // Uncomment the following code to enable 32-bit indices. + //IVectorView^ supportedTriangleIndexFormats = m_surfaceMeshOptions->SupportedTriangleIndexFormats; + //if (supportedTriangleIndexFormats->IndexOf(DirectXPixelFormat::R32UInt, &formatIndex)) + //{ + // m_surfaceMeshOptions->TriangleIndexFormat = DirectXPixelFormat::R32UInt; + //} + + // Create the observer. + m_surfaceObserver = ref new SpatialSurfaceObserver(); + if (m_surfaceObserver) + { + m_surfaceObserver->SetBoundingVolume(bounds); + + // If the surface observer was successfully created, we can initialize our + // collection by pulling the current data set. + auto mapContainingSurfaceCollection = m_surfaceObserver->GetObservedSurfaces(); + for (auto const& pair : mapContainingSurfaceCollection) + { + // Store the ID and metadata for each surface. + auto const& id = pair->Key; + auto const& surfaceInfo = pair->Value; + m_meshRenderer->AddSurface(id, surfaceInfo); + } + + // We then subcribe to an event to receive up-to-date data. + m_surfacesChangedToken = m_surfaceObserver->ObservedSurfacesChanged += + ref new TypedEventHandler(bind(&HoloLensNavigationMain::OnSurfacesChanged, this, _1, _2)); + } + } + + // Keep the surface observer positioned at the device's location. + m_surfaceObserver->SetBoundingVolume(bounds); + + // Note that it is possible to set multiple bounding volumes. Pseudocode: + // m_surfaceObserver->SetBoundingVolumes(/* iterable collection of bounding volumes*/); + // + // It is also possible to use other bounding shapes - such as a view frustum. Pseudocode: + // SpatialBoundingVolume^ bounds = SpatialBoundingVolume::FromFrustum(coordinateSystem, viewFrustum); + // m_surfaceObserver->SetBoundingVolume(bounds); + } + + // Check for new input state since the last frame. + SpatialInteractionSourceState^ pointerState = m_spatialInputHandler->CheckForInput(); + if (pointerState != nullptr) + { + // When a Pressed gesture is detected, the rendering mode will be changed to wireframe. + m_drawWireframe = !m_drawWireframe; + } + + m_timer.Tick([&] () + { +#ifdef TODO + if (m_baseAnchor != nullptr) { + const auto tryTransform = m_baseAnchor->CoordinateSystem->TryGetTransformTo(stationaryCoordinateSystem); + m_meshRenderer->Update(m_timer, m_baseAnchor->CoordinateSystem); + } + else +#endif // #ifdef TODO + { + m_meshRenderer->Update(m_timer, currentCoordinateSystem); + } + }); + + // + // collecting vertex data is expensive. When debugging and to ease CPU and GPU + // impact, disable the CollectSpatialMappinginformation() call if not part of + // investigation. +#ifndef DISABLE_COLLECTING_SPATIAL_MAPPING_DATA + CollectSpatialMappinginformation(); +#else // #ifndef DISABLE_COLLECTING_SPATIAL_MAPPING_DATA + #pragma message("====================== CollectSpatialMappinginformation() disabled ======================") +#endif // #ifndef DISABLE_COLLECTING_SPATIAL_MAPPING_DATA + + // This code uses default image stabilization settings, and does not set the focus point. + + // The holographic frame will be used to get up-to-date view and projection matrices and + // to present the swap chain. + return holographicFrame; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +bool HoloLensNavigationMain::Render(HolographicFrame^ holographicFrame) +{ + // + // Renders the current frame to each holographic camera, according to the + // current application and spatial positioning state. Returns true if the + // frame was rendered to at least one camera. + + // Don't try to render anything before the first Update. + if (m_timer.GetFrameCount() == 0) + return false; + + // Lock the set of holographic camera resources, then draw to each camera + // in this frame. + return m_deviceResources->UseHolographicCameraResources( + [this, holographicFrame](std::map>& cameraResourceMap) + { + // Up-to-date frame predictions enhance the effectiveness of image stablization and + // allow more accurate positioning of holograms. + holographicFrame->UpdateCurrentPrediction(); + HolographicFramePrediction^ prediction = holographicFrame->CurrentPrediction; + SpatialCoordinateSystem^ currentCoordinateSystem = m_referenceFrame->GetStationaryCoordinateSystemAtTimestamp(prediction->Timestamp); + + bool atLeastOneCameraRendered = false; + for (auto cameraPose : prediction->CameraPoses) + { + // This represents the device-based resources for a HolographicCamera. + DX::CameraResources* pCameraResources = cameraResourceMap[cameraPose->HolographicCamera->Id].get(); + + // Get the device context. + const auto context = m_deviceResources->GetD3DDeviceContext(); + const auto depthStencilView = pCameraResources->GetDepthStencilView(); + + // Set render targets to the current holographic camera. + ID3D11RenderTargetView* const targets[1] = { pCameraResources->GetBackBufferRenderTargetView() }; + context->OMSetRenderTargets(1, targets, depthStencilView); + + // Clear the back buffer and depth stencil view. + context->ClearRenderTargetView(targets[0], DirectX::Colors::Transparent); + context->ClearDepthStencilView(depthStencilView, D3D11_CLEAR_DEPTH | D3D11_CLEAR_STENCIL, 1.0f, 0); + + // The view and projection matrices for each holographic camera will change + // every frame. This function refreshes the data in the constant buffer for + // the holographic camera indicated by cameraPose. + pCameraResources->UpdateViewProjectionBuffer(m_deviceResources, cameraPose, currentCoordinateSystem); + + // Attach the view/projection constant buffer for this camera to the graphics pipeline. + bool cameraActive = pCameraResources->AttachViewProjectionBuffer(m_deviceResources); + + // Only render world-locked content when positional tracking is active. + if (cameraActive) + { + // Draw the hologram. + m_meshRenderer->Render(pCameraResources->IsRenderingStereoscopic(), m_drawWireframe); + + // On versions of the platform that support the CommitDirect3D11DepthBuffer API, we can + // provide the depth buffer to the system, and it will use depth information to stabilize + // the image at a per-pixel level. + static const bool canCommitDirect3D11DepthBuffer = + Windows::Foundation::Metadata::ApiInformation::IsMethodPresent("Windows.Graphics.Holographic.HolographicCameraRenderingParameters", "CommitDirect3D11DepthBuffer"); + + if (canCommitDirect3D11DepthBuffer) + { + HolographicCameraRenderingParameters^ renderingParameters = holographicFrame->GetRenderingParameters(cameraPose); + ComPtr spDepthStencil = pCameraResources->GetDepthStencilTexture2D(); + + // Direct3D interop APIs are used to provide the buffer to the WinRT API. + ComPtr depthStencilResource; + DX::ThrowIfFailed(spDepthStencil.As(&depthStencilResource)); + ComPtr depthDxgiSurface; + DX::ThrowIfFailed(depthStencilResource->CreateSubresourceSurface(0, &depthDxgiSurface)); + IDirect3DSurface^ depthD3DSurface = CreateDirect3DSurface(depthDxgiSurface.Get()); + + // Calling CommitDirect3D11DepthBuffer causes the system to queue Direct3D commands to + // read the depth buffer. It will then use that information to stabilize the image as + // the HolographicFrame is presented. + renderingParameters->CommitDirect3D11DepthBuffer(depthD3DSurface); + } + } + + atLeastOneCameraRendered = true; + } + + return atLeastOneCameraRendered; + }); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::SaveAppState() +{ + if (m_spatialAnchorHelper != nullptr) + { + m_spatialAnchorHelper->TrySaveToAnchorStore(); + } +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::LoadAppState() +{ + LoadAnchorStore(); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::OnDeviceLost() +{ + // Notifies classes that use Direct3D device resources that the device resources + // need to be released before this method returns. + + m_meshRenderer->ReleaseDeviceDependentResources(); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::OnDeviceRestored() +{ + // Notifies classes that use Direct3D device resources that the device resources + // may now be recreated. + + m_meshRenderer->CreateDeviceDependentResources(); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::OnPositionalTrackingDeactivating(SpatialLocator^ sender, SpatialLocatorPositionalTrackingDeactivatingEventArgs^ args) +{ + // Without positional tracking, spatial meshes will not be locatable. + args->Canceled = true; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::OnCameraAdded(HolographicSpace^ sender, HolographicSpaceCameraAddedEventArgs^ args) +{ + Deferral^ deferral = args->GetDeferral(); + HolographicCamera^ holographicCamera = args->Camera; + create_task([this, deferral, holographicCamera] () + { + // Create device-based resources for the holographic camera and add it to the list of + // cameras used for updates and rendering. Notes: + // * Since this function may be called at any time, the AddHolographicCamera function + // waits until it can get a lock on the set of holographic camera resources before + // adding the new camera. At 60 frames per second this wait should not take long. + // * A subsequent Update will take the back buffer from the RenderingParameters of this + // camera's CameraPose and use it to create the ID3D11RenderTargetView for this camera. + // Content can then be rendered for the HolographicCamera. + m_deviceResources->AddHolographicCamera(holographicCamera); + + // Holographic frame predictions will not include any information about this camera until + // the deferral is completed. + deferral->Complete(); + }); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::OnCameraRemoved(HolographicSpace^ sender, HolographicSpaceCameraRemovedEventArgs^ args) +{ + // Before letting this callback return, ensure that all references to the back buffer + // are released. + // Since this function may be called at any time, the RemoveHolographicCamera function + // waits until it can get a lock on the set of holographic camera resources before + // deallocating resources for this camera. At 60 frames per second this wait should + // not take long. + m_deviceResources->RemoveHolographicCamera(args->Camera); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void HoloLensNavigationMain::OnLocatabilityChanged(SpatialLocator^ sender, Object^ args) +{ + // String^ mes = sender->Locatability.ToString(); + + switch (sender->Locatability) + { + case SpatialLocatability::Unavailable: + // Holograms cannot be rendered. + break; + case SpatialLocatability::PositionalTrackingActivating: + break; + case SpatialLocatability::OrientationOnly: + break; + case SpatialLocatability::PositionalTrackingInhibited: + break; + case SpatialLocatability::PositionalTrackingActive: + break; + } +} diff --git a/windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMappingMain.h b/windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMappingMain.h new file mode 100644 index 0000000..4aaba7a --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/MSRHoloLensSpatialMappingMain.h @@ -0,0 +1,232 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#pragma once + +#include "Common\DeviceResources.h" +#include "Common\StepTimer.h" + +#include "Content\SpatialInputHandler.h" +#include "Content\RealtimeSurfaceMeshRenderer.h" + +#include "Content\SurfaceMesh.h" + +#include "SpatialAnchor.h" + +#include +#include +#include +#include + +#define PORT "1234" + +namespace HoloLensNavigation +{ + enum InternalStatus { + UNCONNECTED, + READY_TO_RECEIVE, + RECEIVING, + PROCESSING, + READY_TO_SEND, + SENDING + }; + + enum EnumAskedState { + Default_Ask_Pose, + Refresh_Anchor_And_Render_Map, + Update_Anchor + }; + + enum EnumRepliedState { + Reply_Pose, + Reply_Anchor_Pose, + Reply_Anchor_Pose_Map + }; + + class HoloLensNavigationMain; + + ref class ListenerContext + { + internal: + ListenerContext(HoloLensNavigationMain* mappingmain) + { + m_mappingmain = mappingmain; + } + delegate void OnConnectionEvent(Windows::Networking::Sockets::StreamSocketListener^ listener, Windows::Networking::Sockets::StreamSocketListenerConnectionReceivedEventArgs^ object); + public: + void OnConnection(Windows::Networking::Sockets::StreamSocketListener^ listener, Windows::Networking::Sockets::StreamSocketListenerConnectionReceivedEventArgs^ object); + + internal: + Windows::Storage::Streams::DataWriter ^ m_writer; + Windows::Storage::Streams::DataReader ^ m_reader; + Windows::Networking::Sockets::StreamSocket ^ m_socket; + std::mutex m_sockLock; + + private: + HoloLensNavigationMain * m_mappingmain; + }; + + // + // Updates, renders, and presents holographic content using Direct3D. + class HoloLensNavigationMain : public DX::IDeviceNotify + { + public: + HoloLensNavigationMain(const std::shared_ptr& deviceResources); + ~HoloLensNavigationMain(); + + // Sets the holographic space. This is our closest analogue to setting a new window + // for the app. + void SetHolographicSpace(Windows::Graphics::Holographic::HolographicSpace^ holographicSpace); + + // Starts the holographic frame and updates the content. + Windows::Graphics::Holographic::HolographicFrame^ Update(); + + // Renders holograms, including world-locked content. + bool Render(Windows::Graphics::Holographic::HolographicFrame^ holographicFrame); + + // Handle saving and loading of app state owned by AppMain. + void SaveAppState(); + void LoadAppState(); + + // IDeviceNotify + virtual void OnDeviceLost(); + virtual void OnDeviceRestored(); + + // Handle surface change events. + void OnSurfacesChanged(Windows::Perception::Spatial::Surfaces::SpatialSurfaceObserver^ sender, Platform::Object^ args); + + public: + // + // socket connection state handlers + Windows::Networking::Sockets::StreamSocketListener^ StartListener(ListenerContext::OnConnectionEvent^ onConnectionEvent, Platform::String^ port); + void StateSender(); + void StateReceiver(); + + private: + // Asynchronously creates resources for new holographic cameras. + void OnCameraAdded( + Windows::Graphics::Holographic::HolographicSpace^ sender, + Windows::Graphics::Holographic::HolographicSpaceCameraAddedEventArgs^ args); + + // Synchronously releases resources for holographic cameras that are no longer + // attached to the system. + void OnCameraRemoved( + Windows::Graphics::Holographic::HolographicSpace^ sender, + Windows::Graphics::Holographic::HolographicSpaceCameraRemovedEventArgs^ args); + + // Used to prevent the device from deactivating positional tracking, which is + // necessary to continue to receive spatial mapping data. + void OnPositionalTrackingDeactivating( + Windows::Perception::Spatial::SpatialLocator^ sender, + Windows::Perception::Spatial::SpatialLocatorPositionalTrackingDeactivatingEventArgs^ args); + + void OnLocatabilityChanged( + Windows::Perception::Spatial::SpatialLocator^ sender, + Platform::Object^ args); + + // Clears event registration state. Used when changing to a new HolographicSpace + // and when tearing down AppMain. + void UnregisterHolographicEventHandlers(); + + // Listens for the Pressed spatial input event. + std::shared_ptr m_spatialInputHandler; + + // A data handler for surface meshes. + std::unique_ptr m_meshRenderer; + + private: + // Cached pointer to device resources. + std::shared_ptr m_deviceResources; + + // Render loop timer. + DX::StepTimer m_timer; + + // Represents the holographic space around the user. + Windows::Graphics::Holographic::HolographicSpace ^ m_holographicSpace; + + // SpatialLocator that is attached to the primary camera. + Windows::Perception::Spatial::SpatialLocator ^ m_locator; + + // A reference frame attached to the holographic camera. + Windows::Perception::Spatial::SpatialLocatorAttachedFrameOfReference^ m_referenceFrame; + + // Event registration tokens. + Windows::Foundation::EventRegistrationToken m_cameraAddedToken; + Windows::Foundation::EventRegistrationToken m_cameraRemovedToken; + Windows::Foundation::EventRegistrationToken m_positionalTrackingDeactivatingToken; + Windows::Foundation::EventRegistrationToken m_surfacesChangedToken; + Windows::Foundation::EventRegistrationToken m_locatabilityChangedToken; + + // Indicates whether access to spatial mapping data has been granted. + bool m_surfaceAccessAllowed = false; + + // Indicates whether the surface observer initialization process was started. + bool m_spatialPerceptionAccessRequested = false; + + // Obtains spatial mapping data from the device in real time. + Windows::Perception::Spatial::Surfaces::SpatialSurfaceObserver ^ m_surfaceObserver; + Windows::Perception::Spatial::Surfaces::SpatialSurfaceMeshOptions ^ m_surfaceMeshOptions; + + // Determines the rendering mode. + bool m_drawWireframe = true; + + + // + // hololens navigation +private: + // A frame of reference that remains stationary relative to the user's surroundings at a point in time. + Windows::Perception::Spatial::SpatialStationaryFrameOfReference^ m_stationaryReferenceFrame; + + bool InternalUpdate(Windows::Graphics::Holographic::HolographicFrame^ holographicFrame); + void CollectSpatialMappinginformation(); + void FloorDetection(unsigned char* buffer, unsigned int uBufferSize, double& HoloHeight, Eigen::Vector3d& floorpt); + + std::shared_ptr m_spatialAnchorHelper; + Windows::Perception::Spatial::SpatialAnchor ^ m_baseAnchor; + Windows::Perception::Spatial::SpatialAnchor ^ m_nextAnchor; + Windows::Perception::Spatial::SpatialAnchor ^ m_anchor; + + void LoadAnchorStore(); + Platform::String ^ m_newKey; + Platform::String ^ m_AnchorKey; + int m_spatialId = 0; + Windows::Foundation::Numerics::float4x4 m_initNewAnchorPositionFromPrevAnchor; + + // kept current state + Windows::Foundation::Numerics::float4x4 m_curPositionFromAnchor; + float m_floorAndHeight[4] = { 0,0,0,0 }; + + // send functions + void SendPose(); + void SendInitAnchorPose(); + void SendAnchorID(); + void SendPointCloud(); + + // + // socket management + friend ListenerContext; + ListenerContext ^ m_listenercontext; + Windows::Networking::Sockets::StreamSocketListener ^ m_listener; + + // + // connection status + bool m_connecting = false; + bool m_bCommunicating = false, m_bNextSend = false; + EnumAskedState m_askedState = EnumAskedState::Default_Ask_Pose; + EnumRepliedState m_replyedState = EnumRepliedState::Reply_Pose; + InternalStatus m_internalState = InternalStatus::UNCONNECTED; + + // + // log output flag + bool m_fVerbose; + }; + +} // namespace HoloLensNavigation diff --git a/windows/MSRHoloLensSpatialMapping/Miscellaneous.cpp b/windows/MSRHoloLensSpatialMapping/Miscellaneous.cpp new file mode 100644 index 0000000..559e9c3 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Miscellaneous.cpp @@ -0,0 +1,93 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "pch.h" +#include + +using namespace HoloLensNavigation; + +DX::StepTimer * _pGlobalTimer = nullptr; + +/*************************************************************************************************/ +/* */ +/*************************************************************************************************/ +void HoloLensNavigation::DebugMsgW(PCWSTR pwszMessage, ...) +{ + WCHAR ach[2048]; + va_list vArgs; + + va_start(vArgs, pwszMessage); + + StringCchVPrintfW(ach, _countof(ach), pwszMessage, vArgs); + + va_end(vArgs); + + StringCchCatW(ach, _countof(ach), L"\r\n"); + + OutputDebugStringW(ach); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +StaticMemoryBuffer::StaticMemoryBuffer(void) +{ + InitializeCriticalSection(&m_cs); + m_pvBuffer = nullptr; + m_uAllocatedBufferSize = 0; + m_uRequestedBufferSize = 0; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +StaticMemoryBuffer::~StaticMemoryBuffer(void) +{ + LockRWAccess(); + if (m_pvBuffer) { + free(m_pvBuffer); + m_pvBuffer = nullptr; + } + m_uAllocatedBufferSize = 0; + m_uRequestedBufferSize = 0; + UnlockRWAccess(); + + DeleteCriticalSection(&m_cs); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void* StaticMemoryBuffer::realloc(unsigned int uBufferSize) +{ + LockRWAccess(); + + if (m_uAllocatedBufferSize < uBufferSize) { + if (m_pvBuffer == nullptr) + m_pvBuffer = ::malloc(uBufferSize); + else + m_pvBuffer = ::realloc(m_pvBuffer, uBufferSize); + + // + // out of memory? + if (m_pvBuffer == nullptr) { + m_uAllocatedBufferSize = 0; + m_uRequestedBufferSize = 0; + UnlockRWAccess(); + return nullptr; + } + + m_uAllocatedBufferSize = uBufferSize; + } + + m_uRequestedBufferSize = uBufferSize; + + UnlockRWAccess(); + + return m_pvBuffer; +} diff --git a/windows/MSRHoloLensSpatialMapping/Miscellaneous.h b/windows/MSRHoloLensSpatialMapping/Miscellaneous.h new file mode 100644 index 0000000..c2663e1 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Miscellaneous.h @@ -0,0 +1,63 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#pragma once + +namespace DX +{ + class StepTimer; +}; + +extern DX::StepTimer * _pGlobalTimer; + +namespace HoloLensNavigation +{ + void DebugMsgW(PCWSTR pwszMessage, ...); + + class CSLock + { + public: + //---------------------------------------------------------- + CSLock(CRITICAL_SECTION* pcs) + { + m_pcs = pcs; + EnterCriticalSection(m_pcs); + } + //---------------------------------------------------------- + ~CSLock() + { + LeaveCriticalSection(m_pcs); + } + + private: + CRITICAL_SECTION* m_pcs; + }; + + class StaticMemoryBuffer + { + public: + StaticMemoryBuffer(void); + ~StaticMemoryBuffer(void); + + void* realloc(unsigned int uBufferSize); + _inline void LockRWAccess(void) { EnterCriticalSection(&m_cs); } + _inline void UnlockRWAccess(void) { LeaveCriticalSection(&m_cs); } + _inline void* getPointer(void) { return m_pvBuffer; } + _inline unsigned int getBufferSize(void) { return m_uRequestedBufferSize; } + + private: + CRITICAL_SECTION m_cs; + void* m_pvBuffer; + unsigned int m_uAllocatedBufferSize; + unsigned int m_uRequestedBufferSize; + }; + +} // namespace HoloLensNavigation diff --git a/windows/MSRHoloLensSpatialMapping/Package.appxmanifest b/windows/MSRHoloLensSpatialMapping/Package.appxmanifest new file mode 100644 index 0000000..f1afb97 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/Package.appxmanifest @@ -0,0 +1,32 @@ + + + + + + MSRHoloLensSpatialMapping + Microsoft Applied Robotics Research + Assets\StoreLogo.png + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/windows/MSRHoloLensSpatialMapping/SpatialAnchor.cpp b/windows/MSRHoloLensSpatialMapping/SpatialAnchor.cpp new file mode 100644 index 0000000..a55efa8 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/SpatialAnchor.cpp @@ -0,0 +1,87 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#include "pch.h" +#include "SpatialAnchor.h" + + +using namespace HoloLensNavigation; +using namespace Windows::Perception::Spatial; +using namespace Platform; + +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +SpatialAnchorHelper::SpatialAnchorHelper(SpatialAnchorStore^ anchorStore) +{ + m_anchorStore = anchorStore; + m_anchorMap = ref new Platform::Collections::Map(); +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +bool SpatialAnchorHelper::TrySaveToAnchorStore() +{ + // This function returns true if all the anchors in the in-memory collection are saved to the anchor + // store. If zero anchors are in the in-memory collection, we will still return true because the + // condition has been met. + bool success = true; + + // If access is denied, 'anchorStore' will not be obtained. + if (m_anchorStore != nullptr) + { + for each (auto & pair in m_anchorMap) + { + auto const& id = pair->Key; + auto const& anchor = pair->Value; + + // Try to save the anchors. + if (!m_anchorStore->TrySave(id, anchor)) + { + // This may indicate the anchor ID is taken, or the anchor limit is reached for the app. + success = false; + } + } + } + + return success; +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void SpatialAnchorHelper::LoadFromAnchorStore() +{ + // If access is denied, 'anchorStore' will not be obtained. + if (m_anchorStore != nullptr) + { + // Get all saved anchors. + auto anchorMapView = m_anchorStore->GetAllSavedAnchors(); + for each (auto const& pair in anchorMapView) + { + auto const& id = pair->Key; + auto const& anchor = pair->Value; + m_anchorMap->Insert(id, anchor); + } + } +} +/***********************************************************************************************************/ +/* */ +/***********************************************************************************************************/ +void SpatialAnchorHelper::ClearAnchorStore() +{ + // If access is denied, 'anchorStore' will not be obtained. + if (m_anchorStore != nullptr) + { + // Clear all anchors from the store. + m_anchorMap->Clear(); + m_anchorStore->Clear(); + } +} diff --git a/windows/MSRHoloLensSpatialMapping/SpatialAnchor.h b/windows/MSRHoloLensSpatialMapping/SpatialAnchor.h new file mode 100644 index 0000000..8ecc7ef --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/SpatialAnchor.h @@ -0,0 +1,32 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#pragma once + +#include + +namespace HoloLensNavigation +{ + class SpatialAnchorHelper + { + public: + SpatialAnchorHelper(Windows::Perception::Spatial::SpatialAnchorStore^ anchorStore); + Windows::Foundation::Collections::IMap^ GetAnchorMap() { return m_anchorMap; }; + void LoadFromAnchorStore(); + void ClearAnchorStore(); + bool TrySaveToAnchorStore(); + + private: + Windows::Perception::Spatial::SpatialAnchorStore^ m_anchorStore; + Windows::Foundation::Collections::IMap^ m_anchorMap; + }; + +} // namespace HoloLensNavigation diff --git a/windows/MSRHoloLensSpatialMapping/packages.config b/windows/MSRHoloLensSpatialMapping/packages.config new file mode 100644 index 0000000..caa5e56 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/packages.config @@ -0,0 +1,4 @@ + + + + \ No newline at end of file diff --git a/windows/MSRHoloLensSpatialMapping/pch.cpp b/windows/MSRHoloLensSpatialMapping/pch.cpp new file mode 100644 index 0000000..bcb5590 --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/pch.cpp @@ -0,0 +1 @@ +#include "pch.h" diff --git a/windows/MSRHoloLensSpatialMapping/pch.h b/windows/MSRHoloLensSpatialMapping/pch.h new file mode 100644 index 0000000..ce324da --- /dev/null +++ b/windows/MSRHoloLensSpatialMapping/pch.h @@ -0,0 +1,30 @@ +//********************************************************* +// +// Copyright (c) Microsoft. All rights reserved. +// This code is licensed under the MIT License (MIT). +// THIS CODE IS PROVIDED *AS IS* WITHOUT WARRANTY OF +// ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING ANY +// IMPLIED WARRANTIES OF FITNESS FOR A PARTICULAR +// PURPOSE, MERCHANTABILITY, OR NON-INFRINGEMENT. +// +//********************************************************* + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "Miscellaneous.h"